SITL: move simulated height_agl into fdm structure
allows value to be shipped via multicast to simulated peripherals
This commit is contained in:
parent
c583edc34b
commit
3a37796eb2
@ -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:
|
||||
|
@ -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[];
|
||||
|
Loading…
Reference in New Issue
Block a user