SITL: move simulated height_agl into fdm structure

allows value to be shipped via multicast to simulated peripherals
This commit is contained in:
Peter Barker 2024-01-08 13:07:46 +11:00 committed by Andrew Tridgell
parent c583edc34b
commit 3a37796eb2
2 changed files with 5 additions and 4 deletions

View File

@ -490,7 +490,7 @@ float Aircraft::perpendicular_distance_to_rangefinder_surface() const
{
switch ((Rotation)sitl->sonar_rot.get()) {
case Rotation::ROTATION_PITCH_270:
return sitl->height_agl;
return sitl->state.height_agl;
case ROTATION_NONE ... ROTATION_YAW_315:
return sitl->measure_distance_at_angle_bf(location, sitl->sonar_rot.get()*45);
default:

View File

@ -92,6 +92,10 @@ struct sitl_fdm {
// earthframe wind, from backends that know it
Vector3f wind_ef;
// AGL altitude, usually derived from the terrain database in simulation:
float height_agl;
};
// number of rc output channels
@ -152,9 +156,6 @@ public:
// throttle when motors are active
float throttle;
// height above ground
float height_agl;
static const struct AP_Param::GroupInfo var_info[];
static const struct AP_Param::GroupInfo var_info2[];
static const struct AP_Param::GroupInfo var_info3[];