Copter: extend Stream rates param count to match MAVLINK_COMM_NUM_BUFFER

This commit is contained in:
Tom Pittenger 2020-12-22 11:43:42 -08:00 committed by Tom Pittenger
parent 558fe34945
commit b80f003c98
2 changed files with 27 additions and 0 deletions

View File

@ -539,17 +539,41 @@ const AP_Param::Info Copter::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
// @Group: AHRS_ // @Group: AHRS_
// @Path: ../libraries/AP_AHRS/AP_AHRS.cpp // @Path: ../libraries/AP_AHRS/AP_AHRS.cpp

View File

@ -218,6 +218,9 @@ public:
k_param_takeoff_trigger_dz_old, k_param_takeoff_trigger_dz_old,
k_param_gcs3, k_param_gcs3,
k_param_gcs_pid_mask, // 126 k_param_gcs_pid_mask, // 126
k_param_gcs4,
k_param_gcs5,
k_param_gcs6,
// //
// 135 : reserved for Solo until features merged with master // 135 : reserved for Solo until features merged with master