#include <AP_Relay/AP_Relay.h> #include <AP_Math/AP_Math.h> #include <RC_Channel/RC_Channel.h> #include <AP_Notify/AP_Notify.h> #include <AP_HAL/AP_HAL.h> extern const AP_HAL::HAL& hal; const AP_Param::GroupInfo AP_Parachute::var_info[] = { // @Param: ENABLED // @DisplayName: Parachute release enabled or disabled // @Description: Parachute release enabled or disabled // @Values: 0:Disabled,1:Enabled // @User: Standard AP_GROUPINFO("ENABLED", 0, AP_Parachute, _enabled, 0), // @Param: TYPE // @DisplayName: Parachute release mechanism type (relay or servo) // @Description: Parachute release mechanism type (relay or servo) // @Values: 0:First Relay,1:Second Relay,2:Third Relay,3:Fourth Relay,10:Servo // @User: Standard AP_GROUPINFO("TYPE", 1, AP_Parachute, _release_type, AP_PARACHUTE_TRIGGER_TYPE_RELAY_0), // @Param: SERVO_ON // @DisplayName: Parachute Servo ON PWM value // @Description: Parachute Servo PWM value when parachute is released // @Range: 1000 2000 // @Units: pwm // @Increment: 1 // @User: Standard
#include <stdio.h> # define Debug(fmt, args ...) do {printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); hal.scheduler->delay(1); } while(0) #else # define Debug(fmt, args ...) #endif //Debug("%.2f %.2f %.2f %.2f \n", var1, var2, var3, var4); // table of user settable parameters const AP_Param::GroupInfo AP_TECS::var_info[] PROGMEM = { // @Param: CLMB_MAX // @DisplayName: Maximum Climb Rate (metres/sec) // @Description: This is the best climb rate that the aircraft can achieve with the throttle set to THR_MAX and the airspeed set to the default value. For electric aircraft make sure this number can be achieved towards the end of flight when the battery voltage has reduced. The setting of this parameter can be checked by commanding a positive altitude change of 100m in loiter, RTL or guided mode. If the throttle required to climb is close to THR_MAX and the aircraft is maintaining airspeed, then this parameter is set correctly. If the airspeed starts to reduce, then the parameter is set to high, and if the throttle demand require to climb and maintain speed is noticeably less than THR_MAX, then either CLMB_MAX should be increased or THR_MAX reduced. // @Increment: 0.1 // @User: User AP_GROUPINFO("CLMB_MAX", 0, AP_TECS, _maxClimbRate, 5.0f), // @Param: SINK_MIN // @DisplayName: Minimum Sink Rate (metres/sec) // @Description: This is the sink rate of the aircraft with the throttle set to THR_MIN and the same airspeed as used to measure CLMB_MAX. // @Increment: 0.1 // @User: User AP_GROUPINFO("SINK_MIN", 1, AP_TECS, _minSinkRate, 2.0f), // @Param: TIME_CONST // @DisplayName: Controller time constant (sec) // @Description: This is the time constant of the TECS control algorithm. Smaller values make it faster to respond, large values make it slower to respond. // @Range: 3.0-10.0 // @Increment: 0.2 // @User: Advanced AP_GROUPINFO("TIME_CONST", 2, AP_TECS, _timeConst, 5.0f),
# define MNT_MOUNT2_OPTION DISABLED // second mount, can for example be used to keep an antenna pointed at the home position #else # define MNT_JSTICK_SPD_OPTION ENABLED // uses 844 bytes of memory # define MNT_RETRACT_OPTION ENABLED // uses 244 bytes of memory # define MNT_GPSPOINT_OPTION ENABLED // uses 580 bytes of memory # define MNT_STABILIZE_OPTION ENABLED // uses 2424 bytes of memory # define MNT_MOUNT2_OPTION ENABLED // uses 58 bytes of memory (must also be enabled in APM_Config.h) #endif const AP_Param::GroupInfo AP_Mount::var_info[] PROGMEM = { // @Param: MODE // @DisplayName: Mount operation mode // @Description: Camera or antenna mount operation mode // @Values: 0:retract,1:neutral,2:MavLink_targeting,3:RC_targeting,4:GPS_point // @User: Standard AP_GROUPINFO("MODE", 0, AP_Mount, _mount_mode, MAV_MOUNT_MODE_RETRACT), // see MAV_MOUNT_MODE at ardupilotmega.h #if MNT_RETRACT_OPTION == ENABLED // @Param: RETRACT_X // @DisplayName: Mount roll angle when in retracted position // @Description: Mount roll angle when in retracted position // @Units: Centi-Degrees // @Range: -18000 17999 // @Increment: 1 // @User: Standard // @Param: RETRACT_Y // @DisplayName: Mount tilt/pitch angle when in retracted position // @Description: Mount tilt/pitch angle when in retracted position // @Units: Centi-Degrees // @Range: -18000 17999
} return true; } /* default stream rates to 1Hz */ const AP_Param::GroupInfo GCS_MAVLINK::var_info[] = { // @Param: RAW_SENS // @DisplayName: Raw sensor stream rate // @Description: Raw sensor stream rate to ground station // @Units: Hz // @Range: 0 10 // @Increment: 1 // @User: Advanced AP_GROUPINFO("RAW_SENS", 0, GCS_MAVLINK, streamRates[0], 1), // @Param: EXT_STAT // @DisplayName: Extended status stream rate to ground station // @Description: Extended status stream rate to ground station // @Units: Hz // @Range: 0 10 // @Increment: 1 // @User: Advanced AP_GROUPINFO("EXT_STAT", 1, GCS_MAVLINK, streamRates[1], 1), // @Param: RC_CHAN // @DisplayName: RC Channel stream rate to ground station // @Description: RC Channel stream rate to ground station // @Units: Hz // @Range: 0 10
# define Debug(fmt, args ...) do {printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); hal.scheduler->delay(1); } while(0) #else # define Debug(fmt, args ...) #endif //Debug("%.2f %.2f %.2f %.2f \n", var1, var2, var3, var4); // table of user settable parameters const AP_Param::GroupInfo AP_TECS::var_info[] = { // @Param: CLMB_MAX // @DisplayName: Maximum Climb Rate (metres/sec) // @Description: This is the best climb rate that the aircraft can achieve with the throttle set to THR_MAX and the airspeed set to the default value. For electric aircraft make sure this number can be achieved towards the end of flight when the battery voltage has reduced. The setting of this parameter can be checked by commanding a positive altitude change of 100m in loiter, RTL or guided mode. If the throttle required to climb is close to THR_MAX and the aircraft is maintaining airspeed, then this parameter is set correctly. If the airspeed starts to reduce, then the parameter is set to high, and if the throttle demand require to climb and maintain speed is noticeably less than THR_MAX, then either CLMB_MAX should be increased or THR_MAX reduced. // @Increment: 0.1 // @Range: 0.1 20.0 // @User: User AP_GROUPINFO("CLMB_MAX", 0, AP_TECS, _maxClimbRate, 5.0f), // @Param: SINK_MIN // @DisplayName: Minimum Sink Rate (metres/sec) // @Description: This is the sink rate of the aircraft with the throttle set to THR_MIN and the same airspeed as used to measure CLMB_MAX. // @Increment: 0.1 // @Range: 0.1 10.0 // @User: User AP_GROUPINFO("SINK_MIN", 1, AP_TECS, _minSinkRate, 2.0f), // @Param: TIME_CONST // @DisplayName: Controller time constant (sec) // @Description: This is the time constant of the TECS control algorithm. Smaller values make it faster to respond, large values make it slower to respond. // @Range: 3.0 10.0 // @Increment: 0.2 // @User: Advanced
*/ /* SITL.cpp - software in the loop state */ #include <AP_Common.h> #include <AP_HAL.h> #include <GCS_MAVLink.h> #include <SITL.h> extern const AP_HAL::HAL& hal; // table of user settable parameters const AP_Param::GroupInfo SITL::var_info[] PROGMEM = { AP_GROUPINFO("BARO_RND", 0, SITL, baro_noise, 0.2f), AP_GROUPINFO("GYR_RND", 1, SITL, gyro_noise, 0), AP_GROUPINFO("ACC_RND", 2, SITL, accel_noise, 0), AP_GROUPINFO("MAG_RND", 3, SITL, mag_noise, 0), AP_GROUPINFO("GPS_DISABLE",4, SITL, gps_disable, 0), AP_GROUPINFO("DRIFT_SPEED",5, SITL, drift_speed, 0.05f), AP_GROUPINFO("DRIFT_TIME", 6, SITL, drift_time, 5), AP_GROUPINFO("GPS_DELAY", 7, SITL, gps_delay, 1), AP_GROUPINFO("ENGINE_MUL", 8, SITL, engine_mul, 1), AP_GROUPINFO("WIND_SPD", 9, SITL, wind_speed, 0), AP_GROUPINFO("WIND_DIR", 10, SITL, wind_direction, 180), AP_GROUPINFO("WIND_TURB", 11, SITL, wind_turbulance, 0), AP_GROUPINFO("GPS_TYPE", 12, SITL, gps_type, SITL::GPS_TYPE_UBLOX), AP_GROUPINFO("GPS_BYTELOSS", 13, SITL, gps_byteloss, 0), AP_GROUPINFO("GPS_NUMSATS", 14, SITL, gps_numsats, 10), AP_GROUPINFO("MAG_ERROR", 15, SITL, mag_error, 0),
#include <AP_HAL.h> #include <AC_WPNav.h> extern const AP_HAL::HAL& hal; const AP_Param::GroupInfo AC_WPNav::var_info[] PROGMEM = { // index 0 was used for the old orientation matrix // @Param: SPEED // @DisplayName: Waypoint Horizontal Speed Target // @Description: Defines the speed in cm/s which the aircraft will attempt to maintain horizontally during a WP mission // @Units: cm/s // @Range: 0 2000 // @Increment: 50 // @User: Standard AP_GROUPINFO("SPEED", 0, AC_WPNav, _wp_speed_cms, WPNAV_WP_SPEED), // @Param: RADIUS // @DisplayName: Waypoint Radius // @Description: Defines the distance from a waypoint, that when crossed indicates the wp has been hit. // @Units: cm // @Range: 100 1000 // @Increment: 1 // @User: Standard AP_GROUPINFO("RADIUS", 1, AC_WPNav, _wp_radius_cm, WPNAV_WP_RADIUS), // @Param: SPEED_UP // @DisplayName: Waypoint Climb Speed Target // @Description: Defines the speed in cm/s which the aircraft will attempt to maintain while climbing during a WP mission // @Units: cm/s // @Range: 0 1000
#include <AP_HAL.h> #include "AP_MotorsHeli.h" extern const AP_HAL::HAL& hal; const AP_Param::GroupInfo AP_MotorsHeli::var_info[] PROGMEM = { // @Param: SV1_POS // @DisplayName: Servo 1 Position // @Description: This is the angular location of swash servo #1. // @Range: -180 180 // @Units: Degrees // @User: Standard // @Increment: 1 AP_GROUPINFO("SV1_POS", 1, AP_MotorsHeli, servo1_pos, -60), // @Param: SV2_POS // @DisplayName: Servo 2 Position // @Description: This is the angular location of swash servo #2. // @Range: -180 180 // @Units: Degrees // @User: Standard // @Increment: 1 AP_GROUPINFO("SV2_POS", 2, AP_MotorsHeli, servo2_pos, 60), // @Param: SV3_POS // @DisplayName: Servo 3 Position // @Description: This is the angular location of swash servo #3. // @Range: -180 180 // @Units: Degrees
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #include <AP_HAL/AP_HAL.h> #include "AP_L1_Control.h" extern const AP_HAL::HAL& hal; // table of user settable parameters const AP_Param::GroupInfo AP_L1_Control::var_info[] = { // @Param: PERIOD // @DisplayName: L1 control period // @Description: Period in seconds of L1 tracking loop. This parameter is the primary control for agressiveness of turns in auto mode. This needs to be larger for less responsive airframes. The default of 20 is quite conservative, but for most RC aircraft will lead to reasonable flight. For smaller more agile aircraft a value closer to 15 is appropriate, or even as low as 10 for some very agile aircraft. When tuning, change this value in small increments, as a value that is much too small (say 5 or 10 below the right value) can lead to very radical turns, and a risk of stalling. // @Units: seconds // @Range: 1 60 // @Increment: 1 AP_GROUPINFO("PERIOD", 0, AP_L1_Control, _L1_period, 20), // @Param: DAMPING // @DisplayName: L1 control damping ratio // @Description: Damping ratio for L1 control. Increase this in increments of 0.05 if you are getting overshoot in path tracking. You should not need a value below 0.7 or above 0.85. // @Range: 0.6 1.0 // @Increment: 0.05 AP_GROUPINFO("DAMPING", 1, AP_L1_Control, _L1_damping, 0.75f), // @Param: XTRACK_I // @DisplayName: L1 control crosstrack integrator gain // @Description: Crosstrack error integrator gain. This gain is applied to the crosstrack error to ensure it converges to zero. Set to zero to disable. Smaller values converge slower, higher values will cause crosstrack error oscillation. // @Range: 0 0.1 // @Increment: 0.01 AP_GROUPINFO("XTRACK_I", 2, AP_L1_Control, _L1_xtrack_i_gain, 0.02),
extern const AP_HAL::HAL& hal; // table of user settable parameters const AP_Param::GroupInfo AP_Baro::var_info[] = { // NOTE: Index numbers 0 and 1 were for the old integer // ground temperature and pressure // @Param: ABS_PRESS // @DisplayName: Absolute Pressure // @Description: calibrated ground pressure in Pascals // @Units: Pa // @Increment: 1 // @ReadOnly: True // @Volatile: True // @User: Advanced AP_GROUPINFO("ABS_PRESS", 2, AP_Baro, sensors[0].ground_pressure, 0), // @Param: TEMP // @DisplayName: ground temperature // @Description: User provided ambient ground temperature in degrees Celsius. This is used to improve the calculation of the altitude the vehicle is at. This parameter is not persistent and will be reset to 0 every time the vehicle is rebooted. A value of 0 means use the internal measurement ambient temperature. // @Units: degC // @Increment: 1 // @Volatile: True // @User: Advanced AP_GROUPINFO("TEMP", 3, AP_Baro, _user_ground_temperature, 0), // index 4 reserved for old AP_Int8 version in legacy FRAM //AP_GROUPINFO("ALT_OFFSET", 4, AP_Baro, _alt_offset, 0), // @Param: ALT_OFFSET // @DisplayName: altitude offset
#include <systemlib/airspeed.h> #include <drivers/drv_airspeed.h> #include <uORB/topics/differential_pressure.h> #define ARSPD_DEFAULT_PIN 11 #else #define ARSPD_DEFAULT_PIN 0 #endif // table of user settable parameters const AP_Param::GroupInfo AP_Airspeed::var_info[] PROGMEM = { // @Param: ENABLE // @DisplayName: Airspeed enable // @Description: enable airspeed sensor // @Values: 0:Disable,1:Enable AP_GROUPINFO("ENABLE", 0, AP_Airspeed, _enable, 1), // @Param: USE // @DisplayName: Airspeed use // @Description: use airspeed for flight control // @Values: 1:Use,0:Don't Use AP_GROUPINFO("USE", 1, AP_Airspeed, _use, 0), // @Param: OFFSET // @DisplayName: Airspeed offset // @Description: Airspeed calibration offset // @Increment: 0.1 AP_GROUPINFO("OFFSET", 2, AP_Airspeed, _offset, 0), // @Param: RATIO // @DisplayName: Airspeed ratio
#include <AP_Common.h> #include <AP_Math.h> #include <AP_HAL.h> #include <AP_Notify.h> #include <AP_GPS.h> extern const AP_HAL::HAL& hal; // table of user settable parameters const AP_Param::GroupInfo AP_GPS::var_info[] PROGMEM = { // @Param: TYPE // @DisplayName: GPS type // @Description: GPS type // @Values: 0:None,1:AUTO,2:uBlox,3:MTK,4:MTK19,5:NMEA,6:SiRF,7:HIL,8:SwiftNav,9:PX4EXPERIMENTAL AP_GROUPINFO("TYPE", 0, AP_GPS, _type[0], 1), #if GPS_MAX_INSTANCES > 1 // @Param: TYPE2 // @DisplayName: 2nd GPS type // @Description: GPS type of 2nd GPS // @Values: 0:None,1:AUTO,2:uBlox,3:MTK,4:MTK19,5:NMEA,6:SiRF,7:HIL,8:SwiftNav,9:PX4EXPERIMENTAL AP_GROUPINFO("TYPE2", 1, AP_GPS, _type[1], 0), #endif // @Param: NAVFILTER // @DisplayName: Navigation filter setting // @Description: Navigation filter engine setting // @Values: 0:Portable,2:Stationary,3:Pedestrian,4:Automotive,5:Sea,6:Airborne1G,7:Airborne2G,8:Airborne4G
#if AVOIDANCE_DEBUGGING #include <stdio.h> #define debug(fmt, args ...) do {::fprintf(stderr,"%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); } while(0) #else #define debug(fmt, args ...) #endif // table of user settable parameters const AP_Param::GroupInfo AP_Avoidance::var_info[] = { // @Param: ENABLE // @DisplayName: Enable Avoidance using ADSB // @Description: Enable Avoidance using ADSB // @Values: 0:Disabled,1:Enabled // @User: Advanced AP_GROUPINFO("ENABLE", 1, AP_Avoidance, _enabled, 0), // @Param: F_ACTION // @DisplayName: Collision Avoidance Behavior // @Description: Specifies aircraft behaviour when a collision is imminent // The following values should come from the mavlink COLLISION_ACTION enum // @Values: 0:None,1:Report,2:Climb Or Descend,3:Move Horizontally,4:Move Perpendicularly in 3D,5:RTL,6:Hover // @User: Advanced AP_GROUPINFO("F_ACTION", 2, AP_Avoidance, _fail_action, MAV_COLLISION_ACTION_REPORT), // @Param: W_ACTION // @DisplayName: Collision Avoidance Behavior - Warn // @Description: Specifies aircraft behaviour when a collision may occur // The following values should come from the mavlink COLLISION_ACTION enum // @Values: 0:None,1:Report // @User: Advanced
#include <AP_HAL/AP_HAL.h> #include <AP_Math/AP_Math.h> // table of user settable parameters const AP_Param::GroupInfo AC_AttitudeControl::var_info[] PROGMEM = { // 0, 1 were RATE_RP_MAX, RATE_Y_MAX // @Param: SLEW_YAW // @DisplayName: Yaw target slew rate // @Description: Maximum rate the yaw target can be updated in Loiter, RTL, Auto flight modes // @Units: Centi-Degrees/Sec // @Range: 500 18000 // @Increment: 100 // @User: Advanced AP_GROUPINFO("SLEW_YAW", 2, AC_AttitudeControl, _slew_yaw, AC_ATTITUDE_CONTROL_SLEW_YAW_DEFAULT), // 3 was for ACCEL_RP_MAX // @Param: ACCEL_Y_MAX // @DisplayName: Acceleration Max for Yaw // @Description: Maximum acceleration in yaw axis // @Units: Centi-Degrees/Sec/Sec // @Range: 0 72000 // @Values: 0:Disabled, 18000:Slow, 36000:Medium, 54000:Fast // @Increment: 1000 // @User: Advanced AP_GROUPINFO("ACCEL_Y_MAX", 4, AC_AttitudeControl, _accel_yaw_max, AC_ATTITUDE_CONTROL_ACCEL_Y_MAX_DEFAULT), // @Param: RATE_FF_ENAB // @DisplayName: Rate Feedforward Enable
const AP_Param::GroupInfo AC_Sprayer::var_info[] = { // @Param: ENABLE // @DisplayName: Sprayer enable/disable // @Description: Allows you to enable (1) or disable (0) the sprayer // @Values: 0:Disabled,1:Enabled // @User: Standard AP_GROUPINFO_FLAGS("ENABLE", 0, AC_Sprayer, _enabled, 0, AP_PARAM_FLAG_ENABLE), // @Param: PUMP_RATE // @DisplayName: Pump speed // @Description: Desired pump speed when traveling 1m/s expressed as a percentage // @Units: percentage // @Range: 0 100 // @User: Standard AP_GROUPINFO("PUMP_RATE", 1, AC_Sprayer, _pump_pct_1ms, AC_SPRAYER_DEFAULT_PUMP_RATE), // @Param: SPINNER // @DisplayName: Spinner rotation speed // @Description: Spinner's rotation speed in PWM (a higher rate will disperse the spray over a wider area horizontally) // @Units: ms // @Range: 1000 2000 // @User: Standard AP_GROUPINFO("SPINNER", 2, AC_Sprayer, _spinner_pwm, AC_SPRAYER_DEFAULT_SPINNER_PWM), // @Param: SPEED_MIN // @DisplayName: Speed minimum // @Description: Speed minimum at which we will begin spraying // @Units: cm/s // @Range: 0 1000 // @User: Standard
#include "AP_Beacon_Backend.h" #include "AP_Beacon_Pozyx.h" #include "AP_Beacon_Marvelmind.h" #include "AP_Beacon_SITL.h" extern const AP_HAL::HAL &hal; // table of user settable parameters const AP_Param::GroupInfo AP_Beacon::var_info[] = { // @Param: _TYPE // @DisplayName: Beacon based position estimation device type // @Description: What type of beacon based position estimation device is connected // @Values: 0:None,1:Pozyx,2:Marvelmind // @User: Advanced AP_GROUPINFO("_TYPE", 0, AP_Beacon, _type, 0), // @Param: _LATITUDE // @DisplayName: Beacon origin's latitude // @Description: Beacon origin's latitude // @Units: deg // @Increment: 0.000001 // @Range: -90 90 // @User: Advanced AP_GROUPINFO("_LATITUDE", 1, AP_Beacon, origin_lat, 0), // @Param: _LONGITUDE // @DisplayName: Beacon origin's longitude // @Description: Beacon origin's longitude // @Units: deg // @Increment: 0.000001
#include <AP_Math.h> #include <AP_HAL.h> #include "AP_RollController.h" extern const AP_HAL::HAL& hal; const AP_Param::GroupInfo AP_RollController::var_info[] PROGMEM = { // @Param: TCONST // @DisplayName: Roll Time Constant // @Description: This controls the time constant in seconds from demanded to achieved bank angle. A value of 0.5 is a good default and will work with nearly all models. Advanced users may want to reduce this time to obtain a faster response but there is no point setting a time less than the aircraft can achieve. // @Range: 0.4 1.0 // @Units: seconds // @Increment: 0.1 // @User: Advanced AP_GROUPINFO("TCONST", 0, AP_RollController, gains.tau, 0.5f), // @Param: P // @DisplayName: Proportional Gain // @Description: This is the gain from bank angle to aileron. This gain works the same way as the P term in the old PID (RLL2SRV_P) and can be set to the same value. // @Range: 0.1 4.0 // @Increment: 0.1 // @User: User AP_GROUPINFO("P", 1, AP_RollController, gains.P, 0.4f), // @Param: D // @DisplayName: Damping Gain // @Description: This is the gain from roll rate to aileron. This adjusts the damping of the roll control loop. It has the same effect as RLL2SRV_D in the old PID controller but without the spikes in servo demands. This gain helps to reduce rolling in turbulence. It should be increased in 0.01 increments as too high a value can lead to a high frequency roll oscillation that could overstress the airframe. // @Range: 0 0.1 // @Increment: 0.01 // @User: User
// Modified by Paul Riseborough to implement a three loop autopilot // topology // #include <AP_HAL/AP_HAL.h> #include "AP_YawController.h" extern const AP_HAL::HAL& hal; const AP_Param::GroupInfo AP_YawController::var_info[] PROGMEM = { // @Param: SLIP // @DisplayName: Sideslip control gain // @Description: This is the gain from measured lateral acceleration to demanded yaw rate. It should be set to zero unless active control of sideslip is desired. This will only work effectively if there is enough fuselage side area to generate a measureable lateral acceleration when the model sideslips. Flying wings and most gliders cannot use this term. This term should only be adjusted after the basic yaw damper gain YAW2SRV_DAMP is tuned and the YAW2SRV_INT integrator gain has been set. Set this gain to zero if only yaw damping is required. // @Range: 0 4 // @Increment: 0.25 AP_GROUPINFO("SLIP", 0, AP_YawController, _K_A, 0), // @Param: INT // @DisplayName: Sideslip control integrator // @Description: This is the integral gain from lateral acceleration error. This gain should only be non-zero if active control over sideslip is desired. If active control over sideslip is required then this can be set to 1.0 as a first try. // @Range: 0 2 // @Increment: 0.25 AP_GROUPINFO("INT", 1, AP_YawController, _K_I, 0), // @Param: DAMP // @DisplayName: Yaw damping // @Description: This is the gain from yaw rate to rudder. It acts as a damper on yaw motion. If a basic yaw damper is required, this gain term can be incremented, whilst leaving the YAW2SRV_SLIP and YAW2SRV_INT gains at zero. Note that unlike with a standard PID controller, if this damping term is zero then the integrator will also be disabled. // @Range: 0 2 // @Increment: 0.25 AP_GROUPINFO("DAMP", 2, AP_YawController, _K_D, 0),
#include <stdio.h> #include <unistd.h> #include <sys/types.h> #include <sys/stat.h> #include <fcntl.h> #include <errno.h> extern const AP_HAL::HAL& hal; // table of user settable parameters const AP_Param::GroupInfo AP_Terrain::var_info[] = { // @Param: ENABLE // @DisplayName: Terrain data enable // @Description: enable terrain data. This enables the vehicle storing a database of terrain data on the SD card. The terrain data is requested from the ground station as needed, and stored for later use on the SD card. To be useful the ground station must support TERRAIN_REQUEST messages and have access to a terrain database, such as the SRTM database. // @Values: 0:Disable,1:Enable AP_GROUPINFO("ENABLE", 0, AP_Terrain, enable, 1), // @Param: SPACING // @DisplayName: Terrain grid spacing // @Description: Distance between terrain grid points in meters. This controls the horizontal resolution of the terrain data that is stored on te SD card and requested from the ground station. If your GCS is using the worldwide SRTM database then a resolution of 100 meters is appropriate. Some parts of the world may have higher resolution data available, such as 30 meter data available in the SRTM database in the USA. The grid spacing also controls how much data is kept in memory during flight. A larger grid spacing will allow for a larger amount of data in memory. A grid spacing of 100 meters results in the vehicle keeping 12 grid squares in memory with each grid square having a size of 2.7 kilometers by 3.2 kilometers. Any additional grid squares are stored on the SD once they are fetched from the GCS and will be demand loaded as needed. // @Units: meters // @Increment: 1 AP_GROUPINFO("SPACING", 1, AP_Terrain, grid_spacing, 100), AP_GROUPEND }; // constructor AP_Terrain::AP_Terrain(AP_AHRS &_ahrs, const AP_Mission &_mission, const AP_Rally &_rally) : ahrs(_ahrs), mission(_mission),
#include <AP_Common/AP_Common.h> #include <AP_HAL/AP_HAL.h> #include <AP_Math/AP_Math.h> #include <AP_Notify/AP_Notify.h> extern const AP_HAL::HAL &hal; // table of user settable parameters const AP_Param::GroupInfo AP_GPS::var_info[] = { // @Param: TYPE // @DisplayName: GPS type // @Description: GPS type // @Values: 0:None,1:AUTO,2:uBlox,3:MTK,4:MTK19,5:NMEA,6:SiRF,7:HIL,8:SwiftNav,9:PX4-UAVCAN,10:SBF,11:GSOF // @RebootRequired: True AP_GROUPINFO("TYPE", 0, AP_GPS, _type[0], 1), // @Param: TYPE2 // @DisplayName: 2nd GPS type // @Description: GPS type of 2nd GPS // @Values: 0:None,1:AUTO,2:uBlox,3:MTK,4:MTK19,5:NMEA,6:SiRF,7:HIL,8:SwiftNav,9:PX4-UAVCAN,10:SBF,11:GSOF // @RebootRequired: True AP_GROUPINFO("TYPE2", 1, AP_GPS, _type[1], 0), // @Param: NAVFILTER // @DisplayName: Navigation filter setting // @Description: Navigation filter engine setting // @Values: 0:Portable,2:Stationary,3:Pedestrian,4:Automotive,5:Sea,6:Airborne1G,7:Airborne2G,8:Airborne4G AP_GROUPINFO("NAVFILTER", 2, AP_GPS, _navfilter, GPS_ENGINE_AIRBORNE_4G), // @Param: AUTO_SWITCH
#include <AP_Progmem.h> #include <AP_Param.h> #include <AP_Mount.h> #include <AP_Mount_Backend.h> #include <AP_Mount_Servo.h> #include <AP_Mount_MAVLink.h> #include <AP_Mount_Alexmos.h> #include <AP_Mount_SToRM32.h> const AP_Param::GroupInfo AP_Mount::var_info[] PROGMEM = { // @Param: _DEFLT_MODE // @DisplayName: Mount default operating mode // @Description: Mount default operating mode on startup and after control is returned from autopilot // @Values: 0:Retracted,1:Neutral,2:MavLink Targeting,3:RC Targeting,4:GPS Point // @User: Standard AP_GROUPINFO("_DEFLT_MODE", 0, AP_Mount, state[0]._default_mode, MAV_MOUNT_MODE_RC_TARGETING), // @Param: _RETRACT_X // @DisplayName: Mount roll angle when in retracted position // @Description: Mount roll angle when in retracted position // @Units: Degrees // @Range: -180.00 179.99 // @Increment: 1 // @User: Standard // @Param: _RETRACT_Y // @DisplayName: Mount tilt/pitch angle when in retracted position // @Description: Mount tilt/pitch angle when in retracted position // @Units: Degrees // @Range: -180.00 179.99 // @Increment: 1
#include "AP_MotorsMulticopter.h" #include <AP_HAL/AP_HAL.h> extern const AP_HAL::HAL& hal; // parameters for the motor class const AP_Param::GroupInfo AP_MotorsMulticopter::var_info[] = { // 0 was used by TB_RATIO // 1,2,3 were used by throttle curve // @Param: SPIN_ARMED // @DisplayName: Motors always spin when armed // @Description: Controls whether motors always spin when armed (must be below THR_MIN) // @Values: 0:Do Not Spin,70:VerySlow,100:Slow,130:Medium,150:Fast // @User: Standard AP_GROUPINFO("SPIN_ARMED", 5, AP_MotorsMulticopter, _spin_when_armed, AP_MOTORS_SPIN_WHEN_ARMED), // @Param: YAW_HEADROOM // @DisplayName: Matrix Yaw Min // @Description: Yaw control is given at least this pwm range // @Range: 0 500 // @Units: pwm // @User: Advanced AP_GROUPINFO("YAW_HEADROOM", 6, AP_MotorsMulticopter, _yaw_headroom, AP_MOTORS_YAW_HEADROOM_DEFAULT), // 7 was THR_LOW_CMP // @Param: THST_EXPO // @DisplayName: Thrust Curve Expo // @Description: Motor thrust curve exponent (from 0 for linear to 1.0 for second order curve) // @Range: 0.25 0.8
#define RALLY_LIMIT_KM_DEFAULT 5.0f #define RALLY_INCLUDE_HOME_DEFAULT 0 #elif APM_BUILD_TYPE(APM_BUILD_APMrover2) #define RALLY_LIMIT_KM_DEFAULT 0.5f #define RALLY_INCLUDE_HOME_DEFAULT 1 #else #define RALLY_LIMIT_KM_DEFAULT 1.0f #define RALLY_INCLUDE_HOME_DEFAULT 0 #endif const AP_Param::GroupInfo AP_Rally::var_info[] = { // @Param: TOTAL // @DisplayName: Rally Total // @Description: Number of rally points currently loaded // @User: Advanced AP_GROUPINFO("TOTAL", 0, AP_Rally, _rally_point_total_count, 0), // @Param: LIMIT_KM // @DisplayName: Rally Limit // @Description: Maximum distance to rally point. If the closest rally point is more than this number of kilometers from the current position and the home location is closer than any of the rally points from the current position then do RTL to home rather than to the closest rally point. This prevents a leftover rally point from a different airfield being used accidentally. If this is set to 0 then the closest rally point is always used. // @User: Advanced // @Units: km // @Increment: 0.1 AP_GROUPINFO("LIMIT_KM", 1, AP_Rally, _rally_limit_km, RALLY_LIMIT_KM_DEFAULT), // @Param: INCL_HOME // @DisplayName: Rally Include Home // @Description: Controls if Home is included as a Rally point (i.e. as a safe landing place) for RTL // @User: Standard // @Values: 0:DoNotIncludeHome,1:IncludeHome AP_GROUPINFO("INCL_HOME", 2, AP_Rally, _rally_incl_home, RALLY_INCLUDE_HOME_DEFAULT),
#include <AP_HAL.h> #include "AP_MotorsHeli.h" extern const AP_HAL::HAL& hal; const AP_Param::GroupInfo AP_MotorsHeli::var_info[] PROGMEM = { // @Param: SV1_POS // @DisplayName: Servo 1 Position // @Description: Angular location of swash servo #1 // @Range: -180 180 // @Units: Degrees // @User: Standard // @Increment: 1 AP_GROUPINFO("SV1_POS", 1, AP_MotorsHeli, _servo1_pos, AP_MOTORS_HELI_SERVO1_POS), // @Param: SV2_POS // @DisplayName: Servo 2 Position // @Description: Angular location of swash servo #2 // @Range: -180 180 // @Units: Degrees // @User: Standard // @Increment: 1 AP_GROUPINFO("SV2_POS", 2, AP_MotorsHeli, _servo2_pos, AP_MOTORS_HELI_SERVO2_POS), // @Param: SV3_POS // @DisplayName: Servo 3 Position // @Description: Angular location of swash servo #3 // @Range: -180 180 // @Units: Degrees
}; /* 2nd group of parameters */ const AP_Param::GroupInfo ParametersG2::var_info[] = { // @Group: STAT // @Path: ../libraries/AP_Stats/AP_Stats.cpp AP_SUBGROUPINFO(stats, "STAT", 1, ParametersG2, AP_Stats), // @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", 2, ParametersG2, sysid_enforce, 0), // @Group: SERVO // @Path: ../libraries/SRV_Channel/SRV_Channels.cpp AP_SUBGROUPINFO(servo_channels, "SERVO", 3, ParametersG2, SRV_Channels), // @Group: RC // @Path: ../libraries/RC_Channel/RC_Channels.cpp AP_SUBGROUPINFO(rc_channels, "RC", 4, ParametersG2, RC_Channels), #if ADVANCED_FAILSAFE == ENABLED // @Group: AFS_ // @Path: ../libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.cpp AP_SUBGROUPINFO(afs, "AFS_", 5, ParametersG2, AP_AdvancedFailsafe), #endif
#include <GCS_MAVLink/GCS.h> #include <AC_Avoidance/AC_Avoid.h> #include <AC_Sprayer/AC_Sprayer.h> #include <AP_Gripper/AP_Gripper.h> #include <AP_LandingGear/AP_LandingGear.h> const AP_Param::GroupInfo RC_Channel::var_info[] = { // @Param: MIN // @DisplayName: RC min PWM // @Description: RC minimum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit. // @Units: PWM // @Range: 800 2200 // @Increment: 1 // @User: Advanced AP_GROUPINFO("MIN", 1, RC_Channel, radio_min, 1100), // @Param: TRIM // @DisplayName: RC trim PWM // @Description: RC trim (neutral) PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit. // @Units: PWM // @Range: 800 2200 // @Increment: 1 // @User: Advanced AP_GROUPINFO("TRIM", 2, RC_Channel, radio_trim, 1500), // @Param: MAX // @DisplayName: RC max PWM // @Description: RC maximum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit. // @Units: PWM // @Range: 800 2200
#define SCHEDULER_DEFAULT_LOOP_RATE 50 #endif #define debug(level, fmt, args...) do { if ((level) <= _debug.get()) { hal.console->printf(fmt, ##args); }} while (0) extern const AP_HAL::HAL& hal; int8_t AP_Scheduler::current_task = -1; const AP_Param::GroupInfo AP_Scheduler::var_info[] = { // @Param: DEBUG // @DisplayName: Scheduler debug level // @Description: Set to non-zero to enable scheduler debug messages. When set to show "Slips" the scheduler will display a message whenever a scheduled task is delayed due to too much CPU load. When set to ShowOverruns the scheduled will display a message whenever a task takes longer than the limit promised in the task table. // @Values: 0:Disabled,2:ShowSlips,3:ShowOverruns // @User: Advanced AP_GROUPINFO("DEBUG", 0, AP_Scheduler, _debug, 0), // @Param: LOOP_RATE // @DisplayName: Scheduling main loop rate // @Description: This controls the rate of the main control loop in Hz. This should only be changed by developers. This only takes effect on restart. Values over 400 are considered highly experimental. // @Values: 50:50Hz,100:100Hz,200:200Hz,250:250Hz,300:300Hz,400:400Hz // @RebootRequired: True // @User: Advanced AP_GROUPINFO("LOOP_RATE", 1, AP_Scheduler, _loop_rate_hz, SCHEDULER_DEFAULT_LOOP_RATE), AP_GROUPEND }; // constructor AP_Scheduler::AP_Scheduler(scheduler_fastloop_fn_t fastloop_fn) : _fastloop_fn(fastloop_fn)
#include <AP_Math.h> #include "AC_PID2.h" // Examples for _filter: // f_cut = 10 Hz -> _filter = 15.9155e-3 // f_cut = 15 Hz -> _filter = 10.6103e-3 // f_cut = 20 Hz -> _filter = 7.9577e-3 // f_cut = 25 Hz -> _filter = 6.3662e-3 // f_cut = 30 Hz -> _filter = 5.3052e-3 const float AC_PID2::_filter = 7.9577e-3; // Set to "1 / ( 2 * PI * f_cut )"; const AP_Param::GroupInfo AC_PID2::var_info[] PROGMEM = { // @Param: P // @DisplayName: PID2 Proportional Gain // @Description: P Gain which produces an output value that is proportional to the current error value AP_GROUPINFO("P", 0, AC_PID2, _kp, 0), // @Param: I // @DisplayName: PID2 Integral Gain // @Description: I Gain which produces an output that is proportional to both the magnitude and the duration of the error AP_GROUPINFO("I", 1, AC_PID2, _ki, 0), // @Param: D // @DisplayName: PID2 Derivative Gain // @Description: D Gain which produces an output that is proportional to the rate of change of the error AP_GROUPINFO("D", 2, AC_PID2, _kd, 0), // @Param: IMAX // @DisplayName: PID2 Integral Maximum // @Description: The maximum/minimum value that the I term can output AP_GROUPINFO("IMAX", 3, AC_PID2, _imax, 0), AP_GROUPEND };
#include <AP_HAL.h> extern const AP_HAL::HAL& hal; #define FLASH_LEDS(on) do { if (flash_leds_cb != NULL) flash_leds_cb(on); } while (0) #define SAMPLE_UNIT 1 // Class level parameters const AP_Param::GroupInfo AP_InertialSensor::var_info[] PROGMEM = { // @Param: PRODUCT_ID // @DisplayName: IMU Product ID // @Description: Which type of IMU is installed (read-only) // @User: Standard AP_GROUPINFO("PRODUCT_ID", 0, AP_InertialSensor, _product_id, 0), // @Param: ACCSCAL_X // @DisplayName: Accelerometer scaling of X axis // @Description: Accelerometer scaling of X axis. Calculated during acceleration calibration routine // @Range: 0.8 1.2 // @User: Advanced // @Param: ACCSCAL_Y // @DisplayName: Accelerometer scaling of Y axis // @Description: Accelerometer scaling of Y axis Calculated during acceleration calibration routine // @Range: 0.8 1.2 // @User: Advanced // @Param: ACCSCAL_Z // @DisplayName: Accelerometer scaling of Z axis