2015-06-01 02:04:25 -03:00
# include "Tracker.h"
2013-10-13 04:14:13 -03:00
/*
* AntennaTracker parameter definitions
*
*/
2015-06-01 02:04:25 -03:00
# define GSCALAR(v, name, def) { tracker.g.v.vtype, name, Parameters::k_param_ ## v, &tracker.g.v, {def_value : def} }
# define ASCALAR(v, name, def) { tracker.aparm.v.vtype, name, Parameters::k_param_ ## v, (const void *)&tracker.aparm.v, {def_value : def} }
# define GGROUP(v, name, class) { AP_PARAM_GROUP, name, Parameters::k_param_ ## v, &tracker.g.v, {group_info : class::var_info} }
# define GOBJECT(v, name, class) { AP_PARAM_GROUP, name, Parameters::k_param_ ## v, (const void *)&tracker.v, {group_info : class::var_info} }
# define GOBJECTN(v, pname, name, class) { AP_PARAM_GROUP, name, Parameters::k_param_ ## pname, (const void *)&tracker.v, {group_info : class::var_info} }
2013-10-13 04:14:13 -03:00
2015-10-25 14:03:46 -03:00
const AP_Param : : Info Tracker : : var_info [ ] = {
2016-02-08 07:40:31 -04:00
// @Param: FORMAT_VERSION
// @DisplayName: Eeprom format version number
// @Description: This value is incremented when changes are made to the eeprom format
// @User: Advanced
2013-10-13 04:14:13 -03:00
GSCALAR ( format_version , " FORMAT_VERSION " , 0 ) ,
2016-02-08 07:40:31 -04:00
2013-10-13 04:14:13 -03:00
// @Param: SYSID_THISMAV
2015-05-10 21:22:01 -03:00
// @DisplayName: MAVLink system ID of this vehicle
// @Description: Allows setting an individual system id for this vehicle to distinguish it from others on the same network
2013-10-13 04:14:13 -03:00
// @Range: 1 255
// @User: Advanced
GSCALAR ( sysid_this_mav , " SYSID_THISMAV " , MAV_SYSTEM_ID ) ,
// @Param: SYSID_MYGCS
// @DisplayName: Ground station MAVLink system ID
// @Description: The identifier of the ground station in the MAVLink protocol. Don't change this unless you also modify the ground station to match.
// @Range: 1 255
// @User: Advanced
GSCALAR ( sysid_my_gcs , " SYSID_MYGCS " , 255 ) ,
2015-04-27 04:44:32 -03:00
// @Param: SYSID_TARGET
// @DisplayName: Target vehicle's MAVLink system ID
// @Description: The identifier of the vehicle being tracked. This should be zero (to auto detect) or be the same as the SYSID_THISMAV parameter of the vehicle being tracked.
// @Range: 1 255
// @User: Advanced
GSCALAR ( sysid_target , " SYSID_TARGET " , 0 ) ,
2014-03-22 05:08:00 -03:00
// @Param: YAW_SLEW_TIME
// @DisplayName: Time for yaw to slew through its full range
// @Description: This controls how rapidly the tracker will change the servo output for yaw. It is set as the number of seconds to do a full rotation. You can use this parameter to slow the trackers movements, which may help with some types of trackers. A value of zero will allow for unlimited servo movement per update.
2017-05-02 10:35:51 -03:00
// @Units: s
2014-03-22 05:08:00 -03:00
// @Increment: 0.1
// @Range: 0 20
2014-08-14 17:19:55 -03:00
// @User: Standard
2014-03-22 05:08:00 -03:00
GSCALAR ( yaw_slew_time , " YAW_SLEW_TIME " , 2 ) ,
// @Param: PITCH_SLEW_TIME
// @DisplayName: Time for pitch to slew through its full range
// @Description: This controls how rapidly the tracker will change the servo output for pitch. It is set as the number of seconds to do a full range of pitch movement. You can use this parameter to slow the trackers movements, which may help with some types of trackers. A value of zero will allow for unlimited servo movement per update.
2017-05-02 10:35:51 -03:00
// @Units: s
2014-03-22 05:08:00 -03:00
// @Increment: 0.1
// @Range: 0 20
2014-08-14 17:19:55 -03:00
// @User: Standard
2014-03-22 05:08:00 -03:00
GSCALAR ( pitch_slew_time , " PITCH_SLEW_TIME " , 2 ) ,
// @Param: MIN_REVERSE_TIME
// @DisplayName: Minimum time to apply a yaw reversal
// @Description: When the tracker detects it has reached the limit of servo movement in yaw it will reverse and try moving to the other extreme of yaw. This parameter controls the minimum time it should reverse for. It is used to cope with trackers that have a significant lag in movement to ensure they do move all the way around.
2017-05-02 10:35:51 -03:00
// @Units: s
2014-03-22 05:08:00 -03:00
// @Increment: 1
// @Range: 0 20
2014-08-14 17:19:55 -03:00
// @User: Standard
2014-03-22 05:08:00 -03:00
GSCALAR ( min_reverse_time , " MIN_REVERSE_TIME " , 1 ) ,
// @Param: START_LATITUDE
// @DisplayName: Initial Latitude before GPS lock
// @Description: Combined with START_LONGITUDE this parameter allows for an initial position of the tracker to be set. This position will be used until the GPS gets lock. It can also be used to run a stationary tracker with no GPS attached.
2017-05-02 10:35:51 -03:00
// @Units: deg
2014-03-22 05:08:00 -03:00
// @Increment: 0.000001
// @Range: -90 90
2014-08-14 17:19:55 -03:00
// @User: Standard
2014-03-22 05:08:00 -03:00
GSCALAR ( start_latitude , " START_LATITUDE " , 0 ) ,
// @Param: START_LONGITUDE
// @DisplayName: Initial Longitude before GPS lock
// @Description: Combined with START_LATITUDE this parameter allows for an initial position of the tracker to be set. This position will be used until the GPS gets lock. It can also be used to run a stationary tracker with no GPS attached.
2017-05-02 10:35:51 -03:00
// @Units: deg
2014-03-22 05:08:00 -03:00
// @Increment: 0.000001
// @Range: -180 180
2014-08-14 17:19:55 -03:00
// @User: Standard
2014-03-22 05:08:00 -03:00
GSCALAR ( start_longitude , " START_LONGITUDE " , 0 ) ,
// @Param: STARTUP_DELAY
// @DisplayName: Delay before first servo movement from trim
// @Description: This parameter can be used to force the servos to their trim value for a time on startup. This can help with some servo types
2017-05-02 10:35:51 -03:00
// @Units: s
2014-03-22 05:08:00 -03:00
// @Increment: 0.1
// @Range: 0 10
2014-08-14 17:19:55 -03:00
// @User: Standard
2014-03-22 05:08:00 -03:00
GSCALAR ( startup_delay , " STARTUP_DELAY " , 0 ) ,
2016-05-23 04:54:47 -03:00
// @Param: SERVO_PITCH_TYPE
// @DisplayName: Type of servo system being used for pitch
// @Description: This allows selection of position servos or on/off servos for pitch
2015-06-03 11:05:58 -03:00
// @Values: 0:Position,1:OnOff,2:ContinuousRotation
2014-08-14 17:19:55 -03:00
// @User: Standard
2016-05-23 04:54:47 -03:00
GSCALAR ( servo_pitch_type , " SERVO_PITCH_TYPE " , SERVO_TYPE_POSITION ) ,
// @Param: SERVO_YAW_TYPE
// @DisplayName: Type of servo system being used for yaw
// @Description: This allows selection of position servos or on/off servos for yaw
// @Values: 0:Position,1:OnOff,2:ContinuousRotation
// @User: Standard
GSCALAR ( servo_yaw_type , " SERVO_YAW_TYPE " , SERVO_TYPE_POSITION ) ,
2014-07-23 05:41:25 -03:00
// @Param: ONOFF_YAW_RATE
// @DisplayName: Yaw rate for on/off servos
// @Description: Rate of change of yaw in degrees/second for on/off servos
2017-05-02 10:35:51 -03:00
// @Units: deg/s
2014-07-23 05:41:25 -03:00
// @Increment: 0.1
// @Range: 0 50
2014-08-14 17:19:55 -03:00
// @User: Standard
2014-07-23 05:41:25 -03:00
GSCALAR ( onoff_yaw_rate , " ONOFF_YAW_RATE " , 9.0f ) ,
// @Param: ONOFF_PITCH_RATE
// @DisplayName: Pitch rate for on/off servos
// @Description: Rate of change of pitch in degrees/second for on/off servos
2017-05-02 10:35:51 -03:00
// @Units: deg/s
2014-07-23 05:41:25 -03:00
// @Increment: 0.1
// @Range: 0 50
2014-08-14 17:19:55 -03:00
// @User: Standard
2014-07-23 05:41:25 -03:00
GSCALAR ( onoff_pitch_rate , " ONOFF_PITCH_RATE " , 1.0f ) ,
// @Param: ONOFF_YAW_MINT
// @DisplayName: Yaw minimum movement time
// @Description: Minimum amount of time in seconds to move in yaw
2017-05-02 10:35:51 -03:00
// @Units: s
2014-07-23 05:41:25 -03:00
// @Increment: 0.01
// @Range: 0 2
2014-08-14 17:19:55 -03:00
// @User: Standard
2014-07-23 05:41:25 -03:00
GSCALAR ( onoff_yaw_mintime , " ONOFF_YAW_MINT " , 0.1f ) ,
// @Param: ONOFF_PITCH_MINT
// @DisplayName: Pitch minimum movement time
// @Description: Minimim amount of time in seconds to move in pitch
2017-05-02 10:35:51 -03:00
// @Units: s
2014-07-23 05:41:25 -03:00
// @Increment: 0.01
// @Range: 0 2
2014-08-14 17:19:55 -03:00
// @User: Standard
2014-07-23 05:41:25 -03:00
GSCALAR ( onoff_pitch_mintime , " ONOFF_PITCH_MINT " , 0.1f ) ,
2014-08-03 05:16:37 -03:00
// @Param: YAW_TRIM
// @DisplayName: Yaw trim
// @Description: Amount of extra yaw to add when tracking. This allows for small adjustments for an out of trim compass.
2017-05-02 10:35:51 -03:00
// @Units: deg
2014-08-03 05:16:37 -03:00
// @Increment: 0.1
// @Range: -10 10
2014-08-14 17:19:55 -03:00
// @User: Standard
2014-08-03 05:16:37 -03:00
GSCALAR ( yaw_trim , " YAW_TRIM " , 0 ) ,
// @Param: PITCH_TRIM
// @DisplayName: Pitch trim
// @Description: Amount of extra pitch to add when tracking. This allows for small adjustments for a badly calibrated barometer.
2017-05-02 10:35:51 -03:00
// @Units: deg
2014-08-03 05:16:37 -03:00
// @Increment: 0.1
// @Range: -10 10
2014-08-14 17:19:55 -03:00
// @User: Standard
2014-08-03 05:16:37 -03:00
GSCALAR ( pitch_trim , " PITCH_TRIM " , 0 ) ,
2014-10-06 02:51:53 -03:00
// @Param: YAW_RANGE
// @DisplayName: Yaw Angle Range
// @Description: Yaw axis total range of motion in degrees
2017-05-02 10:35:51 -03:00
// @Units: deg
2014-10-06 02:51:53 -03:00
// @Increment: 0.1
// @Range: 0 360
// @User: Standard
GSCALAR ( yaw_range , " YAW_RANGE " , YAW_RANGE_DEFAULT ) ,
2015-04-26 23:24:47 -03:00
// @Param: DISTANCE_MIN
// @DisplayName: Distance minimum to target
// @Description: Tracker will track targets at least this distance away
2017-05-02 10:35:51 -03:00
// @Units: m
2015-04-26 23:24:47 -03:00
// @Increment: 1
// @Range: 0 100
// @User: Standard
GSCALAR ( distance_min , " DISTANCE_MIN " , DISTANCE_MIN_DEFAULT ) ,
2016-05-24 08:53:57 -03:00
// @Param: ALT_SOURCE
// @DisplayName: Altitude Source
2016-07-06 04:49:52 -03:00
// @Description: What provides altitude information for vehicle. Vehicle only assumes tracker has same altitude as vehicle's home
// @Values: 0:Barometer,1:GPS,2:GPS vehicle only
2016-05-24 08:53:57 -03:00
// @User: Standard
GSCALAR ( alt_source , " ALT_SOURCE " , 0 ) ,
2016-06-12 22:44:56 -03:00
// @Param: MAV_UPDATE_RATE
// @DisplayName: Mavlink Update Rate
// @Description: The rate at which Mavlink updates position and baro data
2016-06-15 06:23:48 -03:00
// @Units: Hz
2016-06-12 22:44:56 -03:00
// @Increment: 1
// @Range: 1 10
// @User: Standard
GSCALAR ( mavlink_update_rate , " MAV_UPDATE_RATE " , 1 ) ,
2016-07-01 00:40:01 -03:00
// @Param: PITCH_MIN
// @DisplayName: Minimum Pitch Angle
// @Description: The lowest angle the pitch can reach
2017-05-02 10:35:51 -03:00
// @Units: deg
2016-07-01 00:40:01 -03:00
// @Increment: 1
2016-07-27 23:20:41 -03:00
// @Range: -90 0
2016-07-01 00:40:01 -03:00
// @User: Standard
GSCALAR ( pitch_min , " PITCH_MIN " , PITCH_MIN_DEFAULT ) ,
// @Param: PITCH_MAX
// @DisplayName: Maximum Pitch Angle
// @Description: The highest angle the pitch can reach
2017-05-02 10:35:51 -03:00
// @Units: deg
2016-07-01 00:40:01 -03:00
// @Increment: 1
// @Range: 0 90
// @User: Standard
GSCALAR ( pitch_max , " PITCH_MAX " , PITCH_MAX_DEFAULT ) ,
2020-12-03 04:13:33 -04:00
// barometer library
// @Group: BARO
2013-10-13 04:14:13 -03:00
// @Path: ../libraries/AP_Baro/AP_Baro.cpp
2020-12-03 04:13:33 -04:00
GOBJECT ( barometer , " BARO " , AP_Baro ) ,
2013-10-13 04:14:13 -03:00
2021-12-04 00:22:56 -04:00
// @Group: COMPASS_
2016-03-15 11:16:23 -03:00
// @Path: ../libraries/AP_Compass/AP_Compass.cpp
2021-12-04 00:22:56 -04:00
GOBJECT ( compass , " COMPASS_ " , Compass ) ,
2013-10-13 04:14:13 -03:00
// @Group: SCHED_
// @Path: ../libraries/AP_Scheduler/AP_Scheduler.cpp
GOBJECT ( scheduler , " SCHED_ " , AP_Scheduler ) ,
// @Group: SR0_
2015-06-15 20:59:27 -03:00
// @Path: GCS_Mavlink.cpp
2019-06-19 08:13:57 -03:00
GOBJECTN ( _gcs . chan_parameters [ 0 ] , gcs0 , " SR0_ " , GCS_MAVLINK_Parameters ) ,
2014-03-05 02:38:22 -04:00
2020-12-22 15:43:29 -04:00
# if MAVLINK_COMM_NUM_BUFFERS >= 2
2014-03-05 02:38:22 -04:00
// @Group: SR1_
2015-06-15 20:59:27 -03:00
// @Path: GCS_Mavlink.cpp
2019-06-19 08:13:57 -03:00
GOBJECTN ( _gcs . chan_parameters [ 1 ] , gcs1 , " SR1_ " , GCS_MAVLINK_Parameters ) ,
2020-12-22 15:43:29 -04:00
# endif
2013-10-13 04:14:13 -03:00
2020-12-22 15:43:29 -04:00
# if MAVLINK_COMM_NUM_BUFFERS >= 3
2014-03-05 02:38:22 -04:00
// @Group: SR2_
2015-06-15 20:59:27 -03:00
// @Path: GCS_Mavlink.cpp
2019-06-19 08:13:57 -03:00
GOBJECTN ( _gcs . chan_parameters [ 2 ] , gcs2 , " SR2_ " , GCS_MAVLINK_Parameters ) ,
2020-12-22 15:43:29 -04:00
# endif
2013-10-13 04:14:13 -03:00
2020-12-22 15:43:29 -04:00
# if MAVLINK_COMM_NUM_BUFFERS >= 4
2015-05-02 09:38:58 -03:00
// @Group: SR3_
2015-06-15 20:59:27 -03:00
// @Path: GCS_Mavlink.cpp
2019-06-19 08:13:57 -03:00
GOBJECTN ( _gcs . chan_parameters [ 3 ] , gcs3 , " SR3_ " , GCS_MAVLINK_Parameters ) ,
2020-12-22 15:43:29 -04:00
# 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
2015-05-02 09:38:58 -03:00
2015-12-27 03:05:14 -04:00
// @Param: LOG_BITMASK
// @DisplayName: Log bitmask
// @Description: 4 byte bitmap of log types to enable
2018-01-16 16:06:27 -04:00
// @Bitmask: 0:ATTITUDE,1:GPS,2:RCIN,3:IMU,4:RCOUT,5:COMPASS,6:Battery
2015-12-27 03:05:14 -04:00
// @User: Standard
GSCALAR ( log_bitmask , " LOG_BITMASK " , DEFAULT_LOG_BITMASK ) ,
2013-10-13 04:14:13 -03:00
// @Group: INS_
// @Path: ../libraries/AP_InertialSensor/AP_InertialSensor.cpp
GOBJECT ( ins , " INS_ " , AP_InertialSensor ) ,
// @Group: AHRS_
// @Path: ../libraries/AP_AHRS/AP_AHRS.cpp
GOBJECT ( ahrs , " AHRS_ " , AP_AHRS ) ,
2021-10-29 21:37:05 -03:00
# if AP_SIM_ENABLED
2013-10-13 04:14:13 -03:00
// @Group: SIM_
// @Path: ../libraries/SITL/SITL.cpp
2021-07-30 07:08:31 -03:00
GOBJECT ( sitl , " SIM_ " , SITL : : SIM ) ,
2013-10-13 04:14:13 -03:00
# endif
2014-03-26 18:06:50 -03:00
// @Group: BRD_
// @Path: ../libraries/AP_BoardConfig/AP_BoardConfig.cpp
GOBJECT ( BoardConfig , " BRD_ " , AP_BoardConfig ) ,
2020-05-31 08:46:53 -03:00
# if HAL_MAX_CAN_PROTOCOL_DRIVERS
2017-05-06 06:11:29 -03:00
// @Group: CAN_
2020-05-31 08:46:53 -03:00
// @Path: ../libraries/AP_CANManager/AP_CANManager.cpp
GOBJECT ( can_mgr , " CAN_ " , AP_CANManager ) ,
2017-05-06 06:11:29 -03:00
# endif
2014-03-31 16:18:07 -03:00
// GPS driver
2020-12-30 11:00:40 -04:00
// @Group: GPS
2014-03-31 16:18:07 -03:00
// @Path: ../libraries/AP_GPS/AP_GPS.cpp
2020-12-30 11:00:40 -04:00
GOBJECT ( gps , " GPS " , AP_GPS ) ,
2014-03-31 16:18:07 -03:00
2015-12-30 22:10:13 -04:00
// @Group: NTF_
// @Path: ../libraries/AP_Notify/AP_Notify.cpp
GOBJECT ( notify , " NTF_ " , AP_Notify ) ,
2020-02-18 20:16:38 -04:00
// @Group: RC
// @Path: ../libraries/RC_Channel/RC_Channels_VarInfo.h
2018-04-26 23:27:00 -03:00
GOBJECT ( rc_channels , " RC " , RC_Channels_Tracker ) ,
2013-10-13 04:14:13 -03:00
2020-02-18 20:16:38 -04:00
// @Group: SERVO
2017-02-05 22:16:00 -04:00
// @Path: ../libraries/SRV_Channel/SRV_Channels.cpp
2017-01-06 22:51:56 -04:00
GOBJECT ( servo_channels , " SERVO " , SRV_Channels ) ,
2015-01-28 01:27:03 -04:00
// @Group: SERIAL
// @Path: ../libraries/AP_SerialManager/AP_SerialManager.cpp
GOBJECT ( serial_manager , " SERIAL " , AP_SerialManager ) ,
2016-02-08 07:40:31 -04:00
// @Param: PITCH2SRV_P
// @DisplayName: Pitch axis controller P gain
// @Description: Pitch axis controller P gain. Converts the difference between desired pitch angle and actual pitch angle into a pitch servo pwm change
// @Range: 0.0 3.0
// @Increment: 0.01
// @User: Standard
// @Param: PITCH2SRV_I
// @DisplayName: Pitch axis controller I gain
// @Description: Pitch axis controller I gain. Corrects long-term difference in desired pitch angle vs actual pitch angle
// @Range: 0.0 3.0
// @Increment: 0.01
// @User: Standard
// @Param: PITCH2SRV_IMAX
// @DisplayName: Pitch axis controller I gain maximum
// @Description: Pitch axis controller I gain maximum. Constrains the maximum pwm change that the I gain will output
// @Range: 0 4000
// @Increment: 10
2017-05-02 10:35:51 -03:00
// @Units: d%
2016-02-08 07:40:31 -04:00
// @User: Standard
// @Param: PITCH2SRV_D
// @DisplayName: Pitch axis controller D gain
// @Description: Pitch axis controller D gain. Compensates for short-term change in desired pitch angle vs actual pitch angle
// @Range: 0.001 0.1
// @Increment: 0.001
2020-02-18 20:16:38 -04:00
// @User: Standard
// @Param: PITCH2SRV_FF
// @DisplayName: Pitch axis controller feed forward
// @Description: Pitch axis controller feed forward
// @Range: 0 0.5
// @Increment: 0.001
// @User: Standard
// @Param: PITCH2SRV_FLTT
// @DisplayName: Pitch axis controller target frequency in Hz
// @Description: Pitch axis controller target frequency in Hz
// @Range: 1 50
// @Increment: 1
// @Units: Hz
// @User: Standard
// @Param: PITCH2SRV_FLTE
// @DisplayName: Pitch axis controller error frequency in Hz
// @Description: Pitch axis controller error frequency in Hz
// @Range: 1 100
// @Increment: 1
// @Units: Hz
// @User: Standard
// @Param: PITCH2SRV_FLTD
// @DisplayName: Pitch axis controller derivative frequency in Hz
// @Description: Pitch axis controller derivative frequency in Hz
// @Range: 1 100
// @Increment: 1
// @Units: Hz
2016-02-08 07:40:31 -04:00
// @User: Standard
2020-09-24 04:26:05 -03:00
// @Param: PITCH2SRV_SMAX
// @DisplayName: Pitch slew rate limit
// @Description: Sets an upper limit on the slew rate produced by the combined P and D gains. If the amplitude of the control action produced by the rate feedback exceeds this value, then the D+P gain is reduced to respect the limit. This limits the amplitude of high frequency oscillations caused by an excessive gain. The limit should be set to no more than 25% of the actuators maximum slew rate to allow for load effects. Note: The gain will not be reduced to less than 10% of the nominal value. A value of zero will disable this feature.
// @Range: 0 200
// @Increment: 0.5
// @User: Advanced
GGROUP ( pidPitch2Srv , " PITCH2SRV_ " , AC_PID ) ,
2016-02-08 07:40:31 -04:00
// @Param: YAW2SRV_P
// @DisplayName: Yaw axis controller P gain
// @Description: Yaw axis controller P gain. Converts the difference between desired yaw angle (heading) and actual yaw angle into a yaw servo pwm change
// @Range: 0.0 3.0
// @Increment: 0.01
// @User: Standard
// @Param: YAW2SRV_I
// @DisplayName: Yaw axis controller I gain
// @Description: Yaw axis controller I gain. Corrects long-term difference in desired yaw angle (heading) vs actual yaw angle
// @Range: 0.0 3.0
// @Increment: 0.01
// @User: Standard
// @Param: YAW2SRV_IMAX
// @DisplayName: Yaw axis controller I gain maximum
// @Description: Yaw axis controller I gain maximum. Constrains the maximum pwm change that the I gain will output
// @Range: 0 4000
// @Increment: 10
2017-05-02 10:35:51 -03:00
// @Units: d%
2016-02-08 07:40:31 -04:00
// @User: Standard
// @Param: YAW2SRV_D
// @DisplayName: Yaw axis controller D gain
// @Description: Yaw axis controller D gain. Compensates for short-term change in desired yaw angle (heading) vs actual yaw angle
// @Range: 0.001 0.1
// @Increment: 0.001
2020-02-18 20:16:38 -04:00
// @User: Standard
// @Param: YAW2SRV_FF
// @DisplayName: Yaw axis controller feed forward
// @Description: Yaw axis controller feed forward
// @Range: 0 0.5
// @Increment: 0.001
// @User: Standard
// @Param: YAW2SRV_FLTT
// @DisplayName: Yaw axis controller target frequency in Hz
// @Description: Yaw axis controller target frequency in Hz
// @Range: 1 50
// @Increment: 1
// @Units: Hz
// @User: Standard
// @Param: YAW2SRV_FLTE
// @DisplayName: Yaw axis controller error frequency in Hz
// @Description: Yaw axis controller error frequency in Hz
// @Range: 1 100
// @Increment: 1
// @Units: Hz
// @User: Standard
// @Param: YAW2SRV_FLTD
// @DisplayName: Yaw axis controller derivative frequency in Hz
// @Description: Yaw axis controller derivative frequency in Hz
// @Range: 1 100
// @Increment: 1
// @Units: Hz
2016-02-08 07:40:31 -04:00
// @User: Standard
2020-09-24 04:26:05 -03:00
// @Param: YAW2SRV_SMAX
// @DisplayName: Yaw slew rate limit
// @Description: Sets an upper limit on the slew rate produced by the combined P and D gains. If the amplitude of the control action produced by the rate feedback exceeds this value, then the D+P gain is reduced to respect the limit. This limits the amplitude of high frequency oscillations caused by an excessive gain. The limit should be set to no more than 25% of the actuators maximum slew rate to allow for load effects. Note: The gain will not be reduced to less than 10% of the nominal value. A value of zero will disable this feature.
// @Range: 0 200
// @Increment: 0.5
// @User: Advanced
GGROUP ( pidYaw2Srv , " YAW2SRV_ " , AC_PID ) ,
2013-10-13 04:14:13 -03:00
2021-11-15 01:08:32 -04:00
# if AP_SCRIPTING_ENABLED
2019-06-17 19:28:09 -03:00
// @Group: SCR_
// @Path: ../libraries/AP_Scripting/AP_Scripting.cpp
2019-03-01 02:40:18 -04:00
GOBJECT ( scripting , " SCR_ " , AP_Scripting ) ,
# endif
2014-03-02 03:00:37 -04:00
// @Param: CMD_TOTAL
// @DisplayName: Number of loaded mission items
// @Description: Set to 1 if HOME location has been loaded by the ground station. Do not change this manually.
// @Range: 1 255
// @User: Advanced
GSCALAR ( command_total , " CMD_TOTAL " , 0 ) ,
2018-01-16 16:06:27 -04:00
// @Group: BATT
// @Path: ../libraries/AP_BattMonitor/AP_BattMonitor.cpp
GOBJECT ( battery , " BATT " , AP_BattMonitor ) ,
2014-03-02 03:00:37 -04:00
2019-02-28 17:38:28 -04:00
// @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:Pitch,2:Yaw
// @Bitmask: 0:Pitch,1:Yaw
GSCALAR ( gcs_pid_mask , " GCS_PID_MASK " , 0 ) ,
2019-03-10 07:53:28 -03:00
// @Param: SCAN_SPEED_YAW
// @DisplayName: Speed at which to rotate the yaw axis in scan mode
// @Description: This controls how rapidly the tracker will move the servos in SCAN mode
// @Units: deg/s
// @Increment: 1
// @Range: 0 100
// @User: Standard
GSCALAR ( scan_speed_yaw , " SCAN_SPEED_YAW " , 2 ) ,
// @Param: SCAN_SPEED_PIT
// @DisplayName: Speed at which to rotate pitch axis in scan mode
// @Description: This controls how rapidly the tracker will move the servos in SCAN mode
// @Units: deg/s
// @Increment: 1
// @Range: 0 100
// @User: Standard
GSCALAR ( scan_speed_pitch , " SCAN_SPEED_PIT " , 5 ) ,
2019-03-10 07:54:17 -03:00
// @Param: INITIAL_MODE
// @DisplayName: Mode tracker will switch into after initialization
// @Description: 0:MANUAL, 1:STOP, 2:SCAN, 10:AUTO
// @User: Standard
GSCALAR ( initial_mode , " INITIAL_MODE " , 10 ) ,
2019-06-13 14:16:29 -03:00
// @Param: SAFE_DISARM_PWM
// @DisplayName: PWM that will be output when disarmed or in stop mode
// @Description: 0:zero pwm, 1:trim pwm
// @User: Standard
GSCALAR ( disarm_pwm , " SAFE_DISARM_PWM " , 0 ) ,
2020-02-18 20:16:38 -04:00
// @Group: STAT
2019-08-06 04:09:08 -03:00
// @Path: ../libraries/AP_Stats/AP_Stats.cpp
GOBJECT ( stats , " STAT " , AP_Stats ) ,
2019-10-21 03:50:19 -03:00
// @Param: AUTO_OPTIONS
// @DisplayName: Auto mode options
// @Description: 1: Scan for unknown target
// @User: Standard
// @Values: 0:None, 1: Scan for unknown target in auto mode
// @Bitmask: 0:Scan for unknown target
GSCALAR ( auto_opts , " AUTO_OPTIONS " , 0 ) ,
2019-12-19 18:59:06 -04:00
// @Group:
// @Path: ../libraries/AP_Vehicle/AP_Vehicle.cpp
{ AP_PARAM_GROUP , " " , Parameters : : k_param_vehicle , ( const void * ) & tracker , { group_info : AP_Vehicle : : var_info } } ,
2020-05-20 08:20:17 -03:00
// @Group: LOG
// @Path: ../libraries/AP_Logger/AP_Logger.cpp
GOBJECT ( logger , " LOG " , AP_Logger ) ,
2013-10-13 04:14:13 -03:00
AP_VAREND
} ;
2015-06-01 02:04:25 -03:00
void Tracker : : load_parameters ( void )
2013-10-13 04:14:13 -03:00
{
if ( ! g . format_version . load ( ) | |
g . format_version ! = Parameters : : k_format_version ) {
// erase all parameters
2017-01-21 00:32:39 -04:00
hal . console - > printf ( " Firmware change: erasing EEPROM... \n " ) ;
2018-12-28 21:05:56 -04:00
StorageManager : : erase ( ) ;
2013-10-13 04:14:13 -03:00
AP_Param : : erase_all ( ) ;
// save the current format version
g . format_version . set_and_save ( Parameters : : k_format_version ) ;
2017-01-21 00:32:39 -04:00
hal . console - > printf ( " done. \n " ) ;
2013-10-13 04:14:13 -03:00
}
2022-07-04 22:56:59 -03:00
g . format_version . set_default ( Parameters : : k_format_version ) ;
2016-01-06 18:32:32 -04:00
uint32_t before = AP_HAL : : micros ( ) ;
// Load all auto-loaded EEPROM variables
AP_Param : : load_all ( ) ;
hal . console - > printf ( " load_all took %luus \n " , ( unsigned long ) ( AP_HAL : : micros ( ) - before ) ) ;
2018-09-05 20:25:23 -03:00
# if HAL_HAVE_SAFETY_SWITCH
// configure safety switch to allow stopping the motors while armed
AP_Param : : set_default_by_name ( " BRD_SAFETYOPTION " , AP_BoardConfig : : BOARD_SAFETY_OPTION_BUTTON_ACTIVE_SAFETY_OFF |
AP_BoardConfig : : BOARD_SAFETY_OPTION_BUTTON_ACTIVE_SAFETY_ON |
AP_BoardConfig : : BOARD_SAFETY_OPTION_BUTTON_ACTIVE_ARMED ) ;
# endif
2013-10-13 04:14:13 -03:00
}