mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
Copter: g.rc_3.control_in range 0 to 1000
Previously the range was throttle_min (normally 130) to 1000 but we can remove this awkward range and use 0 to 1000 now that the attitude controller and motor library inputs are in the 0 to 1 range.
This commit is contained in:
parent
a00a9601a4
commit
e132ea34d9
@ -32,7 +32,7 @@ void Copter::init_rc_in()
|
||||
channel_roll->set_angle(ROLL_PITCH_INPUT_MAX);
|
||||
channel_pitch->set_angle(ROLL_PITCH_INPUT_MAX);
|
||||
channel_yaw->set_angle(4500);
|
||||
channel_throttle->set_range(g.throttle_min, THR_MAX);
|
||||
channel_throttle->set_range(0, THR_MAX);
|
||||
|
||||
channel_roll->set_type(RC_CHANNEL_TYPE_ANGLE_RAW);
|
||||
channel_pitch->set_type(RC_CHANNEL_TYPE_ANGLE_RAW);
|
||||
|
Loading…
Reference in New Issue
Block a user