mirror of https://github.com/ArduPilot/ardupilot
Rover: add ADSB message stream and send oadb objects
This commit is contained in:
parent
6d1362d569
commit
a381502ad1
|
@ -332,6 +332,18 @@ bool GCS_MAVLINK_Rover::try_send_message(enum ap_message id)
|
||||||
rover.g2.windvane.send_wind(chan);
|
rover.g2.windvane.send_wind(chan);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
case MSG_ADSB_VEHICLE: {
|
||||||
|
AP_OADatabase *oadb = AP::oadatabase();
|
||||||
|
if (oadb != nullptr) {
|
||||||
|
CHECK_PAYLOAD_SIZE(ADSB_VEHICLE);
|
||||||
|
uint16_t interval_ms = 0;
|
||||||
|
if (get_ap_message_interval(id, interval_ms)) {
|
||||||
|
oadb->send_adsb_vehicle(chan, interval_ms);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
default:
|
default:
|
||||||
return GCS_MAVLINK::try_send_message(id);
|
return GCS_MAVLINK::try_send_message(id);
|
||||||
}
|
}
|
||||||
|
@ -429,6 +441,16 @@ const AP_Param::GroupInfo GCS_MAVLINK::var_info[] = {
|
||||||
// @Increment: 1
|
// @Increment: 1
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
AP_GROUPINFO("PARAMS", 8, GCS_MAVLINK, streamRates[8], 10),
|
AP_GROUPINFO("PARAMS", 8, GCS_MAVLINK, streamRates[8], 10),
|
||||||
|
|
||||||
|
// @Param: ADSB
|
||||||
|
// @DisplayName: ADSB stream rate to ground station
|
||||||
|
// @Description: ADSB stream rate to ground station
|
||||||
|
// @Units: Hz
|
||||||
|
// @Range: 0 50
|
||||||
|
// @Increment: 1
|
||||||
|
// @User: Advanced
|
||||||
|
AP_GROUPINFO("ADSB", 9, GCS_MAVLINK, streamRates[9], 0),
|
||||||
|
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
};
|
};
|
||||||
|
|
||||||
|
@ -497,6 +519,9 @@ static const ap_message STREAM_EXTRA3_msgs[] = {
|
||||||
static const ap_message STREAM_PARAMS_msgs[] = {
|
static const ap_message STREAM_PARAMS_msgs[] = {
|
||||||
MSG_NEXT_PARAM
|
MSG_NEXT_PARAM
|
||||||
};
|
};
|
||||||
|
static const ap_message STREAM_ADSB_msgs[] = {
|
||||||
|
MSG_ADSB_VEHICLE
|
||||||
|
};
|
||||||
|
|
||||||
const struct GCS_MAVLINK::stream_entries GCS_MAVLINK::all_stream_entries[] = {
|
const struct GCS_MAVLINK::stream_entries GCS_MAVLINK::all_stream_entries[] = {
|
||||||
MAV_STREAM_ENTRY(STREAM_RAW_SENSORS),
|
MAV_STREAM_ENTRY(STREAM_RAW_SENSORS),
|
||||||
|
@ -507,6 +532,7 @@ const struct GCS_MAVLINK::stream_entries GCS_MAVLINK::all_stream_entries[] = {
|
||||||
MAV_STREAM_ENTRY(STREAM_EXTRA1),
|
MAV_STREAM_ENTRY(STREAM_EXTRA1),
|
||||||
MAV_STREAM_ENTRY(STREAM_EXTRA2),
|
MAV_STREAM_ENTRY(STREAM_EXTRA2),
|
||||||
MAV_STREAM_ENTRY(STREAM_EXTRA3),
|
MAV_STREAM_ENTRY(STREAM_EXTRA3),
|
||||||
|
MAV_STREAM_ENTRY(STREAM_ADSB),
|
||||||
MAV_STREAM_ENTRY(STREAM_PARAMS),
|
MAV_STREAM_ENTRY(STREAM_PARAMS),
|
||||||
MAV_STREAM_TERMINATOR // must have this at end of stream_entries
|
MAV_STREAM_TERMINATOR // must have this at end of stream_entries
|
||||||
};
|
};
|
||||||
|
|
Loading…
Reference in New Issue