mirror of https://github.com/ArduPilot/ardupilot
ArduCopter: avoid nullptr dereference on bad rcmap value entry
This commit is contained in:
parent
11b04b7610
commit
9be4cc65c7
|
@ -20,10 +20,11 @@ void Copter::default_dead_zones()
|
||||||
|
|
||||||
void Copter::init_rc_in()
|
void Copter::init_rc_in()
|
||||||
{
|
{
|
||||||
channel_roll = rc().get_roll_channel();
|
// the library gaurantees that these are non-nullptr:
|
||||||
channel_pitch = rc().get_pitch_channel();
|
channel_roll = &rc().get_roll_channel();
|
||||||
channel_throttle = rc().get_throttle_channel();
|
channel_pitch = &rc().get_pitch_channel();
|
||||||
channel_yaw = rc().get_yaw_channel();
|
channel_throttle = &rc().get_throttle_channel();
|
||||||
|
channel_yaw = &rc().get_yaw_channel();
|
||||||
|
|
||||||
// set rc channel ranges
|
// set rc channel ranges
|
||||||
channel_roll->set_angle(ROLL_PITCH_YAW_INPUT_MAX);
|
channel_roll->set_angle(ROLL_PITCH_YAW_INPUT_MAX);
|
||||||
|
|
Loading…
Reference in New Issue