Rover: update servo ranges on change of RCMAP_*

This commit is contained in:
Andrew Tridgell 2013-06-03 22:22:47 +10:00
parent 340c451caf
commit 537d0032a8
1 changed files with 4 additions and 4 deletions

View File

@ -7,14 +7,14 @@ static void set_control_channels(void)
{
channel_steer = RC_Channel::rc_channel(rcmap.roll()-1);
channel_throttle = RC_Channel::rc_channel(rcmap.throttle()-1);
// set rc channel ranges
channel_steer->set_angle(SERVO_MAX);
channel_throttle->set_angle(100);
}
static void init_rc_in()
{
// set rc channel ranges
channel_steer->set_angle(SERVO_MAX);
channel_throttle->set_angle(100);
// set rc dead zones
channel_steer->set_dead_zone(60);
channel_throttle->set_dead_zone(6);