diff --git a/ArduPlane/Parameters.cpp b/ArduPlane/Parameters.cpp index 4b8a06001f..f71a7b9361 100644 --- a/ArduPlane/Parameters.cpp +++ b/ArduPlane/Parameters.cpp @@ -967,17 +967,41 @@ const AP_Param::Info Plane::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: INS_ // @Path: ../libraries/AP_InertialSensor/AP_InertialSensor.cpp diff --git a/ArduPlane/Parameters.h b/ArduPlane/Parameters.h index dca38ab706..98c9fd2a74 100644 --- a/ArduPlane/Parameters.h +++ b/ArduPlane/Parameters.h @@ -347,6 +347,9 @@ public: // 254,255: reserved k_param_vehicle = 257, // vehicle common block of parameters + k_param_gcs4, // stream rates + k_param_gcs5, // stream rates + k_param_gcs6, // stream rates }; AP_Int16 format_version;