mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
Rover: use AP::ahrs() for GCS_MAVLink
This commit is contained in:
parent
15f212adc0
commit
78ecf55fec
@ -311,11 +311,6 @@ bool GCS_MAVLINK_Rover::try_send_message(enum ap_message id)
|
||||
rover.send_location(chan);
|
||||
break;
|
||||
|
||||
case MSG_LOCAL_POSITION:
|
||||
CHECK_PAYLOAD_SIZE(LOCAL_POSITION_NED);
|
||||
send_local_position(rover.ahrs);
|
||||
break;
|
||||
|
||||
case MSG_NAV_CONTROLLER_OUTPUT:
|
||||
if (rover.control_mode->is_autopilot_mode()) {
|
||||
CHECK_PAYLOAD_SIZE(NAV_CONTROLLER_OUTPUT);
|
||||
@ -358,11 +353,6 @@ bool GCS_MAVLINK_Rover::try_send_message(enum ap_message id)
|
||||
send_sensor_offsets(rover.ins, rover.compass, rover.barometer);
|
||||
break;
|
||||
|
||||
case MSG_AHRS:
|
||||
CHECK_PAYLOAD_SIZE(AHRS);
|
||||
send_ahrs(rover.ahrs);
|
||||
break;
|
||||
|
||||
case MSG_SIMSTATE:
|
||||
CHECK_PAYLOAD_SIZE(SIMSTATE);
|
||||
rover.send_simstate(chan);
|
||||
|
Loading…
Reference in New Issue
Block a user