Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/ArduCopter/Parameters.cpp
Views: 1798
#include "Copter.h"12#include <AP_Gripper/AP_Gripper.h>3#include <AP_InertialSensor/AP_InertialSensor_rate_config.h>45/*6This program is free software: you can redistribute it and/or modify7it under the terms of the GNU General Public License as published by8the Free Software Foundation, either version 3 of the License, or9(at your option) any later version.1011This program is distributed in the hope that it will be useful,12but WITHOUT ANY WARRANTY; without even the implied warranty of13MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the14GNU General Public License for more details.1516You should have received a copy of the GNU General Public License17along with this program. If not, see <http://www.gnu.org/licenses/>.18*/1920/*21* ArduCopter parameter definitions22*23*/2425#if FRAME_CONFIG == HELI_FRAME26// 6 here is AP_Motors::MOTOR_FRAME_HELI27#define DEFAULT_FRAME_CLASS 628#else29#define DEFAULT_FRAME_CLASS 030#endif3132const AP_Param::Info Copter::var_info[] = {33// @Param: FORMAT_VERSION34// @DisplayName: Eeprom format version number35// @Description: This value is incremented when changes are made to the eeprom format36// @User: Advanced37GSCALAR(format_version, "FORMAT_VERSION", 0),3839// @Param: SYSID_THISMAV40// @DisplayName: MAVLink system ID of this vehicle41// @Description: Allows setting an individual MAVLink system id for this vehicle to distinguish it from others on the same network42// @Range: 1 25543// @User: Advanced44GSCALAR(sysid_this_mav, "SYSID_THISMAV", MAV_SYSTEM_ID),4546// @Param: SYSID_MYGCS47// @DisplayName: My ground station number48// @Description: Allows restricting radio overrides to only come from my ground station49// @Range: 1 25550// @Increment: 151// @User: Advanced52GSCALAR(sysid_my_gcs, "SYSID_MYGCS", 255),5354// @Param: PILOT_THR_FILT55// @DisplayName: Throttle filter cutoff56// @Description: Throttle filter cutoff (Hz) - active whenever altitude control is inactive - 0 to disable57// @User: Advanced58// @Units: Hz59// @Range: 0 1060// @Increment: 0.561GSCALAR(throttle_filt, "PILOT_THR_FILT", 0),6263// @Param: PILOT_TKOFF_ALT64// @DisplayName: Pilot takeoff altitude65// @Description: Altitude that altitude control modes will climb to when a takeoff is triggered with the throttle stick.66// @User: Standard67// @Units: cm68// @Range: 0.0 1000.069// @Increment: 1070GSCALAR(pilot_takeoff_alt, "PILOT_TKOFF_ALT", PILOT_TKOFF_ALT_DEFAULT),7172// @Param: PILOT_THR_BHV73// @DisplayName: Throttle stick behavior74// @Description: Bitmask containing various throttle stick options. TX with sprung throttle can set PILOT_THR_BHV to "1" so motor feedback when landed starts from mid-stick instead of bottom of stick.75// @User: Standard76// @Bitmask: 0:Feedback from mid stick,1:High throttle cancels landing,2:Disarm on land detection77GSCALAR(throttle_behavior, "PILOT_THR_BHV", 0),7879// AP_SerialManager was here8081// @Param: TELEM_DELAY82// @DisplayName: Telemetry startup delay83// @Description: The amount of time (in seconds) to delay radio telemetry to prevent an Xbee bricking on power up84// @User: Advanced85// @Units: s86// @Range: 0 3087// @Increment: 188GSCALAR(telem_delay, "TELEM_DELAY", 0),8990// @Param: GCS_PID_MASK91// @DisplayName: GCS PID tuning mask92// @Description: bitmask of PIDs to send MAVLink PID_TUNING messages for93// @User: Advanced94// @Bitmask: 0:Roll,1:Pitch,2:Yaw,3:AccelZ95GSCALAR(gcs_pid_mask, "GCS_PID_MASK", 0),9697#if MODE_RTL_ENABLED98// @Param: RTL_ALT99// @DisplayName: RTL Altitude100// @Description: The minimum alt above home the vehicle will climb to before returning. If the vehicle is flying higher than this value it will return at its current altitude.101// @Units: cm102// @Range: 30 300000103// @Increment: 1104// @User: Standard105GSCALAR(rtl_altitude, "RTL_ALT", RTL_ALT),106107// @Param: RTL_CONE_SLOPE108// @DisplayName: RTL cone slope109// @Description: Defines a cone above home which determines maximum climb110// @Range: 0.5 10.0111// @Increment: 0.1112// @Values: 0:Disabled,1:Shallow,3:Steep113// @User: Standard114GSCALAR(rtl_cone_slope, "RTL_CONE_SLOPE", RTL_CONE_SLOPE_DEFAULT),115116// @Param: RTL_SPEED117// @DisplayName: RTL speed118// @Description: Defines the speed in cm/s which the aircraft will attempt to maintain horizontally while flying home. If this is set to zero, WPNAV_SPEED will be used instead.119// @Units: cm/s120// @Range: 0 2000121// @Increment: 50122// @User: Standard123GSCALAR(rtl_speed_cms, "RTL_SPEED", 0),124125// @Param: RTL_ALT_FINAL126// @DisplayName: RTL Final Altitude127// @Description: This is the altitude the vehicle will move to as the final stage of Returning to Launch or after completing a mission. Set to zero to land.128// @Units: cm129// @Range: 0 1000130// @Increment: 1131// @User: Standard132GSCALAR(rtl_alt_final, "RTL_ALT_FINAL", RTL_ALT_FINAL),133134// @Param: RTL_CLIMB_MIN135// @DisplayName: RTL minimum climb136// @Description: The vehicle will climb this many cm during the initial climb portion of the RTL137// @Units: cm138// @Range: 0 3000139// @Increment: 10140// @User: Standard141GSCALAR(rtl_climb_min, "RTL_CLIMB_MIN", RTL_CLIMB_MIN_DEFAULT),142143// @Param: RTL_LOIT_TIME144// @DisplayName: RTL loiter time145// @Description: Time (in milliseconds) to loiter above home before beginning final descent146// @Units: ms147// @Range: 0 60000148// @Increment: 1000149// @User: Standard150GSCALAR(rtl_loiter_time, "RTL_LOIT_TIME", RTL_LOITER_TIME),151152// @Param: RTL_ALT_TYPE153// @DisplayName: RTL mode altitude type154// @Description: RTL altitude type. Set to 1 for Terrain following during RTL and then set WPNAV_RFND_USE=1 to use rangefinder or WPNAV_RFND_USE=0 to use Terrain database155// @Values: 0:Relative to Home, 1:Terrain156// @User: Standard157GSCALAR(rtl_alt_type, "RTL_ALT_TYPE", 0),158#endif159160// @Param: FS_GCS_ENABLE161// @DisplayName: Ground Station Failsafe Enable162// @Description: Controls whether failsafe will be invoked (and what action to take) when connection with Ground station is lost for at least 5 seconds. See FS_OPTIONS param for additional actions, or for cases allowing Mission continuation, when GCS failsafe is enabled.163// @Values: 0:Disabled/NoAction,1:RTL,2:RTL or Continue with Mission in Auto Mode (Removed in 4.0+-see FS_OPTIONS),3:SmartRTL or RTL,4:SmartRTL or Land,5:Land,6:Auto DO_LAND_START/DO_RETURN_PATH_START or RTL,7:Brake or Land164// @User: Standard165GSCALAR(failsafe_gcs, "FS_GCS_ENABLE", FS_GCS_DISABLED),166167// @Param: GPS_HDOP_GOOD168// @DisplayName: GPS Hdop Good169// @Description: GPS Hdop value at or below this value represent a good position. Used for pre-arm checks170// @Range: 100 900171// @User: Advanced172GSCALAR(gps_hdop_good, "GPS_HDOP_GOOD", GPS_HDOP_GOOD_DEFAULT),173174// @Param: SUPER_SIMPLE175// @DisplayName: Super Simple Mode176// @Description: Bitmask to enable Super Simple mode for some flight modes. Setting this to Disabled(0) will disable Super Simple Mode. The bitmask is for flight mode switch positions177// @Bitmask: 0:SwitchPos1, 1:SwitchPos2, 2:SwitchPos3, 3:SwitchPos4, 4:SwitchPos5, 5:SwitchPos6178// @User: Standard179GSCALAR(super_simple, "SUPER_SIMPLE", 0),180181// @Param: WP_YAW_BEHAVIOR182// @DisplayName: Yaw behaviour during missions183// @Description: Determines how the autopilot controls the yaw during missions and RTL184// @Values: 0:Never change yaw, 1:Face next waypoint, 2:Face next waypoint except RTL, 3:Face along GPS course185// @User: Standard186GSCALAR(wp_yaw_behavior, "WP_YAW_BEHAVIOR", WP_YAW_BEHAVIOR_DEFAULT),187188// @Param: LAND_SPEED189// @DisplayName: Land speed190// @Description: The descent speed for the final stage of landing in cm/s191// @Units: cm/s192// @Range: 30 200193// @Increment: 10194// @User: Standard195GSCALAR(land_speed, "LAND_SPEED", LAND_SPEED),196197// @Param: LAND_SPEED_HIGH198// @DisplayName: Land speed high199// @Description: The descent speed for the first stage of landing in cm/s. If this is zero then WPNAV_SPEED_DN is used200// @Units: cm/s201// @Range: 0 500202// @Increment: 10203// @User: Standard204GSCALAR(land_speed_high, "LAND_SPEED_HIGH", 0),205206// @Param: PILOT_SPEED_UP207// @DisplayName: Pilot maximum vertical speed ascending208// @Description: The maximum vertical ascending velocity the pilot may request in cm/s209// @Units: cm/s210// @Range: 50 500211// @Increment: 10212// @User: Standard213GSCALAR(pilot_speed_up, "PILOT_SPEED_UP", PILOT_VELZ_MAX),214215// @Param: PILOT_ACCEL_Z216// @DisplayName: Pilot vertical acceleration217// @Description: The vertical acceleration used when pilot is controlling the altitude218// @Units: cm/s/s219// @Range: 50 500220// @Increment: 10221// @User: Standard222GSCALAR(pilot_accel_z, "PILOT_ACCEL_Z", PILOT_ACCEL_Z_DEFAULT),223224// @Param: FS_THR_ENABLE225// @DisplayName: Throttle Failsafe Enable226// @Description: The throttle failsafe allows you to configure a software failsafe activated by a setting on the throttle input channel227// @Values: 0:Disabled,1:Enabled always RTL,2:Enabled Continue with Mission in Auto Mode (Removed in 4.0+),3:Enabled always Land,4:Enabled always SmartRTL or RTL,5:Enabled always SmartRTL or Land,6:Enabled Auto DO_LAND_START/DO_RETURN_PATH_START or RTL,7:Enabled always Brake or Land228// @User: Standard229GSCALAR(failsafe_throttle, "FS_THR_ENABLE", FS_THR_ENABLED_ALWAYS_RTL),230231// @Param: FS_THR_VALUE232// @DisplayName: Throttle Failsafe Value233// @Description: The PWM level in microseconds on channel 3 below which throttle failsafe triggers234// @Range: 910 1100235// @Units: PWM236// @Increment: 1237// @User: Standard238GSCALAR(failsafe_throttle_value, "FS_THR_VALUE", FS_THR_VALUE_DEFAULT),239240// @Param: THR_DZ241// @DisplayName: Throttle deadzone242// @Description: The deadzone above and below mid throttle in PWM microseconds. Used in AltHold, Loiter, PosHold flight modes243// @User: Standard244// @Range: 0 300245// @Units: PWM246// @Increment: 1247GSCALAR(throttle_deadzone, "THR_DZ", THR_DZ_DEFAULT),248249// @Param: FLTMODE1250// @DisplayName: Flight Mode 1251// @Description: Flight mode when pwm of Flightmode channel(FLTMODE_CH) is <= 1230252// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,11:Drift,13:Sport,14:Flip,15:AutoTune,16:PosHold,17:Brake,18:Throw,19:Avoid_ADSB,20:Guided_NoGPS,21:Smart_RTL,22:FlowHold,23:Follow,24:ZigZag,25:SystemID,26:Heli_Autorotate,27:Auto RTL,28:Turtle253// @User: Standard254GSCALAR(flight_mode1, "FLTMODE1", (uint8_t)FLIGHT_MODE_1),255256// @Param: FLTMODE2257// @CopyFieldsFrom: FLTMODE1258// @DisplayName: Flight Mode 2259// @Description: Flight mode when pwm of Flightmode channel(FLTMODE_CH) is >1230, <= 1360260GSCALAR(flight_mode2, "FLTMODE2", (uint8_t)FLIGHT_MODE_2),261262// @Param: FLTMODE3263// @CopyFieldsFrom: FLTMODE1264// @DisplayName: Flight Mode 3265// @Description: Flight mode when pwm of Flightmode channel(FLTMODE_CH) is >1360, <= 1490266GSCALAR(flight_mode3, "FLTMODE3", (uint8_t)FLIGHT_MODE_3),267268// @Param: FLTMODE4269// @CopyFieldsFrom: FLTMODE1270// @DisplayName: Flight Mode 4271// @Description: Flight mode when pwm of Flightmode channel(FLTMODE_CH) is >1490, <= 1620272GSCALAR(flight_mode4, "FLTMODE4", (uint8_t)FLIGHT_MODE_4),273274// @Param: FLTMODE5275// @CopyFieldsFrom: FLTMODE1276// @DisplayName: Flight Mode 5277// @Description: Flight mode when pwm of Flightmode channel(FLTMODE_CH) is >1620, <= 1749278GSCALAR(flight_mode5, "FLTMODE5", (uint8_t)FLIGHT_MODE_5),279280// @Param: FLTMODE6281// @CopyFieldsFrom: FLTMODE1282// @DisplayName: Flight Mode 6283// @Description: Flight mode when pwm of Flightmode channel(FLTMODE_CH) is >=1750284GSCALAR(flight_mode6, "FLTMODE6", (uint8_t)FLIGHT_MODE_6),285286// @Param: FLTMODE_CH287// @DisplayName: Flightmode channel288// @Description: RC Channel to use for flight mode control289// @Values: 0:Disabled,5:Channel5,6:Channel6,7:Channel7,8:Channel8,9:Channel9,10:Channel 10,11:Channel 11,12:Channel 12,13:Channel 13,14:Channel 14,15:Channel 15290// @User: Advanced291GSCALAR(flight_mode_chan, "FLTMODE_CH", CH_MODE_DEFAULT),292293// @Param: INITIAL_MODE294// @DisplayName: Initial flight mode295// @Description: This selects the mode to start in on boot. This is useful for when you want to start in AUTO mode on boot without a receiver.296// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,11:Drift,13:Sport,14:Flip,15:AutoTune,16:PosHold,17:Brake,18:Throw,19:Avoid_ADSB,20:Guided_NoGPS,21:Smart_RTL,22:FlowHold,23:Follow,24:ZigZag,25:SystemID,26:Heli_Autorotate297// @User: Advanced298GSCALAR(initial_mode, "INITIAL_MODE", (uint8_t)Mode::Number::STABILIZE),299300// @Param: SIMPLE301// @DisplayName: Simple mode bitmask302// @Description: Bitmask which holds which flight modes use simple heading mode (eg bit 0 = 1 means Flight Mode 0 uses simple mode). The bitmask is for flightmode switch positions.303// @Bitmask: 0:SwitchPos1, 1:SwitchPos2, 2:SwitchPos3, 3:SwitchPos4, 4:SwitchPos5, 5:SwitchPos6304// @User: Advanced305GSCALAR(simple_modes, "SIMPLE", 0),306307// @Param: LOG_BITMASK308// @DisplayName: Log bitmask309// @Description: Bitmap of what on-board log types to enable. This value is made up of the sum of each of the log types you want to be saved. It is usually best just to enable all basiclog types by setting this to 65535.310// @Bitmask: 0:Fast Attitude,1:Medium Attitude,2:GPS,3:System Performance,4:Control Tuning,5:Navigation Tuning,6:RC input,7:IMU,8:Mission Commands,9:Battery Monitor,10:RC output,11:Optical Flow,12:PID,13:Compass,15:Camera,17:Motors,18:Fast IMU,19:Raw IMU,20:Video Stabilization,21:Fast harmonic notch logging311// @User: Standard312GSCALAR(log_bitmask, "LOG_BITMASK", DEFAULT_LOG_BITMASK),313314// @Param: ESC_CALIBRATION315// @DisplayName: ESC Calibration316// @Description: Controls whether ArduCopter will enter ESC calibration on the next restart. Do not adjust this parameter manually.317// @User: Advanced318// @Values: 0:Normal Start-up, 1:Start-up in ESC Calibration mode if throttle high, 2:Start-up in ESC Calibration mode regardless of throttle, 3:Start-up and automatically calibrate ESCs, 9:Disabled319GSCALAR(esc_calibrate, "ESC_CALIBRATION", 0),320321// @Param: TUNE322// @DisplayName: Channel 6 Tuning323// @Description: Controls which parameters (normally PID gains) are being tuned with transmitter's channel 6 knob324// @User: Standard325// @Values: 0:None,1:Stab Roll/Pitch kP,4:Rate Roll/Pitch kP,5:Rate Roll/Pitch kI,21:Rate Roll/Pitch kD,3:Stab Yaw kP,6:Rate Yaw kP,26:Rate Yaw kD,56:Rate Yaw Filter,55:Motor Yaw Headroom,14:AltHold kP,7:Throttle Rate kP,34:Throttle Accel kP,35:Throttle Accel kI,36:Throttle Accel kD,12:Loiter Pos kP,22:Velocity XY kP,28:Velocity XY kI,10:WP Speed,25:Acro Roll/Pitch deg/s,40:Acro Yaw deg/s,45:RC Feel,13:Heli Ext Gyro,38:Declination,39:Circle Rate,46:Rate Pitch kP,47:Rate Pitch kI,48:Rate Pitch kD,49:Rate Roll kP,50:Rate Roll kI,51:Rate Roll kD,52:Rate Pitch FF,53:Rate Roll FF,54:Rate Yaw FF,58:SysID Magnitude,59:PSC Angle Max326GSCALAR(radio_tuning, "TUNE", 0),327328// @Param: FRAME_TYPE329// @DisplayName: Frame Type (+, X, V, etc)330// @Description: Controls motor mixing for multicopters. Not used for Tri or Traditional Helicopters.331// @Values: 0:Plus, 1:X, 2:V, 3:H, 4:V-Tail, 5:A-Tail, 10:Y6B, 11:Y6F, 12:BetaFlightX, 13:DJIX, 14:ClockwiseX, 15: I, 18: BetaFlightXReversed, 19:Y4332// @User: Standard333// @RebootRequired: True334GSCALAR(frame_type, "FRAME_TYPE", HAL_FRAME_TYPE_DEFAULT),335336// @Group: ARMING_337// @Path: ../libraries/AP_Arming/AP_Arming.cpp338GOBJECT(arming, "ARMING_", AP_Arming_Copter),339340// @Param: DISARM_DELAY341// @DisplayName: Disarm delay342// @Description: Delay before automatic disarm in seconds after landing touchdown detection. A value of zero disables auto disarm. If Emergency Motor stop active, delay time is half this value.343// @Units: s344// @Range: 0 127345// @User: Advanced346GSCALAR(disarm_delay, "DISARM_DELAY", AUTO_DISARMING_DELAY),347348// @Param: ANGLE_MAX349// @DisplayName: Angle Max350// @Description: Maximum lean angle in all flight modes351// @Units: cdeg352// @Increment: 10353// @Range: 1000 8000354// @User: Advanced355ASCALAR(angle_max, "ANGLE_MAX", DEFAULT_ANGLE_MAX),356357#if MODE_POSHOLD_ENABLED358// @Param: PHLD_BRAKE_RATE359// @DisplayName: PosHold braking rate360// @Description: PosHold flight mode's rotation rate during braking in deg/sec361// @Units: deg/s362// @Range: 4 12363// @User: Advanced364GSCALAR(poshold_brake_rate, "PHLD_BRAKE_RATE", POSHOLD_BRAKE_RATE_DEFAULT),365366// @Param: PHLD_BRAKE_ANGLE367// @DisplayName: PosHold braking angle max368// @Description: PosHold flight mode's max lean angle during braking in centi-degrees369// @Units: cdeg370// @Increment: 10371// @Range: 2000 4500372// @User: Advanced373GSCALAR(poshold_brake_angle_max, "PHLD_BRAKE_ANGLE", POSHOLD_BRAKE_ANGLE_DEFAULT),374#endif375376// @Param: LAND_REPOSITION377// @DisplayName: Land repositioning378// @Description: Enables user input during LAND mode, the landing phase of RTL, and auto mode landings.379// @Values: 0:No repositioning, 1:Repositioning380// @User: Advanced381GSCALAR(land_repositioning, "LAND_REPOSITION", LAND_REPOSITION_DEFAULT),382383// @Param: FS_EKF_ACTION384// @DisplayName: EKF Failsafe Action385// @Description: Controls the action that will be taken when an EKF failsafe is invoked386// @Values: 1:Land, 2:AltHold, 3:Land even in Stabilize387// @User: Advanced388GSCALAR(fs_ekf_action, "FS_EKF_ACTION", FS_EKF_ACTION_DEFAULT),389390// @Param: FS_EKF_THRESH391// @DisplayName: EKF failsafe variance threshold392// @Description: Allows setting the maximum acceptable compass, velocity, position and height variances. Used in arming check and EKF failsafe.393// @Values: 0.6:Strict, 0.8:Default, 1.0:Relaxed394// @User: Advanced395GSCALAR(fs_ekf_thresh, "FS_EKF_THRESH", FS_EKF_THRESHOLD_DEFAULT),396397// @Param: FS_CRASH_CHECK398// @DisplayName: Crash check enable399// @Description: This enables automatic crash checking. When enabled the motors will disarm if a crash is detected.400// @Values: 0:Disabled, 1:Enabled401// @User: Advanced402GSCALAR(fs_crash_check, "FS_CRASH_CHECK", 1),403404// @Param: RC_SPEED405// @DisplayName: ESC Update Speed406// @Description: This is the speed in Hertz that your ESCs will receive updates407// @Units: Hz408// @Range: 50 490409// @Increment: 1410// @User: Advanced411GSCALAR(rc_speed, "RC_SPEED", RC_FAST_SPEED),412413#if MODE_ACRO_ENABLED || MODE_SPORT_ENABLED414// @Param: ACRO_BAL_ROLL415// @DisplayName: Acro Balance Roll416// @Description: rate at which roll angle returns to level in acro and sport mode. A higher value causes the vehicle to return to level faster. For helicopter sets the decay rate of the virtual flybar in the roll axis. A higher value causes faster decay of desired to actual attitude.417// @Range: 0 3418// @Increment: 0.1419// @User: Advanced420GSCALAR(acro_balance_roll, "ACRO_BAL_ROLL", ACRO_BALANCE_ROLL),421422// @Param: ACRO_BAL_PITCH423// @DisplayName: Acro Balance Pitch424// @Description: rate at which pitch angle returns to level in acro and sport mode. A higher value causes the vehicle to return to level faster. For helicopter sets the decay rate of the virtual flybar in the pitch axis. A higher value causes faster decay of desired to actual attitude.425// @Range: 0 3426// @Increment: 0.1427// @User: Advanced428GSCALAR(acro_balance_pitch, "ACRO_BAL_PITCH", ACRO_BALANCE_PITCH),429#endif430431// ACRO_RP_EXPO moved to Command Model class432433#if MODE_ACRO_ENABLED434// @Param: ACRO_TRAINER435// @DisplayName: Acro Trainer436// @Description: Type of trainer used in acro mode437// @Values: 0:Disabled,1:Leveling,2:Leveling and Limited438// @User: Advanced439GSCALAR(acro_trainer, "ACRO_TRAINER", (uint8_t)ModeAcro::Trainer::LIMITED),440#endif441442// variables not in the g class which contain EEPROM saved variables443444#if AP_CAMERA_ENABLED445// @Group: CAM446// @Path: ../libraries/AP_Camera/AP_Camera.cpp447GOBJECT(camera, "CAM", AP_Camera),448#endif449450#if AP_RELAY_ENABLED451// @Group: RELAY452// @Path: ../libraries/AP_Relay/AP_Relay.cpp453GOBJECT(relay, "RELAY", AP_Relay),454#endif455456#if HAL_PARACHUTE_ENABLED457// @Group: CHUTE_458// @Path: ../libraries/AP_Parachute/AP_Parachute.cpp459GOBJECT(parachute, "CHUTE_", AP_Parachute),460#endif461462#if AP_LANDINGGEAR_ENABLED463// @Group: LGR_464// @Path: ../libraries/AP_LandingGear/AP_LandingGear.cpp465GOBJECT(landinggear, "LGR_", AP_LandingGear),466#endif467468#if FRAME_CONFIG == HELI_FRAME469// @Group: IM_470// @Path: ../libraries/AC_InputManager/AC_InputManager_Heli.cpp471GOBJECT(input_manager, "IM_", AC_InputManager_Heli),472#endif473474// @Group: COMPASS_475// @Path: ../libraries/AP_Compass/AP_Compass.cpp476GOBJECT(compass, "COMPASS_", Compass),477478// @Group: INS479// @Path: ../libraries/AP_InertialSensor/AP_InertialSensor.cpp480GOBJECT(ins, "INS", AP_InertialSensor),481482// @Group: WPNAV_483// @Path: ../libraries/AC_WPNav/AC_WPNav.cpp484GOBJECTPTR(wp_nav, "WPNAV_", AC_WPNav),485486// @Group: LOIT_487// @Path: ../libraries/AC_WPNav/AC_Loiter.cpp488GOBJECTPTR(loiter_nav, "LOIT_", AC_Loiter),489490#if MODE_CIRCLE_ENABLED491// @Group: CIRCLE_492// @Path: ../libraries/AC_WPNav/AC_Circle.cpp493GOBJECTPTR(circle_nav, "CIRCLE_", AC_Circle),494#endif495496// @Group: ATC_497// @Path: ../libraries/AC_AttitudeControl/AC_AttitudeControl.cpp,../libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp,../libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp498GOBJECTVARPTR(attitude_control, "ATC_", &copter.attitude_control_var_info),499500// @Group: PSC501// @Path: ../libraries/AC_AttitudeControl/AC_PosControl.cpp502GOBJECTPTR(pos_control, "PSC", AC_PosControl),503504// @Group: SR0_505// @Path: GCS_MAVLink_Copter.cpp506GOBJECTN(_gcs.chan_parameters[0], gcs0, "SR0_", GCS_MAVLINK_Parameters),507508#if MAVLINK_COMM_NUM_BUFFERS >= 2509// @Group: SR1_510// @Path: GCS_MAVLink_Copter.cpp511GOBJECTN(_gcs.chan_parameters[1], gcs1, "SR1_", GCS_MAVLINK_Parameters),512#endif513514#if MAVLINK_COMM_NUM_BUFFERS >= 3515// @Group: SR2_516// @Path: GCS_MAVLink_Copter.cpp517GOBJECTN(_gcs.chan_parameters[2], gcs2, "SR2_", GCS_MAVLINK_Parameters),518#endif519520#if MAVLINK_COMM_NUM_BUFFERS >= 4521// @Group: SR3_522// @Path: GCS_MAVLink_Copter.cpp523GOBJECTN(_gcs.chan_parameters[3], gcs3, "SR3_", GCS_MAVLINK_Parameters),524#endif525526#if MAVLINK_COMM_NUM_BUFFERS >= 5527// @Group: SR4_528// @Path: GCS_MAVLink_Copter.cpp529GOBJECTN(_gcs.chan_parameters[4], gcs4, "SR4_", GCS_MAVLINK_Parameters),530#endif531532#if MAVLINK_COMM_NUM_BUFFERS >= 6533// @Group: SR5_534// @Path: GCS_MAVLink_Copter.cpp535GOBJECTN(_gcs.chan_parameters[5], gcs5, "SR5_", GCS_MAVLINK_Parameters),536#endif537538#if MAVLINK_COMM_NUM_BUFFERS >= 7539// @Group: SR6_540// @Path: GCS_MAVLink_Copter.cpp541GOBJECTN(_gcs.chan_parameters[6], gcs6, "SR6_", GCS_MAVLINK_Parameters),542#endif543544// @Group: AHRS_545// @Path: ../libraries/AP_AHRS/AP_AHRS.cpp546GOBJECT(ahrs, "AHRS_", AP_AHRS),547548#if HAL_MOUNT_ENABLED549// @Group: MNT550// @Path: ../libraries/AP_Mount/AP_Mount.cpp551GOBJECT(camera_mount, "MNT", AP_Mount),552#endif553554// @Group: BATT555// @Path: ../libraries/AP_BattMonitor/AP_BattMonitor.cpp556GOBJECT(battery, "BATT", AP_BattMonitor),557558// @Group: BRD_559// @Path: ../libraries/AP_BoardConfig/AP_BoardConfig.cpp560GOBJECT(BoardConfig, "BRD_", AP_BoardConfig),561562#if HAL_MAX_CAN_PROTOCOL_DRIVERS563// @Group: CAN_564// @Path: ../libraries/AP_CANManager/AP_CANManager.cpp565GOBJECT(can_mgr, "CAN_", AP_CANManager),566#endif567568#if HAL_SPRAYER_ENABLED569// @Group: SPRAY_570// @Path: ../libraries/AC_Sprayer/AC_Sprayer.cpp571GOBJECT(sprayer, "SPRAY_", AC_Sprayer),572#endif573574#if AP_SIM_ENABLED575// @Group: SIM_576// @Path: ../libraries/SITL/SITL.cpp577GOBJECT(sitl, "SIM_", SITL::SIM),578#endif579580// @Group: BARO581// @Path: ../libraries/AP_Baro/AP_Baro.cpp582GOBJECT(barometer, "BARO", AP_Baro),583584// GPS driver585// @Group: GPS586// @Path: ../libraries/AP_GPS/AP_GPS.cpp587GOBJECT(gps, "GPS", AP_GPS),588589// @Group: SCHED_590// @Path: ../libraries/AP_Scheduler/AP_Scheduler.cpp591GOBJECT(scheduler, "SCHED_", AP_Scheduler),592593// @Group: AVOID_594// @Path: ../libraries/AC_Avoidance/AC_Avoid.cpp595#if AP_AVOIDANCE_ENABLED596GOBJECT(avoid, "AVOID_", AC_Avoid),597#endif598599#if HAL_RALLY_ENABLED600// @Group: RALLY_601// @Path: AP_Rally.cpp,../libraries/AP_Rally/AP_Rally.cpp602GOBJECT(rally, "RALLY_", AP_Rally_Copter),603#endif604605#if FRAME_CONFIG == HELI_FRAME606// @Group: H_607// @Path: ../libraries/AP_Motors/AP_MotorsHeli_Single.cpp,../libraries/AP_Motors/AP_MotorsHeli_Dual.cpp,../libraries/AP_Motors/AP_MotorsHeli.cpp608GOBJECTVARPTR(motors, "H_", &copter.motors_var_info),609#else610// @Group: MOT_611// @Path: ../libraries/AP_Motors/AP_MotorsMulticopter.cpp612GOBJECTVARPTR(motors, "MOT_", &copter.motors_var_info),613#endif614615// @Group: RCMAP_616// @Path: ../libraries/AP_RCMapper/AP_RCMapper.cpp617GOBJECT(rcmap, "RCMAP_", RCMapper),618619#if HAL_NAVEKF2_AVAILABLE620// @Group: EK2_621// @Path: ../libraries/AP_NavEKF2/AP_NavEKF2.cpp622GOBJECTN(ahrs.EKF2, NavEKF2, "EK2_", NavEKF2),623#endif624625#if HAL_NAVEKF3_AVAILABLE626// @Group: EK3_627// @Path: ../libraries/AP_NavEKF3/AP_NavEKF3.cpp628GOBJECTN(ahrs.EKF3, NavEKF3, "EK3_", NavEKF3),629#endif630631#if MODE_AUTO_ENABLED632// @Group: MIS_633// @Path: ../libraries/AP_Mission/AP_Mission.cpp634GOBJECTN(mode_auto.mission, mission, "MIS_", AP_Mission),635#endif636637#if AP_RSSI_ENABLED638// @Group: RSSI_639// @Path: ../libraries/AP_RSSI/AP_RSSI.cpp640GOBJECT(rssi, "RSSI_", AP_RSSI),641#endif642643#if AP_RANGEFINDER_ENABLED644// @Group: RNGFND645// @Path: ../libraries/AP_RangeFinder/AP_RangeFinder.cpp646GOBJECT(rangefinder, "RNGFND", RangeFinder),647#endif648649#if AP_TERRAIN_AVAILABLE650// @Group: TERRAIN_651// @Path: ../libraries/AP_Terrain/AP_Terrain.cpp652GOBJECT(terrain, "TERRAIN_", AP_Terrain),653#endif654655#if AP_OPTICALFLOW_ENABLED656// @Group: FLOW657// @Path: ../libraries/AP_OpticalFlow/AP_OpticalFlow.cpp658GOBJECT(optflow, "FLOW", AP_OpticalFlow),659#endif660661#if AC_PRECLAND_ENABLED662// @Group: PLND_663// @Path: ../libraries/AC_PrecLand/AC_PrecLand.cpp664GOBJECT(precland, "PLND_", AC_PrecLand),665#endif666667#if AP_RPM_ENABLED668// @Group: RPM669// @Path: ../libraries/AP_RPM/AP_RPM.cpp670GOBJECT(rpm_sensor, "RPM", AP_RPM),671#endif672673#if HAL_ADSB_ENABLED674// @Group: ADSB_675// @Path: ../libraries/AP_ADSB/AP_ADSB.cpp676GOBJECT(adsb, "ADSB_", AP_ADSB),677678// @Group: AVD_679// @Path: ../libraries/AP_Avoidance/AP_Avoidance.cpp680GOBJECT(avoidance_adsb, "AVD_", AP_Avoidance_Copter),681#endif682683// @Group: NTF_684// @Path: ../libraries/AP_Notify/AP_Notify.cpp685GOBJECT(notify, "NTF_", AP_Notify),686687#if MODE_THROW_ENABLED688// @Param: THROW_MOT_START689// @DisplayName: Start motors before throwing is detected690// @Description: Used by Throw mode. Controls whether motors will run at the speed set by MOT_SPIN_MIN or will be stopped when armed and waiting for the throw.691// @Values: 0:Stopped,1:Running692// @User: Standard693GSCALAR(throw_motor_start, "THROW_MOT_START", (float)ModeThrow::PreThrowMotorState::STOPPED),694695// @Param: THROW_ALT_MIN696// @DisplayName: Throw mode minimum altitude697// @Description: Minimum altitude above which Throw mode will detect a throw or a drop - 0 to disable the check698// @Units: m699// @User: Advanced700GSCALAR(throw_altitude_min, "THROW_ALT_MIN", 0),701702// @Param: THROW_ALT_MAX703// @DisplayName: Throw mode maximum altitude704// @Description: Maximum altitude under which Throw mode will detect a throw or a drop - 0 to disable the check705// @Units: m706// @User: Advanced707GSCALAR(throw_altitude_max, "THROW_ALT_MAX", 0),708#endif709710#if OSD_ENABLED || OSD_PARAM_ENABLED711// @Group: OSD712// @Path: ../libraries/AP_OSD/AP_OSD.cpp713GOBJECT(osd, "OSD", AP_OSD),714#endif715716#if AC_CUSTOMCONTROL_MULTI_ENABLED717// @Group: CC718// @Path: ../libraries/AC_CustomControl/AC_CustomControl.cpp719GOBJECT(custom_control, "CC", AC_CustomControl),720#endif721722// @Group:723// @Path: Parameters.cpp724GOBJECT(g2, "", ParametersG2),725726// @Group:727// @Path: ../libraries/AP_Vehicle/AP_Vehicle.cpp728PARAM_VEHICLE_INFO,729730AP_VAREND731};732733/*7342nd group of parameters735*/736const AP_Param::GroupInfo ParametersG2::var_info[] = {737738// @Param: WP_NAVALT_MIN739// @DisplayName: Minimum navigation altitude740// @Description: This is the altitude in meters above which for navigation can begin. This applies in auto takeoff and auto landing.741// @Range: 0 5742// @User: Standard743AP_GROUPINFO("WP_NAVALT_MIN", 1, ParametersG2, wp_navalt_min, 0),744745#if HAL_BUTTON_ENABLED746// @Group: BTN_747// @Path: ../libraries/AP_Button/AP_Button.cpp748AP_SUBGROUPPTR(button_ptr, "BTN_", 2, ParametersG2, AP_Button),749#endif750751#if MODE_THROW_ENABLED752// @Param: THROW_NEXTMODE753// @DisplayName: Throw mode's follow up mode754// @Description: Vehicle will switch to this mode after the throw is successfully completed. Default is to stay in throw mode (18)755// @Values: 3:Auto,4:Guided,5:LOITER,6:RTL,9:Land,17:Brake,18:Throw756// @User: Standard757AP_GROUPINFO("THROW_NEXTMODE", 3, ParametersG2, throw_nextmode, 18),758759// @Param: THROW_TYPE760// @DisplayName: Type of Type761// @Description: Used by Throw mode. Specifies whether Copter is thrown upward or dropped.762// @Values: 0:Upward Throw,1:Drop763// @User: Standard764AP_GROUPINFO("THROW_TYPE", 4, ParametersG2, throw_type, (float)ModeThrow::ThrowType::Upward),765#endif766767// @Param: GND_EFFECT_COMP768// @DisplayName: Ground Effect Compensation Enable/Disable769// @Description: Ground Effect Compensation Enable/Disable770// @Values: 0:Disabled,1:Enabled771// @User: Advanced772AP_GROUPINFO("GND_EFFECT_COMP", 5, ParametersG2, gndeffect_comp_enabled, 1),773774#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED775// @Group: AFS_776// @Path: ../libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.cpp777AP_SUBGROUPINFO(afs, "AFS_", 6, ParametersG2, AP_AdvancedFailsafe),778#endif779780// @Param: DEV_OPTIONS781// @DisplayName: Development options782// @Description: Bitmask of developer options. The meanings of the bit fields in this parameter may vary at any time. Developers should check the source code for current meaning783// @Bitmask: 0:ADSBMavlinkProcessing,1:DevOptionVFR_HUDRelativeAlt784// @User: Advanced785AP_GROUPINFO("DEV_OPTIONS", 7, ParametersG2, dev_options, 0),786787#if AP_BEACON_ENABLED788// @Group: BCN789// @Path: ../libraries/AP_Beacon/AP_Beacon.cpp790AP_SUBGROUPINFO(beacon, "BCN", 14, ParametersG2, AP_Beacon),791#endif792793#if HAL_PROXIMITY_ENABLED794// @Group: PRX795// @Path: ../libraries/AP_Proximity/AP_Proximity.cpp796AP_SUBGROUPINFO(proximity, "PRX", 8, ParametersG2, AP_Proximity),797#endif798799// ACRO_Y_EXPO (9) moved to Command Model Class800801#if MODE_ACRO_ENABLED802// @Param: ACRO_THR_MID803// @DisplayName: Acro Thr Mid804// @Description: Acro Throttle Mid805// @Range: 0 1806// @User: Advanced807AP_GROUPINFO("ACRO_THR_MID", 10, ParametersG2, acro_thr_mid, ACRO_THR_MID_DEFAULT),808#endif809810// @Param: SYSID_ENFORCE811// @DisplayName: GCS sysid enforcement812// @Description: This controls whether packets from other than the expected GCS system ID will be accepted813// @Values: 0:NotEnforced,1:Enforced814// @User: Advanced815AP_GROUPINFO("SYSID_ENFORCE", 11, ParametersG2, sysid_enforce, 0),816817// 12 was AP_Stats818819// 13 was AP_Gripper820821// @Param: FRAME_CLASS822// @DisplayName: Frame Class823// @Description: Controls major frame class for multicopter component824// @Values: 0:Undefined, 1:Quad, 2:Hexa, 3:Octa, 4:OctaQuad, 5:Y6, 6:Heli, 7:Tri, 8:SingleCopter, 9:CoaxCopter, 10:BiCopter, 11:Heli_Dual, 12:DodecaHexa, 13:HeliQuad, 14:Deca, 15:Scripting Matrix, 16:6DoF Scripting, 17:Dynamic Scripting Matrix825// @User: Standard826// @RebootRequired: True827AP_GROUPINFO("FRAME_CLASS", 15, ParametersG2, frame_class, DEFAULT_FRAME_CLASS),828829// @Group: SERVO830// @Path: ../libraries/SRV_Channel/SRV_Channels.cpp831AP_SUBGROUPINFO(servo_channels, "SERVO", 16, ParametersG2, SRV_Channels),832833// @Group: RC834// @Path: ../libraries/RC_Channel/RC_Channels_VarInfo.h835AP_SUBGROUPINFO(rc_channels, "RC", 17, ParametersG2, RC_Channels_Copter),836837// 18 was used by AP_VisualOdom838839#if AP_TEMPCALIBRATION_ENABLED840// @Group: TCAL841// @Path: ../libraries/AP_TempCalibration/AP_TempCalibration.cpp842AP_SUBGROUPINFO(temp_calibration, "TCAL", 19, ParametersG2, AP_TempCalibration),843#endif844845#if TOY_MODE_ENABLED846// @Group: TMODE847// @Path: toy_mode.cpp848AP_SUBGROUPINFO(toy_mode, "TMODE", 20, ParametersG2, ToyMode),849#endif850851#if MODE_SMARTRTL_ENABLED852// @Group: SRTL_853// @Path: ../libraries/AP_SmartRTL/AP_SmartRTL.cpp854AP_SUBGROUPINFO(smart_rtl, "SRTL_", 21, ParametersG2, AP_SmartRTL),855#endif856857#if AP_WINCH_ENABLED858// 22 was AP_WheelEncoder859860// @Group: WINCH861// @Path: ../libraries/AP_Winch/AP_Winch.cpp862AP_SUBGROUPINFO(winch, "WINCH", 23, ParametersG2, AP_Winch),863#endif864865// @Param: PILOT_SPEED_DN866// @DisplayName: Pilot maximum vertical speed descending867// @Description: The maximum vertical descending velocity the pilot may request in cm/s. If 0 PILOT_SPEED_UP value is used.868// @Units: cm/s869// @Range: 0 500870// @Increment: 10871// @User: Standard872AP_GROUPINFO("PILOT_SPEED_DN", 24, ParametersG2, pilot_speed_dn, 0),873874// @Param: LAND_ALT_LOW875// @DisplayName: Land alt low876// @Description: Altitude during Landing at which vehicle slows to LAND_SPEED877// @Units: cm878// @Range: 100 10000879// @Increment: 10880// @User: Advanced881AP_GROUPINFO("LAND_ALT_LOW", 25, ParametersG2, land_alt_low, 1000),882883#if MODE_FLOWHOLD_ENABLED884// @Group: FHLD885// @Path: mode_flowhold.cpp886AP_SUBGROUPPTR(mode_flowhold_ptr, "FHLD", 26, ParametersG2, ModeFlowHold),887#endif888889#if MODE_FOLLOW_ENABLED890// @Group: FOLL891// @Path: ../libraries/AP_Follow/AP_Follow.cpp892AP_SUBGROUPINFO(follow, "FOLL", 27, ParametersG2, AP_Follow),893#endif894895#if USER_PARAMS_ENABLED896AP_SUBGROUPINFO(user_parameters, "USR", 28, ParametersG2, UserParameters),897#endif898899#if AUTOTUNE_ENABLED900// @Group: AUTOTUNE_901// @Path: ../libraries/AC_AutoTune/AC_AutoTune_Multi.cpp,../libraries/AC_AutoTune/AC_AutoTune_Heli.cpp902AP_SUBGROUPPTR(autotune_ptr, "AUTOTUNE_", 29, ParametersG2, AutoTune),903#endif904905// 30 was AP_Scripting906907// @Param: TUNE_MIN908// @DisplayName: Tuning minimum909// @Description: Minimum value that the parameter currently being tuned with the transmitter's channel 6 knob will be set to910// @User: Standard911AP_GROUPINFO("TUNE_MIN", 31, ParametersG2, tuning_min, 0),912913// @Param: TUNE_MAX914// @DisplayName: Tuning maximum915// @Description: Maximum value that the parameter currently being tuned with the transmitter's channel 6 knob will be set to916// @User: Standard917AP_GROUPINFO("TUNE_MAX", 32, ParametersG2, tuning_max, 0),918919#if AP_OAPATHPLANNER_ENABLED920// @Group: OA_921// @Path: ../libraries/AC_Avoidance/AP_OAPathPlanner.cpp922AP_SUBGROUPINFO(oa, "OA_", 33, ParametersG2, AP_OAPathPlanner),923#endif924925#if MODE_SYSTEMID_ENABLED926// @Group: SID927// @Path: mode_systemid.cpp928AP_SUBGROUPPTR(mode_systemid_ptr, "SID", 34, ParametersG2, ModeSystemId),929#endif930931// @Param: FS_VIBE_ENABLE932// @DisplayName: Vibration Failsafe enable933// @Description: This enables the vibration failsafe which will use modified altitude estimation and control during high vibrations934// @Values: 0:Disabled, 1:Enabled935// @User: Standard936AP_GROUPINFO("FS_VIBE_ENABLE", 35, ParametersG2, fs_vibe_enabled, 1),937938// @Param: FS_OPTIONS939// @DisplayName: Failsafe options bitmask940// @Description: Bitmask of additional options for battery, radio, & GCS failsafes. 0 (default) disables all options.941// @Bitmask: 0:Continue if in Auto on RC failsafe, 1:Continue if in Auto on GCS failsafe, 2:Continue if in Guided on RC failsafe, 3:Continue if landing on any failsafe, 4:Continue if in pilot controlled modes on GCS failsafe, 5:Release Gripper942// @User: Advanced943AP_GROUPINFO("FS_OPTIONS", 36, ParametersG2, fs_options, (float)Copter::FailsafeOption::GCS_CONTINUE_IF_PILOT_CONTROL),944945#if MODE_AUTOROTATE_ENABLED946// @Group: AROT_947// @Path: ../libraries/AC_Autorotation/AC_Autorotation.cpp948AP_SUBGROUPINFO(arot, "AROT_", 37, ParametersG2, AC_Autorotation),949#endif950951#if MODE_ZIGZAG_ENABLED952// @Group: ZIGZ_953// @Path: mode_zigzag.cpp954AP_SUBGROUPPTR(mode_zigzag_ptr, "ZIGZ_", 38, ParametersG2, ModeZigZag),955#endif956957#if MODE_ACRO_ENABLED958// @Param: ACRO_OPTIONS959// @DisplayName: Acro mode options960// @Description: A range of options that can be applied to change acro mode behaviour. Air-mode enables ATC_THR_MIX_MAN at all times (air-mode has no effect on helicopters). Rate Loop Only disables the use of angle stabilization and uses angular rate stabilization only.961// @Bitmask: 0:Air-mode,1:Rate Loop Only962// @User: Advanced963AP_GROUPINFO("ACRO_OPTIONS", 39, ParametersG2, acro_options, 0),964#endif965966#if MODE_AUTO_ENABLED967// @Param: AUTO_OPTIONS968// @DisplayName: Auto mode options969// @Description: A range of options that can be applied to change auto mode behaviour. Allow Arming allows the copter to be armed in Auto. Allow Takeoff Without Raising Throttle allows takeoff without the pilot having to raise the throttle. Ignore pilot yaw overrides the pilot's yaw stick being used while in auto.970// @Bitmask: 0:Allow Arming,1:Allow Takeoff Without Raising Throttle,2:Ignore pilot yaw,7:Allow weathervaning971// @User: Advanced972AP_GROUPINFO("AUTO_OPTIONS", 40, ParametersG2, auto_options, 0),973#endif974975#if MODE_GUIDED_ENABLED976// @Param: GUID_OPTIONS977// @DisplayName: Guided mode options978// @Description: Options that can be applied to change guided mode behaviour979// @Bitmask: 0:Allow Arming from Transmitter,2:Ignore pilot yaw,3:SetAttitudeTarget interprets Thrust As Thrust,4:Do not stabilize PositionXY,5:Do not stabilize VelocityXY,6:Waypoint navigation used for position targets,7:Allow weathervaning980// @User: Advanced981AP_GROUPINFO("GUID_OPTIONS", 41, ParametersG2, guided_options, 0),982#endif983984// @Param: FS_GCS_TIMEOUT985// @DisplayName: GCS failsafe timeout986// @Description: Timeout before triggering the GCS failsafe987// @Units: s988// @Range: 2 120989// @Increment: 1990// @User: Standard991AP_GROUPINFO("FS_GCS_TIMEOUT", 42, ParametersG2, fs_gcs_timeout, 5),992993#if MODE_RTL_ENABLED994// @Param: RTL_OPTIONS995// @DisplayName: RTL mode options996// @Description: Options that can be applied to change RTL mode behaviour997// @Bitmask: 2:Ignore pilot yaw998// @User: Advanced999AP_GROUPINFO("RTL_OPTIONS", 43, ParametersG2, rtl_options, 0),1000#endif10011002// @Param: FLIGHT_OPTIONS1003// @DisplayName: Flight mode options1004// @Description: Flight mode specific options1005// @Bitmask: 0:Disable thrust loss check, 1:Disable yaw imbalance warning, 2:Release gripper on thrust loss, 3:Require position for arming1006// @User: Advanced1007AP_GROUPINFO("FLIGHT_OPTIONS", 44, ParametersG2, flight_options, 0),10081009#if AP_RANGEFINDER_ENABLED1010// @Param: RNGFND_FILT1011// @DisplayName: Rangefinder filter1012// @Description: Rangefinder filter to smooth distance. Set to zero to disable filtering1013// @Units: Hz1014// @Range: 0 51015// @Increment: 0.051016// @User: Standard1017// @RebootRequired: True1018AP_GROUPINFO("RNGFND_FILT", 45, ParametersG2, rangefinder_filt, RANGEFINDER_FILT_DEFAULT),1019#endif10201021#if MODE_GUIDED_ENABLED1022// @Param: GUID_TIMEOUT1023// @DisplayName: Guided mode timeout1024// @Description: Guided mode timeout after which vehicle will stop or return to level if no updates are received from caller. Only applicable during any combination of velocity, acceleration, angle control, and/or angular rate control1025// @Units: s1026// @Range: 0.1 51027// @User: Advanced1028AP_GROUPINFO("GUID_TIMEOUT", 46, ParametersG2, guided_timeout, 3.0),1029#endif10301031// ACRO_PR_RATE (47), ACRO_Y_RATE (48), PILOT_Y_RATE (49) and PILOT_Y_EXPO (50) moved to command model class10321033#if AP_RANGEFINDER_ENABLED1034// @Param: SURFTRAK_MODE1035// @DisplayName: Surface Tracking Mode1036// @Description: set which surface to track in surface tracking1037// @Values: 0:Do not track, 1:Ground, 2:Ceiling1038// @User: Advanced1039// @RebootRequired: True1040AP_GROUPINFO("SURFTRAK_MODE", 51, ParametersG2, surftrak_mode, (uint8_t)Copter::SurfaceTracking::Surface::GROUND),1041#endif10421043// @Param: FS_DR_ENABLE1044// @DisplayName: DeadReckon Failsafe Action1045// @Description: Failsafe action taken immediately as deadreckoning starts. Deadreckoning starts when EKF loses position and velocity source and relies only on wind estimates1046// @Values: 0:Disabled/NoAction,1:Land, 2:RTL, 3:SmartRTL or RTL, 4:SmartRTL or Land, 6:Auto DO_LAND_START/DO_RETURN_PATH_START or RTL1047// @User: Standard1048AP_GROUPINFO("FS_DR_ENABLE", 52, ParametersG2, failsafe_dr_enable, (uint8_t)Copter::FailsafeAction::RTL),10491050// @Param: FS_DR_TIMEOUT1051// @DisplayName: DeadReckon Failsafe Timeout1052// @Description: DeadReckoning is available for this many seconds after losing position and/or velocity source. After this timeout elapses the EKF failsafe will trigger in modes requiring a position estimate1053// @Range: 0 1201054// @User: Standard1055AP_GROUPINFO("FS_DR_TIMEOUT", 53, ParametersG2, failsafe_dr_timeout, 30),10561057#if MODE_ACRO_ENABLED || MODE_SPORT_ENABLED1058// @Param: ACRO_RP_RATE1059// @DisplayName: Acro Roll and Pitch Rate1060// @Description: Acro mode maximum roll and pitch rate. Higher values mean faster rate of rotation1061// @Units: deg/s1062// @Range: 1 10801063// @User: Standard10641065// @Param: ACRO_RP_EXPO1066// @DisplayName: Acro Roll/Pitch Expo1067// @Description: Acro roll/pitch Expo to allow faster rotation when stick at edges1068// @Values: 0:Disabled,0.1:Very Low,0.2:Low,0.3:Medium,0.4:High,0.5:Very High1069// @Range: -0.5 0.951070// @User: Advanced10711072// @Param: ACRO_RP_RATE_TC1073// @DisplayName: Acro roll/pitch rate control input time constant1074// @Description: Acro roll and pitch rate control input time constant. Low numbers lead to sharper response, higher numbers to softer response1075// @Units: s1076// @Range: 0 11077// @Increment: 0.011078// @Values: 0.5:Very Soft, 0.2:Soft, 0.15:Medium, 0.1:Crisp, 0.05:Very Crisp1079// @User: Standard1080AP_SUBGROUPINFO(command_model_acro_rp, "ACRO_RP_", 54, ParametersG2, AC_CommandModel),1081#endif10821083#if MODE_ACRO_ENABLED || MODE_DRIFT_ENABLED1084// @Param: ACRO_Y_RATE1085// @DisplayName: Acro Yaw Rate1086// @Description: Acro mode maximum yaw rate. Higher value means faster rate of rotation1087// @Units: deg/s1088// @Range: 1 3601089// @User: Standard10901091// @Param: ACRO_Y_EXPO1092// @DisplayName: Acro Yaw Expo1093// @Description: Acro yaw expo to allow faster rotation when stick at edges1094// @Values: 0:Disabled,0.1:Very Low,0.2:Low,0.3:Medium,0.4:High,0.5:Very High1095// @Range: -1.0 0.951096// @User: Advanced10971098// @Param: ACRO_Y_RATE_TC1099// @DisplayName: Acro yaw rate control input time constant1100// @Description: Acro yaw rate control input time constant. Low numbers lead to sharper response, higher numbers to softer response1101// @Units: s1102// @Range: 0 11103// @Increment: 0.011104// @Values: 0.5:Very Soft, 0.2:Soft, 0.15:Medium, 0.1:Crisp, 0.05:Very Crisp1105// @User: Standard1106AP_SUBGROUPINFO(command_model_acro_y, "ACRO_Y_", 55, ParametersG2, AC_CommandModel),1107#endif11081109// @Param: PILOT_Y_RATE1110// @DisplayName: Pilot controlled yaw rate1111// @Description: Pilot controlled yaw rate max. Used in all pilot controlled modes except Acro1112// @Units: deg/s1113// @Range: 1 3601114// @User: Standard11151116// @Param: PILOT_Y_EXPO1117// @DisplayName: Pilot controlled yaw expo1118// @Description: Pilot controlled yaw expo to allow faster rotation when stick at edges1119// @Values: 0:Disabled,0.1:Very Low,0.2:Low,0.3:Medium,0.4:High,0.5:Very High1120// @Range: -0.5 1.01121// @User: Advanced11221123// @Param: PILOT_Y_RATE_TC1124// @DisplayName: Pilot yaw rate control input time constant1125// @Description: Pilot yaw rate control input time constant. Low numbers lead to sharper response, higher numbers to softer response1126// @Units: s1127// @Range: 0 11128// @Increment: 0.011129// @Values: 0.5:Very Soft, 0.2:Soft, 0.15:Medium, 0.1:Crisp, 0.05:Very Crisp1130// @User: Standard1131AP_SUBGROUPINFO(command_model_pilot, "PILOT_Y_", 56, ParametersG2, AC_CommandModel),11321133// @Param: TKOFF_SLEW_TIME1134// @DisplayName: Slew time of throttle during take-off1135// @Description: Time to slew the throttle from minimum to maximum while checking for a succsessful takeoff.1136// @Units: s1137// @Range: 0.25 5.01138// @User: Standard1139AP_GROUPINFO("TKOFF_SLEW_TIME", 57, ParametersG2, takeoff_throttle_slew_time, 2.0),11401141#if HAL_WITH_ESC_TELEM && FRAME_CONFIG != HELI_FRAME1142// @Param: TKOFF_RPM_MIN1143// @DisplayName: Takeoff Check RPM minimum1144// @Description: Takeoff is not permitted until motors report at least this RPM. Set to zero to disable check1145// @Range: 0 100001146// @User: Standard1147AP_GROUPINFO("TKOFF_RPM_MIN", 58, ParametersG2, takeoff_rpm_min, 0),1148#endif11491150#if WEATHERVANE_ENABLED1151// @Group: WVANE_1152// @Path: ../libraries/AC_AttitudeControl/AC_WeatherVane.cpp1153AP_SUBGROUPINFO(weathervane, "WVANE_", 59, ParametersG2, AC_WeatherVane),1154#endif11551156// ID 60 is reserved for the SHIP_OPS11571158// extend to a new group1159AP_SUBGROUPEXTENSION("", 61, ParametersG2, var_info2),11601161// ID 62 is reserved for the SHOW_... parameters from the Skybrush fork at1162// https://github.com/skybrush-io/ardupilot11631164AP_GROUPEND1165};11661167/*1168extension to g2 parameters1169*/1170const AP_Param::GroupInfo ParametersG2::var_info2[] = {11711172// @Param: PLDP_THRESH1173// @DisplayName: Payload Place thrust ratio threshold1174// @Description: Ratio of vertical thrust during decent below which payload touchdown will trigger.1175// @Range: 0.5 0.91176// @User: Standard1177AP_GROUPINFO("PLDP_THRESH", 1, ParametersG2, pldp_thrust_placed_fraction, 0.9),11781179// @Param: PLDP_RNG_MAX1180// @DisplayName: Payload Place maximum range finder altitude1181// @Description: Maximum range finder altitude in m to trigger payload touchdown, set to zero to disable.1182// @Units: m1183// @Range: 0 1001184// @User: Standard1185AP_GROUPINFO("PLDP_RNG_MAX", 2, ParametersG2, pldp_range_finder_maximum_m, 0.0),11861187// @Param: PLDP_DELAY1188// @DisplayName: Payload Place climb delay1189// @Description: Delay after release, in seconds, before aircraft starts to climb back to starting altitude.1190// @Units: s1191// @Range: 0 1201192// @User: Standard1193AP_GROUPINFO("PLDP_DELAY", 3, ParametersG2, pldp_delay_s, 0.0),11941195// @Param: PLDP_SPEED_DN1196// @DisplayName: Payload Place decent speed1197// @Description: The maximum vertical decent velocity in m/s. If 0 LAND_SPEED value is used.1198// @Units: m/s1199// @Range: 0 51200// @User: Standard1201AP_GROUPINFO("PLDP_SPEED_DN", 4, ParametersG2, pldp_descent_speed_ms, 0.0),12021203// @Param: SURFTRAK_TC1204// @DisplayName: Surface Tracking Filter Time Constant1205// @Description: Time to achieve 63.2% of the surface altitude measurement change. If 0 filtering is disabled1206// @Units: s1207// @Range: 0 51208// @User: Advanced1209AP_GROUPINFO("SURFTRAK_TC", 5, ParametersG2, surftrak_tc, 1.0),12101211// @Param: TKOFF_THR_MAX1212// @DisplayName: Takeoff maximum throttle during take-off ramp up1213// @Description: Takeoff maximum throttle allowed before controllers assume the aircraft is airborne during the takeoff process.1214// @Range: 0.0 0.91215// @User: Advanced1216AP_GROUPINFO("TKOFF_THR_MAX", 6, ParametersG2, takeoff_throttle_max, 0.9),12171218#if HAL_WITH_ESC_TELEM && FRAME_CONFIG != HELI_FRAME1219// @Param: TKOFF_RPM_MAX1220// @DisplayName: Takeoff Check RPM maximum1221// @Description: Takeoff is not permitted until motors report no more than this RPM. Set to zero to disable check1222// @Range: 0 100001223// @User: Standard1224AP_GROUPINFO("TKOFF_RPM_MAX", 7, ParametersG2, takeoff_rpm_max, 0),1225#endif12261227// @Param: FS_EKF_FILT1228// @DisplayName: EKF Failsafe filter cutoff1229// @Description: EKF Failsafe filter cutoff frequency. EKF variances are filtered using this value to avoid spurious failsafes from transient high variances. A higher value means the failsafe is more likely to trigger.1230// @Range: 0 101231// @Units: Hz1232// @User: Advanced1233AP_GROUPINFO("FS_EKF_FILT", 8, ParametersG2, fs_ekf_filt_hz, FS_EKF_FILT_DEFAULT),12341235#if AP_INERTIALSENSOR_FAST_SAMPLE_WINDOW_ENABLED1236// @Param: FSTRATE_ENABLE1237// @DisplayName: Enable the fast Rate thread1238// @Description: Enable the fast Rate thread. In the default case the fast rate divisor, which controls the update frequency of the thread, is dynamically scaled from FSTRATE_DIV to avoid overrun in the gyro sample buffer and main loop slow-downs. Other values can be selected to fix the divisor to FSTRATE_DIV on arming or always.1239// @User: Advanced1240// @Values: 0:Disabled,1:Enabled-Dynamic,2:Enabled-FixedWhenArmed,3:Enabled-Fixed1241AP_GROUPINFO("FSTRATE_ENABLE", 9, ParametersG2, att_enable, 0),12421243// @Param: FSTRATE_DIV1244// @DisplayName: Fast rate thread divisor1245// @Description: Fast rate thread divisor used to control the maximum fast rate update rate. The actual rate is the gyro rate in Hz divided by this value. This value is scaled depending on the configuration of FSTRATE_ENABLE.1246// @User: Advanced1247// @Range: 1 101248AP_GROUPINFO("FSTRATE_DIV", 10, ParametersG2, att_decimation, 1),1249#endif12501251// ID 62 is reserved for the AP_SUBGROUPEXTENSION12521253AP_GROUPEND1254};12551256/*1257constructor for g2 object1258*/1259ParametersG2::ParametersG2(void) :1260unused_integer{17}1261#if HAL_BUTTON_ENABLED1262,button_ptr(&copter.button)1263#endif1264#if AP_TEMPCALIBRATION_ENABLED1265, temp_calibration()1266#endif1267#if AP_BEACON_ENABLED1268, beacon()1269#endif1270#if HAL_PROXIMITY_ENABLED1271, proximity()1272#endif1273#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED1274,afs()1275#endif1276#if MODE_SMARTRTL_ENABLED1277,smart_rtl()1278#endif1279#if USER_PARAMS_ENABLED1280,user_parameters()1281#endif1282#if MODE_FLOWHOLD_ENABLED1283,mode_flowhold_ptr(&copter.mode_flowhold)1284#endif1285#if MODE_FOLLOW_ENABLED1286,follow()1287#endif1288#if AUTOTUNE_ENABLED1289,autotune_ptr(&copter.mode_autotune.autotune)1290#endif1291#if MODE_SYSTEMID_ENABLED1292,mode_systemid_ptr(&copter.mode_systemid)1293#endif1294#if MODE_AUTOROTATE_ENABLED1295,arot()1296#endif1297#if MODE_ZIGZAG_ENABLED1298,mode_zigzag_ptr(&copter.mode_zigzag)1299#endif1300#if MODE_ACRO_ENABLED || MODE_SPORT_ENABLED1301,command_model_acro_rp(ACRO_RP_RATE_DEFAULT, ACRO_RP_EXPO_DEFAULT, 0.0f)1302#endif13031304#if MODE_ACRO_ENABLED || MODE_DRIFT_ENABLED1305,command_model_acro_y(ACRO_Y_RATE_DEFAULT, ACRO_Y_EXPO_DEFAULT, 0.0f)1306#endif13071308,command_model_pilot(PILOT_Y_RATE_DEFAULT, PILOT_Y_EXPO_DEFAULT, 0.0f)13091310#if WEATHERVANE_ENABLED1311,weathervane()1312#endif1313{1314AP_Param::setup_object_defaults(this, var_info);1315AP_Param::setup_object_defaults(this, var_info2);1316}13171318void Copter::load_parameters(void)1319{1320AP_Vehicle::load_parameters(g.format_version, Parameters::k_format_version);13211322#if MODE_RTL_ENABLED1323// PARAMETER_CONVERSION - Added: Sep-20211324g.rtl_altitude.convert_parameter_width(AP_PARAM_INT16);1325#endif13261327// PARAMETER_CONVERSION - Added: Mar-20221328#if AP_FENCE_ENABLED1329AP_Param::convert_class(g.k_param_fence_old, &fence, fence.var_info, 0, true);1330#endif13311332static const AP_Param::G2ObjectConversion g2_conversions[] {1333#if AP_STATS_ENABLED1334// PARAMETER_CONVERSION - Added: Jan-2024 for Copter-4.61335{ &stats, stats.var_info, 12 },1336#endif1337#if AP_SCRIPTING_ENABLED1338// PARAMETER_CONVERSION - Added: Jan-2024 for Copter-4.61339{ &scripting, scripting.var_info, 30 },1340#endif1341#if AP_GRIPPER_ENABLED1342// PARAMETER_CONVERSION - Added: Feb-2024 for Copter-4.61343{ &gripper, gripper.var_info, 13 },1344#endif1345};13461347AP_Param::convert_g2_objects(&g2, g2_conversions, ARRAY_SIZE(g2_conversions));13481349// PARAMETER_CONVERSION - Added: Feb-2024 for Copter-4.61350#if HAL_LOGGING_ENABLED1351AP_Param::convert_class(g.k_param_logger, &logger, logger.var_info, 0, true);1352#endif13531354static const AP_Param::TopLevelObjectConversion toplevel_conversions[] {1355#if AP_SERIALMANAGER_ENABLED1356// PARAMETER_CONVERSION - Added: Feb-2024 for Copter-4.61357{ &serial_manager, serial_manager.var_info, Parameters::k_param_serial_manager_old },1358#endif1359};13601361AP_Param::convert_toplevel_objects(toplevel_conversions, ARRAY_SIZE(toplevel_conversions));136213631364// setup AP_Param frame type flags1365AP_Param::set_frame_type_flags(AP_PARAM_FRAME_COPTER);1366}13671368// handle conversion of PID gains1369void Copter::convert_pid_parameters(void)1370{1371const AP_Param::ConversionInfo angle_and_filt_conversion_info[] = {1372// PARAMETER_CONVERSION - Added: Aug-20211373{ Parameters::k_param_pi_vel_xy, 3, AP_PARAM_FLOAT, "PSC_VELXY_FLTE" },1374};13751376// convert angle controller gain and filter without scaling1377for (const auto &info : angle_and_filt_conversion_info) {1378AP_Param::convert_old_parameter(&info, 1.0f);1379}13801381// TradHeli default parameters1382#if FRAME_CONFIG == HELI_FRAME1383static const struct AP_Param::defaults_table_struct heli_defaults_table[] = {1384{ "LOIT_ACC_MAX", 500.0f },1385{ "LOIT_BRK_ACCEL", 125.0f },1386{ "LOIT_BRK_DELAY", 1.0f },1387{ "LOIT_BRK_JERK", 250.0f },1388{ "LOIT_SPEED", 3000.0f },1389{ "PHLD_BRAKE_ANGLE", 800.0f },1390{ "PHLD_BRAKE_RATE", 4.0f },1391{ "PSC_ACCZ_P", 0.28f },1392{ "PSC_VELXY_D", 0.0f },1393{ "PSC_VELXY_I", 0.5f },1394{ "PSC_VELXY_P", 1.0f },1395{ "RC8_OPTION", 32 },1396{ "RC_OPTIONS", 0 },1397{ "ATC_RAT_RLL_ILMI", 0.05},1398{ "ATC_RAT_PIT_ILMI", 0.05},1399};1400AP_Param::set_defaults_from_table(heli_defaults_table, ARRAY_SIZE(heli_defaults_table));1401#endif // FRAME_CONFIG == HELI_FRAME14021403#if AP_INERTIALSENSOR_HARMONICNOTCH_ENABLED1404#if HAL_INS_NUM_HARMONIC_NOTCH_FILTERS > 11405if (!ins.harmonic_notches[1].params.enabled()) {1406// notch filter parameter conversions (moved to INS_HNTC2) for 4.2.x, converted from fixed notch1407const AP_Param::ConversionInfo notchfilt_conversion_info[] {1408// PARAMETER_CONVERSION - Added: Apr 20221409{ Parameters::k_param_ins, 101, AP_PARAM_INT8, "INS_HNTC2_ENABLE" },1410{ Parameters::k_param_ins, 293, AP_PARAM_FLOAT, "INS_HNTC2_ATT" },1411{ Parameters::k_param_ins, 357, AP_PARAM_FLOAT, "INS_HNTC2_FREQ" },1412{ Parameters::k_param_ins, 421, AP_PARAM_FLOAT, "INS_HNTC2_BW" },1413};1414AP_Param::convert_old_parameters(¬chfilt_conversion_info[0], ARRAY_SIZE(notchfilt_conversion_info));1415AP_Param::set_default_by_name("INS_HNTC2_MODE", 0);1416AP_Param::set_default_by_name("INS_HNTC2_HMNCS", 1);1417}1418#endif1419#endif // AP_INERTIALSENSOR_HARMONICNOTCH_ENABLED14201421// ACRO_RP_P and ACRO_Y_P replaced with ACRO_RP_RATE and ACRO_Y_RATE for Copter-4.21422// PARAMETER_CONVERSION - Added: Sep-20211423const AP_Param::ConversionInfo acro_rpy_conversion_info[] = {1424{ Parameters::k_param_acro_rp_p, 0, AP_PARAM_FLOAT, "ACRO_RP_RATE" },1425{ Parameters::k_param_acro_yaw_p, 0, AP_PARAM_FLOAT, "ACRO_Y_RATE" }1426};1427for (const auto &info : acro_rpy_conversion_info) {1428AP_Param::convert_old_parameter(&info, 45.0);1429}14301431// convert rate and expo command model parameters for Copter-4.31432// PARAMETER_CONVERSION - Added: June-20221433const AP_Param::ConversionInfo cmd_mdl_conversion_info[] = {1434{ Parameters::k_param_g2, 47, AP_PARAM_FLOAT, "ACRO_RP_RATE" },1435{ Parameters::k_param_acro_rp_expo, 0, AP_PARAM_FLOAT, "ACRO_RP_EXPO" },1436{ Parameters::k_param_g2, 48, AP_PARAM_FLOAT, "ACRO_Y_RATE" },1437{ Parameters::k_param_g2, 9, AP_PARAM_FLOAT, "ACRO_Y_EXPO" },1438{ Parameters::k_param_g2, 49, AP_PARAM_FLOAT, "PILOT_Y_RATE" },1439{ Parameters::k_param_g2, 50, AP_PARAM_FLOAT, "PILOT_Y_EXPO" },1440};1441for (const auto &info : cmd_mdl_conversion_info) {1442AP_Param::convert_old_parameter(&info, 1.0);1443}14441445// make any SRV_Channel upgrades needed1446SRV_Channels::upgrade_parameters();1447}14481449#if HAL_PROXIMITY_ENABLED1450void Copter::convert_prx_parameters()1451{1452// convert PRX to PRX1_ parameters for Copter-4.31453// PARAMETER_CONVERSION - Added: Aug-20221454const AP_Param::ConversionInfo prx_conversion_info[] = {1455{ Parameters::k_param_g2, 72, AP_PARAM_INT8, "PRX1_TYPE" },1456{ Parameters::k_param_g2, 136, AP_PARAM_INT8, "PRX1_ORIENT" },1457{ Parameters::k_param_g2, 200, AP_PARAM_INT16, "PRX1_YAW_CORR" },1458{ Parameters::k_param_g2, 264, AP_PARAM_INT16, "PRX1_IGN_ANG1" },1459{ Parameters::k_param_g2, 328, AP_PARAM_INT8, "PRX1_IGN_WID1" },1460{ Parameters::k_param_g2, 392, AP_PARAM_INT16, "PRX1_IGN_ANG2" },1461{ Parameters::k_param_g2, 456, AP_PARAM_INT8, "PRX1_IGN_WID2" },1462{ Parameters::k_param_g2, 520, AP_PARAM_INT16, "PRX1_IGN_ANG3" },1463{ Parameters::k_param_g2, 584, AP_PARAM_INT8, "PRX1_IGN_WID3" },1464{ Parameters::k_param_g2, 648, AP_PARAM_INT16, "PRX1_IGN_ANG4" },1465{ Parameters::k_param_g2, 712, AP_PARAM_INT8, "PRX1_IGN_WID4" },1466{ Parameters::k_param_g2, 1224, AP_PARAM_FLOAT, "PRX1_MIN" },1467{ Parameters::k_param_g2, 1288, AP_PARAM_FLOAT, "PRX1_MAX" },1468};1469for (const auto &info : prx_conversion_info) {1470AP_Param::convert_old_parameter(&info, 1.0);1471}1472}1473#endif147414751476