mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Tracker: extend Stream rates param count to match MAVLINK_COMM_NUM_BUFFER
This commit is contained in:
parent
c653ff880a
commit
558fe34945
@ -230,17 +230,41 @@ const AP_Param::Info Tracker::var_info[] = {
|
|||||||
// @Path: GCS_Mavlink.cpp
|
// @Path: GCS_Mavlink.cpp
|
||||||
GOBJECTN(_gcs.chan_parameters[0], gcs0, "SR0_", GCS_MAVLINK_Parameters),
|
GOBJECTN(_gcs.chan_parameters[0], gcs0, "SR0_", GCS_MAVLINK_Parameters),
|
||||||
|
|
||||||
|
#if MAVLINK_COMM_NUM_BUFFERS >= 2
|
||||||
// @Group: SR1_
|
// @Group: SR1_
|
||||||
// @Path: GCS_Mavlink.cpp
|
// @Path: GCS_Mavlink.cpp
|
||||||
GOBJECTN(_gcs.chan_parameters[1], gcs1, "SR1_", GCS_MAVLINK_Parameters),
|
GOBJECTN(_gcs.chan_parameters[1], gcs1, "SR1_", GCS_MAVLINK_Parameters),
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if MAVLINK_COMM_NUM_BUFFERS >= 3
|
||||||
// @Group: SR2_
|
// @Group: SR2_
|
||||||
// @Path: GCS_Mavlink.cpp
|
// @Path: GCS_Mavlink.cpp
|
||||||
GOBJECTN(_gcs.chan_parameters[2], gcs2, "SR2_", GCS_MAVLINK_Parameters),
|
GOBJECTN(_gcs.chan_parameters[2], gcs2, "SR2_", GCS_MAVLINK_Parameters),
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if MAVLINK_COMM_NUM_BUFFERS >= 4
|
||||||
// @Group: SR3_
|
// @Group: SR3_
|
||||||
// @Path: GCS_Mavlink.cpp
|
// @Path: GCS_Mavlink.cpp
|
||||||
GOBJECTN(_gcs.chan_parameters[3], gcs3, "SR3_", GCS_MAVLINK_Parameters),
|
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
|
// @Param: LOG_BITMASK
|
||||||
// @DisplayName: Log bitmask
|
// @DisplayName: Log bitmask
|
||||||
|
@ -98,6 +98,9 @@ public:
|
|||||||
k_param_mavlink_update_rate,
|
k_param_mavlink_update_rate,
|
||||||
k_param_pitch_min,
|
k_param_pitch_min,
|
||||||
k_param_pitch_max,
|
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
|
// 200 : Radio settings
|
||||||
|
Loading…
Reference in New Issue
Block a user