Path: blob/master/libraries/AC_PrecLand/AC_PrecLand.cpp
9460 views
#include "AC_PrecLand_config.h"12#if AC_PRECLAND_ENABLED34#include "AC_PrecLand.h"5#include <AP_HAL/AP_HAL.h>6#include <AP_AHRS/AP_AHRS.h>78#include "AC_PrecLand_Backend.h"9#include "AC_PrecLand_MAVLink.h"10#include "AC_PrecLand_IRLock.h"11#include "AC_PrecLand_SITL_Gazebo.h"12#include "AC_PrecLand_SITL.h"13#include <AP_Logger/AP_Logger.h>14#include <GCS_MAVLink/GCS.h>15#include <AP_Vehicle/AP_Vehicle_Type.h>1617extern const AP_HAL::HAL& hal;1819#if APM_BUILD_TYPE(APM_BUILD_Rover)20# define AC_PRECLAND_ORIENT_DEFAULT Rotation::ROTATION_NONE21#else22# define AC_PRECLAND_ORIENT_DEFAULT Rotation::ROTATION_PITCH_27023#endif2425static const uint32_t EKF_INIT_TIME_MS = 2000; // EKF initialisation requires this many milliseconds of good sensor data26static const uint32_t EKF_INIT_SENSOR_MIN_UPDATE_MS = 500; // Sensor must update within this many ms during EKF init, else init will fail27static const uint32_t LANDING_TARGET_TIMEOUT_MS = 2000; // Sensor must update within this many ms, else prec landing will be switched off28static const uint32_t LANDING_TARGET_LOST_TIMEOUT_MS = 180000; // Target will be considered as "lost" if the last known location of the target is more than this many ms ago29static const float LANDING_TARGET_LOST_DIST_THRESH_M = 30; // If the last known location of the landing target is beyond this many meters, then we will consider it lost3031const AP_Param::GroupInfo AC_PrecLand::var_info[] = {32// @Param: ENABLED33// @DisplayName: Precision Land enabled/disabled34// @Description: Precision Land enabled/disabled35// @Values: 0:Disabled, 1:Enabled36// @User: Advanced37AP_GROUPINFO_FLAGS("ENABLED", 0, AC_PrecLand, _enabled, 0, AP_PARAM_FLAG_ENABLE),3839// @Param: TYPE40// @DisplayName: Precision Land Type41// @Description: Precision Land Type42// @Values: 0:None, 1:MAVLink, 2:IRLock, 3:SITL_Gazebo, 4:SITL43// @User: Advanced44AP_GROUPINFO("TYPE", 1, AC_PrecLand, _type, 0),4546// @Param: YAW_ALIGN47// @DisplayName: Sensor yaw alignment48// @Description: Yaw angle from body x-axis to sensor x-axis.49// @Range: 0 3600050// @Increment: 1051// @User: Advanced52// @Units: cdeg53AP_GROUPINFO("YAW_ALIGN", 2, AC_PrecLand, _yaw_align_cd, 0),5455// @Param: LAND_OFS_X56// @DisplayName: Land offset forward57// @Description: Desired landing position of the camera forward of the target in vehicle body frame58// @Range: -20 2059// @Increment: 160// @User: Advanced61// @Units: cm62AP_GROUPINFO("LAND_OFS_X", 3, AC_PrecLand, _land_ofs_cm_x, 0),6364// @Param: LAND_OFS_Y65// @DisplayName: Land offset right66// @Description: desired landing position of the camera right of the target in vehicle body frame67// @Range: -20 2068// @Increment: 169// @User: Advanced70// @Units: cm71AP_GROUPINFO("LAND_OFS_Y", 4, AC_PrecLand, _land_ofs_cm_y, 0),7273// @Param: EST_TYPE74// @DisplayName: Precision Land Estimator Type75// @Description: Specifies the estimation method to be used76// @Values: 0:RawSensor, 1:KalmanFilter77// @User: Advanced78AP_GROUPINFO("EST_TYPE", 5, AC_PrecLand, _estimator_type, 1),7980// @Param: ACC_P_NSE81// @DisplayName: Kalman Filter Accelerometer Noise82// @Description: Kalman Filter Accelerometer Noise, higher values weight the input from the camera more, accels less83// @Range: 0.5 584// @User: Advanced85AP_GROUPINFO("ACC_P_NSE", 6, AC_PrecLand, _accel_noise, 2.5f),8687// @Param: CAM_POS_X88// @DisplayName: Camera X position offset89// @Description: X position of the camera in body frame. Positive X is forward of the origin.90// @Units: m91// @Range: -5 592// @Increment: 0.0193// @User: Advanced9495// @Param: CAM_POS_Y96// @DisplayName: Camera Y position offset97// @Description: Y position of the camera in body frame. Positive Y is to the right of the origin.98// @Units: m99// @Range: -5 5100// @Increment: 0.01101// @User: Advanced102103// @Param: CAM_POS_Z104// @DisplayName: Camera Z position offset105// @Description: Z position of the camera in body frame. Positive Z is down from the origin.106// @Units: m107// @Range: -5 5108// @Increment: 0.01109// @User: Advanced110AP_GROUPINFO("CAM_POS", 7, AC_PrecLand, _cam_offset_m, 0.0f),111112// @Param: BUS113// @DisplayName: Sensor Bus114// @Description: Precland sensor bus for I2C sensors.115// @Values: -1:DefaultBus,0:InternalI2C,1:ExternalI2C116// @User: Advanced117AP_GROUPINFO("BUS", 8, AC_PrecLand, _bus, -1),118119// @Param: LAG120// @DisplayName: Precision Landing sensor lag121// @Description: Precision Landing sensor lag, to cope with variable landing_target latency122// @Range: 0.02 0.250123// @Increment: 1124// @Units: s125// @User: Advanced126// @RebootRequired: True127AP_GROUPINFO("LAG", 9, AC_PrecLand, _lag_s, 0.02f), // 20ms is the old default buffer size (8 frames @ 400hz/2.5ms)128129// @Param: XY_DIST_MAX130// @DisplayName: Precision Landing maximum distance to target before descending131// @Description: The vehicle will not start descending if the landing target is detected and it is further than this many meters away. Set 0 to always descend.132// @Range: 0 10133// @Units: m134// @User: Advanced135AP_GROUPINFO("XY_DIST_MAX", 10, AC_PrecLand, _xy_max_dist_desc_m, 2.5f),136137// @Param: STRICT138// @DisplayName: PrecLand strictness139// @Description: How strictly should the vehicle land on the target if target is lost140// @Values: 0: Land Vertically (Not strict), 1: Retry Landing(Normal Strictness), 2: Do not land (just Hover) (Very Strict)141AP_GROUPINFO("STRICT", 11, AC_PrecLand, _strict, 1),142143// @Param: RET_MAX144// @DisplayName: PrecLand Maximum number of retires for a failed landing145// @Description: PrecLand Maximum number of retires for a failed landing. Set to zero to disable landing retry.146// @Range: 0 10147// @Increment: 1148AP_GROUPINFO("RET_MAX", 12, AC_PrecLand, _retry_max, 4),149150// @Param: TIMEOUT151// @DisplayName: PrecLand retry timeout152// @Description: Time for which vehicle continues descend even if target is lost. After this time period, vehicle will attempt a landing retry depending on PLND_STRICT parameter.153// @Range: 0 20154// @Units: s155AP_GROUPINFO("TIMEOUT", 13, AC_PrecLand, _retry_timeout_s, 4),156157// @Param: RET_BEHAVE158// @DisplayName: PrecLand retry behaviour159// @Description: Prec Land will do the action selected by this parameter if a retry to a landing is needed160// @Values: 0: Go to the last location where landing target was detected, 1: Go towards the approximate location of the detected landing target161AP_GROUPINFO("RET_BEHAVE", 14, AC_PrecLand, _retry_behave, 0),162163// @Param: ALT_MIN164// @DisplayName: PrecLand minimum alt for retry165// @Description: Vehicle will continue landing vertically even if target is lost below this height. This needs a rangefinder to work. Set to zero to disable this.166// @Range: 0 5167// @Units: m168AP_GROUPINFO("ALT_MIN", 15, AC_PrecLand, _sensor_min_alt_m, 0.75),169170// @Param: ALT_MAX171// @DisplayName: PrecLand maximum alt for retry172// @Description: Vehicle will continue landing vertically until this height if target is not found. Below this height if landing target is not found, landing retry/failsafe might be attempted. This needs a rangefinder to work. Set to zero to disable this.173// @Range: 0 50174// @Units: m175AP_GROUPINFO("ALT_MAX", 16, AC_PrecLand, _sensor_max_alt_m, 8),176177// @Param: OPTIONS178// @DisplayName: Precision Landing Extra Options179// @Description: Precision Landing Extra Options180// @Bitmask: 0: Moving Landing Target, 1: Allow Precision Landing after manual reposition, 2: Maintain high speed in final descent181// @User: Advanced182AP_GROUPINFO("OPTIONS", 17, AC_PrecLand, _options, 0),183184// @Param{Rover,Copter}: ORIENT185// @DisplayName: Camera Orientation186// @Description: Orientation of camera/sensor on body187// @Values: 0:Forward, 4:Back, 25:Down188// @User: Advanced189// @RebootRequired: True190AP_GROUPINFO_FRAME("ORIENT", 18, AC_PrecLand, _orient, AC_PRECLAND_ORIENT_DEFAULT, AP_PARAM_FRAME_ROVER | AP_PARAM_FRAME_COPTER | AP_PARAM_FRAME_TRICOPTER | AP_PARAM_FRAME_HELI),191192AP_GROUPEND193};194195// Default constructor.196AC_PrecLand::AC_PrecLand()197{198if (_singleton != nullptr) {199AP_HAL::panic("AC_PrecLand must be singleton");200}201_singleton = this;202203// set parameters to defaults204AP_Param::setup_object_defaults(this, var_info);205}206207// perform any required initialisation of landing controllers208// update_rate_hz should be the rate at which the update method will be called in hz209void AC_PrecLand::init(uint16_t update_rate_hz)210{211// exit immediately if init has already been run212if (_backend != nullptr) {213return;214}215216// init as target TARGET_NEVER_SEEN, we will update this later217_current_target_state = TargetState::TARGET_NEVER_SEEN;218219// default health to false220_backend = nullptr;221_backend_state.healthy = false;222223// create inertial history buffer224// constrain lag parameter to be within bounds225_lag_s.set(constrain_float(_lag_s, 0.02f, 0.25f)); // must match LAG parameter range at line 124226227// calculate inertial buffer size from lag and minimum of main loop rate and update_rate_hz argument228const uint16_t inertial_buffer_size = MAX((uint16_t)roundf(_lag_s * update_rate_hz), 1);229230// instantiate ring buffer to hold inertial history, return on failure so no backends are created231_inertial_history = NEW_NOTHROW ObjectArray<inertial_data_frame_s>(inertial_buffer_size);232if (_inertial_history == nullptr) {233return;234}235236// instantiate backend based on type parameter237switch ((Type)(_type.get())) {238// no type defined239case Type::NONE:240default:241return;242// companion computer243#if AC_PRECLAND_MAVLINK_ENABLED244case Type::MAVLINK:245_backend = NEW_NOTHROW AC_PrecLand_MAVLink(*this, _backend_state);246break;247// IR Lock248#endif249#if AC_PRECLAND_IRLOCK_ENABLED250case Type::IRLOCK:251_backend = NEW_NOTHROW AC_PrecLand_IRLock(*this, _backend_state);252break;253#endif254#if AC_PRECLAND_SITL_GAZEBO_ENABLED255case Type::SITL_GAZEBO:256_backend = NEW_NOTHROW AC_PrecLand_SITL_Gazebo(*this, _backend_state);257break;258#endif259#if AC_PRECLAND_SITL_ENABLED260case Type::SITL:261_backend = NEW_NOTHROW AC_PrecLand_SITL(*this, _backend_state);262break;263#endif264}265266// init backend267if (_backend != nullptr) {268_backend->init();269}270271_approach_vector_body.x = 1;272_approach_vector_body.rotate(_orient);273}274275// update - give chance to driver to get updates from sensor276void AC_PrecLand::update(float rangefinder_alt_cm, bool rangefinder_alt_valid)277{278// exit immediately if not enabled279if (_backend == nullptr || _inertial_history == nullptr) {280return;281}282283// append current velocity and attitude correction into history buffer284struct inertial_data_frame_s inertial_data_newest;285const auto &_ahrs = AP::ahrs();286_ahrs.getCorrectedDeltaVelocityNED(inertial_data_newest.correctedVehicleDeltaVelocityNED, inertial_data_newest.dt);287inertial_data_newest.Tbn = _ahrs.get_rotation_body_to_ned();288Vector3f curr_vel;289nav_filter_status status;290if (!_ahrs.get_velocity_NED(curr_vel) || !_ahrs.get_filter_status(status)) {291inertial_data_newest.inertialNavVelocityValid = false;292} else {293inertial_data_newest.inertialNavVelocityValid = status.flags.horiz_vel;294}295curr_vel.z = -curr_vel.z; // NED to NEU296inertial_data_newest.inertialNavVelocity = curr_vel;297298inertial_data_newest.time_usec = AP_HAL::micros64();299_inertial_history->push_force(inertial_data_newest);300301const float rangefinder_alt_m = rangefinder_alt_cm*0.01f; //cm to meter302303// update estimator of target position304if (_backend != nullptr && _enabled) {305_backend->update();306run_estimator(rangefinder_alt_m, rangefinder_alt_valid);307}308309// check the status of the landing target location310check_target_status(rangefinder_alt_m, rangefinder_alt_valid);311312#if HAL_LOGGING_ENABLED313const uint32_t now = AP_HAL::millis();314if (now - _last_log_ms > 40) { // 25Hz315_last_log_ms = now;316Write_Precland();317}318#endif319}320321// check the status of the target322void AC_PrecLand::check_target_status(float rangefinder_alt_m, bool rangefinder_alt_valid)323{324if (target_acquired()) {325// target in sight326_current_target_state = TargetState::TARGET_FOUND;327// early return because we already know the status328return;329}330331// target not in sight332if (_current_target_state == TargetState::TARGET_FOUND ||333_current_target_state == TargetState::TARGET_RECENTLY_LOST) {334// we had target in sight, but not any more, i.e we have lost the target335_current_target_state = TargetState::TARGET_RECENTLY_LOST;336} else {337// we never had the target in sight338_current_target_state = TargetState::TARGET_NEVER_SEEN;339}340341// We definitely do not have the target in sight342// check if the precision landing sensor is supposed to be in range343// this needs a valid rangefinder to work344if (!check_if_sensor_in_range(rangefinder_alt_m, rangefinder_alt_valid)) {345// Target is not in range (vehicle is either too high or too low). Vehicle will not be attempting any sort of landing retries during this period346_current_target_state = TargetState::TARGET_OUT_OF_RANGE;347return;348}349350if (_current_target_state == TargetState::TARGET_RECENTLY_LOST) {351// check if it's nearby/found recently, else the status will be demoted to "TARGET_LOST"352Vector2p curr_pos_ne_m;353if (AP::ahrs().get_relative_position_NE_origin(curr_pos_ne_m)) {354const float dist_to_last_target_loc_xy = (curr_pos_ne_m - _last_target_pos_rel_origin_ned_m.xy()).length();355const float dist_to_last_loc_ne_m = (curr_pos_ne_m - _last_vehicle_pos_ned_m.xy()).length();356if ((AP_HAL::millis() - _last_valid_target_ms) > LANDING_TARGET_LOST_TIMEOUT_MS) {357// the target has not been seen for a long time358// might as well consider it as "never seen"359_current_target_state = TargetState::TARGET_NEVER_SEEN;360return;361}362363if ((dist_to_last_target_loc_xy > LANDING_TARGET_LOST_DIST_THRESH_M) || (dist_to_last_loc_ne_m > LANDING_TARGET_LOST_DIST_THRESH_M)) {364// the last known location of target is too far away365_current_target_state = TargetState::TARGET_NEVER_SEEN;366return;367}368}369}370}371372// Check if the landing target is supposed to be in sight based on the height of the vehicle from the ground373// This needs a valid rangefinder to work, if the min/max parameters are non zero374bool AC_PrecLand::check_if_sensor_in_range(float rangefinder_alt_m, bool rangefinder_alt_valid) const375{376if (is_zero(_sensor_max_alt_m) && is_zero(_sensor_min_alt_m)) {377// no sensor limits have been specified, assume sensor is always in range378return true;379}380381if (!rangefinder_alt_valid) {382// rangefinder isn't healthy. We might be at a very high altitude383return false;384}385386if (rangefinder_alt_m > _sensor_max_alt_m && !is_zero(_sensor_max_alt_m)) {387// this prevents triggering a retry when we are too far away from the target388return false;389}390391if (rangefinder_alt_m < _sensor_min_alt_m && !is_zero(_sensor_min_alt_m)) {392// this prevents triggering a retry when we are very close to the target393return false;394}395396// target should be in range397return true;398}399400// returns true when the landing target has been detected401bool AC_PrecLand::target_acquired()402{403if ((AP_HAL::millis()-_last_update_ms) > LANDING_TARGET_TIMEOUT_MS) {404if (_target_acquired) {405// just lost the landing target, inform the user. This message will only be sent once every time target is lost406GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "PrecLand: Target Lost");407}408// not had a sensor update since a long time409// probably lost the target410_estimator_initialized = false;411_target_acquired = false;412}413return _target_acquired;414}415416// returns target position relative to the EKF origin417bool AC_PrecLand::get_target_position_m(Vector2p& ret)418{419if (!target_acquired()) {420return false;421}422Vector2p curr_pos_ne_m;423if (!AP::ahrs().get_relative_position_NE_origin(curr_pos_ne_m)) {424return false;425}426ret.x = (_target_pos_rel_out_ne_m.x + curr_pos_ne_m.x);427ret.y = (_target_pos_rel_out_ne_m.y + curr_pos_ne_m.y);428return true;429}430431// returns target relative position as 3D vector432void AC_PrecLand::get_target_position_measurement_NED_m(Vector3f& ret)433{434ret = _target_pos_rel_meas_ned_m;435return;436}437438// returns target position relative to vehicle439bool AC_PrecLand::get_target_position_relative_NE_m(Vector2f& ret)440{441if (!target_acquired()) {442return false;443}444ret = _target_pos_rel_out_ne_m;445return true;446}447448// returns target velocity relative to vehicle449bool AC_PrecLand::get_target_velocity_relative_NE_ms(Vector2f& ret)450{451if (!target_acquired()) {452return false;453}454ret = _target_vel_rel_out_ne_ms;455return true;456}457458// get the absolute velocity of the vehicle459void AC_PrecLand::get_target_velocity_ms(const Vector2f& vehicle_velocity_ne_ms, Vector2f& target_vel_ne_ms)460{461if (!(_options & PLND_OPTION_MOVING_TARGET)) {462// the target should not be moving463target_vel_ne_ms.zero();464return;465}466if ((EstimatorType)_estimator_type.get() == EstimatorType::RAW_SENSOR) {467// We do not predict the velocity of the target in this case468// assume velocity to be zero469target_vel_ne_ms.zero();470return;471}472Vector2f target_vel_rel_ne_ms;473if (!get_target_velocity_relative_NE_ms(target_vel_rel_ne_ms)) {474// Don't know where the target is475// assume velocity to be zero476target_vel_ne_ms.zero();477return;478}479// return the absolute velocity480target_vel_ne_ms = target_vel_rel_ne_ms + vehicle_velocity_ne_ms;481}482483// handle_msg - Process a LANDING_TARGET mavlink message484void AC_PrecLand::handle_msg(const mavlink_landing_target_t &packet, uint32_t timestamp_ms)485{486// run backend update487if (_backend != nullptr) {488_backend->handle_msg(packet, timestamp_ms);489}490}491492//493// Private methods494//495496// run target position estimator497void AC_PrecLand::run_estimator(float rangefinder_alt_m, bool rangefinder_alt_valid)498{499_inertial_data_delayed = (*_inertial_history)[0];500501switch ((EstimatorType)_estimator_type.get()) {502case EstimatorType::RAW_SENSOR: {503// Return if there's any invalid velocity data504for (uint8_t i=0; i<_inertial_history->available(); i++) {505const struct inertial_data_frame_s *inertial_data = (*_inertial_history)[i];506if (!inertial_data->inertialNavVelocityValid) {507_target_acquired = false;508return;509}510}511512// Predict513if (target_acquired()) {514_target_pos_rel_est_ne_m.x -= _inertial_data_delayed->inertialNavVelocity.x * _inertial_data_delayed->dt;515_target_pos_rel_est_ne_m.y -= _inertial_data_delayed->inertialNavVelocity.y * _inertial_data_delayed->dt;516_target_vel_rel_est_ne_ms.x = -_inertial_data_delayed->inertialNavVelocity.x;517_target_vel_rel_est_ne_ms.y = -_inertial_data_delayed->inertialNavVelocity.y;518}519520// Update if a new Line-Of-Sight measurement is available521if (construct_pos_meas_using_rangefinder(rangefinder_alt_m, rangefinder_alt_valid)) {522if (!_estimator_initialized) {523GCS_SEND_TEXT(MAV_SEVERITY_INFO, "PrecLand: Target Found");524_estimator_initialized = true;525}526_target_pos_rel_est_ne_m.x = _target_pos_rel_meas_ned_m.x;527_target_pos_rel_est_ne_m.y = _target_pos_rel_meas_ned_m.y;528_target_vel_rel_est_ne_ms.x = -_inertial_data_delayed->inertialNavVelocity.x;529_target_vel_rel_est_ne_ms.y = -_inertial_data_delayed->inertialNavVelocity.y;530531_last_update_ms = AP_HAL::millis();532_target_acquired = true;533}534535// Output prediction536if (target_acquired()) {537run_output_prediction();538}539break;540}541case EstimatorType::KALMAN_FILTER: {542// Predict543if (target_acquired() || _estimator_initialized) {544const float& dt = _inertial_data_delayed->dt;545const Vector3f& vehicleDelVel = _inertial_data_delayed->correctedVehicleDeltaVelocityNED;546547_ekf_x.predict(dt, -vehicleDelVel.x, _accel_noise*dt);548_ekf_y.predict(dt, -vehicleDelVel.y, _accel_noise*dt);549}550551// Update if a new Line-Of-Sight measurement is available552if (construct_pos_meas_using_rangefinder(rangefinder_alt_m, rangefinder_alt_valid)) {553float xy_pos_var = sq(_target_pos_rel_meas_ned_m.z*(0.01f + 0.01f*AP::ahrs().get_gyro().length()) + 0.02f);554if (!_estimator_initialized) {555// Inform the user landing target has been found556GCS_SEND_TEXT(MAV_SEVERITY_INFO, "PrecLand: Target Found");557// start init of EKF. We will let the filter consume the data for a while before it available for consumption558// reset filter state559if (_inertial_data_delayed->inertialNavVelocityValid) {560_ekf_x.init(_target_pos_rel_meas_ned_m.x, xy_pos_var, -_inertial_data_delayed->inertialNavVelocity.x, sq(2.0f));561_ekf_y.init(_target_pos_rel_meas_ned_m.y, xy_pos_var, -_inertial_data_delayed->inertialNavVelocity.y, sq(2.0f));562} else {563_ekf_x.init(_target_pos_rel_meas_ned_m.x, xy_pos_var, 0.0f, sq(10.0f));564_ekf_y.init(_target_pos_rel_meas_ned_m.y, xy_pos_var, 0.0f, sq(10.0f));565}566_last_update_ms = AP_HAL::millis();567_estimator_init_ms = AP_HAL::millis();568// we have initialized the estimator but will not use the values for sometime so that EKF settles down569_estimator_initialized = true;570} else {571float NIS_x = _ekf_x.getPosNIS(_target_pos_rel_meas_ned_m.x, xy_pos_var);572float NIS_y = _ekf_y.getPosNIS(_target_pos_rel_meas_ned_m.y, xy_pos_var);573if (MAX(NIS_x, NIS_y) < 3.0f || _outlier_reject_count >= 3) {574_outlier_reject_count = 0;575_ekf_x.fusePos(_target_pos_rel_meas_ned_m.x, xy_pos_var);576_ekf_y.fusePos(_target_pos_rel_meas_ned_m.y, xy_pos_var);577_last_update_ms = AP_HAL::millis();578} else {579_outlier_reject_count++;580}581}582}583584// check EKF was properly initialized when the sensor detected a landing target585check_ekf_init_timeout();586587// Output prediction588if (target_acquired()) {589_target_pos_rel_est_ne_m.x = _ekf_x.getPos();590_target_pos_rel_est_ne_m.y = _ekf_y.getPos();591_target_vel_rel_est_ne_ms.x = _ekf_x.getVel();592_target_vel_rel_est_ne_ms.y = _ekf_y.getVel();593594run_output_prediction();595}596break;597}598}599}600601602// check if EKF got the time to initialize when the landing target was first detected603// Expects sensor to update within EKF_INIT_SENSOR_MIN_UPDATE_MS milliseconds till EKF_INIT_TIME_MS milliseconds have passed604// after this period landing target estimates can be used by vehicle605void AC_PrecLand::check_ekf_init_timeout()606{607if (!target_acquired() && _estimator_initialized) {608// we have just got the target in sight609if (AP_HAL::millis()-_last_update_ms > EKF_INIT_SENSOR_MIN_UPDATE_MS) {610// we have lost the target, not enough readings to initialize the EKF611_estimator_initialized = false;612GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "PrecLand: Init Failed");613} else if (AP_HAL::millis()-_estimator_init_ms > EKF_INIT_TIME_MS) {614// the target has been visible for a while, EKF should now have initialized to a good value615_target_acquired = true;616GCS_SEND_TEXT(MAV_SEVERITY_INFO, "PrecLand: Init Complete");617}618}619}620621// get 3D vector from vehicle to target and frame. returns true on success, false on failure622bool AC_PrecLand::retrieve_los_meas(Vector3f& target_vec_unit, VectorFrame& frame)623{624const uint32_t los_meas_time_ms = _backend->los_meas_time_ms();625if ((los_meas_time_ms != _last_backend_los_meas_ms) && _backend->get_los_meas(target_vec_unit, frame)) {626_last_backend_los_meas_ms = los_meas_time_ms;627if (!is_zero(_yaw_align_cd)) {628// Apply sensor yaw alignment rotation629target_vec_unit.rotate_xy(cd_to_rad(_yaw_align_cd));630}631632// rotate vector based on sensor orientation to get correct body frame vector633if (_orient != ROTATION_PITCH_270) {634// by default, the vector is constructed downwards in body frame635// hence, we do not do any rotation if the orientation is downwards636// if it is some other orientation, we first bring the vector to forward637// and then we rotate it to desired orientation638// because the rotations are measured with respect to a vector pointing towards front in body frame639// for eg, if orientation is back, i.e., ROTATION_YAW_180,640// the vector is first brought to front and then rotation by YAW 180 to take it to the back of vehicle641target_vec_unit.rotate(ROTATION_PITCH_90); // bring vector to front642target_vec_unit.rotate(_orient); // rotate it to desired orientation643}644645return true;646}647return false;648}649650// If a new measurement was retrieved, sets _target_pos_rel_meas_ned_m and returns true651bool AC_PrecLand::construct_pos_meas_using_rangefinder(float rangefinder_alt_m, bool rangefinder_alt_valid)652{653Vector3f target_vec_unit;654VectorFrame target_vec_frame;655if (retrieve_los_meas(target_vec_unit, target_vec_frame)) {656_inertial_data_delayed = (*_inertial_history)[0];657658// sanity check vector is pointing in the right direction659const bool target_vec_valid = target_vec_unit.projected(_approach_vector_body).dot(_approach_vector_body) > 0.0f;660661// calculate 3D vector to target in NED frame662Vector3f target_vec_unit_ned;663switch (target_vec_frame) {664case VectorFrame::BODY_FRD:665// convert to NED666target_vec_unit_ned = _inertial_data_delayed->Tbn * target_vec_unit;667break;668case VectorFrame::LOCAL_FRD:669// rotate vector using delayed yaw670float roll_rad, pitch_rad, yaw_rad;671_inertial_data_delayed->Tbn.to_euler(&roll_rad, &pitch_rad, &yaw_rad);672target_vec_unit_ned = target_vec_unit;673target_vec_unit_ned.rotate_xy(-yaw_rad);674break;675}676677const Vector3f approach_vector_NED_m = _inertial_data_delayed->Tbn * _approach_vector_body;678const bool alt_valid = (rangefinder_alt_valid && rangefinder_alt_m > 0.0f) || (_backend->distance_to_target() > 0.0f);679if (target_vec_valid && alt_valid) {680// distance to target and distance to target along approach vector681float dist_to_target_m, dist_to_target_along_av_m;682// figure out ned camera orientation w.r.t its offset683Vector3f cam_pos_ned_m;684if (!_cam_offset_m.get().is_zero()) {685// user has specifed offset for camera686// take its height into account while calculating distance687cam_pos_ned_m = _inertial_data_delayed->Tbn * _cam_offset_m;688}689if (_backend->distance_to_target() > 0.0f) {690// sensor has provided distance to landing target691dist_to_target_m = _backend->distance_to_target();692} else {693// sensor only knows the horizontal location of the landing target694// rely on rangefinder for the vertical target695dist_to_target_along_av_m = MAX(rangefinder_alt_m - cam_pos_ned_m.projected(approach_vector_NED_m).length(), 0.0f);696dist_to_target_m = dist_to_target_along_av_m / target_vec_unit_ned.projected(approach_vector_NED_m).length();697}698699// Compute camera position relative to IMU700const Vector3f accel_pos_ned_m = _inertial_data_delayed->Tbn * AP::ins().get_imu_pos_offset(AP::ahrs().get_primary_accel_index());701const Vector3f cam_pos_ned_rel_imu_ned_m = cam_pos_ned_m - accel_pos_ned_m;702703// Compute target position relative to IMU704_target_pos_rel_meas_ned_m = (target_vec_unit_ned * dist_to_target_m) + cam_pos_ned_rel_imu_ned_m;705706// store the current relative down position so that if we need to retry landing, we know at this height landing target can be found707const AP_AHRS &_ahrs = AP::ahrs();708Vector3p pos_NED;709if (_ahrs.get_relative_position_NED_origin(pos_NED)) {710_last_target_pos_rel_origin_ned_m.z = pos_NED.z;711_last_vehicle_pos_ned_m = pos_NED;712}713return true;714}715}716return false;717}718719// calculate target's position and velocity relative to the vehicle (used as input to position controller)720// results are stored in_target_pos_rel_out_NE, _target_vel_rel_out_ne_ms721void AC_PrecLand::run_output_prediction()722{723_target_pos_rel_out_ne_m = _target_pos_rel_est_ne_m;724_target_vel_rel_out_ne_ms = _target_vel_rel_est_ne_ms;725726// Predict forward from delayed time horizon727for (uint8_t i=1; i<_inertial_history->available(); i++) {728const struct inertial_data_frame_s *inertial_data = (*_inertial_history)[i];729_target_vel_rel_out_ne_ms.x -= inertial_data->correctedVehicleDeltaVelocityNED.x;730_target_vel_rel_out_ne_ms.y -= inertial_data->correctedVehicleDeltaVelocityNED.y;731_target_pos_rel_out_ne_m.x += _target_vel_rel_out_ne_ms.x * inertial_data->dt;732_target_pos_rel_out_ne_m.y += _target_vel_rel_out_ne_ms.y * inertial_data->dt;733}734735const AP_AHRS &_ahrs = AP::ahrs();736737const Matrix3f& Tbn = (*_inertial_history)[_inertial_history->available()-1]->Tbn;738Vector3f accel_body_offset = AP::ins().get_imu_pos_offset(_ahrs.get_primary_accel_index());739740// Apply position correction for CG offset from IMU741Vector3f imu_pos_ned = Tbn * accel_body_offset;742_target_pos_rel_out_ne_m.x += imu_pos_ned.x;743_target_pos_rel_out_ne_m.y += imu_pos_ned.y;744745// Apply position correction for body-frame horizontal camera offset from CG, so that vehicle lands lens-to-target746Vector3f cam_pos_horizontal_ned = Tbn * Vector3f{_cam_offset_m.get().x, _cam_offset_m.get().y, 0};747_target_pos_rel_out_ne_m.x -= cam_pos_horizontal_ned.x;748_target_pos_rel_out_ne_m.y -= cam_pos_horizontal_ned.y;749750// Apply velocity correction for IMU offset from CG751Vector3f vel_ned_rel_imu = Tbn * (_ahrs.get_gyro() % (-accel_body_offset));752_target_vel_rel_out_ne_ms.x -= vel_ned_rel_imu.x;753_target_vel_rel_out_ne_ms.y -= vel_ned_rel_imu.y;754755// remember vehicle velocity756UNUSED_RESULT(_ahrs.get_velocity_NED(_last_veh_velocity_NED_ms));757758// Apply land offset759Vector3f land_ofs_ned_m = _ahrs.get_rotation_body_to_ned() * Vector3f{_land_ofs_cm_x, _land_ofs_cm_y, 0} * 0.01f;760_target_pos_rel_out_ne_m.x += land_ofs_ned_m.x;761_target_pos_rel_out_ne_m.y += land_ofs_ned_m.y;762763// store the landing target as a offset from current position. This is used in landing retry764Vector2p last_target_loc_rel_origin_ne_m;765get_target_position_m(last_target_loc_rel_origin_ne_m);766_last_target_pos_rel_origin_ned_m.x = last_target_loc_rel_origin_ne_m.x;767_last_target_pos_rel_origin_ned_m.y = last_target_loc_rel_origin_ne_m.y;768769// record the last time there was a target output770_last_valid_target_ms = AP_HAL::millis();771}772773/*774get target location lat/lon. Note that altitude in returned775location is not reliable776*/777bool AC_PrecLand::get_target_location(Location &loc)778{779if (!target_acquired()) {780return false;781}782if (!AP::ahrs().get_origin(loc)) {783return false;784}785loc.offset(_last_target_pos_rel_origin_ned_m.x, _last_target_pos_rel_origin_ned_m.y);786loc.offset_up_m(-_last_target_pos_rel_origin_ned_m.z);787return true;788}789790/*791get the absolute velocity of the target in m/s.792return false if we cannot estimate target velocity or if the target is not acquired793*/794bool AC_PrecLand::get_target_velocity(Vector2f& target_vel)795{796if (!(_options & PLND_OPTION_MOVING_TARGET)) {797// the target should not be moving798return false;799}800if ((EstimatorType)_estimator_type.get() == EstimatorType::RAW_SENSOR) {801return false;802}803Vector2f target_vel_rel_ne_ms;804if (!get_target_velocity_relative_NE_ms(target_vel_rel_ne_ms)) {805return false;806}807// return the absolute velocity808target_vel = (target_vel_rel_ne_ms) + _last_veh_velocity_NED_ms.xy();809return true;810}811812#if HAL_LOGGING_ENABLED813// Write a precision landing entry814void AC_PrecLand::Write_Precland()815{816// exit immediately if not enabled817if (!enabled()) {818return;819}820821Vector2f target_pos_rel_ne_m;822Vector2f target_vel_rel_ne_ms;823Vector3f target_pos_meas_ned_m;824get_target_position_relative_NE_m(target_pos_rel_ne_m);825get_target_velocity_relative_NE_ms(target_vel_rel_ne_ms);826get_target_position_measurement_NED_m(target_pos_meas_ned_m);827828const struct log_Precland pkt {829LOG_PACKET_HEADER_INIT(LOG_PRECLAND_MSG),830time_us : AP_HAL::micros64(),831healthy : healthy(),832target_acquired : target_acquired(),833pos_x : target_pos_rel_ne_m.x,834pos_y : target_pos_rel_ne_m.y,835vel_x : target_vel_rel_ne_ms.x,836vel_y : target_vel_rel_ne_ms.y,837meas_x : target_pos_meas_ned_m.x,838meas_y : target_pos_meas_ned_m.y,839meas_z : target_pos_meas_ned_m.z,840last_meas : last_backend_los_meas_ms(),841ekf_outcount : ekf_outlier_count(),842estimator : (uint8_t)_estimator_type843};844AP::logger().WriteBlock(&pkt, sizeof(pkt));845}846#endif847848// singleton instance849AC_PrecLand *AC_PrecLand::_singleton;850851namespace AP {852853AC_PrecLand *ac_precland()854{855return AC_PrecLand::get_singleton();856}857858}859860#endif // AC_PRECLAND_ENABLED861862863