From 9be4cc65c74e6e0ad8a63e99f66378651032722c Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sun, 8 Sep 2024 00:22:48 +1000 Subject: [PATCH] ArduCopter: avoid nullptr dereference on bad rcmap value entry --- ArduCopter/radio.cpp | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/ArduCopter/radio.cpp b/ArduCopter/radio.cpp index 212763d03a..b92178d098 100644 --- a/ArduCopter/radio.cpp +++ b/ArduCopter/radio.cpp @@ -20,10 +20,11 @@ void Copter::default_dead_zones() void Copter::init_rc_in() { - channel_roll = rc().get_roll_channel(); - channel_pitch = rc().get_pitch_channel(); - channel_throttle = rc().get_throttle_channel(); - channel_yaw = rc().get_yaw_channel(); + // the library gaurantees that these are non-nullptr: + channel_roll = &rc().get_roll_channel(); + channel_pitch = &rc().get_pitch_channel(); + channel_throttle = &rc().get_throttle_channel(); + channel_yaw = &rc().get_yaw_channel(); // set rc channel ranges channel_roll->set_angle(ROLL_PITCH_YAW_INPUT_MAX);