From f2604f2f3462fe6a39b3bd75e6434a5a880fe494 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sun, 8 Sep 2024 00:22:49 +1000 Subject: [PATCH] Rover: avoid nullptr dereference on bad rcmap value entry --- Rover/radio.cpp | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/Rover/radio.cpp b/Rover/radio.cpp index cf1f159689..9fdb5c0c98 100644 --- a/Rover/radio.cpp +++ b/Rover/radio.cpp @@ -6,9 +6,10 @@ void Rover::set_control_channels(void) { // check change on RCMAP - channel_steer = rc().channel(rcmap.roll()-1); - channel_throttle = rc().channel(rcmap.throttle()-1); - channel_lateral = rc().channel(rcmap.yaw()-1); + // the library gaurantees that these are non-nullptr: + channel_steer = &rc().get_roll_channel(); + channel_throttle = &rc().get_throttle_channel(); + channel_lateral = &rc().get_yaw_channel(); // set rc channel ranges channel_steer->set_angle(SERVO_MAX);