mirror of https://github.com/ArduPilot/ardupilot
AP_IRLock: convert SITL backends to double precision position
This commit is contained in:
parent
f209504a12
commit
4895a08ab2
|
@ -41,9 +41,9 @@ bool AP_IRLock_SITL::update()
|
|||
}
|
||||
|
||||
if (_sitl->precland_sim.last_update_ms() != _last_timestamp) {
|
||||
const Vector3f position = _sitl->precland_sim.get_target_position();
|
||||
const Matrix3f &body_to_ned = AP::ahrs().get_rotation_body_to_ned();
|
||||
const Vector3f real_position = body_to_ned.mul_transpose(-position);
|
||||
const Vector3d position = _sitl->precland_sim.get_target_position();
|
||||
const Matrix3d body_to_ned = AP::ahrs().get_rotation_body_to_ned().todouble();
|
||||
const Vector3d real_position = body_to_ned.mul_transpose(-position);
|
||||
_last_timestamp = _sitl->precland_sim.last_update_ms();
|
||||
_last_update_ms = _last_timestamp;
|
||||
_target_info.timestamp = _last_timestamp;
|
||||
|
|
Loading…
Reference in New Issue