mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Avoidance: correct ADSB vertical velocity conversion
This commit is contained in:
parent
16c11fc4fa
commit
85e57a3bd8
@ -272,9 +272,9 @@ void AP_Avoidance::get_adsb_samples()
|
|||||||
MAV_COLLISION_SRC_ADSB,
|
MAV_COLLISION_SRC_ADSB,
|
||||||
src_id,
|
src_id,
|
||||||
loc,
|
loc,
|
||||||
vehicle.info.heading/100.0f,
|
vehicle.info.heading * 0.01,
|
||||||
vehicle.info.hor_velocity/100.0f,
|
vehicle.info.hor_velocity * 0.01,
|
||||||
-vehicle.info.ver_velocity/1000.0f); // convert mm-up to m-down
|
-vehicle.info.ver_velocity * 0.01); // convert cm-up to m-down
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user