Skip to content

Commit

Permalink
SITL: move simulated height_agl into fdm structure
Browse files Browse the repository at this point in the history
allows value to be shipped via multicast to simulated peripherals
  • Loading branch information
peterbarker authored and tridge committed Jan 8, 2024
1 parent c583edc commit 3a37796
Show file tree
Hide file tree
Showing 2 changed files with 5 additions and 4 deletions.
2 changes: 1 addition & 1 deletion libraries/SITL/SIM_Aircraft.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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:
Expand Down
7 changes: 4 additions & 3 deletions libraries/SITL/SITL.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -152,9 +156,6 @@ class SIM {
// 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[];
Expand Down

0 comments on commit 3a37796

Please sign in to comment.