From 0dea007ce76d4021bdc55783b1128ffc4c53def3 Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Tue, 16 Jul 2019 13:40:08 -0700 Subject: [PATCH] Rover: null check for unconfigured RCMAP_YAW which is not use don all vehicle types --- APMrover2/mode.cpp | 2 +- APMrover2/radio.cpp | 8 ++++++-- 2 files changed, 7 insertions(+), 3 deletions(-) diff --git a/APMrover2/mode.cpp b/APMrover2/mode.cpp index b82825fd46d66..d89d30c73bdf0 100644 --- a/APMrover2/mode.cpp +++ b/APMrover2/mode.cpp @@ -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; } diff --git a/APMrover2/radio.cpp b/APMrover2/radio.cpp index 769dada98886e..f6e6a73af2250 100644 --- a/APMrover2/radio.cpp +++ b/APMrover2/radio.cpp @@ -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); + } } /*