mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
Copter: fixed collective input with H_SV_MAN=1 for heli
when H_SV_MAN=1 we do direct pass-thru so the user can test swash range. The problem is that it uses norm_input() for throttle, which depends on RC3_TRIM. Nowhere else in heli or copter do we depend on RC3_TRIM, so the user gets a misleading idea of behaviour when testing their swash.
This commit is contained in:
parent
85ab3edc5f
commit
8cf8f3a288
@ -182,5 +182,8 @@ void Copter::set_throttle_zero_flag(int16_t throttle_control)
|
|||||||
// pass pilot's inputs to motors library (used to allow wiggling servos while disarmed on heli, single, coax copters)
|
// pass pilot's inputs to motors library (used to allow wiggling servos while disarmed on heli, single, coax copters)
|
||||||
void Copter::radio_passthrough_to_motors()
|
void Copter::radio_passthrough_to_motors()
|
||||||
{
|
{
|
||||||
motors->set_radio_passthrough(channel_roll->norm_input(), channel_pitch->norm_input(), channel_throttle->norm_input(), channel_yaw->norm_input());
|
motors->set_radio_passthrough(channel_roll->norm_input(),
|
||||||
|
channel_pitch->norm_input(),
|
||||||
|
channel_throttle->get_control_in_zero_dz()*0.001,
|
||||||
|
channel_yaw->norm_input());
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user