mirror of https://github.com/ArduPilot/ardupilot
Plane: fixed RCMAP_* to fix channel ranges for no-reboot changes
This commit is contained in:
parent
5a9485a419
commit
6bac13f9e2
|
@ -13,6 +13,12 @@ static void set_control_channels(void)
|
|||
channel_pitch = RC_Channel::rc_channel(rcmap.pitch()-1);
|
||||
channel_throttle = RC_Channel::rc_channel(rcmap.throttle()-1);
|
||||
channel_rudder = RC_Channel::rc_channel(rcmap.yaw()-1);
|
||||
|
||||
// set rc channel ranges
|
||||
channel_roll->set_angle(SERVO_MAX);
|
||||
channel_pitch->set_angle(SERVO_MAX);
|
||||
channel_rudder->set_angle(SERVO_MAX);
|
||||
channel_throttle->set_range(0, 100);
|
||||
}
|
||||
|
||||
/*
|
||||
|
@ -20,12 +26,6 @@ static void set_control_channels(void)
|
|||
*/
|
||||
static void init_rc_in()
|
||||
{
|
||||
// set rc channel ranges
|
||||
channel_roll->set_angle(SERVO_MAX);
|
||||
channel_pitch->set_angle(SERVO_MAX);
|
||||
channel_rudder->set_angle(SERVO_MAX);
|
||||
channel_throttle->set_range(0, 100);
|
||||
|
||||
// set rc dead zones
|
||||
channel_roll->set_dead_zone(60);
|
||||
channel_pitch->set_dead_zone(60);
|
||||
|
|
Loading…
Reference in New Issue