mirror of https://github.com/ArduPilot/ardupilot
AP_Proximity: move simulated height_agl into fdm structure
allows value to be shipped via multicast to simulated peripherals
This commit is contained in:
parent
b1311d6d25
commit
c583edc34b
|
@ -131,7 +131,7 @@ float AP_Proximity_SITL::distance_min() const
|
||||||
bool AP_Proximity_SITL::get_upward_distance(float &distance) const
|
bool AP_Proximity_SITL::get_upward_distance(float &distance) const
|
||||||
{
|
{
|
||||||
// return distance to fence altitude
|
// return distance to fence altitude
|
||||||
distance = MAX(0.0f, fence_alt_max->get() - sitl->height_agl);
|
distance = MAX(0.0f, fence_alt_max->get() - sitl->state.height_agl);
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue