12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758 |
- #include <AP_HAL/AP_HAL.h>
- #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
- #include "AP_IRLock_SITL.h"
- #include "AP_AHRS/AP_AHRS.h"
- void AP_IRLock_SITL::init(int8_t bus)
- {
- _sitl = AP::sitl();
- _sitl->precland_sim._type.set_and_notify(SITL::SIM_Precland::PreclandType::PRECLAND_TYPE_CONE);
- }
- bool AP_IRLock_SITL::update()
- {
-
- _flags.healthy = _sitl->precland_sim.healthy();
- if (!_flags.healthy) {
- return false;
- }
- 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);
- _last_timestamp = _sitl->precland_sim.last_update_ms();
- _last_update_ms = _last_timestamp;
- _target_info.timestamp = _last_timestamp;
- _target_info.pos_x = real_position.y;
- _target_info.pos_y = -real_position.x;
- _target_info.pos_z = real_position.z;
- return true;
- }
- return false;
- }
- #endif
|