mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 05:58:30 -04:00
RC_Channel: added set_radio() and set_radio_to_trim() functions
This commit is contained in:
parent
8c46fced16
commit
024e5c3cc7
@ -99,6 +99,19 @@ enable_aux_servos()
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
set radio_out for all channels matching the given function type
|
||||||
|
*/
|
||||||
|
void
|
||||||
|
RC_Channel_aux::set_radio(RC_Channel_aux::Aux_servo_function_t function, int16_t value)
|
||||||
|
{
|
||||||
|
for (uint8_t i = 0; i < 7; i++) {
|
||||||
|
if (_aux_channels[i] && _aux_channels[i]->function.get() == function) {
|
||||||
|
_aux_channels[i]->radio_out = value;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
/*
|
/*
|
||||||
set and save the trim value to radio_in for all channels matching
|
set and save the trim value to radio_in for all channels matching
|
||||||
@ -141,6 +154,19 @@ RC_Channel_aux::set_radio_to_max(RC_Channel_aux::Aux_servo_function_t function)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
set the radio_out value for any channel with the given function to radio_trim
|
||||||
|
*/
|
||||||
|
void
|
||||||
|
RC_Channel_aux::set_radio_to_trim(RC_Channel_aux::Aux_servo_function_t function)
|
||||||
|
{
|
||||||
|
for (uint8_t i = 0; i < 7; i++) {
|
||||||
|
if (_aux_channels[i] && _aux_channels[i]->function.get() == function) {
|
||||||
|
_aux_channels[i]->radio_out = _aux_channels[i]->radio_trim;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
copy radio_in to radio_out for a given function
|
copy radio_in to radio_out for a given function
|
||||||
*/
|
*/
|
||||||
|
@ -50,6 +50,9 @@ public:
|
|||||||
|
|
||||||
void output_ch(unsigned char ch_nr);
|
void output_ch(unsigned char ch_nr);
|
||||||
|
|
||||||
|
// set radio_out for a function channel
|
||||||
|
static void set_radio(Aux_servo_function_t function, int16_t value);
|
||||||
|
|
||||||
// set and save the trim for a function channel to radio_in
|
// set and save the trim for a function channel to radio_in
|
||||||
static void set_radio_trim(Aux_servo_function_t function);
|
static void set_radio_trim(Aux_servo_function_t function);
|
||||||
|
|
||||||
@ -59,6 +62,9 @@ public:
|
|||||||
// set radio_out to radio_max
|
// set radio_out to radio_max
|
||||||
static void set_radio_to_max(Aux_servo_function_t function);
|
static void set_radio_to_max(Aux_servo_function_t function);
|
||||||
|
|
||||||
|
// set radio_out to radio_trim
|
||||||
|
static void set_radio_to_trim(Aux_servo_function_t function);
|
||||||
|
|
||||||
// copy radio_in to radio_out
|
// copy radio_in to radio_out
|
||||||
static void copy_radio_in_out(Aux_servo_function_t function);
|
static void copy_radio_in_out(Aux_servo_function_t function);
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user