mirror of https://github.com/ArduPilot/ardupilot
ArduPlane: avoid nullptr dereference on bad rcmap value entry
This commit is contained in:
parent
9cbb494092
commit
c99fc688e1
|
@ -8,16 +8,17 @@
|
|||
*/
|
||||
void Plane::set_control_channels(void)
|
||||
{
|
||||
// the library gaurantees that these are non-nullptr:
|
||||
if (g.rudder_only) {
|
||||
// in rudder only mode the roll and rudder channels are the
|
||||
// same.
|
||||
channel_roll = RC_Channels::rc_channel(rcmap.yaw()-1);
|
||||
channel_roll = &rc().get_yaw_channel();
|
||||
} else {
|
||||
channel_roll = RC_Channels::rc_channel(rcmap.roll()-1);
|
||||
channel_roll = &rc().get_roll_channel();
|
||||
}
|
||||
channel_pitch = RC_Channels::rc_channel(rcmap.pitch()-1);
|
||||
channel_throttle = RC_Channels::rc_channel(rcmap.throttle()-1);
|
||||
channel_rudder = RC_Channels::rc_channel(rcmap.yaw()-1);
|
||||
channel_pitch = &rc().get_pitch_channel();
|
||||
channel_throttle = &rc().get_throttle_channel();
|
||||
channel_rudder = &rc().get_yaw_channel();
|
||||
|
||||
// set rc channel ranges
|
||||
channel_roll->set_angle(SERVO_MAX);
|
||||
|
|
Loading…
Reference in New Issue