mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 21:48:28 -04:00
Rover: now sends SCALED_PRESSURE msg
This commit is contained in:
parent
2c73b374f5
commit
c14af79975
@ -352,6 +352,11 @@ bool GCS_MAVLINK_Rover::try_send_message(enum ap_message id)
|
||||
send_raw_imu(rover.ins, rover.compass);
|
||||
break;
|
||||
|
||||
case MSG_RAW_IMU2:
|
||||
CHECK_PAYLOAD_SIZE(SCALED_PRESSURE);
|
||||
send_scaled_pressure(rover.barometer);
|
||||
break;
|
||||
|
||||
case MSG_RAW_IMU3:
|
||||
CHECK_PAYLOAD_SIZE(SENSOR_OFFSETS);
|
||||
send_sensor_offsets(rover.ins, rover.compass, rover.barometer);
|
||||
@ -541,6 +546,7 @@ GCS_MAVLINK_Rover::data_stream_send(void)
|
||||
|
||||
if (stream_trigger(STREAM_RAW_SENSORS)) {
|
||||
send_message(MSG_RAW_IMU1);
|
||||
send_message(MSG_RAW_IMU2);
|
||||
send_message(MSG_RAW_IMU3);
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user