mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Plane: move sending of airspeed_autocal into AP_AirSpeed
This commit is contained in:
parent
b4af1dae0f
commit
bd444d97dc
@ -347,7 +347,6 @@ void Plane::airspeed_ratio_update(void)
|
||||
}
|
||||
const Vector3f &vg = gps.velocity();
|
||||
airspeed.update_calibration(vg, aparm.airspeed_max);
|
||||
gcs_send_airspeed_calibration(vg);
|
||||
}
|
||||
|
||||
|
||||
|
@ -1416,14 +1416,6 @@ void Plane::mavlink_delay_cb()
|
||||
logger.EnableWrites(true);
|
||||
}
|
||||
|
||||
/*
|
||||
send airspeed calibration data
|
||||
*/
|
||||
void Plane::gcs_send_airspeed_calibration(const Vector3f &vg)
|
||||
{
|
||||
gcs().send_airspeed_calibration(vg);
|
||||
}
|
||||
|
||||
void GCS_MAVLINK_Plane::handle_mission_set_current(AP_Mission &mission, mavlink_message_t *msg)
|
||||
{
|
||||
plane.auto_state.next_wp_crosstrack = false;
|
||||
|
@ -1,17 +1,6 @@
|
||||
#include "GCS_Plane.h"
|
||||
#include "Plane.h"
|
||||
|
||||
void GCS_Plane::send_airspeed_calibration(const Vector3f &vg)
|
||||
{
|
||||
for (uint8_t i=0; i<num_gcs(); i++) {
|
||||
if (_chan[i].initialised) {
|
||||
if (HAVE_PAYLOAD_SPACE((mavlink_channel_t)i, AIRSPEED_AUTOCAL)) {
|
||||
plane.airspeed.log_mavlink_send((mavlink_channel_t)i, vg);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// update error mask of sensors and subsystems. The mask
|
||||
// uses the MAV_SYS_STATUS_* values from mavlink. If a bit is set
|
||||
// then it indicates that the sensor or subsystem is present but
|
||||
|
@ -20,8 +20,6 @@ public:
|
||||
return _chan[ofs];
|
||||
};
|
||||
|
||||
void send_airspeed_calibration(const Vector3f &vg);
|
||||
|
||||
protected:
|
||||
|
||||
void update_sensor_status_flags(void) override;
|
||||
|
@ -796,8 +796,6 @@ private:
|
||||
|
||||
void send_aoa_ssa(mavlink_channel_t chan);
|
||||
|
||||
void gcs_send_airspeed_calibration(const Vector3f &vg);
|
||||
|
||||
void Log_Write_Fast(void);
|
||||
void Log_Write_Attitude(void);
|
||||
void Log_Write_Performance();
|
||||
|
Loading…
Reference in New Issue
Block a user