Browse Source

Tracker: extend Stream rates param count to match MAVLINK_COMM_NUM_BUFFER

zr-v5.1
Tom Pittenger 4 years ago committed by Tom Pittenger
parent
commit
558fe34945
  1. 24
      AntennaTracker/Parameters.cpp
  2. 3
      AntennaTracker/Parameters.h

24
AntennaTracker/Parameters.cpp

@ -230,17 +230,41 @@ const AP_Param::Info Tracker::var_info[] = { @@ -230,17 +230,41 @@ const AP_Param::Info Tracker::var_info[] = {
// @Path: GCS_Mavlink.cpp
GOBJECTN(_gcs.chan_parameters[0], gcs0, "SR0_", GCS_MAVLINK_Parameters),
#if MAVLINK_COMM_NUM_BUFFERS >= 2
// @Group: SR1_
// @Path: GCS_Mavlink.cpp
GOBJECTN(_gcs.chan_parameters[1], gcs1, "SR1_", GCS_MAVLINK_Parameters),
#endif
#if MAVLINK_COMM_NUM_BUFFERS >= 3
// @Group: SR2_
// @Path: GCS_Mavlink.cpp
GOBJECTN(_gcs.chan_parameters[2], gcs2, "SR2_", GCS_MAVLINK_Parameters),
#endif
#if MAVLINK_COMM_NUM_BUFFERS >= 4
// @Group: SR3_
// @Path: GCS_Mavlink.cpp
GOBJECTN(_gcs.chan_parameters[3], gcs3, "SR3_", GCS_MAVLINK_Parameters),
#endif
#if MAVLINK_COMM_NUM_BUFFERS >= 5
// @Group: SR4_
// @Path: GCS_Mavlink.cpp
GOBJECTN(_gcs.chan_parameters[4], gcs4, "SR4_", GCS_MAVLINK_Parameters),
#endif
#if MAVLINK_COMM_NUM_BUFFERS >= 6
// @Group: SR5_
// @Path: GCS_Mavlink.cpp
GOBJECTN(_gcs.chan_parameters[5], gcs5, "SR5_", GCS_MAVLINK_Parameters),
#endif
#if MAVLINK_COMM_NUM_BUFFERS >= 7
// @Group: SR6_
// @Path: GCS_Mavlink.cpp
GOBJECTN(_gcs.chan_parameters[6], gcs6, "SR6_", GCS_MAVLINK_Parameters),
#endif
// @Param: LOG_BITMASK
// @DisplayName: Log bitmask

3
AntennaTracker/Parameters.h

@ -98,6 +98,9 @@ public: @@ -98,6 +98,9 @@ public:
k_param_mavlink_update_rate,
k_param_pitch_min,
k_param_pitch_max,
k_param_gcs4, // stream rates for fourth MAVLink port
k_param_gcs5, // stream rates for fourth MAVLink port
k_param_gcs6, // stream rates for fourth MAVLink port
//
// 200 : Radio settings

Loading…
Cancel
Save