mirror of https://github.com/ArduPilot/ardupilot
Rover: avoid nullptr dereference on bad rcmap value entry
This commit is contained in:
parent
a868fb8861
commit
f2604f2f34
|
@ -6,9 +6,10 @@
|
||||||
void Rover::set_control_channels(void)
|
void Rover::set_control_channels(void)
|
||||||
{
|
{
|
||||||
// check change on RCMAP
|
// check change on RCMAP
|
||||||
channel_steer = rc().channel(rcmap.roll()-1);
|
// the library gaurantees that these are non-nullptr:
|
||||||
channel_throttle = rc().channel(rcmap.throttle()-1);
|
channel_steer = &rc().get_roll_channel();
|
||||||
channel_lateral = rc().channel(rcmap.yaw()-1);
|
channel_throttle = &rc().get_throttle_channel();
|
||||||
|
channel_lateral = &rc().get_yaw_channel();
|
||||||
|
|
||||||
// set rc channel ranges
|
// set rc channel ranges
|
||||||
channel_steer->set_angle(SERVO_MAX);
|
channel_steer->set_angle(SERVO_MAX);
|
||||||
|
|
Loading…
Reference in New Issue