mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-28 11:38:44 -04:00
ArduCopter: radio fix passthrough range on heli/coax/single
This commit is contained in:
parent
f0d5017b43
commit
30243ed5fc
@ -182,5 +182,5 @@ 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->get_control_in()/1000.0f, channel_pitch->get_control_in()/1000.0f, channel_throttle->get_control_in()/1000.0f, channel_yaw->get_control_in()/1000.0f);
|
motors->set_radio_passthrough(channel_roll->norm_input(), channel_pitch->norm_input(), channel_throttle->norm_input(), channel_yaw->norm_input());
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user