mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Blimp: Add support for HIGH_LATENCY2 messages
This commit is contained in:
parent
7f0bd06e8b
commit
2821e6815e
@ -647,3 +647,31 @@ void GCS_MAVLINK_Blimp::send_wind() const
|
|||||||
wind.length(),
|
wind.length(),
|
||||||
wind.z);
|
wind.z);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if HAL_HIGH_LATENCY2_ENABLED
|
||||||
|
uint8_t GCS_MAVLINK_Blimp::high_latency_wind_speed() const
|
||||||
|
{
|
||||||
|
Vector3f airspeed_vec_bf;
|
||||||
|
if (!AP::ahrs().airspeed_vector_true(airspeed_vec_bf)) {
|
||||||
|
// if we don't have an airspeed estimate then we don't have a
|
||||||
|
// valid wind estimate on blimps
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
// return units are m/s*5
|
||||||
|
const Vector3f wind = AP::ahrs().wind_estimate();
|
||||||
|
return wind.length() * 5;
|
||||||
|
}
|
||||||
|
|
||||||
|
uint8_t GCS_MAVLINK_Blimp::high_latency_wind_direction() const
|
||||||
|
{
|
||||||
|
Vector3f airspeed_vec_bf;
|
||||||
|
if (!AP::ahrs().airspeed_vector_true(airspeed_vec_bf)) {
|
||||||
|
// if we don't have an airspeed estimate then we don't have a
|
||||||
|
// valid wind estimate on blimps
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
const Vector3f wind = AP::ahrs().wind_estimate();
|
||||||
|
// need to convert -180->180 to 0->360/2
|
||||||
|
return wrap_360(degrees(atan2f(-wind.y, -wind.x))) / 2;
|
||||||
|
}
|
||||||
|
#endif // HAL_HIGH_LATENCY2_ENABLED
|
@ -76,4 +76,9 @@ private:
|
|||||||
POSZ = 7,
|
POSZ = 7,
|
||||||
POSYAW = 8,
|
POSYAW = 8,
|
||||||
};
|
};
|
||||||
|
|
||||||
|
#if HAL_HIGH_LATENCY2_ENABLED
|
||||||
|
uint8_t high_latency_wind_speed() const override;
|
||||||
|
uint8_t high_latency_wind_direction() const override;
|
||||||
|
#endif // HAL_HIGH_LATENCY2_ENABLED
|
||||||
};
|
};
|
||||||
|
Loading…
Reference in New Issue
Block a user