mirror of
https://github.com/ArduPilot/ardupilot.git
synced 2025-12-06 21:45:52 +08:00
Blimp: rename airspeed methods on AHRS to include EAS or TAS
mixing these up has caused confusion in the past. "estimate" could also be confused as to mean "synthetic", when it will often come from a sensor.
This commit is contained in:
committed by
Thomas Watson
parent
99a727d907
commit
00f06c653c
@@ -85,7 +85,7 @@ void GCS_MAVLINK_Blimp::send_nav_controller_output() const
|
||||
float GCS_MAVLINK_Blimp::vfr_hud_airspeed() const
|
||||
{
|
||||
Vector3f airspeed_vec_bf;
|
||||
if (AP::ahrs().airspeed_vector_true(airspeed_vec_bf)) {
|
||||
if (AP::ahrs().airspeed_vector_TAS(airspeed_vec_bf)) {
|
||||
// we are running the EKF3 wind estimation code which can give
|
||||
// us an airspeed estimate
|
||||
return airspeed_vec_bf.length();
|
||||
@@ -348,7 +348,7 @@ MAV_LANDED_STATE GCS_MAVLINK_Blimp::landed_state() const
|
||||
void GCS_MAVLINK_Blimp::send_wind() const
|
||||
{
|
||||
Vector3f airspeed_vec_bf;
|
||||
if (!AP::ahrs().airspeed_vector_true(airspeed_vec_bf)) {
|
||||
if (!AP::ahrs().airspeed_vector_TAS(airspeed_vec_bf)) {
|
||||
// if we don't have an airspeed estimate then we don't have a
|
||||
// valid wind estimate on blimps
|
||||
return;
|
||||
@@ -365,7 +365,7 @@ void GCS_MAVLINK_Blimp::send_wind() const
|
||||
uint8_t GCS_MAVLINK_Blimp::high_latency_wind_speed() const
|
||||
{
|
||||
Vector3f airspeed_vec_bf;
|
||||
if (!AP::ahrs().airspeed_vector_true(airspeed_vec_bf)) {
|
||||
if (!AP::ahrs().airspeed_vector_TAS(airspeed_vec_bf)) {
|
||||
// if we don't have an airspeed estimate then we don't have a
|
||||
// valid wind estimate on blimps
|
||||
return 0;
|
||||
@@ -378,7 +378,7 @@ uint8_t GCS_MAVLINK_Blimp::high_latency_wind_speed() const
|
||||
uint8_t GCS_MAVLINK_Blimp::high_latency_wind_direction() const
|
||||
{
|
||||
Vector3f airspeed_vec_bf;
|
||||
if (!AP::ahrs().airspeed_vector_true(airspeed_vec_bf)) {
|
||||
if (!AP::ahrs().airspeed_vector_TAS(airspeed_vec_bf)) {
|
||||
// if we don't have an airspeed estimate then we don't have a
|
||||
// valid wind estimate on blimps
|
||||
return 0;
|
||||
|
||||
Reference in New Issue
Block a user