mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-05 21:23:58 -04:00
Plane: fixed MANUAL_RCMASK
ensure it only applies in MANUAL, and fixed input scaling in px4io
This commit is contained in:
parent
c090818d5e
commit
3d16ca7144
@ -269,6 +269,7 @@ bool Plane::setup_failsafe_mixing(void)
|
||||
enum AP_HAL::Util::safety_state old_state = hal.util->safety_switch_state();
|
||||
struct pwm_output_values pwm_values = {.values = {0}, .channel_count = 8};
|
||||
unsigned mixer_status = 0;
|
||||
uint16_t manual_mask = uint16_t(g2.manual_rc_mask.get());
|
||||
|
||||
buf = (char *)malloc(buf_size);
|
||||
if (buf == nullptr) {
|
||||
@ -365,6 +366,13 @@ bool Plane::setup_failsafe_mixing(void)
|
||||
config.rc_max = 1813; // round 1812.5 up to grant > 1750
|
||||
config.rc_min = 1000;
|
||||
config.rc_trim = 1500;
|
||||
} else if (manual_mask & (1U<<i)) {
|
||||
// use fixed limits for manual_mask channels
|
||||
config.rc_assignment = i;
|
||||
config.rc_reverse = i==1?true:false;
|
||||
config.rc_max = PX4_LIM_RC_MAX;
|
||||
config.rc_min = PX4_LIM_RC_MIN;
|
||||
config.rc_trim = 1500;
|
||||
} else {
|
||||
config.rc_assignment = i;
|
||||
}
|
||||
|
@ -663,7 +663,7 @@ void Plane::servos_output(void)
|
||||
servo_output_mixers();
|
||||
|
||||
// support MANUAL_RCMASK
|
||||
if (g2.manual_rc_mask.get() != 0) {
|
||||
if (g2.manual_rc_mask.get() != 0 && control_mode == MANUAL) {
|
||||
SRV_Channels::copy_radio_in_out_mask(uint16_t(g2.manual_rc_mask.get()));
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user