mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
AP_Param: update remaining libraries for new constructor syntax
This commit is contained in:
parent
7be604cffd
commit
e9d0ae3e7f
@ -20,25 +20,25 @@ const AP_Param::GroupInfo AP_Airspeed::var_info[] PROGMEM = {
|
|||||||
// @DisplayName: Airspeed enable
|
// @DisplayName: Airspeed enable
|
||||||
// @Description: enable airspeed sensor
|
// @Description: enable airspeed sensor
|
||||||
// @Values: 0:Disable,1:Enable
|
// @Values: 0:Disable,1:Enable
|
||||||
AP_GROUPINFO("ENABLE", 0, AP_Airspeed, _enable),
|
AP_GROUPINFO("ENABLE", 0, AP_Airspeed, _enable, 1),
|
||||||
|
|
||||||
// @Param: USE
|
// @Param: USE
|
||||||
// @DisplayName: Airspeed use
|
// @DisplayName: Airspeed use
|
||||||
// @Description: use airspeed for flight control
|
// @Description: use airspeed for flight control
|
||||||
// @Values: 0:Use,1:Don't Use
|
// @Values: 0:Use,1:Don't Use
|
||||||
AP_GROUPINFO("USE", 1, AP_Airspeed, _use),
|
AP_GROUPINFO("USE", 1, AP_Airspeed, _use, 0),
|
||||||
|
|
||||||
// @Param: OFFSET
|
// @Param: OFFSET
|
||||||
// @DisplayName: Airspeed offset
|
// @DisplayName: Airspeed offset
|
||||||
// @Description: Airspeed calibration offset
|
// @Description: Airspeed calibration offset
|
||||||
// @Increment: 0.1
|
// @Increment: 0.1
|
||||||
AP_GROUPINFO("OFFSET", 2, AP_Airspeed, _offset),
|
AP_GROUPINFO("OFFSET", 2, AP_Airspeed, _offset, 0),
|
||||||
|
|
||||||
// @Param: RATIO
|
// @Param: RATIO
|
||||||
// @DisplayName: Airspeed ratio
|
// @DisplayName: Airspeed ratio
|
||||||
// @Description: Airspeed calibration ratio
|
// @Description: Airspeed calibration ratio
|
||||||
// @Increment: 0.1
|
// @Increment: 0.1
|
||||||
AP_GROUPINFO("RATIO", 3, AP_Airspeed, _ratio),
|
AP_GROUPINFO("RATIO", 3, AP_Airspeed, _ratio, 0),
|
||||||
|
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
};
|
};
|
||||||
|
@ -21,13 +21,13 @@ const AP_Param::GroupInfo AP_Baro::var_info[] PROGMEM = {
|
|||||||
// @DisplayName: Absolute Pressure
|
// @DisplayName: Absolute Pressure
|
||||||
// @Description: calibrated ground pressure
|
// @Description: calibrated ground pressure
|
||||||
// @Increment: 1
|
// @Increment: 1
|
||||||
AP_GROUPINFO("ABS_PRESS", 2, AP_Baro, _ground_pressure),
|
AP_GROUPINFO("ABS_PRESS", 2, AP_Baro, _ground_pressure, 0),
|
||||||
|
|
||||||
// @Param: ABS_PRESS
|
// @Param: ABS_PRESS
|
||||||
// @DisplayName: ground temperature
|
// @DisplayName: ground temperature
|
||||||
// @Description: calibrated ground temperature
|
// @Description: calibrated ground temperature
|
||||||
// @Increment: 1
|
// @Increment: 1
|
||||||
AP_GROUPINFO("TEMP", 3, AP_Baro, _ground_temperature),
|
AP_GROUPINFO("TEMP", 3, AP_Baro, _ground_temperature, 0),
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
};
|
};
|
||||||
|
|
||||||
|
@ -17,7 +17,7 @@ const AP_Param::GroupInfo AP_Camera::var_info[] PROGMEM = {
|
|||||||
// @Description: how to trigger the camera to take a picture
|
// @Description: how to trigger the camera to take a picture
|
||||||
// @Values: 0:Servo,1:relay,2:throttle_off_time,3:throttle_off_waypoint,4:transistor
|
// @Values: 0:Servo,1:relay,2:throttle_off_time,3:throttle_off_waypoint,4:transistor
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("TRIGG_TYPE", 0, AP_Camera, trigger_type),
|
AP_GROUPINFO("TRIGG_TYPE", 0, AP_Camera, trigger_type, 0),
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
};
|
};
|
||||||
|
|
||||||
|
@ -22,8 +22,7 @@ public:
|
|||||||
wp_distance_min (10),
|
wp_distance_min (10),
|
||||||
keep_cam_trigg_active_cycles (0),
|
keep_cam_trigg_active_cycles (0),
|
||||||
thr_pic (0), // timer variable for throttle_pic
|
thr_pic (0), // timer variable for throttle_pic
|
||||||
camtrig (83), // PK6 chosen as it not near anything so safer for soldering
|
camtrig (83) // PK6 chosen as it not near anything so safer for soldering
|
||||||
trigger_type (0)
|
|
||||||
{}
|
{}
|
||||||
|
|
||||||
// single entry point to take pictures
|
// single entry point to take pictures
|
||||||
|
@ -3,11 +3,11 @@
|
|||||||
|
|
||||||
const AP_Param::GroupInfo Compass::var_info[] PROGMEM = {
|
const AP_Param::GroupInfo Compass::var_info[] PROGMEM = {
|
||||||
// index 0 was used for the old orientation matrix
|
// index 0 was used for the old orientation matrix
|
||||||
AP_GROUPINFO("OFS", 1, Compass, _offset),
|
AP_GROUPINFO("OFS", 1, Compass, _offset, 0),
|
||||||
AP_GROUPINFO("DEC", 2, Compass, _declination),
|
AP_GROUPINFO("DEC", 2, Compass, _declination, 0),
|
||||||
AP_GROUPINFO("LEARN", 3, Compass, _learn), // true if learning calibration
|
AP_GROUPINFO("LEARN", 3, Compass, _learn, 1), // true if learning calibration
|
||||||
AP_GROUPINFO("USE", 4, Compass, _use_for_yaw), // true if used for DCM yaw
|
AP_GROUPINFO("USE", 4, Compass, _use_for_yaw, 1), // true if used for DCM yaw
|
||||||
AP_GROUPINFO("AUTODEC",5, Compass, _auto_declination),
|
AP_GROUPINFO("AUTODEC",5, Compass, _auto_declination, 1),
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
};
|
};
|
||||||
|
|
||||||
@ -18,10 +18,6 @@ const AP_Param::GroupInfo Compass::var_info[] PROGMEM = {
|
|||||||
Compass::Compass(void) :
|
Compass::Compass(void) :
|
||||||
product_id(AP_COMPASS_TYPE_UNKNOWN),
|
product_id(AP_COMPASS_TYPE_UNKNOWN),
|
||||||
_orientation(ROTATION_NONE),
|
_orientation(ROTATION_NONE),
|
||||||
_declination (0.0),
|
|
||||||
_learn(1),
|
|
||||||
_use_for_yaw(1),
|
|
||||||
_auto_declination(1),
|
|
||||||
_null_init_done(false)
|
_null_init_done(false)
|
||||||
{
|
{
|
||||||
}
|
}
|
||||||
|
@ -3,8 +3,8 @@
|
|||||||
|
|
||||||
// this allows the sensor calibration to be saved to EEPROM
|
// this allows the sensor calibration to be saved to EEPROM
|
||||||
const AP_Param::GroupInfo IMU::var_info[] PROGMEM = {
|
const AP_Param::GroupInfo IMU::var_info[] PROGMEM = {
|
||||||
AP_GROUPINFO("CAL", 0, IMU, _sensor_cal),
|
AP_GROUPINFO("CAL", 0, IMU, _sensor_cal, 0),
|
||||||
AP_GROUPINFO("PRODUCT_ID", 1, IMU, _product_id),
|
AP_GROUPINFO("PRODUCT_ID", 1, IMU, _product_id, 0),
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
};
|
};
|
||||||
|
|
||||||
|
@ -39,12 +39,12 @@ const float AP_InertialSensor_Oilpan::_gyro_gain_z = ToRad(0.41);
|
|||||||
|
|
||||||
const AP_Param::GroupInfo AP_InertialSensor_Oilpan::var_info[] PROGMEM = {
|
const AP_Param::GroupInfo AP_InertialSensor_Oilpan::var_info[] PROGMEM = {
|
||||||
// index 0 was used for the old orientation matrix
|
// index 0 was used for the old orientation matrix
|
||||||
AP_GROUPINFO("XH", 0, AP_InertialSensor_Oilpan, _x_high),
|
AP_GROUPINFO("XH", 0, AP_InertialSensor_Oilpan, _x_high, 2465),
|
||||||
AP_GROUPINFO("XL", 1, AP_InertialSensor_Oilpan, _x_low),
|
AP_GROUPINFO("XL", 1, AP_InertialSensor_Oilpan, _x_low, 1617),
|
||||||
AP_GROUPINFO("YH", 2, AP_InertialSensor_Oilpan, _y_high),
|
AP_GROUPINFO("YH", 2, AP_InertialSensor_Oilpan, _y_high, 2465),
|
||||||
AP_GROUPINFO("YL", 3, AP_InertialSensor_Oilpan, _y_low),
|
AP_GROUPINFO("YL", 3, AP_InertialSensor_Oilpan, _y_low, 1617),
|
||||||
AP_GROUPINFO("ZH", 4, AP_InertialSensor_Oilpan, _z_high),
|
AP_GROUPINFO("ZH", 4, AP_InertialSensor_Oilpan, _z_high, 2465),
|
||||||
AP_GROUPINFO("ZL", 5, AP_InertialSensor_Oilpan, _z_low),
|
AP_GROUPINFO("ZL", 5, AP_InertialSensor_Oilpan, _z_low, 1617),
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
};
|
};
|
||||||
|
|
||||||
@ -52,12 +52,6 @@ const AP_Param::GroupInfo AP_InertialSensor_Oilpan::var_info[] PROGMEM = {
|
|||||||
/* ------ Public functions -------------------------------------------*/
|
/* ------ Public functions -------------------------------------------*/
|
||||||
|
|
||||||
AP_InertialSensor_Oilpan::AP_InertialSensor_Oilpan( AP_ADC * adc ) :
|
AP_InertialSensor_Oilpan::AP_InertialSensor_Oilpan( AP_ADC * adc ) :
|
||||||
_x_high(2465),
|
|
||||||
_x_low(1617),
|
|
||||||
_y_high(2465),
|
|
||||||
_y_low(1617),
|
|
||||||
_z_high(2465),
|
|
||||||
_z_low(1617),
|
|
||||||
_adc(adc)
|
_adc(adc)
|
||||||
{
|
{
|
||||||
_gyro.x = 0;
|
_gyro.x = 0;
|
||||||
|
@ -15,14 +15,14 @@ const AP_Param::GroupInfo AP_Limit_Altitude::var_info[] PROGMEM = {
|
|||||||
// @Description: Setting this to Enabled(1) will enable the altitude. Setting this to Disabled(0) will disable the altitude
|
// @Description: Setting this to Enabled(1) will enable the altitude. Setting this to Disabled(0) will disable the altitude
|
||||||
// @Values: 0:Disabled,1:Enabled
|
// @Values: 0:Disabled,1:Enabled
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("ALT_ON", 0, AP_Limit_Altitude, _enabled),
|
AP_GROUPINFO("ALT_ON", 0, AP_Limit_Altitude, _enabled, 0),
|
||||||
|
|
||||||
// @Param: ALT_REQD
|
// @Param: ALT_REQD
|
||||||
// @DisplayName: Require altitude
|
// @DisplayName: Require altitude
|
||||||
// @Description: Setting this to Enabled(1) will make being inside the altitude a required check before arming the vehicle.
|
// @Description: Setting this to Enabled(1) will make being inside the altitude a required check before arming the vehicle.
|
||||||
// @Values: 0:Disabled,1:Enabled
|
// @Values: 0:Disabled,1:Enabled
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("ALT_REQ", 1, AP_Limit_Altitude, _required),
|
AP_GROUPINFO("ALT_REQ", 1, AP_Limit_Altitude, _required, 0),
|
||||||
|
|
||||||
// @Param: ALT_MIN
|
// @Param: ALT_MIN
|
||||||
// @DisplayName: Minimum Altitude
|
// @DisplayName: Minimum Altitude
|
||||||
@ -31,7 +31,7 @@ const AP_Param::GroupInfo AP_Limit_Altitude::var_info[] PROGMEM = {
|
|||||||
// @Range: 0 250000
|
// @Range: 0 250000
|
||||||
// @Increment: 1
|
// @Increment: 1
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("ALT_MIN", 2, AP_Limit_Altitude, _min_alt),
|
AP_GROUPINFO("ALT_MIN", 2, AP_Limit_Altitude, _min_alt, 0),
|
||||||
|
|
||||||
// @Param: ALT_MAX
|
// @Param: ALT_MAX
|
||||||
// @DisplayName: Maximum Altitude
|
// @DisplayName: Maximum Altitude
|
||||||
@ -40,7 +40,7 @@ const AP_Param::GroupInfo AP_Limit_Altitude::var_info[] PROGMEM = {
|
|||||||
// @Range: 0 250000
|
// @Range: 0 250000
|
||||||
// @Increment: 1
|
// @Increment: 1
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("ALT_MAX", 3, AP_Limit_Altitude, _max_alt),
|
AP_GROUPINFO("ALT_MAX", 3, AP_Limit_Altitude, _max_alt, 0),
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
};
|
};
|
||||||
|
|
||||||
|
@ -15,14 +15,14 @@ const AP_Param::GroupInfo AP_Limit_GPSLock::var_info[] PROGMEM = {
|
|||||||
// @Description: Setting this to Enabled(1) will enable the gpslock. Setting this to Disabled(0) will disable the gpslock
|
// @Description: Setting this to Enabled(1) will enable the gpslock. Setting this to Disabled(0) will disable the gpslock
|
||||||
// @Values: 0:Disabled,1:Enabled
|
// @Values: 0:Disabled,1:Enabled
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("GPSLCK_ON", 0, AP_Limit_GPSLock, _enabled),
|
AP_GROUPINFO("GPSLCK_ON", 0, AP_Limit_GPSLock, _enabled, 0),
|
||||||
|
|
||||||
// @Param: GPSLCK_REQ
|
// @Param: GPSLCK_REQ
|
||||||
// @DisplayName: Require gpslock
|
// @DisplayName: Require gpslock
|
||||||
// @Description: Setting this to Enabled(1) will make being inside the gpslock a required check before arming the vehicle.
|
// @Description: Setting this to Enabled(1) will make being inside the gpslock a required check before arming the vehicle.
|
||||||
// @Values: 0:Disabled,1:Enabled
|
// @Values: 0:Disabled,1:Enabled
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("GPSLCK_REQ", 1, AP_Limit_GPSLock, _required),
|
AP_GROUPINFO("GPSLCK_REQ", 1, AP_Limit_GPSLock, _required, 0),
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
|
|
||||||
};
|
};
|
||||||
|
@ -14,21 +14,21 @@ const AP_Param::GroupInfo AP_Limit_Geofence::var_info[] PROGMEM = {
|
|||||||
// @Description: Setting this to Enabled(1) will enable the geofence. Setting this to Disabled(0) will disable the geofence
|
// @Description: Setting this to Enabled(1) will enable the geofence. Setting this to Disabled(0) will disable the geofence
|
||||||
// @Values: 0:Disabled,1:Enabled
|
// @Values: 0:Disabled,1:Enabled
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("FNC_ON", 0, AP_Limit_Geofence, _enabled),
|
AP_GROUPINFO("FNC_ON", 0, AP_Limit_Geofence, _enabled, 0),
|
||||||
|
|
||||||
// @Param: FNC_REQ
|
// @Param: FNC_REQ
|
||||||
// @DisplayName: Require Geofence
|
// @DisplayName: Require Geofence
|
||||||
// @Description: Setting this to Enabled(1) will make being inside the geofence a required check before arming the vehicle.
|
// @Description: Setting this to Enabled(1) will make being inside the geofence a required check before arming the vehicle.
|
||||||
// @Values: 0:Disabled,1:Enabled
|
// @Values: 0:Disabled,1:Enabled
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("FNC_REQ", 1, AP_Limit_Geofence, _required),
|
AP_GROUPINFO("FNC_REQ", 1, AP_Limit_Geofence, _required, 0),
|
||||||
|
|
||||||
// @Param: FNC_SMPL
|
// @Param: FNC_SMPL
|
||||||
// @DisplayName: Require Geofence
|
// @DisplayName: Require Geofence
|
||||||
// @Description: "Simple" geofence (enabled - 1) is based on a radius from the home position, "Complex" (disabled - 0) define a complex fence by lat/long positions
|
// @Description: "Simple" geofence (enabled - 1) is based on a radius from the home position, "Complex" (disabled - 0) define a complex fence by lat/long positions
|
||||||
// @Values: 0:Disabled,1:Enabled
|
// @Values: 0:Disabled,1:Enabled
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("FNC_SMPL", 2, AP_Limit_Geofence, _simple),
|
AP_GROUPINFO("FNC_SMPL", 2, AP_Limit_Geofence, _simple, 0),
|
||||||
|
|
||||||
// @Param: FNC_RAD
|
// @Param: FNC_RAD
|
||||||
// @DisplayName: Require Geofence
|
// @DisplayName: Require Geofence
|
||||||
@ -37,9 +37,9 @@ const AP_Param::GroupInfo AP_Limit_Geofence::var_info[] PROGMEM = {
|
|||||||
// @Range: 0 32767
|
// @Range: 0 32767
|
||||||
// @Increment: 1
|
// @Increment: 1
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("FNC_RAD", 3, AP_Limit_Geofence, _radius),
|
AP_GROUPINFO("FNC_RAD", 3, AP_Limit_Geofence, _radius, 0),
|
||||||
|
|
||||||
AP_GROUPINFO("FNC_TOT", 4, AP_Limit_Geofence, _fence_total),
|
AP_GROUPINFO("FNC_TOT", 4, AP_Limit_Geofence, _fence_total, 0),
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
|
|
||||||
|
|
||||||
|
@ -15,42 +15,42 @@ const AP_Param::GroupInfo AP_Limits::var_info[] PROGMEM = {
|
|||||||
// @Description: Setting this to Enabled(1) will enable the limits system
|
// @Description: Setting this to Enabled(1) will enable the limits system
|
||||||
// @Values: 0:Disabled,1:Enabled
|
// @Values: 0:Disabled,1:Enabled
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("ENABLED", 0, AP_Limits, _enabled),
|
AP_GROUPINFO("ENABLED", 0, AP_Limits, _enabled, 0),
|
||||||
|
|
||||||
// @Param: REQUIRED
|
// @Param: REQUIRED
|
||||||
// @DisplayName: Limits Library Required
|
// @DisplayName: Limits Library Required
|
||||||
// @Description: Setting this to 1 will enable the limits pre-arm checklist
|
// @Description: Setting this to 1 will enable the limits pre-arm checklist
|
||||||
// @Values: 0:Disabled,1:Enabled
|
// @Values: 0:Disabled,1:Enabled
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("REQUIRED", 1, AP_Limits, _required),
|
AP_GROUPINFO("REQUIRED", 1, AP_Limits, _required, 0),
|
||||||
|
|
||||||
// @Param: DEBUG
|
// @Param: DEBUG
|
||||||
// @DisplayName: Enable Limits Debug
|
// @DisplayName: Enable Limits Debug
|
||||||
// @Description: Setting this to 1 will turn on debugging messages on the console and via MAVLink STATUSTEXT messages
|
// @Description: Setting this to 1 will turn on debugging messages on the console and via MAVLink STATUSTEXT messages
|
||||||
// @Values: 0:Disabled,1:Enabled
|
// @Values: 0:Disabled,1:Enabled
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("DEBUG", 2, AP_Limits, _debug),
|
AP_GROUPINFO("DEBUG", 2, AP_Limits, _debug, 0),
|
||||||
|
|
||||||
// @Param: SAFETIME
|
// @Param: SAFETIME
|
||||||
// @DisplayName: Limits Safetime
|
// @DisplayName: Limits Safetime
|
||||||
// @Description: Automatic return of controls to pilot. Set to 0 to disable (full RTL) or a number of seconds after complete recovery to return the controls to the pilot in STABILIZE
|
// @Description: Automatic return of controls to pilot. Set to 0 to disable (full RTL) or a number of seconds after complete recovery to return the controls to the pilot in STABILIZE
|
||||||
// @Values: 0:Disabled,1-255:Seconds before returning control
|
// @Values: 0:Disabled,1-255:Seconds before returning control
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("SAFETIME", 3, AP_Limits, _safetime),
|
AP_GROUPINFO("SAFETIME", 3, AP_Limits, _safetime, 0),
|
||||||
|
|
||||||
// @Param: CHANNEL
|
// @Param: CHANNEL
|
||||||
// @DisplayName: Limits Channel
|
// @DisplayName: Limits Channel
|
||||||
// @Description: Channel for Limits on/off control. If channel exceeds LIMITS_ENABLE_PWM, it turns limits on, and vice-versa.
|
// @Description: Channel for Limits on/off control. If channel exceeds LIMITS_ENABLE_PWM, it turns limits on, and vice-versa.
|
||||||
// @Range: 1-8
|
// @Range: 1-8
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("CHANNEL", 4, AP_Limits, _channel),
|
AP_GROUPINFO("CHANNEL", 4, AP_Limits, _channel, 0),
|
||||||
|
|
||||||
// @Param: RECMODE
|
// @Param: RECMODE
|
||||||
// @DisplayName: Limits Recovery Mode
|
// @DisplayName: Limits Recovery Mode
|
||||||
// @Description: Select how Limits should "recover". Set to 0 for RTL-like mode, where the vehicle navigates back to home until it is "safe". Set to 1, for bounce-mode, where the vehicle will hold position when it hits a limit. RTL mode is better for large fenced areas, Bounce mode for smaller spaces. Note: RTL mode will cause the vehicle to yaw 180 degrees (turn around) to navigate towards home when it hits a limit.
|
// @Description: Select how Limits should "recover". Set to 0 for RTL-like mode, where the vehicle navigates back to home until it is "safe". Set to 1, for bounce-mode, where the vehicle will hold position when it hits a limit. RTL mode is better for large fenced areas, Bounce mode for smaller spaces. Note: RTL mode will cause the vehicle to yaw 180 degrees (turn around) to navigate towards home when it hits a limit.
|
||||||
// @Values: 0:RTL mode, 1: Bounce mode
|
// @Values: 0:RTL mode, 1: Bounce mode
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("RECMODE", 5, AP_Limits, _recmode),
|
AP_GROUPINFO("RECMODE", 5, AP_Limits, _recmode, 0),
|
||||||
|
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
};
|
};
|
||||||
|
@ -12,13 +12,12 @@
|
|||||||
|
|
||||||
// parameters for the motor class
|
// parameters for the motor class
|
||||||
const AP_Param::GroupInfo AP_Motors::var_info[] PROGMEM = {
|
const AP_Param::GroupInfo AP_Motors::var_info[] PROGMEM = {
|
||||||
AP_GROUPINFO("TB_RATIO", 0, AP_Motors, top_bottom_ratio), // not used
|
AP_GROUPINFO("TB_RATIO", 0, AP_Motors, top_bottom_ratio, AP_MOTORS_TOP_BOTTOM_RATIO), // not used
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
};
|
};
|
||||||
|
|
||||||
// Constructor
|
// Constructor
|
||||||
AP_Motors::AP_Motors( uint8_t APM_version, APM_RC_Class* rc_out, RC_Channel* rc_roll, RC_Channel* rc_pitch, RC_Channel* rc_throttle, RC_Channel* rc_yaw, uint16_t speed_hz ) :
|
AP_Motors::AP_Motors( uint8_t APM_version, APM_RC_Class* rc_out, RC_Channel* rc_roll, RC_Channel* rc_pitch, RC_Channel* rc_throttle, RC_Channel* rc_yaw, uint16_t speed_hz ) :
|
||||||
top_bottom_ratio(AP_MOTORS_TOP_BOTTOM_RATIO),
|
|
||||||
_rc(rc_out),
|
_rc(rc_out),
|
||||||
_rc_roll(rc_roll),
|
_rc_roll(rc_roll),
|
||||||
_rc_pitch(rc_pitch),
|
_rc_pitch(rc_pitch),
|
||||||
@ -32,6 +31,8 @@ AP_Motors::AP_Motors( uint8_t APM_version, APM_RC_Class* rc_out, RC_Channel* rc_
|
|||||||
_max_throttle(AP_MOTORS_DEFAULT_MAX_THROTTLE)
|
_max_throttle(AP_MOTORS_DEFAULT_MAX_THROTTLE)
|
||||||
{
|
{
|
||||||
uint8_t i;
|
uint8_t i;
|
||||||
|
|
||||||
|
top_bottom_ratio = AP_MOTORS_TOP_BOTTOM_RATIO;
|
||||||
|
|
||||||
// initialise motor map
|
// initialise motor map
|
||||||
if( APM_version == AP_MOTORS_APM1 ) {
|
if( APM_version == AP_MOTORS_APM1 ) {
|
||||||
|
@ -20,7 +20,7 @@ const AP_Param::GroupInfo AP_MotorsHeli::var_info[] PROGMEM = {
|
|||||||
// @Units: Degrees
|
// @Units: Degrees
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
// @Increment: 1
|
// @Increment: 1
|
||||||
AP_GROUPINFO("SV1_POS", 1, AP_MotorsHeli, servo1_pos),
|
AP_GROUPINFO("SV1_POS", 1, AP_MotorsHeli, servo1_pos, -60),
|
||||||
|
|
||||||
// @Param: SV2_POS
|
// @Param: SV2_POS
|
||||||
// @DisplayName: Servo 2 Position
|
// @DisplayName: Servo 2 Position
|
||||||
@ -29,7 +29,7 @@ const AP_Param::GroupInfo AP_MotorsHeli::var_info[] PROGMEM = {
|
|||||||
// @Units: Degrees
|
// @Units: Degrees
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
// @Increment: 1
|
// @Increment: 1
|
||||||
AP_GROUPINFO("SV2_POS", 2, AP_MotorsHeli, servo2_pos),
|
AP_GROUPINFO("SV2_POS", 2, AP_MotorsHeli, servo2_pos, 60),
|
||||||
|
|
||||||
// @Param: SV3_POS
|
// @Param: SV3_POS
|
||||||
// @DisplayName: Servo 3 Position
|
// @DisplayName: Servo 3 Position
|
||||||
@ -38,7 +38,7 @@ const AP_Param::GroupInfo AP_MotorsHeli::var_info[] PROGMEM = {
|
|||||||
// @Units: Degrees
|
// @Units: Degrees
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
// @Increment: 1
|
// @Increment: 1
|
||||||
AP_GROUPINFO("SV3_POS", 3, AP_MotorsHeli, servo3_pos),
|
AP_GROUPINFO("SV3_POS", 3, AP_MotorsHeli, servo3_pos, 180),
|
||||||
|
|
||||||
// @Param: ROL_MAX
|
// @Param: ROL_MAX
|
||||||
// @DisplayName: Maximum Roll Angle
|
// @DisplayName: Maximum Roll Angle
|
||||||
@ -47,7 +47,7 @@ const AP_Param::GroupInfo AP_MotorsHeli::var_info[] PROGMEM = {
|
|||||||
// @Units: Degrees
|
// @Units: Degrees
|
||||||
// @Increment: 1
|
// @Increment: 1
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
AP_GROUPINFO("ROL_MAX", 4, AP_MotorsHeli, roll_max),
|
AP_GROUPINFO("ROL_MAX", 4, AP_MotorsHeli, roll_max, 4500),
|
||||||
|
|
||||||
// @Param: PIT_MAX
|
// @Param: PIT_MAX
|
||||||
// @DisplayName: Maximum Pitch Angle
|
// @DisplayName: Maximum Pitch Angle
|
||||||
@ -56,7 +56,7 @@ const AP_Param::GroupInfo AP_MotorsHeli::var_info[] PROGMEM = {
|
|||||||
// @Units: Degrees
|
// @Units: Degrees
|
||||||
// @Increment: 1
|
// @Increment: 1
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
AP_GROUPINFO("PIT_MAX", 5, AP_MotorsHeli, pitch_max),
|
AP_GROUPINFO("PIT_MAX", 5, AP_MotorsHeli, pitch_max, 4500),
|
||||||
|
|
||||||
// @Param: COL_MIN
|
// @Param: COL_MIN
|
||||||
// @DisplayName: Collective Pitch Minimum
|
// @DisplayName: Collective Pitch Minimum
|
||||||
@ -65,7 +65,7 @@ const AP_Param::GroupInfo AP_MotorsHeli::var_info[] PROGMEM = {
|
|||||||
// @Units: PWM
|
// @Units: PWM
|
||||||
// @Increment: 1
|
// @Increment: 1
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("COL_MIN", 6, AP_MotorsHeli, collective_min),
|
AP_GROUPINFO("COL_MIN", 6, AP_MotorsHeli, collective_min, 1250),
|
||||||
|
|
||||||
// @Param: COL_MAX
|
// @Param: COL_MAX
|
||||||
// @DisplayName: Collective Pitch Maximum
|
// @DisplayName: Collective Pitch Maximum
|
||||||
@ -74,7 +74,7 @@ const AP_Param::GroupInfo AP_MotorsHeli::var_info[] PROGMEM = {
|
|||||||
// @Units: PWM
|
// @Units: PWM
|
||||||
// @Increment: 1
|
// @Increment: 1
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("COL_MAX", 7, AP_MotorsHeli, collective_max),
|
AP_GROUPINFO("COL_MAX", 7, AP_MotorsHeli, collective_max, 1750),
|
||||||
|
|
||||||
// @Param: COL_MID
|
// @Param: COL_MID
|
||||||
// @DisplayName: Collective Pitch Mid-Point
|
// @DisplayName: Collective Pitch Mid-Point
|
||||||
@ -83,20 +83,20 @@ const AP_Param::GroupInfo AP_MotorsHeli::var_info[] PROGMEM = {
|
|||||||
// @Units: PWM
|
// @Units: PWM
|
||||||
// @Increment: 1
|
// @Increment: 1
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("COL_MID", 8, AP_MotorsHeli, collective_mid),
|
AP_GROUPINFO("COL_MID", 8, AP_MotorsHeli, collective_mid, 1500),
|
||||||
|
|
||||||
// @Param: GYR_ENABLE
|
// @Param: GYR_ENABLE
|
||||||
// @DisplayName: External Gyro Enabled
|
// @DisplayName: External Gyro Enabled
|
||||||
// @Description: Setting this to Enabled(1) will enable an external rudder gyro control which means outputting a gain on channel 7 and using a simpler heading control algorithm. Setting this to Disabled(0) will disable the external gyro gain on channel 7 and revert to a more complex yaw control algorithm.
|
// @Description: Setting this to Enabled(1) will enable an external rudder gyro control which means outputting a gain on channel 7 and using a simpler heading control algorithm. Setting this to Disabled(0) will disable the external gyro gain on channel 7 and revert to a more complex yaw control algorithm.
|
||||||
// @Values: 0:Disabled,1:Enabled
|
// @Values: 0:Disabled,1:Enabled
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("GYR_ENABLE", 9, AP_MotorsHeli, ext_gyro_enabled),
|
AP_GROUPINFO("GYR_ENABLE", 9, AP_MotorsHeli, ext_gyro_enabled, 0),
|
||||||
|
|
||||||
// @Param: SWASH_TYPE
|
// @Param: SWASH_TYPE
|
||||||
// @DisplayName: Swash Plate Type
|
// @DisplayName: Swash Plate Type
|
||||||
// @Description: Setting this to 0 will configure for a 3-servo CCPM. Setting this to 1 will configure for mechanically mixed "H1".
|
// @Description: Setting this to 0 will configure for a 3-servo CCPM. Setting this to 1 will configure for mechanically mixed "H1".
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("SWASH_TYPE", 10, AP_MotorsHeli, swash_type),
|
AP_GROUPINFO("SWASH_TYPE", 10, AP_MotorsHeli, swash_type, AP_MOTORS_HELI_SWASH_CCPM),
|
||||||
|
|
||||||
// @Param: GYR_GAIN
|
// @Param: GYR_GAIN
|
||||||
// @DisplayName: External Gyro Gain
|
// @DisplayName: External Gyro Gain
|
||||||
@ -105,14 +105,14 @@ const AP_Param::GroupInfo AP_MotorsHeli::var_info[] PROGMEM = {
|
|||||||
// @Units: PWM
|
// @Units: PWM
|
||||||
// @Increment: 1
|
// @Increment: 1
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("GYR_GAIN", 11, AP_MotorsHeli, ext_gyro_gain),
|
AP_GROUPINFO("GYR_GAIN", 11, AP_MotorsHeli, ext_gyro_gain, 1350),
|
||||||
|
|
||||||
// @Param: SV_MAN
|
// @Param: SV_MAN
|
||||||
// @DisplayName: Manual Servo Mode
|
// @DisplayName: Manual Servo Mode
|
||||||
// @Description: Setting this to Enabled(1) will pass radio inputs directly to servos. Setting this to Disabled(0) will enable Arducopter control of servos. This is only meant to be used by the Mission Planner using swash plate set-up.
|
// @Description: Setting this to Enabled(1) will pass radio inputs directly to servos. Setting this to Disabled(0) will enable Arducopter control of servos. This is only meant to be used by the Mission Planner using swash plate set-up.
|
||||||
// @Values: 0:Disabled,1:Enabled
|
// @Values: 0:Disabled,1:Enabled
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("SV_MAN", 12, AP_MotorsHeli, servo_manual),
|
AP_GROUPINFO("SV_MAN", 12, AP_MotorsHeli, servo_manual, 0),
|
||||||
|
|
||||||
// @Param: PHANG
|
// @Param: PHANG
|
||||||
// @DisplayName: Swashplate Phase Angle Compensation
|
// @DisplayName: Swashplate Phase Angle Compensation
|
||||||
@ -121,13 +121,13 @@ const AP_Param::GroupInfo AP_MotorsHeli::var_info[] PROGMEM = {
|
|||||||
// @Units: Degrees
|
// @Units: Degrees
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
// @Increment: 1
|
// @Increment: 1
|
||||||
AP_GROUPINFO("PHANG", 13, AP_MotorsHeli, phase_angle),
|
AP_GROUPINFO("PHANG", 13, AP_MotorsHeli, phase_angle, 0),
|
||||||
|
|
||||||
// @Param: COLYAW
|
// @Param: COLYAW
|
||||||
// @DisplayName: Collective-Yaw Mixing
|
// @DisplayName: Collective-Yaw Mixing
|
||||||
// @Description: This is a feed-forward compensation to automatically add rudder input when collective pitch is increased.
|
// @Description: This is a feed-forward compensation to automatically add rudder input when collective pitch is increased.
|
||||||
// @Range: 0 5
|
// @Range: 0 5
|
||||||
AP_GROUPINFO("COLYAW", 14, AP_MotorsHeli, collective_yaw_effect),
|
AP_GROUPINFO("COLYAW", 14, AP_MotorsHeli, collective_yaw_effect, 0),
|
||||||
|
|
||||||
// @Param: GOV_SETPOINT
|
// @Param: GOV_SETPOINT
|
||||||
// @DisplayName: External Motor Governor Setpoint
|
// @DisplayName: External Motor Governor Setpoint
|
||||||
@ -136,7 +136,7 @@ const AP_Param::GroupInfo AP_MotorsHeli::var_info[] PROGMEM = {
|
|||||||
// @Units: PWM
|
// @Units: PWM
|
||||||
// @Increment: 10
|
// @Increment: 10
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("GOV_SETPOINT", 15, AP_MotorsHeli, ext_gov_setpoint),
|
AP_GROUPINFO("GOV_SETPOINT", 15, AP_MotorsHeli, ext_gov_setpoint, 1500),
|
||||||
|
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
};
|
};
|
||||||
@ -549,4 +549,4 @@ void AP_MotorsHeli::ext_esc_control()
|
|||||||
default:
|
default:
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
@ -67,28 +67,14 @@ public:
|
|||||||
_servo_2(swash_servo_2),
|
_servo_2(swash_servo_2),
|
||||||
_servo_3(swash_servo_3),
|
_servo_3(swash_servo_3),
|
||||||
_servo_4(yaw_servo),
|
_servo_4(yaw_servo),
|
||||||
_rc_8(rc_8),
|
_rc_8(rc_8)
|
||||||
swash_type(AP_MOTORS_HELI_SWASH_CCPM),
|
{
|
||||||
servo1_pos (-60),
|
throttle_mid = 0;
|
||||||
servo2_pos (60),
|
_roll_scaler = 1;
|
||||||
servo3_pos (180),
|
_pitch_scaler = 1;
|
||||||
collective_min (1250),
|
_collective_scalar = 1;
|
||||||
collective_max (1750),
|
_swash_initialised = false;
|
||||||
collective_mid (1500),
|
};
|
||||||
ext_gyro_enabled (0),
|
|
||||||
ext_gyro_gain (1350),
|
|
||||||
roll_max (4500),
|
|
||||||
pitch_max (4500),
|
|
||||||
phase_angle (0),
|
|
||||||
collective_yaw_effect (0),
|
|
||||||
servo_manual (0),
|
|
||||||
ext_gov_setpoint (1500),
|
|
||||||
throttle_mid (0),
|
|
||||||
_roll_scaler (1),
|
|
||||||
_pitch_scaler (1),
|
|
||||||
_collective_scalar (1),
|
|
||||||
_swash_initialised(false)
|
|
||||||
{};
|
|
||||||
|
|
||||||
RC_Channel *_servo_1;
|
RC_Channel *_servo_1;
|
||||||
RC_Channel *_servo_2;
|
RC_Channel *_servo_2;
|
||||||
@ -171,4 +157,4 @@ protected:
|
|||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif // AP_MOTORSHELI
|
#endif // AP_MOTORSHELI
|
||||||
|
@ -11,7 +11,7 @@ const AP_Param::GroupInfo AP_Mount::var_info[] PROGMEM = {
|
|||||||
// @Description: Camera or antenna mount operation mode
|
// @Description: Camera or antenna mount operation mode
|
||||||
// @Values: 0:retract,1:neutral,2:MavLink_targeting,3:RC_targeting,4:GPS_point
|
// @Values: 0:retract,1:neutral,2:MavLink_targeting,3:RC_targeting,4:GPS_point
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("MODE", 0, AP_Mount, _mount_mode), // see MAV_MOUNT_MODE at ardupilotmega.h
|
AP_GROUPINFO("MODE", 0, AP_Mount, _mount_mode, 0), // see MAV_MOUNT_MODE at ardupilotmega.h
|
||||||
|
|
||||||
// @Param: RETRACT
|
// @Param: RETRACT
|
||||||
// @DisplayName: Mount retract angles
|
// @DisplayName: Mount retract angles
|
||||||
@ -20,7 +20,7 @@ const AP_Param::GroupInfo AP_Mount::var_info[] PROGMEM = {
|
|||||||
// @Range: -18000 17999
|
// @Range: -18000 17999
|
||||||
// @Increment: 1
|
// @Increment: 1
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("RETRACT", 1, AP_Mount, _retract_angles),
|
AP_GROUPINFO("RETRACT", 1, AP_Mount, _retract_angles, 0),
|
||||||
|
|
||||||
// @Param: NEUTRAL
|
// @Param: NEUTRAL
|
||||||
// @DisplayName: Mount neutral angles
|
// @DisplayName: Mount neutral angles
|
||||||
@ -29,7 +29,7 @@ const AP_Param::GroupInfo AP_Mount::var_info[] PROGMEM = {
|
|||||||
// @Range: -18000 17999
|
// @Range: -18000 17999
|
||||||
// @Increment: 1
|
// @Increment: 1
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("NEUTRAL", 2, AP_Mount, _neutral_angles),
|
AP_GROUPINFO("NEUTRAL", 2, AP_Mount, _neutral_angles, 0),
|
||||||
|
|
||||||
// @Param: CONTROL
|
// @Param: CONTROL
|
||||||
// @DisplayName: Mount control angles
|
// @DisplayName: Mount control angles
|
||||||
@ -38,35 +38,35 @@ const AP_Param::GroupInfo AP_Mount::var_info[] PROGMEM = {
|
|||||||
// @Range: -18000 17999
|
// @Range: -18000 17999
|
||||||
// @Increment: 1
|
// @Increment: 1
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("CONTROL", 3, AP_Mount, _control_angles),
|
AP_GROUPINFO("CONTROL", 3, AP_Mount, _control_angles, 0),
|
||||||
|
|
||||||
// @Param: STAB_ROLL
|
// @Param: STAB_ROLL
|
||||||
// @DisplayName: Stabilize mount roll
|
// @DisplayName: Stabilize mount roll
|
||||||
// @Description:enable roll stabilisation relative to Earth
|
// @Description:enable roll stabilisation relative to Earth
|
||||||
// @Values: 0:Disabled,1:Enabled
|
// @Values: 0:Disabled,1:Enabled
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("STAB_ROLL", 4, AP_Mount, _stab_roll),
|
AP_GROUPINFO("STAB_ROLL", 4, AP_Mount, _stab_roll, 0),
|
||||||
|
|
||||||
// @Param: STAB_TILT
|
// @Param: STAB_TILT
|
||||||
// @DisplayName: Stabilize mount tilt
|
// @DisplayName: Stabilize mount tilt
|
||||||
// @Description: enable tilt (pitch) stabilisation relative to Earth
|
// @Description: enable tilt (pitch) stabilisation relative to Earth
|
||||||
// @Values: 0:Disabled,1:Enabled
|
// @Values: 0:Disabled,1:Enabled
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("STAB_TILT", 5, AP_Mount, _stab_tilt),
|
AP_GROUPINFO("STAB_TILT", 5, AP_Mount, _stab_tilt, 0),
|
||||||
|
|
||||||
// @Param: STAB_PAN
|
// @Param: STAB_PAN
|
||||||
// @DisplayName: Stabilize mount pan
|
// @DisplayName: Stabilize mount pan
|
||||||
// @Description: enable pan (yaw) stabilisation relative to Earth
|
// @Description: enable pan (yaw) stabilisation relative to Earth
|
||||||
// @Values: 0:Disabled,1:Enabled
|
// @Values: 0:Disabled,1:Enabled
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("STAB_PAN", 6, AP_Mount, _stab_pan),
|
AP_GROUPINFO("STAB_PAN", 6, AP_Mount, _stab_pan, 0),
|
||||||
|
|
||||||
// @Param: ROLL_RC_IN
|
// @Param: ROLL_RC_IN
|
||||||
// @DisplayName: roll RC input channel
|
// @DisplayName: roll RC input channel
|
||||||
// @Description: 0 for none, any other for the RC channel to be used to control roll movements
|
// @Description: 0 for none, any other for the RC channel to be used to control roll movements
|
||||||
// @Values: 0:Disabled,5:RC5,6:RC6,7:RC7,8:RC8
|
// @Values: 0:Disabled,5:RC5,6:RC6,7:RC7,8:RC8
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("ROLL_RC_IN", 7, AP_Mount, _roll_rc_in),
|
AP_GROUPINFO("ROLL_RC_IN", 7, AP_Mount, _roll_rc_in, 0),
|
||||||
|
|
||||||
// @Param: ROLL_ANGLE_MIN
|
// @Param: ROLL_ANGLE_MIN
|
||||||
// @DisplayName: Minimum roll angle
|
// @DisplayName: Minimum roll angle
|
||||||
@ -75,7 +75,7 @@ const AP_Param::GroupInfo AP_Mount::var_info[] PROGMEM = {
|
|||||||
// @Range: -18000 17999
|
// @Range: -18000 17999
|
||||||
// @Increment: 1
|
// @Increment: 1
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("ROLL_ANGMIN", 8, AP_Mount, _roll_angle_min),
|
AP_GROUPINFO("ROLL_ANGMIN", 8, AP_Mount, _roll_angle_min, 0),
|
||||||
|
|
||||||
// @Param: ROLL_ANGLE_MAX
|
// @Param: ROLL_ANGLE_MAX
|
||||||
// @DisplayName: Maximum roll angle
|
// @DisplayName: Maximum roll angle
|
||||||
@ -84,14 +84,14 @@ const AP_Param::GroupInfo AP_Mount::var_info[] PROGMEM = {
|
|||||||
// @Range: -18000 17999
|
// @Range: -18000 17999
|
||||||
// @Increment: 1
|
// @Increment: 1
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("ROLL_ANGMAX", 9, AP_Mount, _roll_angle_max),
|
AP_GROUPINFO("ROLL_ANGMAX", 9, AP_Mount, _roll_angle_max, 0),
|
||||||
|
|
||||||
// @Param: TILT_RC_IN
|
// @Param: TILT_RC_IN
|
||||||
// @DisplayName: tilt (pitch) RC input channel
|
// @DisplayName: tilt (pitch) RC input channel
|
||||||
// @Description: 0 for none, any other for the RC channel to be used to control tilt (pitch) movements
|
// @Description: 0 for none, any other for the RC channel to be used to control tilt (pitch) movements
|
||||||
// @Values: 0:Disabled,5:RC5,6:RC6,7:RC7,8:RC8
|
// @Values: 0:Disabled,5:RC5,6:RC6,7:RC7,8:RC8
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("TILT_RC_IN", 10, AP_Mount, _tilt_rc_in),
|
AP_GROUPINFO("TILT_RC_IN", 10, AP_Mount, _tilt_rc_in, 0),
|
||||||
|
|
||||||
// @Param: TILT_ANGLE_MIN
|
// @Param: TILT_ANGLE_MIN
|
||||||
// @DisplayName: Minimum tilt angle
|
// @DisplayName: Minimum tilt angle
|
||||||
@ -100,7 +100,7 @@ const AP_Param::GroupInfo AP_Mount::var_info[] PROGMEM = {
|
|||||||
// @Range: -18000 17999
|
// @Range: -18000 17999
|
||||||
// @Increment: 1
|
// @Increment: 1
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("TILT_ANGMIN", 11, AP_Mount, _tilt_angle_min),
|
AP_GROUPINFO("TILT_ANGMIN", 11, AP_Mount, _tilt_angle_min, 0),
|
||||||
|
|
||||||
// @Param: TILT_ANGLE_MAX
|
// @Param: TILT_ANGLE_MAX
|
||||||
// @DisplayName: Maximum tilt angle
|
// @DisplayName: Maximum tilt angle
|
||||||
@ -109,14 +109,14 @@ const AP_Param::GroupInfo AP_Mount::var_info[] PROGMEM = {
|
|||||||
// @Range: -18000 17999
|
// @Range: -18000 17999
|
||||||
// @Increment: 1
|
// @Increment: 1
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("TILT_ANGMAX", 12, AP_Mount, _tilt_angle_max),
|
AP_GROUPINFO("TILT_ANGMAX", 12, AP_Mount, _tilt_angle_max, 0),
|
||||||
|
|
||||||
// @Param: PAN_RC_IN
|
// @Param: PAN_RC_IN
|
||||||
// @DisplayName: pan (yaw) RC input channel
|
// @DisplayName: pan (yaw) RC input channel
|
||||||
// @Description: 0 for none, any other for the RC channel to be used to control pan (yaw) movements
|
// @Description: 0 for none, any other for the RC channel to be used to control pan (yaw) movements
|
||||||
// @Values: 0:Disabled,5:RC5,6:RC6,7:RC7,8:RC8
|
// @Values: 0:Disabled,5:RC5,6:RC6,7:RC7,8:RC8
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("PAN_RC_IN", 13, AP_Mount, _pan_rc_in),
|
AP_GROUPINFO("PAN_RC_IN", 13, AP_Mount, _pan_rc_in, 0),
|
||||||
|
|
||||||
// @Param: PAN_ANGLE_MIN
|
// @Param: PAN_ANGLE_MIN
|
||||||
// @DisplayName: Minimum pan angle
|
// @DisplayName: Minimum pan angle
|
||||||
@ -125,7 +125,7 @@ const AP_Param::GroupInfo AP_Mount::var_info[] PROGMEM = {
|
|||||||
// @Range: -18000 17999
|
// @Range: -18000 17999
|
||||||
// @Increment: 1
|
// @Increment: 1
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("PAN_ANGMIN", 14, AP_Mount, _pan_angle_min),
|
AP_GROUPINFO("PAN_ANGMIN", 14, AP_Mount, _pan_angle_min, 0),
|
||||||
|
|
||||||
// @Param: PAN_ANGLE_MAX
|
// @Param: PAN_ANGLE_MAX
|
||||||
// @DisplayName: Maximum pan angle
|
// @DisplayName: Maximum pan angle
|
||||||
@ -134,7 +134,7 @@ const AP_Param::GroupInfo AP_Mount::var_info[] PROGMEM = {
|
|||||||
// @Range: -18000 17999
|
// @Range: -18000 17999
|
||||||
// @Increment: 1
|
// @Increment: 1
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("PAN_ANGMAX", 15, AP_Mount, _pan_angle_max),
|
AP_GROUPINFO("PAN_ANGMAX", 15, AP_Mount, _pan_angle_max, 0),
|
||||||
/*
|
/*
|
||||||
Must be commented out because the framework does not support more than 16 parameters
|
Must be commented out because the framework does not support more than 16 parameters
|
||||||
// @Param: JOYSTICK_SPEED
|
// @Param: JOYSTICK_SPEED
|
||||||
|
@ -36,7 +36,7 @@ const AP_Param::GroupInfo RC_Channel::var_info[] PROGMEM = {
|
|||||||
// @Range: 800 2200
|
// @Range: 800 2200
|
||||||
// @Increment: 1
|
// @Increment: 1
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
AP_GROUPINFO("MIN", 0, RC_Channel, radio_min),
|
AP_GROUPINFO("MIN", 0, RC_Channel, radio_min, 1100),
|
||||||
|
|
||||||
// @Param: TRIM
|
// @Param: TRIM
|
||||||
// @DisplayName: RC trim PWM
|
// @DisplayName: RC trim PWM
|
||||||
@ -45,7 +45,7 @@ const AP_Param::GroupInfo RC_Channel::var_info[] PROGMEM = {
|
|||||||
// @Range: 800 2200
|
// @Range: 800 2200
|
||||||
// @Increment: 1
|
// @Increment: 1
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
AP_GROUPINFO("TRIM", 1, RC_Channel, radio_trim),
|
AP_GROUPINFO("TRIM", 1, RC_Channel, radio_trim, 1500),
|
||||||
|
|
||||||
// @Param: MAX
|
// @Param: MAX
|
||||||
// @DisplayName: RC max PWM
|
// @DisplayName: RC max PWM
|
||||||
@ -54,20 +54,20 @@ const AP_Param::GroupInfo RC_Channel::var_info[] PROGMEM = {
|
|||||||
// @Range: 800 2200
|
// @Range: 800 2200
|
||||||
// @Increment: 1
|
// @Increment: 1
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
AP_GROUPINFO("MAX", 2, RC_Channel, radio_max),
|
AP_GROUPINFO("MAX", 2, RC_Channel, radio_max, 1900),
|
||||||
|
|
||||||
// @Param: REV
|
// @Param: REV
|
||||||
// @DisplayName: RC reverse
|
// @DisplayName: RC reverse
|
||||||
// @Description: Reverse servo operation. Ignored on APM1 unless dip-switches are disabled.
|
// @Description: Reverse servo operation. Ignored on APM1 unless dip-switches are disabled.
|
||||||
// @Values: -1:Reversed,1:Normal
|
// @Values: -1:Reversed,1:Normal
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
AP_GROUPINFO("REV", 3, RC_Channel, _reverse),
|
AP_GROUPINFO("REV", 3, RC_Channel, _reverse, 1),
|
||||||
|
|
||||||
// @Param: DZ
|
// @Param: DZ
|
||||||
// @DisplayName: RC dead-zone
|
// @DisplayName: RC dead-zone
|
||||||
// @Description: dead zone around trim.
|
// @Description: dead zone around trim.
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
AP_GROUPINFO("DZ", 4, RC_Channel, _dead_zone),
|
AP_GROUPINFO("DZ", 4, RC_Channel, _dead_zone, 0),
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
};
|
};
|
||||||
|
|
||||||
|
@ -19,13 +19,8 @@ class RC_Channel{
|
|||||||
/// @param name Optional name for the group.
|
/// @param name Optional name for the group.
|
||||||
///
|
///
|
||||||
RC_Channel(uint8_t ch_out) :
|
RC_Channel(uint8_t ch_out) :
|
||||||
radio_min (1100),
|
|
||||||
radio_trim(1500),
|
|
||||||
radio_max (1900),
|
|
||||||
scale_output(1.0),
|
scale_output(1.0),
|
||||||
_filter(false),
|
_filter(false),
|
||||||
_reverse(1),
|
|
||||||
_dead_zone(0),
|
|
||||||
_high(1),
|
_high(1),
|
||||||
_ch_out(ch_out) {}
|
_ch_out(ch_out) {}
|
||||||
|
|
||||||
|
@ -11,7 +11,7 @@ const AP_Param::GroupInfo RC_Channel_aux::var_info[] PROGMEM = {
|
|||||||
// @Description: Setting this to Disabled(0) will disable this output, any other value will enable the corresponding function
|
// @Description: Setting this to Disabled(0) will disable this output, any other value will enable the corresponding function
|
||||||
// @Values: 0:Disabled,1:Manual,2:Flap,3:Flap_auto,4:Aileron,5:flaperon,6:mount_pan,7:mount_tilt,8:mount_roll,9:mount_open,10:camera_trigger,11:release
|
// @Values: 0:Disabled,1:Manual,2:Flap,3:Flap_auto,4:Aileron,5:flaperon,6:mount_pan,7:mount_tilt,8:mount_roll,9:mount_open,10:camera_trigger,11:release
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("FUNCTION", 1, RC_Channel_aux, function),
|
AP_GROUPINFO("FUNCTION", 1, RC_Channel_aux, function, 0),
|
||||||
|
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
};
|
};
|
||||||
|
@ -23,8 +23,7 @@ public:
|
|||||||
/// @param name Optional name for the group.
|
/// @param name Optional name for the group.
|
||||||
///
|
///
|
||||||
RC_Channel_aux(uint8_t ch_out) :
|
RC_Channel_aux(uint8_t ch_out) :
|
||||||
RC_Channel(ch_out),
|
RC_Channel(ch_out)
|
||||||
function (0)
|
|
||||||
{}
|
{}
|
||||||
|
|
||||||
typedef enum
|
typedef enum
|
||||||
|
@ -15,14 +15,14 @@
|
|||||||
|
|
||||||
// table of user settable parameters
|
// table of user settable parameters
|
||||||
const AP_Param::GroupInfo SITL::var_info[] PROGMEM = {
|
const AP_Param::GroupInfo SITL::var_info[] PROGMEM = {
|
||||||
AP_GROUPINFO("BARO_RND", 0, SITL, baro_noise),
|
AP_GROUPINFO("BARO_RND", 0, SITL, baro_noise, 3),
|
||||||
AP_GROUPINFO("GYR_RND", 1, SITL, gyro_noise),
|
AP_GROUPINFO("GYR_RND", 1, SITL, gyro_noise, 30),
|
||||||
AP_GROUPINFO("ACC_RND", 2, SITL, accel_noise),
|
AP_GROUPINFO("ACC_RND", 2, SITL, accel_noise, 3),
|
||||||
AP_GROUPINFO("MAG_RND", 3, SITL, mag_noise),
|
AP_GROUPINFO("MAG_RND", 3, SITL, mag_noise, 10),
|
||||||
AP_GROUPINFO("GPS_DISABLE",4, SITL, gps_disable),
|
AP_GROUPINFO("GPS_DISABLE",4, SITL, gps_disable, 0),
|
||||||
AP_GROUPINFO("DRIFT_SPEED",5, SITL, drift_speed),
|
AP_GROUPINFO("DRIFT_SPEED",5, SITL, drift_speed, 0.2),
|
||||||
AP_GROUPINFO("DRIFT_TIME", 6, SITL, drift_time),
|
AP_GROUPINFO("DRIFT_TIME", 6, SITL, drift_time, 5),
|
||||||
AP_GROUPINFO("GPS_DELAY", 7, SITL, gps_delay),
|
AP_GROUPINFO("GPS_DELAY", 7, SITL, gps_delay, 4),
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
};
|
};
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user