|
|
|
@ -240,7 +240,7 @@ bool GCS_MAVLINK_Sub::try_send_message(enum ap_message id)
@@ -240,7 +240,7 @@ bool GCS_MAVLINK_Sub::try_send_message(enum ap_message id)
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
const AP_Param::GroupInfo GCS_MAVLINK::var_info[] = { |
|
|
|
|
const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { |
|
|
|
|
// @Param: RAW_SENS
|
|
|
|
|
// @DisplayName: Raw sensor stream rate
|
|
|
|
|
// @Description: Stream rate of RAW_IMU, SCALED_IMU2, SCALED_PRESSURE, and SENSOR_OFFSETS to ground station
|
|
|
|
@ -248,7 +248,7 @@ const AP_Param::GroupInfo GCS_MAVLINK::var_info[] = {
@@ -248,7 +248,7 @@ const AP_Param::GroupInfo GCS_MAVLINK::var_info[] = {
|
|
|
|
|
// @Range: 0 10
|
|
|
|
|
// @Increment: 1
|
|
|
|
|
// @User: Advanced
|
|
|
|
|
AP_GROUPINFO("RAW_SENS", 0, GCS_MAVLINK, streamRates[STREAM_RAW_SENSORS], 0), |
|
|
|
|
AP_GROUPINFO("RAW_SENS", 0, GCS_MAVLINK_Parameters, streamRates[GCS_MAVLINK::STREAM_RAW_SENSORS], 0), |
|
|
|
|
|
|
|
|
|
// @Param: EXT_STAT
|
|
|
|
|
// @DisplayName: Extended status stream rate to ground station
|
|
|
|
@ -257,7 +257,7 @@ const AP_Param::GroupInfo GCS_MAVLINK::var_info[] = {
@@ -257,7 +257,7 @@ const AP_Param::GroupInfo GCS_MAVLINK::var_info[] = {
|
|
|
|
|
// @Range: 0 10
|
|
|
|
|
// @Increment: 1
|
|
|
|
|
// @User: Advanced
|
|
|
|
|
AP_GROUPINFO("EXT_STAT", 1, GCS_MAVLINK, streamRates[STREAM_EXTENDED_STATUS], 0), |
|
|
|
|
AP_GROUPINFO("EXT_STAT", 1, GCS_MAVLINK_Parameters, streamRates[GCS_MAVLINK::STREAM_EXTENDED_STATUS], 0), |
|
|
|
|
|
|
|
|
|
// @Param: RC_CHAN
|
|
|
|
|
// @DisplayName: RC Channel stream rate to ground station
|
|
|
|
@ -266,7 +266,7 @@ const AP_Param::GroupInfo GCS_MAVLINK::var_info[] = {
@@ -266,7 +266,7 @@ const AP_Param::GroupInfo GCS_MAVLINK::var_info[] = {
|
|
|
|
|
// @Range: 0 10
|
|
|
|
|
// @Increment: 1
|
|
|
|
|
// @User: Advanced
|
|
|
|
|
AP_GROUPINFO("RC_CHAN", 2, GCS_MAVLINK, streamRates[STREAM_RC_CHANNELS], 0), |
|
|
|
|
AP_GROUPINFO("RC_CHAN", 2, GCS_MAVLINK_Parameters, streamRates[GCS_MAVLINK::STREAM_RC_CHANNELS], 0), |
|
|
|
|
|
|
|
|
|
// @Param: POSITION
|
|
|
|
|
// @DisplayName: Position stream rate to ground station
|
|
|
|
@ -275,7 +275,7 @@ const AP_Param::GroupInfo GCS_MAVLINK::var_info[] = {
@@ -275,7 +275,7 @@ const AP_Param::GroupInfo GCS_MAVLINK::var_info[] = {
|
|
|
|
|
// @Range: 0 10
|
|
|
|
|
// @Increment: 1
|
|
|
|
|
// @User: Advanced
|
|
|
|
|
AP_GROUPINFO("POSITION", 4, GCS_MAVLINK, streamRates[STREAM_POSITION], 0), |
|
|
|
|
AP_GROUPINFO("POSITION", 4, GCS_MAVLINK_Parameters, streamRates[GCS_MAVLINK::STREAM_POSITION], 0), |
|
|
|
|
|
|
|
|
|
// @Param: EXTRA1
|
|
|
|
|
// @DisplayName: Extra data type 1 stream rate to ground station
|
|
|
|
@ -284,7 +284,7 @@ const AP_Param::GroupInfo GCS_MAVLINK::var_info[] = {
@@ -284,7 +284,7 @@ const AP_Param::GroupInfo GCS_MAVLINK::var_info[] = {
|
|
|
|
|
// @Range: 0 10
|
|
|
|
|
// @Increment: 1
|
|
|
|
|
// @User: Advanced
|
|
|
|
|
AP_GROUPINFO("EXTRA1", 5, GCS_MAVLINK, streamRates[STREAM_EXTRA1], 0), |
|
|
|
|
AP_GROUPINFO("EXTRA1", 5, GCS_MAVLINK_Parameters, streamRates[GCS_MAVLINK::STREAM_EXTRA1], 0), |
|
|
|
|
|
|
|
|
|
// @Param: EXTRA2
|
|
|
|
|
// @DisplayName: Extra data type 2 stream rate to ground station
|
|
|
|
@ -293,7 +293,7 @@ const AP_Param::GroupInfo GCS_MAVLINK::var_info[] = {
@@ -293,7 +293,7 @@ const AP_Param::GroupInfo GCS_MAVLINK::var_info[] = {
|
|
|
|
|
// @Range: 0 10
|
|
|
|
|
// @Increment: 1
|
|
|
|
|
// @User: Advanced
|
|
|
|
|
AP_GROUPINFO("EXTRA2", 6, GCS_MAVLINK, streamRates[STREAM_EXTRA2], 0), |
|
|
|
|
AP_GROUPINFO("EXTRA2", 6, GCS_MAVLINK_Parameters, streamRates[GCS_MAVLINK::STREAM_EXTRA2], 0), |
|
|
|
|
|
|
|
|
|
// @Param: EXTRA3
|
|
|
|
|
// @DisplayName: Extra data type 3 stream rate to ground station
|
|
|
|
@ -302,7 +302,7 @@ const AP_Param::GroupInfo GCS_MAVLINK::var_info[] = {
@@ -302,7 +302,7 @@ const AP_Param::GroupInfo GCS_MAVLINK::var_info[] = {
|
|
|
|
|
// @Range: 0 10
|
|
|
|
|
// @Increment: 1
|
|
|
|
|
// @User: Advanced
|
|
|
|
|
AP_GROUPINFO("EXTRA3", 7, GCS_MAVLINK, streamRates[STREAM_EXTRA3], 0), |
|
|
|
|
AP_GROUPINFO("EXTRA3", 7, GCS_MAVLINK_Parameters, streamRates[GCS_MAVLINK::STREAM_EXTRA3], 0), |
|
|
|
|
|
|
|
|
|
// @Param: PARAMS
|
|
|
|
|
// @DisplayName: Parameter stream rate to ground station
|
|
|
|
@ -311,7 +311,7 @@ const AP_Param::GroupInfo GCS_MAVLINK::var_info[] = {
@@ -311,7 +311,7 @@ const AP_Param::GroupInfo GCS_MAVLINK::var_info[] = {
|
|
|
|
|
// @Range: 0 10
|
|
|
|
|
// @Increment: 1
|
|
|
|
|
// @User: Advanced
|
|
|
|
|
AP_GROUPINFO("PARAMS", 8, GCS_MAVLINK, streamRates[STREAM_PARAMS], 0), |
|
|
|
|
AP_GROUPINFO("PARAMS", 8, GCS_MAVLINK_Parameters, streamRates[GCS_MAVLINK::STREAM_PARAMS], 0), |
|
|
|
|
AP_GROUPEND |
|
|
|
|
}; |
|
|
|
|
|
|
|
|
@ -794,9 +794,6 @@ void GCS_MAVLINK_Sub::handle_rc_channels_override(const mavlink_message_t &msg)
@@ -794,9 +794,6 @@ void GCS_MAVLINK_Sub::handle_rc_channels_override(const mavlink_message_t &msg)
|
|
|
|
|
void Sub::mavlink_delay_cb() |
|
|
|
|
{ |
|
|
|
|
static uint32_t last_1hz, last_50hz, last_5s; |
|
|
|
|
if (!gcs().chan(0).initialised) { |
|
|
|
|
return; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
logger.EnableWrites(false); |
|
|
|
|
|
|
|
|
|