mirror of https://github.com/ArduPilot/ardupilot
Tracker: tidy handling of barometer calibrations
This commit is contained in:
parent
1de68b78dc
commit
b862e4f3a8
|
@ -446,20 +446,16 @@ uint8_t GCS_MAVLINK_Tracker::sysid_my_gcs() const
|
|||
return tracker.g.sysid_my_gcs;
|
||||
}
|
||||
|
||||
MAV_RESULT GCS_MAVLINK_Tracker::_handle_command_preflight_calibration(const mavlink_command_long_t &packet)
|
||||
MAV_RESULT GCS_MAVLINK_Tracker::_handle_command_preflight_calibration_baro()
|
||||
{
|
||||
|
||||
if (is_equal(packet.param3,1.0f)) {
|
||||
tracker.init_barometer(false);
|
||||
MAV_RESULT ret = GCS_MAVLINK::_handle_command_preflight_calibration_baro();
|
||||
if (ret == MAV_RESULT_ACCEPTED) {
|
||||
// zero the altitude difference on next baro update
|
||||
tracker.nav_status.need_altitude_calibration = true;
|
||||
return MAV_RESULT_ACCEPTED;
|
||||
}
|
||||
|
||||
return GCS_MAVLINK::_handle_command_preflight_calibration(packet);
|
||||
return ret;
|
||||
}
|
||||
|
||||
|
||||
void GCS_MAVLINK_Tracker::handleMessage(mavlink_message_t* msg)
|
||||
{
|
||||
switch (msg->msgid) {
|
||||
|
|
|
@ -28,7 +28,7 @@ protected:
|
|||
|
||||
bool set_mode(uint8_t mode) override;
|
||||
|
||||
MAV_RESULT _handle_command_preflight_calibration(const mavlink_command_long_t &packet) override;
|
||||
MAV_RESULT _handle_command_preflight_calibration_baro() override;
|
||||
|
||||
private:
|
||||
|
||||
|
|
|
@ -221,7 +221,6 @@ private:
|
|||
void update_scan(void);
|
||||
bool servo_test_set_servo(uint8_t servo_num, uint16_t pwm);
|
||||
void read_radio();
|
||||
void init_barometer(bool full_calibration);
|
||||
void update_barometer(void);
|
||||
void update_ahrs();
|
||||
void update_compass(void);
|
||||
|
|
|
@ -1,16 +1,5 @@
|
|||
#include "Tracker.h"
|
||||
|
||||
void Tracker::init_barometer(bool full_calibration)
|
||||
{
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Calibrating barometer");
|
||||
if (full_calibration) {
|
||||
barometer.calibrate();
|
||||
} else {
|
||||
barometer.update_calibration();
|
||||
}
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Barometer calibration complete");
|
||||
}
|
||||
|
||||
// read the barometer and return the updated altitude in meters
|
||||
void Tracker::update_barometer(void)
|
||||
{
|
||||
|
|
|
@ -79,7 +79,7 @@ void Tracker::init_tracker()
|
|||
ins.init(scheduler.get_loop_rate_hz());
|
||||
ahrs.reset();
|
||||
|
||||
init_barometer(true);
|
||||
barometer.calibrate();
|
||||
|
||||
// initialise DataFlash library
|
||||
DataFlash.setVehicle_Startup_Log_Writer(FUNCTOR_BIND(&tracker, &Tracker::Log_Write_Vehicle_Startup_Messages, void));
|
||||
|
|
Loading…
Reference in New Issue