diff --git a/libraries/AP_Airspeed/AP_Airspeed.cpp b/libraries/AP_Airspeed/AP_Airspeed.cpp index 5add2aeec7..bc6ad0e310 100644 --- a/libraries/AP_Airspeed/AP_Airspeed.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed.cpp @@ -20,25 +20,25 @@ const AP_Param::GroupInfo AP_Airspeed::var_info[] PROGMEM = { // @DisplayName: Airspeed enable // @Description: enable airspeed sensor // @Values: 0:Disable,1:Enable - AP_GROUPINFO("ENABLE", 0, AP_Airspeed, _enable), + AP_GROUPINFO("ENABLE", 0, AP_Airspeed, _enable, 1), // @Param: USE // @DisplayName: Airspeed use // @Description: use airspeed for flight control // @Values: 0:Use,1:Don't Use - AP_GROUPINFO("USE", 1, AP_Airspeed, _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), + AP_GROUPINFO("OFFSET", 2, AP_Airspeed, _offset, 0), // @Param: RATIO // @DisplayName: Airspeed ratio // @Description: Airspeed calibration ratio // @Increment: 0.1 - AP_GROUPINFO("RATIO", 3, AP_Airspeed, _ratio), + AP_GROUPINFO("RATIO", 3, AP_Airspeed, _ratio, 0), AP_GROUPEND }; diff --git a/libraries/AP_Baro/AP_Baro.cpp b/libraries/AP_Baro/AP_Baro.cpp index c226cb785d..68dab0208c 100644 --- a/libraries/AP_Baro/AP_Baro.cpp +++ b/libraries/AP_Baro/AP_Baro.cpp @@ -21,13 +21,13 @@ const AP_Param::GroupInfo AP_Baro::var_info[] PROGMEM = { // @DisplayName: Absolute Pressure // @Description: calibrated ground pressure // @Increment: 1 - AP_GROUPINFO("ABS_PRESS", 2, AP_Baro, _ground_pressure), + AP_GROUPINFO("ABS_PRESS", 2, AP_Baro, _ground_pressure, 0), // @Param: ABS_PRESS // @DisplayName: ground temperature // @Description: calibrated ground temperature // @Increment: 1 - AP_GROUPINFO("TEMP", 3, AP_Baro, _ground_temperature), + AP_GROUPINFO("TEMP", 3, AP_Baro, _ground_temperature, 0), AP_GROUPEND }; diff --git a/libraries/AP_Camera/AP_Camera.cpp b/libraries/AP_Camera/AP_Camera.cpp index b67ac43e66..0048b5d693 100644 --- a/libraries/AP_Camera/AP_Camera.cpp +++ b/libraries/AP_Camera/AP_Camera.cpp @@ -17,7 +17,7 @@ const AP_Param::GroupInfo AP_Camera::var_info[] PROGMEM = { // @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 // @User: Standard - AP_GROUPINFO("TRIGG_TYPE", 0, AP_Camera, trigger_type), + AP_GROUPINFO("TRIGG_TYPE", 0, AP_Camera, trigger_type, 0), AP_GROUPEND }; diff --git a/libraries/AP_Camera/AP_Camera.h b/libraries/AP_Camera/AP_Camera.h index 33425069cb..b571afda03 100644 --- a/libraries/AP_Camera/AP_Camera.h +++ b/libraries/AP_Camera/AP_Camera.h @@ -22,8 +22,7 @@ public: wp_distance_min (10), keep_cam_trigg_active_cycles (0), thr_pic (0), // timer variable for throttle_pic - camtrig (83), // PK6 chosen as it not near anything so safer for soldering - trigger_type (0) + camtrig (83) // PK6 chosen as it not near anything so safer for soldering {} // single entry point to take pictures diff --git a/libraries/AP_Compass/Compass.cpp b/libraries/AP_Compass/Compass.cpp index 7a96b6cf76..422e665001 100644 --- a/libraries/AP_Compass/Compass.cpp +++ b/libraries/AP_Compass/Compass.cpp @@ -3,11 +3,11 @@ const AP_Param::GroupInfo Compass::var_info[] PROGMEM = { // index 0 was used for the old orientation matrix - AP_GROUPINFO("OFS", 1, Compass, _offset), - AP_GROUPINFO("DEC", 2, Compass, _declination), - AP_GROUPINFO("LEARN", 3, Compass, _learn), // true if learning calibration - AP_GROUPINFO("USE", 4, Compass, _use_for_yaw), // true if used for DCM yaw - AP_GROUPINFO("AUTODEC",5, Compass, _auto_declination), + AP_GROUPINFO("OFS", 1, Compass, _offset, 0), + AP_GROUPINFO("DEC", 2, Compass, _declination, 0), + AP_GROUPINFO("LEARN", 3, Compass, _learn, 1), // true if learning calibration + AP_GROUPINFO("USE", 4, Compass, _use_for_yaw, 1), // true if used for DCM yaw + AP_GROUPINFO("AUTODEC",5, Compass, _auto_declination, 1), AP_GROUPEND }; @@ -18,10 +18,6 @@ const AP_Param::GroupInfo Compass::var_info[] PROGMEM = { Compass::Compass(void) : product_id(AP_COMPASS_TYPE_UNKNOWN), _orientation(ROTATION_NONE), - _declination (0.0), - _learn(1), - _use_for_yaw(1), - _auto_declination(1), _null_init_done(false) { } diff --git a/libraries/AP_IMU/IMU.cpp b/libraries/AP_IMU/IMU.cpp index 8da7ce22e8..969ecc3e85 100644 --- a/libraries/AP_IMU/IMU.cpp +++ b/libraries/AP_IMU/IMU.cpp @@ -3,8 +3,8 @@ // this allows the sensor calibration to be saved to EEPROM const AP_Param::GroupInfo IMU::var_info[] PROGMEM = { - AP_GROUPINFO("CAL", 0, IMU, _sensor_cal), - AP_GROUPINFO("PRODUCT_ID", 1, IMU, _product_id), + AP_GROUPINFO("CAL", 0, IMU, _sensor_cal, 0), + AP_GROUPINFO("PRODUCT_ID", 1, IMU, _product_id, 0), AP_GROUPEND }; diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_Oilpan.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_Oilpan.cpp index feda81b6dc..5417495fa9 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_Oilpan.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_Oilpan.cpp @@ -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 = { // index 0 was used for the old orientation matrix - AP_GROUPINFO("XH", 0, AP_InertialSensor_Oilpan, _x_high), - AP_GROUPINFO("XL", 1, AP_InertialSensor_Oilpan, _x_low), - AP_GROUPINFO("YH", 2, AP_InertialSensor_Oilpan, _y_high), - AP_GROUPINFO("YL", 3, AP_InertialSensor_Oilpan, _y_low), - AP_GROUPINFO("ZH", 4, AP_InertialSensor_Oilpan, _z_high), - AP_GROUPINFO("ZL", 5, AP_InertialSensor_Oilpan, _z_low), + AP_GROUPINFO("XH", 0, AP_InertialSensor_Oilpan, _x_high, 2465), + AP_GROUPINFO("XL", 1, AP_InertialSensor_Oilpan, _x_low, 1617), + AP_GROUPINFO("YH", 2, AP_InertialSensor_Oilpan, _y_high, 2465), + AP_GROUPINFO("YL", 3, AP_InertialSensor_Oilpan, _y_low, 1617), + AP_GROUPINFO("ZH", 4, AP_InertialSensor_Oilpan, _z_high, 2465), + AP_GROUPINFO("ZL", 5, AP_InertialSensor_Oilpan, _z_low, 1617), AP_GROUPEND }; @@ -52,12 +52,6 @@ const AP_Param::GroupInfo AP_InertialSensor_Oilpan::var_info[] PROGMEM = { /* ------ Public functions -------------------------------------------*/ 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) { _gyro.x = 0; diff --git a/libraries/AP_Limits/AP_Limit_Altitude.cpp b/libraries/AP_Limits/AP_Limit_Altitude.cpp index f07a4318ff..80a198a890 100644 --- a/libraries/AP_Limits/AP_Limit_Altitude.cpp +++ b/libraries/AP_Limits/AP_Limit_Altitude.cpp @@ -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 // @Values: 0:Disabled,1:Enabled // @User: Standard - AP_GROUPINFO("ALT_ON", 0, AP_Limit_Altitude, _enabled), + AP_GROUPINFO("ALT_ON", 0, AP_Limit_Altitude, _enabled, 0), // @Param: ALT_REQD // @DisplayName: Require altitude // @Description: Setting this to Enabled(1) will make being inside the altitude a required check before arming the vehicle. // @Values: 0:Disabled,1:Enabled // @User: Standard - AP_GROUPINFO("ALT_REQ", 1, AP_Limit_Altitude, _required), + AP_GROUPINFO("ALT_REQ", 1, AP_Limit_Altitude, _required, 0), // @Param: ALT_MIN // @DisplayName: Minimum Altitude @@ -31,7 +31,7 @@ const AP_Param::GroupInfo AP_Limit_Altitude::var_info[] PROGMEM = { // @Range: 0 250000 // @Increment: 1 // @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 // @DisplayName: Maximum Altitude @@ -40,7 +40,7 @@ const AP_Param::GroupInfo AP_Limit_Altitude::var_info[] PROGMEM = { // @Range: 0 250000 // @Increment: 1 // @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 }; diff --git a/libraries/AP_Limits/AP_Limit_GPSLock.cpp b/libraries/AP_Limits/AP_Limit_GPSLock.cpp index 19457eb442..60367e522c 100644 --- a/libraries/AP_Limits/AP_Limit_GPSLock.cpp +++ b/libraries/AP_Limits/AP_Limit_GPSLock.cpp @@ -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 // @Values: 0:Disabled,1:Enabled // @User: Standard - AP_GROUPINFO("GPSLCK_ON", 0, AP_Limit_GPSLock, _enabled), + AP_GROUPINFO("GPSLCK_ON", 0, AP_Limit_GPSLock, _enabled, 0), // @Param: GPSLCK_REQ // @DisplayName: Require gpslock // @Description: Setting this to Enabled(1) will make being inside the gpslock a required check before arming the vehicle. // @Values: 0:Disabled,1:Enabled // @User: Standard - AP_GROUPINFO("GPSLCK_REQ", 1, AP_Limit_GPSLock, _required), + AP_GROUPINFO("GPSLCK_REQ", 1, AP_Limit_GPSLock, _required, 0), AP_GROUPEND }; diff --git a/libraries/AP_Limits/AP_Limit_Geofence.cpp b/libraries/AP_Limits/AP_Limit_Geofence.cpp index c60fe735c0..8be11cd3e0 100644 --- a/libraries/AP_Limits/AP_Limit_Geofence.cpp +++ b/libraries/AP_Limits/AP_Limit_Geofence.cpp @@ -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 // @Values: 0:Disabled,1:Enabled // @User: Standard - AP_GROUPINFO("FNC_ON", 0, AP_Limit_Geofence, _enabled), + AP_GROUPINFO("FNC_ON", 0, AP_Limit_Geofence, _enabled, 0), // @Param: FNC_REQ // @DisplayName: Require Geofence // @Description: Setting this to Enabled(1) will make being inside the geofence a required check before arming the vehicle. // @Values: 0:Disabled,1:Enabled // @User: Standard - AP_GROUPINFO("FNC_REQ", 1, AP_Limit_Geofence, _required), + AP_GROUPINFO("FNC_REQ", 1, AP_Limit_Geofence, _required, 0), // @Param: FNC_SMPL // @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 // @Values: 0:Disabled,1:Enabled // @User: Standard - AP_GROUPINFO("FNC_SMPL", 2, AP_Limit_Geofence, _simple), + AP_GROUPINFO("FNC_SMPL", 2, AP_Limit_Geofence, _simple, 0), // @Param: FNC_RAD // @DisplayName: Require Geofence @@ -37,9 +37,9 @@ const AP_Param::GroupInfo AP_Limit_Geofence::var_info[] PROGMEM = { // @Range: 0 32767 // @Increment: 1 // @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 diff --git a/libraries/AP_Limits/AP_Limits.cpp b/libraries/AP_Limits/AP_Limits.cpp index b9b2505970..7cf4e92dde 100644 --- a/libraries/AP_Limits/AP_Limits.cpp +++ b/libraries/AP_Limits/AP_Limits.cpp @@ -15,42 +15,42 @@ const AP_Param::GroupInfo AP_Limits::var_info[] PROGMEM = { // @Description: Setting this to Enabled(1) will enable the limits system // @Values: 0:Disabled,1:Enabled // @User: Standard - AP_GROUPINFO("ENABLED", 0, AP_Limits, _enabled), + AP_GROUPINFO("ENABLED", 0, AP_Limits, _enabled, 0), // @Param: REQUIRED // @DisplayName: Limits Library Required // @Description: Setting this to 1 will enable the limits pre-arm checklist // @Values: 0:Disabled,1:Enabled // @User: Standard - AP_GROUPINFO("REQUIRED", 1, AP_Limits, _required), + AP_GROUPINFO("REQUIRED", 1, AP_Limits, _required, 0), // @Param: DEBUG // @DisplayName: Enable Limits Debug // @Description: Setting this to 1 will turn on debugging messages on the console and via MAVLink STATUSTEXT messages // @Values: 0:Disabled,1:Enabled // @User: Standard - AP_GROUPINFO("DEBUG", 2, AP_Limits, _debug), + AP_GROUPINFO("DEBUG", 2, AP_Limits, _debug, 0), // @Param: 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 // @Values: 0:Disabled,1-255:Seconds before returning control // @User: Standard - AP_GROUPINFO("SAFETIME", 3, AP_Limits, _safetime), + AP_GROUPINFO("SAFETIME", 3, AP_Limits, _safetime, 0), // @Param: CHANNEL // @DisplayName: Limits Channel // @Description: Channel for Limits on/off control. If channel exceeds LIMITS_ENABLE_PWM, it turns limits on, and vice-versa. // @Range: 1-8 // @User: Standard - AP_GROUPINFO("CHANNEL", 4, AP_Limits, _channel), + AP_GROUPINFO("CHANNEL", 4, AP_Limits, _channel, 0), // @Param: RECMODE // @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. // @Values: 0:RTL mode, 1: Bounce mode // @User: Standard - AP_GROUPINFO("RECMODE", 5, AP_Limits, _recmode), + AP_GROUPINFO("RECMODE", 5, AP_Limits, _recmode, 0), AP_GROUPEND }; diff --git a/libraries/AP_Motors/AP_Motors.cpp b/libraries/AP_Motors/AP_Motors.cpp index 02f414601d..fbde225531 100644 --- a/libraries/AP_Motors/AP_Motors.cpp +++ b/libraries/AP_Motors/AP_Motors.cpp @@ -12,13 +12,12 @@ // parameters for the motor class 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 }; // 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 ) : - top_bottom_ratio(AP_MOTORS_TOP_BOTTOM_RATIO), _rc(rc_out), _rc_roll(rc_roll), _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) { uint8_t i; + + top_bottom_ratio = AP_MOTORS_TOP_BOTTOM_RATIO; // initialise motor map if( APM_version == AP_MOTORS_APM1 ) { diff --git a/libraries/AP_Motors/AP_MotorsHeli.cpp b/libraries/AP_Motors/AP_MotorsHeli.cpp index 43d74f7a69..b7f42e19e4 100644 --- a/libraries/AP_Motors/AP_MotorsHeli.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli.cpp @@ -20,7 +20,7 @@ const AP_Param::GroupInfo AP_MotorsHeli::var_info[] PROGMEM = { // @Units: Degrees // @User: Standard // @Increment: 1 - AP_GROUPINFO("SV1_POS", 1, AP_MotorsHeli, servo1_pos), + AP_GROUPINFO("SV1_POS", 1, AP_MotorsHeli, servo1_pos, -60), // @Param: SV2_POS // @DisplayName: Servo 2 Position @@ -29,7 +29,7 @@ const AP_Param::GroupInfo AP_MotorsHeli::var_info[] PROGMEM = { // @Units: Degrees // @User: Standard // @Increment: 1 - AP_GROUPINFO("SV2_POS", 2, AP_MotorsHeli, servo2_pos), + AP_GROUPINFO("SV2_POS", 2, AP_MotorsHeli, servo2_pos, 60), // @Param: SV3_POS // @DisplayName: Servo 3 Position @@ -38,7 +38,7 @@ const AP_Param::GroupInfo AP_MotorsHeli::var_info[] PROGMEM = { // @Units: Degrees // @User: Standard // @Increment: 1 - AP_GROUPINFO("SV3_POS", 3, AP_MotorsHeli, servo3_pos), + AP_GROUPINFO("SV3_POS", 3, AP_MotorsHeli, servo3_pos, 180), // @Param: ROL_MAX // @DisplayName: Maximum Roll Angle @@ -47,7 +47,7 @@ const AP_Param::GroupInfo AP_MotorsHeli::var_info[] PROGMEM = { // @Units: Degrees // @Increment: 1 // @User: Advanced - AP_GROUPINFO("ROL_MAX", 4, AP_MotorsHeli, roll_max), + AP_GROUPINFO("ROL_MAX", 4, AP_MotorsHeli, roll_max, 4500), // @Param: PIT_MAX // @DisplayName: Maximum Pitch Angle @@ -56,7 +56,7 @@ const AP_Param::GroupInfo AP_MotorsHeli::var_info[] PROGMEM = { // @Units: Degrees // @Increment: 1 // @User: Advanced - AP_GROUPINFO("PIT_MAX", 5, AP_MotorsHeli, pitch_max), + AP_GROUPINFO("PIT_MAX", 5, AP_MotorsHeli, pitch_max, 4500), // @Param: COL_MIN // @DisplayName: Collective Pitch Minimum @@ -65,7 +65,7 @@ const AP_Param::GroupInfo AP_MotorsHeli::var_info[] PROGMEM = { // @Units: PWM // @Increment: 1 // @User: Standard - AP_GROUPINFO("COL_MIN", 6, AP_MotorsHeli, collective_min), + AP_GROUPINFO("COL_MIN", 6, AP_MotorsHeli, collective_min, 1250), // @Param: COL_MAX // @DisplayName: Collective Pitch Maximum @@ -74,7 +74,7 @@ const AP_Param::GroupInfo AP_MotorsHeli::var_info[] PROGMEM = { // @Units: PWM // @Increment: 1 // @User: Standard - AP_GROUPINFO("COL_MAX", 7, AP_MotorsHeli, collective_max), + AP_GROUPINFO("COL_MAX", 7, AP_MotorsHeli, collective_max, 1750), // @Param: COL_MID // @DisplayName: Collective Pitch Mid-Point @@ -83,20 +83,20 @@ const AP_Param::GroupInfo AP_MotorsHeli::var_info[] PROGMEM = { // @Units: PWM // @Increment: 1 // @User: Standard - AP_GROUPINFO("COL_MID", 8, AP_MotorsHeli, collective_mid), + AP_GROUPINFO("COL_MID", 8, AP_MotorsHeli, collective_mid, 1500), // @Param: GYR_ENABLE // @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. // @Values: 0:Disabled,1:Enabled // @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 // @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". // @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 // @DisplayName: External Gyro Gain @@ -105,14 +105,14 @@ const AP_Param::GroupInfo AP_MotorsHeli::var_info[] PROGMEM = { // @Units: PWM // @Increment: 1 // @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 // @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. // @Values: 0:Disabled,1:Enabled // @User: Standard - AP_GROUPINFO("SV_MAN", 12, AP_MotorsHeli, servo_manual), + AP_GROUPINFO("SV_MAN", 12, AP_MotorsHeli, servo_manual, 0), // @Param: PHANG // @DisplayName: Swashplate Phase Angle Compensation @@ -121,13 +121,13 @@ const AP_Param::GroupInfo AP_MotorsHeli::var_info[] PROGMEM = { // @Units: Degrees // @User: Advanced // @Increment: 1 - AP_GROUPINFO("PHANG", 13, AP_MotorsHeli, phase_angle), + AP_GROUPINFO("PHANG", 13, AP_MotorsHeli, phase_angle, 0), // @Param: COLYAW // @DisplayName: Collective-Yaw Mixing // @Description: This is a feed-forward compensation to automatically add rudder input when collective pitch is increased. // @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 // @DisplayName: External Motor Governor Setpoint @@ -136,7 +136,7 @@ const AP_Param::GroupInfo AP_MotorsHeli::var_info[] PROGMEM = { // @Units: PWM // @Increment: 10 // @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 }; @@ -549,4 +549,4 @@ void AP_MotorsHeli::ext_esc_control() default: break; } -}; \ No newline at end of file +}; diff --git a/libraries/AP_Motors/AP_MotorsHeli.h b/libraries/AP_Motors/AP_MotorsHeli.h index 509403709a..996065c9ae 100644 --- a/libraries/AP_Motors/AP_MotorsHeli.h +++ b/libraries/AP_Motors/AP_MotorsHeli.h @@ -67,28 +67,14 @@ public: _servo_2(swash_servo_2), _servo_3(swash_servo_3), _servo_4(yaw_servo), - _rc_8(rc_8), - swash_type(AP_MOTORS_HELI_SWASH_CCPM), - servo1_pos (-60), - servo2_pos (60), - servo3_pos (180), - collective_min (1250), - collective_max (1750), - 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_8(rc_8) + { + throttle_mid = 0; + _roll_scaler = 1; + _pitch_scaler = 1; + _collective_scalar = 1; + _swash_initialised = false; + }; RC_Channel *_servo_1; RC_Channel *_servo_2; @@ -171,4 +157,4 @@ protected: }; -#endif // AP_MOTORSHELI \ No newline at end of file +#endif // AP_MOTORSHELI diff --git a/libraries/AP_Mount/AP_Mount.cpp b/libraries/AP_Mount/AP_Mount.cpp index d762e373da..75f94b6c32 100644 --- a/libraries/AP_Mount/AP_Mount.cpp +++ b/libraries/AP_Mount/AP_Mount.cpp @@ -11,7 +11,7 @@ const AP_Param::GroupInfo AP_Mount::var_info[] PROGMEM = { // @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), // 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 // @DisplayName: Mount retract angles @@ -20,7 +20,7 @@ const AP_Param::GroupInfo AP_Mount::var_info[] PROGMEM = { // @Range: -18000 17999 // @Increment: 1 // @User: Standard - AP_GROUPINFO("RETRACT", 1, AP_Mount, _retract_angles), + AP_GROUPINFO("RETRACT", 1, AP_Mount, _retract_angles, 0), // @Param: NEUTRAL // @DisplayName: Mount neutral angles @@ -29,7 +29,7 @@ const AP_Param::GroupInfo AP_Mount::var_info[] PROGMEM = { // @Range: -18000 17999 // @Increment: 1 // @User: Standard - AP_GROUPINFO("NEUTRAL", 2, AP_Mount, _neutral_angles), + AP_GROUPINFO("NEUTRAL", 2, AP_Mount, _neutral_angles, 0), // @Param: CONTROL // @DisplayName: Mount control angles @@ -38,35 +38,35 @@ const AP_Param::GroupInfo AP_Mount::var_info[] PROGMEM = { // @Range: -18000 17999 // @Increment: 1 // @User: Standard - AP_GROUPINFO("CONTROL", 3, AP_Mount, _control_angles), + AP_GROUPINFO("CONTROL", 3, AP_Mount, _control_angles, 0), // @Param: STAB_ROLL // @DisplayName: Stabilize mount roll // @Description:enable roll stabilisation relative to Earth // @Values: 0:Disabled,1:Enabled // @User: Standard - AP_GROUPINFO("STAB_ROLL", 4, AP_Mount, _stab_roll), + AP_GROUPINFO("STAB_ROLL", 4, AP_Mount, _stab_roll, 0), // @Param: STAB_TILT // @DisplayName: Stabilize mount tilt // @Description: enable tilt (pitch) stabilisation relative to Earth // @Values: 0:Disabled,1:Enabled // @User: Standard - AP_GROUPINFO("STAB_TILT", 5, AP_Mount, _stab_tilt), + AP_GROUPINFO("STAB_TILT", 5, AP_Mount, _stab_tilt, 0), // @Param: STAB_PAN // @DisplayName: Stabilize mount pan // @Description: enable pan (yaw) stabilisation relative to Earth // @Values: 0:Disabled,1:Enabled // @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 // @DisplayName: roll RC input channel // @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 // @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 // @DisplayName: Minimum roll angle @@ -75,7 +75,7 @@ const AP_Param::GroupInfo AP_Mount::var_info[] PROGMEM = { // @Range: -18000 17999 // @Increment: 1 // @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 // @DisplayName: Maximum roll angle @@ -84,14 +84,14 @@ const AP_Param::GroupInfo AP_Mount::var_info[] PROGMEM = { // @Range: -18000 17999 // @Increment: 1 // @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 // @DisplayName: tilt (pitch) RC input channel // @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 // @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 // @DisplayName: Minimum tilt angle @@ -100,7 +100,7 @@ const AP_Param::GroupInfo AP_Mount::var_info[] PROGMEM = { // @Range: -18000 17999 // @Increment: 1 // @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 // @DisplayName: Maximum tilt angle @@ -109,14 +109,14 @@ const AP_Param::GroupInfo AP_Mount::var_info[] PROGMEM = { // @Range: -18000 17999 // @Increment: 1 // @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 // @DisplayName: pan (yaw) RC input channel // @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 // @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 // @DisplayName: Minimum pan angle @@ -125,7 +125,7 @@ const AP_Param::GroupInfo AP_Mount::var_info[] PROGMEM = { // @Range: -18000 17999 // @Increment: 1 // @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 // @DisplayName: Maximum pan angle @@ -134,7 +134,7 @@ const AP_Param::GroupInfo AP_Mount::var_info[] PROGMEM = { // @Range: -18000 17999 // @Increment: 1 // @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 // @Param: JOYSTICK_SPEED diff --git a/libraries/RC_Channel/RC_Channel.cpp b/libraries/RC_Channel/RC_Channel.cpp index afa22eef54..9836df5870 100644 --- a/libraries/RC_Channel/RC_Channel.cpp +++ b/libraries/RC_Channel/RC_Channel.cpp @@ -36,7 +36,7 @@ const AP_Param::GroupInfo RC_Channel::var_info[] PROGMEM = { // @Range: 800 2200 // @Increment: 1 // @User: Advanced - AP_GROUPINFO("MIN", 0, RC_Channel, radio_min), + AP_GROUPINFO("MIN", 0, RC_Channel, radio_min, 1100), // @Param: TRIM // @DisplayName: RC trim PWM @@ -45,7 +45,7 @@ const AP_Param::GroupInfo RC_Channel::var_info[] PROGMEM = { // @Range: 800 2200 // @Increment: 1 // @User: Advanced - AP_GROUPINFO("TRIM", 1, RC_Channel, radio_trim), + AP_GROUPINFO("TRIM", 1, RC_Channel, radio_trim, 1500), // @Param: MAX // @DisplayName: RC max PWM @@ -54,20 +54,20 @@ const AP_Param::GroupInfo RC_Channel::var_info[] PROGMEM = { // @Range: 800 2200 // @Increment: 1 // @User: Advanced - AP_GROUPINFO("MAX", 2, RC_Channel, radio_max), + AP_GROUPINFO("MAX", 2, RC_Channel, radio_max, 1900), // @Param: REV // @DisplayName: RC reverse // @Description: Reverse servo operation. Ignored on APM1 unless dip-switches are disabled. // @Values: -1:Reversed,1:Normal // @User: Advanced - AP_GROUPINFO("REV", 3, RC_Channel, _reverse), + AP_GROUPINFO("REV", 3, RC_Channel, _reverse, 1), // @Param: DZ // @DisplayName: RC dead-zone // @Description: dead zone around trim. // @User: Advanced - AP_GROUPINFO("DZ", 4, RC_Channel, _dead_zone), + AP_GROUPINFO("DZ", 4, RC_Channel, _dead_zone, 0), AP_GROUPEND }; diff --git a/libraries/RC_Channel/RC_Channel.h b/libraries/RC_Channel/RC_Channel.h index afaa3cc490..a7cc39b623 100644 --- a/libraries/RC_Channel/RC_Channel.h +++ b/libraries/RC_Channel/RC_Channel.h @@ -19,13 +19,8 @@ class RC_Channel{ /// @param name Optional name for the group. /// RC_Channel(uint8_t ch_out) : - radio_min (1100), - radio_trim(1500), - radio_max (1900), scale_output(1.0), _filter(false), - _reverse(1), - _dead_zone(0), _high(1), _ch_out(ch_out) {} diff --git a/libraries/RC_Channel/RC_Channel_aux.cpp b/libraries/RC_Channel/RC_Channel_aux.cpp index 0502d81c32..2d633f06c2 100644 --- a/libraries/RC_Channel/RC_Channel_aux.cpp +++ b/libraries/RC_Channel/RC_Channel_aux.cpp @@ -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 // @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 - AP_GROUPINFO("FUNCTION", 1, RC_Channel_aux, function), + AP_GROUPINFO("FUNCTION", 1, RC_Channel_aux, function, 0), AP_GROUPEND }; diff --git a/libraries/RC_Channel/RC_Channel_aux.h b/libraries/RC_Channel/RC_Channel_aux.h index a32927780f..b5cfd5bf81 100644 --- a/libraries/RC_Channel/RC_Channel_aux.h +++ b/libraries/RC_Channel/RC_Channel_aux.h @@ -23,8 +23,7 @@ public: /// @param name Optional name for the group. /// RC_Channel_aux(uint8_t ch_out) : - RC_Channel(ch_out), - function (0) + RC_Channel(ch_out) {} typedef enum diff --git a/libraries/SITL/SITL.cpp b/libraries/SITL/SITL.cpp index fdf362cda2..d89f76d80d 100644 --- a/libraries/SITL/SITL.cpp +++ b/libraries/SITL/SITL.cpp @@ -15,14 +15,14 @@ // table of user settable parameters const AP_Param::GroupInfo SITL::var_info[] PROGMEM = { - AP_GROUPINFO("BARO_RND", 0, SITL, baro_noise), - AP_GROUPINFO("GYR_RND", 1, SITL, gyro_noise), - AP_GROUPINFO("ACC_RND", 2, SITL, accel_noise), - AP_GROUPINFO("MAG_RND", 3, SITL, mag_noise), - AP_GROUPINFO("GPS_DISABLE",4, SITL, gps_disable), - AP_GROUPINFO("DRIFT_SPEED",5, SITL, drift_speed), - AP_GROUPINFO("DRIFT_TIME", 6, SITL, drift_time), - AP_GROUPINFO("GPS_DELAY", 7, SITL, gps_delay), + AP_GROUPINFO("BARO_RND", 0, SITL, baro_noise, 3), + AP_GROUPINFO("GYR_RND", 1, SITL, gyro_noise, 30), + AP_GROUPINFO("ACC_RND", 2, SITL, accel_noise, 3), + AP_GROUPINFO("MAG_RND", 3, SITL, mag_noise, 10), + AP_GROUPINFO("GPS_DISABLE",4, SITL, gps_disable, 0), + AP_GROUPINFO("DRIFT_SPEED",5, SITL, drift_speed, 0.2), + AP_GROUPINFO("DRIFT_TIME", 6, SITL, drift_time, 5), + AP_GROUPINFO("GPS_DELAY", 7, SITL, gps_delay, 4), AP_GROUPEND };