Sub: tidy handling of barometer calibrations

This commit is contained in:
Peter Barker 2018-03-18 15:18:59 +11:00 committed by Francisco Ferreira
parent d58e2214d2
commit 05ee33d037
5 changed files with 11 additions and 16 deletions

View File

@ -861,16 +861,18 @@ void GCS_MAVLINK_Sub::handle_change_alt_request(AP_Mission::Mission_Command &cmd
// To-Do: update target altitude for loiter or waypoint controller depending upon nav mode
}
MAV_RESULT GCS_MAVLINK_Sub::_handle_command_preflight_calibration(const mavlink_command_long_t &packet)
MAV_RESULT GCS_MAVLINK_Sub::_handle_command_preflight_calibration_baro()
{
if (is_equal(packet.param3,1.0f)) {
if (!sub.sensor_health.depth || sub.motors.armed()) {
return MAV_RESULT_FAILED;
}
sub.init_barometer(true);
return MAV_RESULT_ACCEPTED;
if (!sub.sensor_health.depth) {
return MAV_RESULT_FAILED;
}
AP::baro().calibrate(true);
return MAV_RESULT_ACCEPTED;
}
MAV_RESULT GCS_MAVLINK_Sub::_handle_command_preflight_calibration(const mavlink_command_long_t &packet)
{
if (is_equal(packet.param6,1.0f)) {
// compassmot calibration
//result = sub.mavlink_compassmot(chan);

View File

@ -28,6 +28,7 @@ protected:
bool set_mode(uint8_t mode) override;
MAV_RESULT _handle_command_preflight_calibration_baro() override;
MAV_RESULT _handle_command_preflight_calibration(const mavlink_command_long_t &packet) override;
private:

View File

@ -618,7 +618,6 @@ private:
JSButton* get_button(uint8_t index);
void default_js_buttons(void);
void clear_input_hold();
void init_barometer(bool save);
void read_barometer(void);
void init_rangefinder(void);
void read_rangefinder(void);

View File

@ -1,12 +1,5 @@
#include "Sub.h"
void Sub::init_barometer(bool save)
{
gcs().send_text(MAV_SEVERITY_INFO, "Calibrating barometer");
barometer.calibrate(save);
gcs().send_text(MAV_SEVERITY_INFO, "Barometer calibration complete");
}
// return barometric altitude in centimeters
void Sub::read_barometer(void)
{

View File

@ -143,7 +143,7 @@ void Sub::init_ardupilot()
#endif
// Init baro and determine if we have external (depth) pressure sensor
init_barometer(false);
barometer.calibrate(false);
barometer.update();
for (uint8_t i = 0; i < barometer.num_instances(); i++) {