mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Plane: add ADSB_streamrate
This commit is contained in:
parent
4fe94bdea3
commit
9b973fb899
@ -873,6 +873,11 @@ bool GCS_MAVLINK_Plane::try_send_message(enum ap_message id)
|
|||||||
CHECK_PAYLOAD_SIZE(MAG_CAL_REPORT);
|
CHECK_PAYLOAD_SIZE(MAG_CAL_REPORT);
|
||||||
plane.compass.send_mag_cal_report(chan);
|
plane.compass.send_mag_cal_report(chan);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
case MSG_ADSB_VEHICLE:
|
||||||
|
CHECK_PAYLOAD_SIZE(ADSB_VEHICLE);
|
||||||
|
plane.adsb.send_adsb_vehicle(chan);
|
||||||
|
break;
|
||||||
}
|
}
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
@ -962,6 +967,15 @@ 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], 5),
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
};
|
};
|
||||||
|
|
||||||
@ -1081,6 +1095,12 @@ GCS_MAVLINK_Plane::data_stream_send(void)
|
|||||||
send_message(MSG_GIMBAL_REPORT);
|
send_message(MSG_GIMBAL_REPORT);
|
||||||
send_message(MSG_VIBRATION);
|
send_message(MSG_VIBRATION);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if (plane.gcs_out_of_time) return;
|
||||||
|
|
||||||
|
if (stream_trigger(STREAM_ADSB)) {
|
||||||
|
send_message(MSG_ADSB_VEHICLE);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user