ArduCopter: avoid nullptr dereference on bad rcmap value entry

This commit is contained in:
Peter Barker 2024-09-08 00:22:48 +10:00 committed by Peter Barker
parent 11b04b7610
commit 9be4cc65c7
1 changed files with 5 additions and 4 deletions

View File

@ -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);