mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 08:13:56 -04:00
RC_Channel_aux: immediately send output to servos when set_radio, set_radio_to_min, set_radio_to_max, set_radio_to_trim or set_servo_out functions are called.
This commit is contained in:
parent
4ca27defb3
commit
eac26b2313
@ -108,12 +108,12 @@ RC_Channel_aux::set_radio(RC_Channel_aux::Aux_servo_function_t function, int16_t
|
|||||||
{
|
{
|
||||||
for (uint8_t i = 0; i < 7; i++) {
|
for (uint8_t i = 0; i < 7; i++) {
|
||||||
if (_aux_channels[i] && _aux_channels[i]->function.get() == function) {
|
if (_aux_channels[i] && _aux_channels[i]->function.get() == function) {
|
||||||
_aux_channels[i]->radio_out = value;
|
_aux_channels[i]->radio_out = constrain(value,_aux_channels[i]->radio_min,_aux_channels[i]->radio_max);
|
||||||
|
_aux_channels[i]->output();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
/*
|
/*
|
||||||
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
|
||||||
the given function type
|
the given function type
|
||||||
@ -138,6 +138,7 @@ RC_Channel_aux::set_radio_to_min(RC_Channel_aux::Aux_servo_function_t function)
|
|||||||
for (uint8_t i = 0; i < 7; i++) {
|
for (uint8_t i = 0; i < 7; i++) {
|
||||||
if (_aux_channels[i] && _aux_channels[i]->function.get() == function) {
|
if (_aux_channels[i] && _aux_channels[i]->function.get() == function) {
|
||||||
_aux_channels[i]->radio_out = _aux_channels[i]->radio_min;
|
_aux_channels[i]->radio_out = _aux_channels[i]->radio_min;
|
||||||
|
_aux_channels[i]->output();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -151,6 +152,7 @@ RC_Channel_aux::set_radio_to_max(RC_Channel_aux::Aux_servo_function_t function)
|
|||||||
for (uint8_t i = 0; i < 7; i++) {
|
for (uint8_t i = 0; i < 7; i++) {
|
||||||
if (_aux_channels[i] && _aux_channels[i]->function.get() == function) {
|
if (_aux_channels[i] && _aux_channels[i]->function.get() == function) {
|
||||||
_aux_channels[i]->radio_out = _aux_channels[i]->radio_max;
|
_aux_channels[i]->radio_out = _aux_channels[i]->radio_max;
|
||||||
|
_aux_channels[i]->output();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -164,6 +166,7 @@ RC_Channel_aux::set_radio_to_trim(RC_Channel_aux::Aux_servo_function_t function)
|
|||||||
for (uint8_t i = 0; i < 7; i++) {
|
for (uint8_t i = 0; i < 7; i++) {
|
||||||
if (_aux_channels[i] && _aux_channels[i]->function.get() == function) {
|
if (_aux_channels[i] && _aux_channels[i]->function.get() == function) {
|
||||||
_aux_channels[i]->radio_out = _aux_channels[i]->radio_trim;
|
_aux_channels[i]->radio_out = _aux_channels[i]->radio_trim;
|
||||||
|
_aux_channels[i]->output();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -197,6 +200,7 @@ RC_Channel_aux::set_servo_out(RC_Channel_aux::Aux_servo_function_t function, int
|
|||||||
if (_aux_channels[i] && _aux_channels[i]->function.get() == function) {
|
if (_aux_channels[i] && _aux_channels[i]->function.get() == function) {
|
||||||
_aux_channels[i]->servo_out = value;
|
_aux_channels[i]->servo_out = value;
|
||||||
_aux_channels[i]->calc_pwm();
|
_aux_channels[i]->calc_pwm();
|
||||||
|
_aux_channels[i]->output();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user