Rover: support MAV_CMD_ACCELCAL_VEHICLE_POS
This commit is contained in:
parent
e763896b6a
commit
e870c4bf99
@ -1082,6 +1082,15 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg)
|
|||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
case MAV_CMD_ACCELCAL_VEHICLE_POS:
|
||||||
|
result = MAV_RESULT_FAILED;
|
||||||
|
|
||||||
|
if (rover.ins.get_acal()->gcs_vehicle_position(packet.param1)) {
|
||||||
|
result = MAV_RESULT_ACCEPTED;
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
|
||||||
|
|
||||||
default:
|
default:
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user