|
|
@ -450,7 +450,7 @@ bool GCS_MAVLINK_Plane::try_send_message(enum ap_message id) |
|
|
|
/*
|
|
|
|
/*
|
|
|
|
default stream rates to 1Hz |
|
|
|
default stream rates to 1Hz |
|
|
|
*/ |
|
|
|
*/ |
|
|
|
const AP_Param::GroupInfo GCS_MAVLINK::var_info[] = { |
|
|
|
const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { |
|
|
|
// @Param: RAW_SENS
|
|
|
|
// @Param: RAW_SENS
|
|
|
|
// @DisplayName: Raw sensor stream rate
|
|
|
|
// @DisplayName: Raw sensor stream rate
|
|
|
|
// @Description: Raw sensor stream rate to ground station
|
|
|
|
// @Description: Raw sensor stream rate to ground station
|
|
|
@ -458,7 +458,7 @@ const AP_Param::GroupInfo GCS_MAVLINK::var_info[] = { |
|
|
|
// @Range: 0 10
|
|
|
|
// @Range: 0 10
|
|
|
|
// @Increment: 1
|
|
|
|
// @Increment: 1
|
|
|
|
// @User: Advanced
|
|
|
|
// @User: Advanced
|
|
|
|
AP_GROUPINFO("RAW_SENS", 0, GCS_MAVLINK, streamRates[0], 1), |
|
|
|
AP_GROUPINFO("RAW_SENS", 0, GCS_MAVLINK_Parameters, streamRates[0], 1), |
|
|
|
|
|
|
|
|
|
|
|
// @Param: EXT_STAT
|
|
|
|
// @Param: EXT_STAT
|
|
|
|
// @DisplayName: Extended status stream rate to ground station
|
|
|
|
// @DisplayName: Extended status stream rate to ground station
|
|
|
@ -467,7 +467,7 @@ const AP_Param::GroupInfo GCS_MAVLINK::var_info[] = { |
|
|
|
// @Range: 0 10
|
|
|
|
// @Range: 0 10
|
|
|
|
// @Increment: 1
|
|
|
|
// @Increment: 1
|
|
|
|
// @User: Advanced
|
|
|
|
// @User: Advanced
|
|
|
|
AP_GROUPINFO("EXT_STAT", 1, GCS_MAVLINK, streamRates[1], 1), |
|
|
|
AP_GROUPINFO("EXT_STAT", 1, GCS_MAVLINK_Parameters, streamRates[1], 1), |
|
|
|
|
|
|
|
|
|
|
|
// @Param: RC_CHAN
|
|
|
|
// @Param: RC_CHAN
|
|
|
|
// @DisplayName: RC Channel stream rate to ground station
|
|
|
|
// @DisplayName: RC Channel stream rate to ground station
|
|
|
@ -476,7 +476,7 @@ const AP_Param::GroupInfo GCS_MAVLINK::var_info[] = { |
|
|
|
// @Range: 0 10
|
|
|
|
// @Range: 0 10
|
|
|
|
// @Increment: 1
|
|
|
|
// @Increment: 1
|
|
|
|
// @User: Advanced
|
|
|
|
// @User: Advanced
|
|
|
|
AP_GROUPINFO("RC_CHAN", 2, GCS_MAVLINK, streamRates[2], 1), |
|
|
|
AP_GROUPINFO("RC_CHAN", 2, GCS_MAVLINK_Parameters, streamRates[2], 1), |
|
|
|
|
|
|
|
|
|
|
|
// @Param: RAW_CTRL
|
|
|
|
// @Param: RAW_CTRL
|
|
|
|
// @DisplayName: Raw Control stream rate to ground station
|
|
|
|
// @DisplayName: Raw Control stream rate to ground station
|
|
|
@ -485,7 +485,7 @@ const AP_Param::GroupInfo GCS_MAVLINK::var_info[] = { |
|
|
|
// @Range: 0 10
|
|
|
|
// @Range: 0 10
|
|
|
|
// @Increment: 1
|
|
|
|
// @Increment: 1
|
|
|
|
// @User: Advanced
|
|
|
|
// @User: Advanced
|
|
|
|
AP_GROUPINFO("RAW_CTRL", 3, GCS_MAVLINK, streamRates[3], 1), |
|
|
|
AP_GROUPINFO("RAW_CTRL", 3, GCS_MAVLINK_Parameters, streamRates[3], 1), |
|
|
|
|
|
|
|
|
|
|
|
// @Param: POSITION
|
|
|
|
// @Param: POSITION
|
|
|
|
// @DisplayName: Position stream rate to ground station
|
|
|
|
// @DisplayName: Position stream rate to ground station
|
|
|
@ -494,7 +494,7 @@ const AP_Param::GroupInfo GCS_MAVLINK::var_info[] = { |
|
|
|
// @Range: 0 10
|
|
|
|
// @Range: 0 10
|
|
|
|
// @Increment: 1
|
|
|
|
// @Increment: 1
|
|
|
|
// @User: Advanced
|
|
|
|
// @User: Advanced
|
|
|
|
AP_GROUPINFO("POSITION", 4, GCS_MAVLINK, streamRates[4], 1), |
|
|
|
AP_GROUPINFO("POSITION", 4, GCS_MAVLINK_Parameters, streamRates[4], 1), |
|
|
|
|
|
|
|
|
|
|
|
// @Param: EXTRA1
|
|
|
|
// @Param: EXTRA1
|
|
|
|
// @DisplayName: Extra data type 1 stream rate to ground station
|
|
|
|
// @DisplayName: Extra data type 1 stream rate to ground station
|
|
|
@ -503,7 +503,7 @@ const AP_Param::GroupInfo GCS_MAVLINK::var_info[] = { |
|
|
|
// @Range: 0 10
|
|
|
|
// @Range: 0 10
|
|
|
|
// @Increment: 1
|
|
|
|
// @Increment: 1
|
|
|
|
// @User: Advanced
|
|
|
|
// @User: Advanced
|
|
|
|
AP_GROUPINFO("EXTRA1", 5, GCS_MAVLINK, streamRates[5], 1), |
|
|
|
AP_GROUPINFO("EXTRA1", 5, GCS_MAVLINK_Parameters, streamRates[5], 1), |
|
|
|
|
|
|
|
|
|
|
|
// @Param: EXTRA2
|
|
|
|
// @Param: EXTRA2
|
|
|
|
// @DisplayName: Extra data type 2 stream rate to ground station
|
|
|
|
// @DisplayName: Extra data type 2 stream rate to ground station
|
|
|
@ -512,7 +512,7 @@ const AP_Param::GroupInfo GCS_MAVLINK::var_info[] = { |
|
|
|
// @Range: 0 10
|
|
|
|
// @Range: 0 10
|
|
|
|
// @Increment: 1
|
|
|
|
// @Increment: 1
|
|
|
|
// @User: Advanced
|
|
|
|
// @User: Advanced
|
|
|
|
AP_GROUPINFO("EXTRA2", 6, GCS_MAVLINK, streamRates[6], 1), |
|
|
|
AP_GROUPINFO("EXTRA2", 6, GCS_MAVLINK_Parameters, streamRates[6], 1), |
|
|
|
|
|
|
|
|
|
|
|
// @Param: EXTRA3
|
|
|
|
// @Param: EXTRA3
|
|
|
|
// @DisplayName: Extra data type 3 stream rate to ground station
|
|
|
|
// @DisplayName: Extra data type 3 stream rate to ground station
|
|
|
@ -521,7 +521,7 @@ const AP_Param::GroupInfo GCS_MAVLINK::var_info[] = { |
|
|
|
// @Range: 0 10
|
|
|
|
// @Range: 0 10
|
|
|
|
// @Increment: 1
|
|
|
|
// @Increment: 1
|
|
|
|
// @User: Advanced
|
|
|
|
// @User: Advanced
|
|
|
|
AP_GROUPINFO("EXTRA3", 7, GCS_MAVLINK, streamRates[7], 1), |
|
|
|
AP_GROUPINFO("EXTRA3", 7, GCS_MAVLINK_Parameters, streamRates[7], 1), |
|
|
|
|
|
|
|
|
|
|
|
// @Param: PARAMS
|
|
|
|
// @Param: PARAMS
|
|
|
|
// @DisplayName: Parameter stream rate to ground station
|
|
|
|
// @DisplayName: Parameter stream rate to ground station
|
|
|
@ -530,7 +530,7 @@ const AP_Param::GroupInfo GCS_MAVLINK::var_info[] = { |
|
|
|
// @Range: 0 10
|
|
|
|
// @Range: 0 10
|
|
|
|
// @Increment: 1
|
|
|
|
// @Increment: 1
|
|
|
|
// @User: Advanced
|
|
|
|
// @User: Advanced
|
|
|
|
AP_GROUPINFO("PARAMS", 8, GCS_MAVLINK, streamRates[8], 10), |
|
|
|
AP_GROUPINFO("PARAMS", 8, GCS_MAVLINK_Parameters, streamRates[8], 10), |
|
|
|
|
|
|
|
|
|
|
|
// @Param: ADSB
|
|
|
|
// @Param: ADSB
|
|
|
|
// @DisplayName: ADSB stream rate to ground station
|
|
|
|
// @DisplayName: ADSB stream rate to ground station
|
|
|
@ -539,7 +539,7 @@ const AP_Param::GroupInfo GCS_MAVLINK::var_info[] = { |
|
|
|
// @Range: 0 50
|
|
|
|
// @Range: 0 50
|
|
|
|
// @Increment: 1
|
|
|
|
// @Increment: 1
|
|
|
|
// @User: Advanced
|
|
|
|
// @User: Advanced
|
|
|
|
AP_GROUPINFO("ADSB", 9, GCS_MAVLINK, streamRates[9], 5), |
|
|
|
AP_GROUPINFO("ADSB", 9, GCS_MAVLINK_Parameters, streamRates[9], 5), |
|
|
|
AP_GROUPEND |
|
|
|
AP_GROUPEND |
|
|
|
}; |
|
|
|
}; |
|
|
|
|
|
|
|
|
|
|
@ -1349,7 +1349,6 @@ void GCS_MAVLINK_Plane::handle_rc_channels_override(const mavlink_message_t &msg |
|
|
|
void Plane::mavlink_delay_cb() |
|
|
|
void Plane::mavlink_delay_cb() |
|
|
|
{ |
|
|
|
{ |
|
|
|
static uint32_t last_1hz, last_50hz, last_5s; |
|
|
|
static uint32_t last_1hz, last_50hz, last_5s; |
|
|
|
if (!gcs().chan(0).initialised) return; |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
logger.EnableWrites(false); |
|
|
|
logger.EnableWrites(false); |
|
|
|
|
|
|
|
|
|
|
|