mirror of https://github.com/ArduPilot/ardupilot
Rover: use handle_rc_bind
This commit is contained in:
parent
57830784e2
commit
8b7c60dcd7
|
@ -897,12 +897,7 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg)
|
|||
switch(packet.command) {
|
||||
|
||||
case MAV_CMD_START_RX_PAIR:
|
||||
// initiate bind procedure
|
||||
if (!hal.rcin->rc_bind(packet.param1)) {
|
||||
result = MAV_RESULT_FAILED;
|
||||
} else {
|
||||
result = MAV_RESULT_ACCEPTED;
|
||||
}
|
||||
result = handle_rc_bind(packet);
|
||||
break;
|
||||
|
||||
case MAV_CMD_NAV_RETURN_TO_LAUNCH:
|
||||
|
|
Loading…
Reference in New Issue