mirror of https://github.com/ArduPilot/ardupilot
AP_OpticalFlow: move simulated height_agl into fdm structure
allows value to be shipped via multicast to simulated peripherals
This commit is contained in:
parent
7201eae4ed
commit
b1311d6d25
|
@ -64,9 +64,9 @@ void AP_OpticalFlow_SITL::update(void)
|
|||
|
||||
// estimate range to centre of image
|
||||
float range;
|
||||
if (rotmat.c.z > 0.05f && _sitl->height_agl > 0) {
|
||||
if (rotmat.c.z > 0.05f && _sitl->state.height_agl > 0) {
|
||||
Vector3f relPosSensorEF = rotmat * posRelSensorBF;
|
||||
range = (_sitl->height_agl - relPosSensorEF.z) / rotmat.c.z;
|
||||
range = (_sitl->state.height_agl - relPosSensorEF.z) / rotmat.c.z;
|
||||
} else {
|
||||
range = 1e38f;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue