mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Plane: added MAVLink sonar logging
This commit is contained in:
parent
5a0cb5dea4
commit
6b4a3ef98b
@ -533,6 +533,18 @@ static void NOINLINE send_wind(mavlink_channel_t chan)
|
||||
wind.z);
|
||||
}
|
||||
|
||||
static void NOINLINE send_rangefinder(mavlink_channel_t chan)
|
||||
{
|
||||
if (!sonar.enabled()) {
|
||||
// no sonar to report
|
||||
return;
|
||||
}
|
||||
mavlink_msg_rangefinder_send(
|
||||
chan,
|
||||
sonar.distance_cm() * 0.01f,
|
||||
sonar.voltage());
|
||||
}
|
||||
|
||||
static void NOINLINE send_current_waypoint(mavlink_channel_t chan)
|
||||
{
|
||||
mavlink_msg_mission_current_send(
|
||||
@ -705,6 +717,11 @@ static bool mavlink_try_send_message(mavlink_channel_t chan, enum ap_message id,
|
||||
send_hwstatus(chan);
|
||||
break;
|
||||
|
||||
case MSG_RANGEFINDER:
|
||||
CHECK_PAYLOAD_SIZE(RANGEFINDER);
|
||||
send_rangefinder(chan);
|
||||
break;
|
||||
|
||||
case MSG_WIND:
|
||||
CHECK_PAYLOAD_SIZE(WIND);
|
||||
send_wind(chan);
|
||||
@ -1099,6 +1116,7 @@ GCS_MAVLINK::data_stream_send(void)
|
||||
send_message(MSG_AHRS);
|
||||
send_message(MSG_HWSTATUS);
|
||||
send_message(MSG_WIND);
|
||||
send_message(MSG_RANGEFINDER);
|
||||
send_message(MSG_SYSTEM_TIME);
|
||||
}
|
||||
}
|
||||
|
@ -140,6 +140,7 @@ enum ap_message {
|
||||
MSG_SIMSTATE,
|
||||
MSG_HWSTATUS,
|
||||
MSG_WIND,
|
||||
MSG_RANGEFINDER,
|
||||
MSG_RETRY_DEFERRED // this must be last
|
||||
};
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user