Rover: null check for unconfigured RCMAP_YAW which is not use don all vehicle types

This commit is contained in:
Tom Pittenger 2019-07-16 13:40:08 -07:00 committed by Andrew Tridgell
parent c6f884221e
commit 692bf1c931
2 changed files with 7 additions and 3 deletions

View File

@ -135,7 +135,7 @@ void Mode::get_pilot_desired_steering_and_speed(float &steering_out, float &spee
void Mode::get_pilot_desired_lateral(float &lateral_out)
{
// no RC input means no lateral input
if (rover.failsafe.bits & FAILSAFE_EVENT_THROTTLE) {
if ((rover.failsafe.bits & FAILSAFE_EVENT_THROTTLE) || (rover.channel_lateral == nullptr)) {
lateral_out = 0;
return;
}

View File

@ -13,7 +13,9 @@ void Rover::set_control_channels(void)
// set rc channel ranges
channel_steer->set_angle(SERVO_MAX);
channel_throttle->set_angle(100);
channel_lateral->set_angle(100);
if (channel_lateral != nullptr) {
channel_lateral->set_angle(100);
}
// Allow to reconfigure output when not armed
if (!arming.is_armed()) {
@ -33,7 +35,9 @@ void Rover::init_rc_in()
// set rc dead zones
channel_steer->set_default_dead_zone(30);
channel_throttle->set_default_dead_zone(30);
channel_lateral->set_default_dead_zone(30);
if (channel_lateral != nullptr) {
channel_lateral->set_default_dead_zone(30);
}
}
/*