mirror of https://github.com/ArduPilot/ardupilot
Sub: extend Stream rates param count to match MAVLINK_COMM_NUM_BUFFER
This commit is contained in:
parent
b80f003c98
commit
d45ff51bd1
|
@ -452,17 +452,41 @@ const AP_Param::Info Sub::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
|
||||
|
||||
// @Group: AHRS_
|
||||
// @Path: ../libraries/AP_AHRS/AP_AHRS.cpp
|
||||
|
|
|
@ -206,6 +206,10 @@ public:
|
|||
// RC_Mapper Library
|
||||
k_param_rcmap, // Disabled
|
||||
|
||||
k_param_gcs4,
|
||||
k_param_gcs5,
|
||||
k_param_gcs6,
|
||||
|
||||
k_param_cam_slew_limit = 237, // deprecated
|
||||
k_param_lights_steps,
|
||||
k_param_pilot_speed_dn,
|
||||
|
|
Loading…
Reference in New Issue