#include "Blimp.h" /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by the Free Software Foundation, either version 3 of the License, or (at your option) any later version. This program is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for more details. You should have received a copy of the GNU General Public License along with this program. If not, see . */ /* * Blimp parameter definitions * */ #define GSCALAR(v, name, def) { blimp.g.v.vtype, name, Parameters::k_param_ ## v, &blimp.g.v, {def_value : def} } #define ASCALAR(v, name, def) { blimp.aparm.v.vtype, name, Parameters::k_param_ ## v, (const void *)&blimp.aparm.v, {def_value : def} } #define GGROUP(v, name, class) { AP_PARAM_GROUP, name, Parameters::k_param_ ## v, &blimp.g.v, {group_info : class::var_info} } #define GOBJECT(v, name, class) { AP_PARAM_GROUP, name, Parameters::k_param_ ## v, (const void *)&blimp.v, {group_info : class::var_info} } #define GOBJECTPTR(v, name, class) { AP_PARAM_GROUP, name, Parameters::k_param_ ## v, (const void *)&blimp.v, {group_info : class::var_info}, AP_PARAM_FLAG_POINTER } #define GOBJECTVARPTR(v, name, var_info_ptr) { AP_PARAM_GROUP, name, Parameters::k_param_ ## v, (const void *)&blimp.v, {group_info_ptr : var_info_ptr}, AP_PARAM_FLAG_POINTER | AP_PARAM_FLAG_INFO_POINTER } #define GOBJECTN(v, pname, name, class) { AP_PARAM_GROUP, name, Parameters::k_param_ ## pname, (const void *)&blimp.v, {group_info : class::var_info} } #define DEFAULT_FRAME_CLASS 0 const AP_Param::Info Blimp::var_info[] = { // @Param: FORMAT_VERSION // @DisplayName: Eeprom format version number // @Description: This value is incremented when changes are made to the eeprom format // @User: Advanced // @ReadOnly: True GSCALAR(format_version, "FORMAT_VERSION", 0), // @Param: SYSID_THISMAV // @DisplayName: MAVLink system ID of this vehicle // @Description: Allows setting an individual MAVLink system id for this vehicle to distinguish it from others on the same network // @Range: 1 255 // @User: Advanced GSCALAR(sysid_this_mav, "SYSID_THISMAV", MAV_SYSTEM_ID), // @Param: SYSID_MYGCS // @DisplayName: My ground station number // @Description: Allows restricting radio overrides to only come from my ground station // @Range: 1 255 // @User: Advanced GSCALAR(sysid_my_gcs, "SYSID_MYGCS", 255), // @Param: PILOT_THR_FILT // @DisplayName: Throttle filter cutoff // @Description: Throttle filter cutoff (Hz) - active whenever altitude control is inactive - 0 to disable // @User: Advanced // @Units: Hz // @Range: 0 10 // @Increment: .5 GSCALAR(throttle_filt, "PILOT_THR_FILT", 0), // @Param: PILOT_TKOFF_ALT // @DisplayName: Pilot takeoff altitude // @Description: Altitude that altitude control modes will climb to when a takeoff is triggered with the throttle stick. // @User: Standard // @Units: cm // @Range: 0.0 1000.0 // @Increment: 10 GSCALAR(pilot_takeoff_alt, "PILOT_TKOFF_ALT", PILOT_TKOFF_ALT_DEFAULT), // @Param: PILOT_THR_BHV // @DisplayName: Throttle stick behavior // @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. // @User: Standard // @Values: 0:None,1:Feedback from mid stick,2:High throttle cancels landing,4:Disarm on land detection // @Bitmask: 0:Feedback from mid stick,1:High throttle cancels landing,2:Disarm on land detection GSCALAR(throttle_behavior, "PILOT_THR_BHV", 0), // @Group: SERIAL // @Path: ../libraries/AP_SerialManager/AP_SerialManager.cpp GOBJECT(serial_manager, "SERIAL", AP_SerialManager), // @Param: TELEM_DELAY // @DisplayName: Telemetry startup delay // @Description: The amount of time (in seconds) to delay radio telemetry to prevent an Xbee bricking on power up // @User: Advanced // @Units: s // @Range: 0 30 // @Increment: 1 GSCALAR(telem_delay, "TELEM_DELAY", 0), // @Param: GCS_PID_MASK // @DisplayName: GCS PID tuning mask // @Description: bitmask of PIDs to send MAVLink PID_TUNING messages for // @User: Advanced // @Values: 0:None,1:Roll,2:Pitch,4:Yaw,8:AccelZ // @Bitmask: 0:Roll,1:Pitch,2:Yaw,3:AccelZ GSCALAR(gcs_pid_mask, "GCS_PID_MASK", 0), // @Param: FS_GCS_ENABLE // @DisplayName: Ground Station Failsafe Enable // @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. // @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 (4.0+ Only) // @User: Standard GSCALAR(failsafe_gcs, "FS_GCS_ENABLE", FS_GCS_DISABLED), // @Param: GPS_HDOP_GOOD // @DisplayName: GPS Hdop Good // @Description: GPS Hdop value at or below this value represent a good position. Used for pre-arm checks // @Range: 100 900 // @User: Advanced GSCALAR(gps_hdop_good, "GPS_HDOP_GOOD", GPS_HDOP_GOOD_DEFAULT), // @Param: WP_YAW_BEHAVIOR // @DisplayName: Yaw behaviour during missions // @Description: Determines how the autopilot controls the yaw during missions and RTL // @Values: 0:Never change yaw, 1:Face next waypoint, 2:Face next waypoint except RTL, 3:Face along GPS course // @User: Standard GSCALAR(wp_yaw_behavior, "WP_YAW_BEHAVIOR", WP_YAW_BEHAVIOR_DEFAULT), // @Param: LAND_SPEED // @DisplayName: Land speed // @Description: The descent speed for the final stage of landing in cm/s // @Units: cm/s // @Range: 30 200 // @Increment: 10 // @User: Standard GSCALAR(land_speed, "LAND_SPEED", LAND_SPEED), // @Param: LAND_SPEED_HIGH // @DisplayName: Land speed high // @Description: The descent speed for the first stage of landing in cm/s. If this is zero then WPNAV_SPEED_DN is used // @Units: cm/s // @Range: 0 500 // @Increment: 10 // @User: Standard GSCALAR(land_speed_high, "LAND_SPEED_HIGH", 0), // @Param: PILOT_SPEED_UP // @DisplayName: Pilot maximum vertical speed ascending // @Description: The maximum vertical ascending velocity the pilot may request in cm/s // @Units: cm/s // @Range: 50 500 // @Increment: 10 // @User: Standard GSCALAR(pilot_speed_up, "PILOT_SPEED_UP", PILOT_VELZ_MAX), // @Param: PILOT_ACCEL_Z // @DisplayName: Pilot vertical acceleration // @Description: The vertical acceleration used when pilot is controlling the altitude // @Units: cm/s/s // @Range: 50 500 // @Increment: 10 // @User: Standard GSCALAR(pilot_accel_z, "PILOT_ACCEL_Z", PILOT_ACCEL_Z_DEFAULT), // @Param: FS_THR_ENABLE // @DisplayName: Throttle Failsafe Enable // @Description: The throttle failsafe allows you to configure a software failsafe activated by a setting on the throttle input channel // @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 // @User: Standard GSCALAR(failsafe_throttle, "FS_THR_ENABLE", FS_THR_ENABLED_ALWAYS_RTL), // @Param: FS_THR_VALUE // @DisplayName: Throttle Failsafe Value // @Description: The PWM level in microseconds on channel 3 below which throttle failsafe triggers // @Range: 910 1100 // @Units: PWM // @Increment: 1 // @User: Standard GSCALAR(failsafe_throttle_value, "FS_THR_VALUE", FS_THR_VALUE_DEFAULT), // @Param: THR_DZ // @DisplayName: Throttle deadzone // @Description: The deadzone above and below mid throttle in PWM microseconds. Used in AltHold, Loiter, PosHold flight modes // @User: Standard // @Range: 0 300 // @Units: PWM // @Increment: 1 GSCALAR(throttle_deadzone, "THR_DZ", THR_DZ_DEFAULT), // @Param: FLTMODE1 // @DisplayName: Flight Mode 1 // @Description: Flight mode when Channel 5 pwm is <= 1230 // @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 // @User: Standard GSCALAR(flight_mode1, "FLTMODE1", (uint8_t)FLIGHT_MODE_1), // @Param: FLTMODE2 // @DisplayName: Flight Mode 2 // @Description: Flight mode when Channel 5 pwm is >1230, <= 1360 // @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 // @User: Standard GSCALAR(flight_mode2, "FLTMODE2", (uint8_t)FLIGHT_MODE_2), // @Param: FLTMODE3 // @DisplayName: Flight Mode 3 // @Description: Flight mode when Channel 5 pwm is >1360, <= 1490 // @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 // @User: Standard GSCALAR(flight_mode3, "FLTMODE3", (uint8_t)FLIGHT_MODE_3), // @Param: FLTMODE4 // @DisplayName: Flight Mode 4 // @Description: Flight mode when Channel 5 pwm is >1490, <= 1620 // @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 // @User: Standard GSCALAR(flight_mode4, "FLTMODE4", (uint8_t)FLIGHT_MODE_4), // @Param: FLTMODE5 // @DisplayName: Flight Mode 5 // @Description: Flight mode when Channel 5 pwm is >1620, <= 1749 // @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 // @User: Standard GSCALAR(flight_mode5, "FLTMODE5", (uint8_t)FLIGHT_MODE_5), // @Param: FLTMODE6 // @DisplayName: Flight Mode 6 // @Description: Flight mode when Channel 5 pwm is >=1750 // @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 // @User: Standard GSCALAR(flight_mode6, "FLTMODE6", (uint8_t)FLIGHT_MODE_6), // @Param: FLTMODE_CH // @DisplayName: Flightmode channel // @Description: RC Channel to use for flight mode control // @Values: 0:Disabled,5:Channel5,6:Channel6,7:Channel7,8:Channel8 // @User: Advanced GSCALAR(flight_mode_chan, "FLTMODE_CH", CH_MODE_DEFAULT), // @Param: INITIAL_MODE // @DisplayName: Initial flight mode // @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. // @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 // @User: Advanced GSCALAR(initial_mode, "INITIAL_MODE", (uint8_t)Mode::Number::MANUAL), // @Param: LOG_BITMASK // @DisplayName: Log bitmask // @Description: 4 byte bitmap of log types to enable // @Values: 830:Default,894:Default+RCIN,958:Default+IMU,1854:Default+Motors,-6146:NearlyAll-AC315,45054:NearlyAll,131071:All+FastATT,262142:All+MotBatt,393214:All+FastIMU,397310:All+FastIMU+PID,655358:All+FullIMU,0:Disabled // @Bitmask: 0:ATTITUDE_FAST,1:ATTITUDE_MED,2:GPS,3:PM,4:CTUN,5:NTUN,6:RCIN,7:IMU,8:CMD,9:CURRENT,10:RCOUT,11:OPTFLOW,12:PID,13:COMPASS,14:INAV,15:CAMERA,17:MOTBATT,18:IMU_FAST,19:IMU_RAW // @User: Standard GSCALAR(log_bitmask, "LOG_BITMASK", DEFAULT_LOG_BITMASK), // @Param: TUNE // @DisplayName: Channel 6 Tuning // @Description: Controls which parameters (normally PID gains) are being tuned with transmitter's channel 6 knob // @User: Standard // @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 RollPitch kP,40:Acro Yaw kP,45:RC Feel,13:Heli Ext Gyro,38:Declination,39:Circle Rate,41:RangeFinder Gain,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 GSCALAR(radio_tuning, "TUNE", 0), // @Param: FRAME_TYPE // @DisplayName: Frame Type (+, X, V, etc) // @Description: Controls motor mixing for multiblimps. Not used for Tri or Traditional Heliblimps. // @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 // @User: Standard // @RebootRequired: True GSCALAR(frame_type, "FRAME_TYPE", HAL_FRAME_TYPE_DEFAULT), // @Group: ARMING_ // @Path: ../libraries/AP_Arming/AP_Arming.cpp GOBJECT(arming, "ARMING_", AP_Arming_Blimp), // @Param: DISARM_DELAY // @DisplayName: Disarm delay // @Description: Delay before automatic disarm in seconds. A value of zero disables auto disarm. // @Units: s // @Range: 0 127 // @User: Advanced GSCALAR(disarm_delay, "DISARM_DELAY", AUTO_DISARMING_DELAY), // @Param: ANGLE_MAX // @DisplayName: Angle Max // @Description: Maximum lean angle in all flight modes // @Units: cdeg // @Range: 1000 8000 // @User: Advanced ASCALAR(angle_max, "ANGLE_MAX", DEFAULT_ANGLE_MAX), // @Param: PHLD_BRAKE_RATE // @DisplayName: PosHold braking rate // @Description: PosHold flight mode's rotation rate during braking in deg/sec // @Units: deg/s // @Range: 4 12 // @User: Advanced GSCALAR(poshold_brake_rate, "PHLD_BRAKE_RATE", POSHOLD_BRAKE_RATE_DEFAULT), // @Param: PHLD_BRAKE_ANGLE // @DisplayName: PosHold braking angle max // @Description: PosHold flight mode's max lean angle during braking in centi-degrees // @Units: cdeg // @Range: 2000 4500 // @User: Advanced GSCALAR(poshold_brake_angle_max, "PHLD_BRAKE_ANGLE", POSHOLD_BRAKE_ANGLE_DEFAULT), // @Param: LAND_REPOSITION // @DisplayName: Land repositioning // @Description: Enables user input during LAND mode, the landing phase of RTL, and auto mode landings. // @Values: 0:No repositioning, 1:Repositioning // @User: Advanced GSCALAR(land_repositioning, "LAND_REPOSITION", LAND_REPOSITION_DEFAULT), // @Param: FS_EKF_ACTION // @DisplayName: EKF Failsafe Action // @Description: Controls the action that will be taken when an EKF failsafe is invoked // @Values: 1:Land, 2:AltHold, 3:Land even in Stabilize // @User: Advanced GSCALAR(fs_ekf_action, "FS_EKF_ACTION", FS_EKF_ACTION_DEFAULT), // @Param: FS_EKF_THRESH // @DisplayName: EKF failsafe variance threshold // @Description: Allows setting the maximum acceptable compass and velocity variance // @Values: 0.6:Strict, 0.8:Default, 1.0:Relaxed // @User: Advanced GSCALAR(fs_ekf_thresh, "FS_EKF_THRESH", FS_EKF_THRESHOLD_DEFAULT), // @Param: FS_CRASH_CHECK // @DisplayName: Crash check enable // @Description: This enables automatic crash checking. When enabled the motors will disarm if a crash is detected. // @Values: 0:Disabled, 1:Enabled // @User: Advanced GSCALAR(fs_crash_check, "FS_CRASH_CHECK", 1), // @Param: RC_SPEED // @DisplayName: ESC Update Speed // @Description: This is the speed in Hertz that your ESCs will receive updates // @Units: Hz // @Range: 50 490 // @Increment: 1 // @User: Advanced GSCALAR(rc_speed, "RC_SPEED", RC_FAST_SPEED), // @Param: ACRO_RP_P // @DisplayName: Acro Roll and Pitch P gain // @Description: Converts pilot roll and pitch into a desired rate of rotation in ACRO and SPORT mode. Higher values mean faster rate of rotation. // @Range: 1 10 // @User: Standard GSCALAR(acro_rp_p, "ACRO_RP_P", ACRO_RP_P), // @Param: ACRO_YAW_P // @DisplayName: Acro Yaw P gain // @Description: Converts pilot yaw input into a desired rate of rotation. Higher values mean faster rate of rotation. // @Range: 1 10 // @User: Standard GSCALAR(acro_yaw_p, "ACRO_YAW_P", ACRO_YAW_P), // variables not in the g class which contain EEPROM saved variables // @Group: RELAY_ // @Path: ../libraries/AP_Relay/AP_Relay.cpp GOBJECT(relay, "RELAY_", AP_Relay), // @Group: COMPASS_ // @Path: ../libraries/AP_Compass/AP_Compass.cpp GOBJECT(compass, "COMPASS_", Compass), // @Group: INS_ // @Path: ../libraries/AP_InertialSensor/AP_InertialSensor.cpp GOBJECT(ins, "INS_", AP_InertialSensor), // // @Group: WPNAV_ // // @Path: ../libraries/AC_WPNav/AC_WPNav.cpp // GOBJECTPTR(wp_nav, "WPNAV_", AC_WPNav), // // @Group: LOIT_ // // @Path: ../libraries/AC_WPNav/AC_Loiter.cpp // GOBJECTPTR(loiter_nav, "LOIT_", AC_Loiter), // @Group: ATC_ // @Path: ../libraries/AC_AttitudeControl/AC_AttitudeControl.cpp,../libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp,../libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp // #if FRAME_CONFIG == HELI_FRAME // GOBJECTPTR(attitude_control, "ATC_", AC_AttitudeControl_Heli), // #else // GOBJECTPTR(attitude_control, "ATC_", AC_AttitudeControl_Multi), // #endif // @Group: PSC // @Path: ../libraries/AC_AttitudeControl/AC_PosControl.cpp // GOBJECTPTR(pos_control, "PSC", AC_PosControl), // @Group: SR0_ // @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 GOBJECT(ahrs, "AHRS_", AP_AHRS), // @Group: LOG // @Path: ../libraries/AP_Logger/AP_Logger.cpp GOBJECT(logger, "LOG", AP_Logger), // @Group: BATT // @Path: ../libraries/AP_BattMonitor/AP_BattMonitor.cpp GOBJECT(battery, "BATT", AP_BattMonitor), // @Group: BRD_ // @Path: ../libraries/AP_BoardConfig/AP_BoardConfig.cpp GOBJECT(BoardConfig, "BRD_", AP_BoardConfig), #if HAL_MAX_CAN_PROTOCOL_DRIVERS // @Group: CAN_ // @Path: ../libraries/AP_CANManager/AP_CANManager.cpp GOBJECT(can_mgr, "CAN_", AP_CANManager), #endif #if CONFIG_HAL_BOARD == HAL_BOARD_SITL GOBJECT(sitl, "SIM_", SITL::SITL), #endif // @Group: BARO // @Path: ../libraries/AP_Baro/AP_Baro.cpp GOBJECT(barometer, "BARO", AP_Baro), // GPS driver // @Group: GPS_ // @Path: ../libraries/AP_GPS/AP_GPS.cpp GOBJECT(gps, "GPS_", AP_GPS), // @Group: SCHED_ // @Path: ../libraries/AP_Scheduler/AP_Scheduler.cpp GOBJECT(scheduler, "SCHED_", AP_Scheduler), // @Group: RCMAP_ // @Path: ../libraries/AP_RCMapper/AP_RCMapper.cpp GOBJECT(rcmap, "RCMAP_", RCMapper), #if HAL_NAVEKF2_AVAILABLE // @Group: EK2_ // @Path: ../libraries/AP_NavEKF2/AP_NavEKF2.cpp GOBJECTN(ahrs.EKF2, NavEKF2, "EK2_", NavEKF2), #endif #if HAL_NAVEKF3_AVAILABLE // @Group: EK3_ // @Path: ../libraries/AP_NavEKF3/AP_NavEKF3.cpp GOBJECTN(ahrs.EKF3, NavEKF3, "EK3_", NavEKF3), #endif // @Group: RSSI_ // @Path: ../libraries/AP_RSSI/AP_RSSI.cpp GOBJECT(rssi, "RSSI_", AP_RSSI), // @Group: NTF_ // @Path: ../libraries/AP_Notify/AP_Notify.cpp GOBJECT(notify, "NTF_", AP_Notify), // @Group: // @Path: Parameters.cpp GOBJECT(g2, "", ParametersG2), // @Group: FINS_ // @Path: Fins.cpp GOBJECTPTR(motors, "FINS_", Fins), // @Group: // @Path: ../libraries/AP_Vehicle/AP_Vehicle.cpp { AP_PARAM_GROUP, "", Parameters::k_param_vehicle, (const void *)&blimp, {group_info : AP_Vehicle::var_info} }, AP_VAREND }; /* 2nd group of parameters */ const AP_Param::GroupInfo ParametersG2::var_info[] = { // @Param: WP_NAVALT_MIN // @DisplayName: Minimum navigation altitude // @Description: This is the altitude in meters above which for navigation can begin. This applies in auto takeoff and auto landing. // @Range: 0 5 // @User: Standard AP_GROUPINFO("WP_NAVALT_MIN", 1, ParametersG2, wp_navalt_min, 0), // @Param: DEV_OPTIONS // @DisplayName: Development options // @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 meaning // @Bitmask: 0:ADSBMavlinkProcessing,1:DevOptionVFR_HUDRelativeAlt,2:SetAttitudeTarget_ThrustAsThrust // @User: Advanced AP_GROUPINFO("DEV_OPTIONS", 7, ParametersG2, dev_options, 0), // @Param: ACRO_Y_EXPO // @DisplayName: Acro Yaw Expo // @Description: Acro yaw expo to allow faster rotation when stick at edges // @Values: 0:Disabled,0.1:Very Low,0.2:Low,0.3:Medium,0.4:High,0.5:Very High // @Range: -0.5 1.0 // @User: Advanced AP_GROUPINFO("ACRO_Y_EXPO", 9, ParametersG2, acro_y_expo, ACRO_Y_EXPO_DEFAULT), // @Param: SYSID_ENFORCE // @DisplayName: GCS sysid enforcement // @Description: This controls whether packets from other than the expected GCS system ID will be accepted // @Values: 0:NotEnforced,1:Enforced // @User: Advanced AP_GROUPINFO("SYSID_ENFORCE", 11, ParametersG2, sysid_enforce, 0), #if STATS_ENABLED == ENABLED // @Group: STAT // @Path: ../libraries/AP_Stats/AP_Stats.cpp AP_SUBGROUPINFO(stats, "STAT", 12, ParametersG2, AP_Stats), #endif // @Param: FRAME_CLASS // @DisplayName: Frame Class // @Description: Controls major frame class for multiblimp component // @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 // @User: Standard // @RebootRequired: True AP_GROUPINFO("FRAME_CLASS", 15, ParametersG2, frame_class, DEFAULT_FRAME_CLASS), // @Group: SERVO // @Path: ../libraries/SRV_Channel/SRV_Channels.cpp AP_SUBGROUPINFO(servo_channels, "SERVO", 16, ParametersG2, SRV_Channels), // @Group: RC // @Path: ../libraries/RC_Channel/RC_Channels_VarInfo.h AP_SUBGROUPINFO(rc_channels, "RC", 17, ParametersG2, RC_Channels_Blimp), // // 18 was used by AP_VisualOdom // // @Group: TCAL // // @Path: ../libraries/AP_TempCalibration/AP_TempCalibration.cpp // AP_SUBGROUPINFO(temp_calibration, "TCAL", 19, ParametersG2, AP_TempCalibration), // @Param: PILOT_SPEED_DN // @DisplayName: Pilot maximum vertical speed descending // @Description: The maximum vertical descending velocity the pilot may request in cm/s // @Units: cm/s // @Range: 50 500 // @Increment: 10 // @User: Standard AP_GROUPINFO("PILOT_SPEED_DN", 24, ParametersG2, pilot_speed_dn, 0), // @Param: LAND_ALT_LOW // @DisplayName: Land alt low // @Description: Altitude during Landing at which vehicle slows to LAND_SPEED // @Units: cm // @Range: 100 10000 // @Increment: 10 // @User: Advanced AP_GROUPINFO("LAND_ALT_LOW", 25, ParametersG2, land_alt_low, 1000), #ifdef ENABLE_SCRIPTING // @Group: SCR_ // @Path: ../libraries/AP_Scripting/AP_Scripting.cpp AP_SUBGROUPINFO(scripting, "SCR_", 30, ParametersG2, AP_Scripting), #endif // @Param: TUNE_MIN // @DisplayName: Tuning minimum // @Description: Minimum value that the parameter currently being tuned with the transmitter's channel 6 knob will be set to // @User: Standard AP_GROUPINFO("TUNE_MIN", 31, ParametersG2, tuning_min, 0), // @Param: TUNE_MAX // @DisplayName: Tuning maximum // @Description: Maximum value that the parameter currently being tuned with the transmitter's channel 6 knob will be set to // @User: Standard AP_GROUPINFO("TUNE_MAX", 32, ParametersG2, tuning_max, 0), // @Param: FS_VIBE_ENABLE // @DisplayName: Vibration Failsafe enable // @Description: This enables the vibration failsafe which will use modified altitude estimation and control during high vibrations // @Values: 0:Disabled, 1:Enabled // @User: Standard AP_GROUPINFO("FS_VIBE_ENABLE", 35, ParametersG2, fs_vibe_enabled, 1), // @Param: FS_OPTIONS // @DisplayName: Failsafe options bitmask // @Description: Bitmask of additional options for battery, radio, & GCS failsafes. 0 (default) disables all options. // @Values: 0:Disabled, 1:Continue if in Auto on RC failsafe only, 2:Continue if in Auto on GCS failsafe only, 3:Continue if in Auto on RC and/or GCS failsafe, 4:Continue if in Guided on RC failsafe only, 8:Continue if landing on any failsafe, 16:Continue if in pilot controlled modes on GCS failsafe, 19:Continue if in Auto on RC and/or GCS failsafe and continue if in pilot controlled modes on GCS failsafe // @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 Gripper // @User: Advanced AP_GROUPINFO("FS_OPTIONS", 36, ParametersG2, fs_options, (float)Blimp::FailsafeOption::GCS_CONTINUE_IF_PILOT_CONTROL), // @Param: FS_GCS_TIMEOUT // @DisplayName: GCS failsafe timeout // @Description: Timeout before triggering the GCS failsafe // @Units: s // @Range: 2 120 // @Increment: 1 // @User: Standard AP_GROUPINFO("FS_GCS_TIMEOUT", 42, ParametersG2, fs_gcs_timeout, 5), AP_GROUPEND }; /* constructor for g2 object */ ParametersG2::ParametersG2(void) // : temp_calibration() // this doesn't actually need constructing, but removing it here is problematic syntax-wise { AP_Param::setup_object_defaults(this, var_info); } void Blimp::load_parameters(void) { if (!AP_Param::check_var_info()) { hal.console->printf("Bad var table\n"); AP_HAL::panic("Bad var table"); } // disable centrifugal force correction, it will be enabled as part of the arming process ahrs.set_correct_centrifugal(false); hal.util->set_soft_armed(false); if (!g.format_version.load() || g.format_version != Parameters::k_format_version) { // erase all parameters hal.console->printf("Firmware change: erasing EEPROM...\n"); StorageManager::erase(); AP_Param::erase_all(); // save the current format version g.format_version.set_and_save(Parameters::k_format_version); hal.console->printf("done.\n"); } uint32_t before = micros(); // Load all auto-loaded EEPROM variables AP_Param::load_all(); hal.console->printf("load_all took %uus\n", (unsigned)(micros() - before)); // setup AP_Param frame type flags AP_Param::set_frame_type_flags(AP_PARAM_FRAME_COPTER); }