mirror of https://github.com/ArduPilot/ardupilot
ArduCopter: avoid nullptr dereference on bad rcmap value entry
This commit is contained in:
parent
c99fc688e1
commit
11b04b7610
|
@ -20,10 +20,10 @@ void Copter::default_dead_zones()
|
||||||
|
|
||||||
void Copter::init_rc_in()
|
void Copter::init_rc_in()
|
||||||
{
|
{
|
||||||
channel_roll = rc().channel(rcmap.roll()-1);
|
channel_roll = rc().get_roll_channel();
|
||||||
channel_pitch = rc().channel(rcmap.pitch()-1);
|
channel_pitch = rc().get_pitch_channel();
|
||||||
channel_throttle = rc().channel(rcmap.throttle()-1);
|
channel_throttle = rc().get_throttle_channel();
|
||||||
channel_yaw = rc().channel(rcmap.yaw()-1);
|
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