diff --git a/ArduPlane/GCS_Mavlink.pde b/ArduPlane/GCS_Mavlink.pde index e67fe6de46..abad8dbf44 100644 --- a/ArduPlane/GCS_Mavlink.pde +++ b/ArduPlane/GCS_Mavlink.pde @@ -465,7 +465,7 @@ static void NOINLINE send_raw_imu2(mavlink_channel_t chan) chan, micros(), pressure/100.0, - (pressure - g.ground_pressure)/100.0, + (pressure - barometer.get_ground_pressure())/100.0, barometer.get_temperature()); } diff --git a/ArduPlane/Parameters.h b/ArduPlane/Parameters.h index f5aa002203..6f5e4bcfa8 100644 --- a/ArduPlane/Parameters.h +++ b/ArduPlane/Parameters.h @@ -91,9 +91,12 @@ public: k_param_imu = 130, // sensor calibration k_param_altitude_mix, k_param_airspeed_ratio, - k_param_ground_temperature, - k_param_ground_pressure, - k_param_compass_enabled, + + // ground_pressure and ground_temperature removed + // do not re-use 133 and 134 unless format_version + // is changed + + k_param_compass_enabled = 135, k_param_compass, k_param_battery_monitoring, k_param_volt_div_ratio, @@ -105,6 +108,7 @@ public: k_param_airspeed_enabled, k_param_ahrs, // AHRS group k_param_airspeed_use, + k_param_barometer, // barometer ground calibration // // 150: Navigation parameters @@ -333,8 +337,6 @@ public: AP_Int16 min_gndspeed; AP_Int16 pitch_trim; AP_Int16 RTL_altitude; - AP_Int16 ground_temperature; - AP_Int32 ground_pressure; AP_Int8 compass_enabled; AP_Int16 angle_of_attack; AP_Int8 battery_monitoring; // 0=disabled, 3=voltage only, 4=voltage and current @@ -454,8 +456,6 @@ public: pitch_trim (0), RTL_altitude (ALT_HOLD_HOME_CM), FBWB_min_altitude (ALT_HOLD_FBW_CM), - ground_temperature (0), - ground_pressure (0), compass_enabled (MAGNETOMETER), flap_1_percent (FLAP_1_PERCENT), flap_1_speed (FLAP_1_SPEED), diff --git a/ArduPlane/Parameters.pde b/ArduPlane/Parameters.pde index 9f957c2fa0..4fbea8dee0 100644 --- a/ArduPlane/Parameters.pde +++ b/ArduPlane/Parameters.pde @@ -234,8 +234,6 @@ static const AP_Param::Info var_info[] PROGMEM = { GSCALAR(pitch_trim, "TRIM_PITCH_CD"), GSCALAR(RTL_altitude, "ALT_HOLD_RTL"), GSCALAR(FBWB_min_altitude, "ALT_HOLD_FBWCM"), - GSCALAR(ground_temperature, "GND_TEMP"), - GSCALAR(ground_pressure, "GND_ABS_PRESS"), // @Param: MAG_ENABLE // @DisplayName: Enable Compass @@ -277,6 +275,10 @@ static const AP_Param::Info var_info[] PROGMEM = { // @User: Advanced GSCALAR(airspeed_use, "ARSPD_USE"), + // barometer ground calibration. The GND_ prefix is chosen for + // compatibility with previous releases of ArduPlane + GOBJECT(barometer, "GND_", AP_Baro), + #if CAMERA == ENABLED // @Group: CAM_ // @Path: ../libraries/AP_Camera/AP_Camera.cpp diff --git a/ArduPlane/sensors.pde b/ArduPlane/sensors.pde index ea7e4925e4..1fe1ca8f67 100644 --- a/ArduPlane/sensors.pde +++ b/ArduPlane/sensors.pde @@ -8,8 +8,6 @@ void ReadSCP1000(void) {} static void init_barometer(void) { barometer.calibrate(mavlink_delay); - g.ground_pressure.set_and_save(barometer.get_ground_pressure()); - g.ground_temperature.set_and_save(barometer.get_ground_temperature() / 10.0f); ahrs.set_barometer(&barometer); gcs_send_text_P(SEVERITY_LOW, PSTR("barometer calibration complete")); } diff --git a/libraries/AP_Baro/AP_Baro.cpp b/libraries/AP_Baro/AP_Baro.cpp index d7cff85326..626e6f9481 100644 --- a/libraries/AP_Baro/AP_Baro.cpp +++ b/libraries/AP_Baro/AP_Baro.cpp @@ -12,6 +12,22 @@ #include #include +// table of user settable parameters +const AP_Param::GroupInfo AP_Baro::var_info[] PROGMEM = { + // @Param: ABS_PRESS + // @DisplayName: Absolute Pressure + // @Description: calibrated ground pressure + // @Increment: 1 + AP_GROUPINFO("ABS_PRESS", 0, AP_Baro, _ground_pressure), + + // @Param: ABS_PRESS + // @DisplayName: ground temperature + // @Description: calibrated ground temperature + // @Increment: 1 + AP_GROUPINFO("TEMP", 1, AP_Baro, _ground_temperature), + AP_GROUPEND +}; + // calibrate the barometer. This must be called at least once before // the altitude() or climb_rate() interfaces can be used void AP_Baro::calibrate(void (*callback)(unsigned long t)) diff --git a/libraries/AP_Baro/AP_Baro.h b/libraries/AP_Baro/AP_Baro.h index 764bc1f7e0..ec9f13194d 100644 --- a/libraries/AP_Baro/AP_Baro.h +++ b/libraries/AP_Baro/AP_Baro.h @@ -38,6 +38,8 @@ class AP_Baro int16_t get_ground_temperature(void) { return _ground_temperature.get(); } int32_t get_ground_pressure(void) { return _ground_pressure.get(); } + static const struct AP_Param::GroupInfo var_info[]; + protected: uint32_t _last_update;