From c99fc688e13f120d0cd1aa293d64a303b7db3bba Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sun, 8 Sep 2024 00:05:57 +1000 Subject: [PATCH] ArduPlane: avoid nullptr dereference on bad rcmap value entry --- ArduPlane/radio.cpp | 11 ++++++----- 1 file changed, 6 insertions(+), 5 deletions(-) diff --git a/ArduPlane/radio.cpp b/ArduPlane/radio.cpp index e601c94fde..3862b390b7 100644 --- a/ArduPlane/radio.cpp +++ b/ArduPlane/radio.cpp @@ -8,16 +8,17 @@ */ void Plane::set_control_channels(void) { + // the library gaurantees that these are non-nullptr: if (g.rudder_only) { // in rudder only mode the roll and rudder channels are the // same. - channel_roll = RC_Channels::rc_channel(rcmap.yaw()-1); + channel_roll = &rc().get_yaw_channel(); } else { - channel_roll = RC_Channels::rc_channel(rcmap.roll()-1); + channel_roll = &rc().get_roll_channel(); } - channel_pitch = RC_Channels::rc_channel(rcmap.pitch()-1); - channel_throttle = RC_Channels::rc_channel(rcmap.throttle()-1); - channel_rudder = RC_Channels::rc_channel(rcmap.yaw()-1); + channel_pitch = &rc().get_pitch_channel(); + channel_throttle = &rc().get_throttle_channel(); + channel_rudder = &rc().get_yaw_channel(); // set rc channel ranges channel_roll->set_angle(SERVO_MAX);