From 11b04b761094090e0fa640860ec0f6f798e2fbe0 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sun, 8 Sep 2024 00:20:05 +1000 Subject: [PATCH] ArduCopter: avoid nullptr dereference on bad rcmap value entry --- ArduCopter/radio.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/ArduCopter/radio.cpp b/ArduCopter/radio.cpp index 49eeee371c..212763d03a 100644 --- a/ArduCopter/radio.cpp +++ b/ArduCopter/radio.cpp @@ -20,10 +20,10 @@ void Copter::default_dead_zones() void Copter::init_rc_in() { - channel_roll = rc().channel(rcmap.roll()-1); - channel_pitch = rc().channel(rcmap.pitch()-1); - channel_throttle = rc().channel(rcmap.throttle()-1); - channel_yaw = rc().channel(rcmap.yaw()-1); + 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);