Path: blob/master/libraries/AC_PrecLand/AC_PrecLand_SITL.cpp
9633 views
#include <AP_HAL/AP_HAL.h>1#include "AC_PrecLand_SITL.h"23#if AC_PRECLAND_SITL_ENABLED45#include "AP_AHRS/AP_AHRS.h"6// init - perform initialisation of this backend7void AC_PrecLand_SITL::init()8{9_sitl = AP::sitl();10}1112// update - give chance to driver to get updates from sensor13void AC_PrecLand_SITL::update()14{15_state.healthy = _sitl->precland_sim.healthy();1617if (_state.healthy && _sitl->precland_sim.last_update_ms() != _los_meas.time_ms) {18const Vector3d position = _sitl->precland_sim.get_target_position();19const Matrix3d body_to_ned = AP::ahrs().get_rotation_body_to_ned().todouble();20_los_meas.vec_unit = body_to_ned.mul_transpose(-position).tofloat();21_distance_to_target = _sitl->precland_sim.option_enabled(SITL::SIM_Precland::Option::ENABLE_TARGET_DISTANCE) ? _los_meas.vec_unit.length() : 0.0f;22_los_meas.vec_unit /= _los_meas.vec_unit.length();23_los_meas.frame = AC_PrecLand::VectorFrame::BODY_FRD;2425if (_frontend._orient != Rotation::ROTATION_PITCH_270) {26// rotate body frame vector based on orientation27// this is done to have homogeneity among backends28// frontend rotates it back to get correct body frame vector29_los_meas.vec_unit.rotate_inverse(_frontend._orient);30_los_meas.vec_unit.rotate_inverse(ROTATION_PITCH_90);31}3233_los_meas.valid = true;34_los_meas.time_ms = _sitl->precland_sim.last_update_ms();35} else {36_los_meas.valid = false;37}3839_los_meas.valid = _los_meas.valid && AP_HAL::millis() - _los_meas.time_ms <= 1000;40}4142#endif // AC_PRECLAND_SITL_ENABLED434445