Skip to content

Commit

Permalink
Rover: avoid nullptr dereference on bad rcmap value entry
Browse files Browse the repository at this point in the history
  • Loading branch information
peterbarker committed Sep 8, 2024
1 parent b2c1be6 commit 99e922c
Showing 1 changed file with 4 additions and 3 deletions.
7 changes: 4 additions & 3 deletions Rover/radio.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down

0 comments on commit 99e922c

Please sign in to comment.