Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AC_PrecLand/AC_PrecLand.cpp
Views: 1798
#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_Companion.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, 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, 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, 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, 2.5f),136// @Param: STRICT137// @DisplayName: PrecLand strictness138// @Description: How strictly should the vehicle land on the target if target is lost139// @Values: 0: Land Vertically (Not strict), 1: Retry Landing(Normal Strictness), 2: Do not land (just Hover) (Very Strict)140AP_GROUPINFO("STRICT", 11, AC_PrecLand, _strict, 1),141142// @Param: RET_MAX143// @DisplayName: PrecLand Maximum number of retires for a failed landing144// @Description: PrecLand Maximum number of retires for a failed landing. Set to zero to disable landing retry.145// @Range: 0 10146// @Increment: 1147AP_GROUPINFO("RET_MAX", 12, AC_PrecLand, _retry_max, 4),148149// @Param: TIMEOUT150// @DisplayName: PrecLand retry timeout151// @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.152// @Range: 0 20153// @Units: s154AP_GROUPINFO("TIMEOUT", 13, AC_PrecLand, _retry_timeout_sec, 4),155156// @Param: RET_BEHAVE157// @DisplayName: PrecLand retry behaviour158// @Description: Prec Land will do the action selected by this parameter if a retry to a landing is needed159// @Values: 0: Go to the last location where landing target was detected, 1: Go towards the approximate location of the detected landing target160AP_GROUPINFO("RET_BEHAVE", 14, AC_PrecLand, _retry_behave, 0),161162// @Param: ALT_MIN163// @DisplayName: PrecLand minimum alt for retry164// @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.165// @Range: 0 5166// @Units: m167AP_GROUPINFO("ALT_MIN", 15, AC_PrecLand, _sensor_min_alt, 0.75),168169// @Param: ALT_MAX170// @DisplayName: PrecLand maximum alt for retry171// @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.172// @Range: 0 50173// @Units: m174AP_GROUPINFO("ALT_MAX", 16, AC_PrecLand, _sensor_max_alt, 8),175176// @Param: OPTIONS177// @DisplayName: Precision Landing Extra Options178// @Description: Precision Landing Extra Options179// @Bitmask: 0: Moving Landing Target, 1: Allow Precision Landing after manual reposition, 2: Maintain high speed in final descent180// @User: Advanced181AP_GROUPINFO("OPTIONS", 17, AC_PrecLand, _options, 0),182183// @Param: ORIENT184// @DisplayName: Camera Orientation185// @Description: Orientation of camera/sensor on body186// @Values: 0:Forward, 4:Back, 25:Down187// @User: Advanced188// @RebootRequired: True189AP_GROUPINFO_FRAME("ORIENT", 18, AC_PrecLand, _orient, AC_PRECLAND_ORIENT_DEFAULT, AP_PARAM_FRAME_ROVER),190191AP_GROUPEND192};193194// Default constructor.195AC_PrecLand::AC_PrecLand()196{197if (_singleton != nullptr) {198AP_HAL::panic("AC_PrecLand must be singleton");199}200_singleton = this;201202// set parameters to defaults203AP_Param::setup_object_defaults(this, var_info);204}205206// perform any required initialisation of landing controllers207// update_rate_hz should be the rate at which the update method will be called in hz208void AC_PrecLand::init(uint16_t update_rate_hz)209{210// exit immediately if init has already been run211if (_backend != nullptr) {212return;213}214215// init as target TARGET_NEVER_SEEN, we will update this later216_current_target_state = TargetState::TARGET_NEVER_SEEN;217218// default health to false219_backend = nullptr;220_backend_state.healthy = false;221222// create inertial history buffer223// constrain lag parameter to be within bounds224_lag.set(constrain_float(_lag, 0.02f, 0.25f)); // must match LAG parameter range at line 124225226// calculate inertial buffer size from lag and minimum of main loop rate and update_rate_hz argument227const uint16_t inertial_buffer_size = MAX((uint16_t)roundf(_lag * update_rate_hz), 1);228229// instantiate ring buffer to hold inertial history, return on failure so no backends are created230_inertial_history = NEW_NOTHROW ObjectArray<inertial_data_frame_s>(inertial_buffer_size);231if (_inertial_history == nullptr) {232return;233}234235// instantiate backend based on type parameter236switch ((Type)(_type.get())) {237// no type defined238case Type::NONE:239default:240return;241// companion computer242#if AC_PRECLAND_COMPANION_ENABLED243case Type::COMPANION:244_backend = NEW_NOTHROW AC_PrecLand_Companion(*this, _backend_state);245break;246// IR Lock247#endif248#if AC_PRECLAND_IRLOCK_ENABLED249case Type::IRLOCK:250_backend = NEW_NOTHROW AC_PrecLand_IRLock(*this, _backend_state);251break;252#endif253#if AC_PRECLAND_SITL_GAZEBO_ENABLED254case Type::SITL_GAZEBO:255_backend = NEW_NOTHROW AC_PrecLand_SITL_Gazebo(*this, _backend_state);256break;257#endif258#if AC_PRECLAND_SITL_ENABLED259case Type::SITL:260_backend = NEW_NOTHROW AC_PrecLand_SITL(*this, _backend_state);261break;262#endif263}264265// init backend266if (_backend != nullptr) {267_backend->init();268}269270_approach_vector_body.x = 1;271_approach_vector_body.rotate(_orient);272}273274// update - give chance to driver to get updates from sensor275void AC_PrecLand::update(float rangefinder_alt_cm, bool rangefinder_alt_valid)276{277// exit immediately if not enabled278if (_backend == nullptr || _inertial_history == nullptr) {279return;280}281282// append current velocity and attitude correction into history buffer283struct inertial_data_frame_s inertial_data_newest;284const auto &_ahrs = AP::ahrs();285_ahrs.getCorrectedDeltaVelocityNED(inertial_data_newest.correctedVehicleDeltaVelocityNED, inertial_data_newest.dt);286inertial_data_newest.Tbn = _ahrs.get_rotation_body_to_ned();287Vector3f curr_vel;288nav_filter_status status;289if (!_ahrs.get_velocity_NED(curr_vel) || !_ahrs.get_filter_status(status)) {290inertial_data_newest.inertialNavVelocityValid = false;291} else {292inertial_data_newest.inertialNavVelocityValid = status.flags.horiz_vel;293}294curr_vel.z = -curr_vel.z; // NED to NEU295inertial_data_newest.inertialNavVelocity = curr_vel;296297inertial_data_newest.time_usec = AP_HAL::micros64();298_inertial_history->push_force(inertial_data_newest);299300const float rangefinder_alt_m = rangefinder_alt_cm*0.01f; //cm to meter301302// update estimator of target position303if (_backend != nullptr && _enabled) {304_backend->update();305run_estimator(rangefinder_alt_m, rangefinder_alt_valid);306}307308// check the status of the landing target location309check_target_status(rangefinder_alt_m, rangefinder_alt_valid);310311#if HAL_LOGGING_ENABLED312const uint32_t now = AP_HAL::millis();313if (now - _last_log_ms > 40) { // 25Hz314_last_log_ms = now;315Write_Precland();316}317#endif318}319320// check the status of the target321void AC_PrecLand::check_target_status(float rangefinder_alt_m, bool rangefinder_alt_valid)322{323if (target_acquired()) {324// target in sight325_current_target_state = TargetState::TARGET_FOUND;326// early return because we already know the status327return;328}329330// target not in sight331if (_current_target_state == TargetState::TARGET_FOUND ||332_current_target_state == TargetState::TARGET_RECENTLY_LOST) {333// we had target in sight, but not any more, i.e we have lost the target334_current_target_state = TargetState::TARGET_RECENTLY_LOST;335} else {336// we never had the target in sight337_current_target_state = TargetState::TARGET_NEVER_SEEN;338}339340// We definitely do not have the target in sight341// check if the precision landing sensor is supposed to be in range342// this needs a valid rangefinder to work343if (!check_if_sensor_in_range(rangefinder_alt_m, rangefinder_alt_valid)) {344// 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 period345_current_target_state = TargetState::TARGET_OUT_OF_RANGE;346return;347}348349if (_current_target_state == TargetState::TARGET_RECENTLY_LOST) {350// check if it's nearby/found recently, else the status will be demoted to "TARGET_LOST"351Vector2f curr_pos;352if (AP::ahrs().get_relative_position_NE_origin(curr_pos)) {353const float dist_to_last_target_loc_xy = (curr_pos - Vector2f{_last_target_pos_rel_origin_NED.x, _last_target_pos_rel_origin_NED.y}).length();354const float dist_to_last_loc_xy = (curr_pos - Vector2f{_last_vehicle_pos_NED.x, _last_vehicle_pos_NED.y}).length();355if ((AP_HAL::millis() - _last_valid_target_ms) > LANDING_TARGET_LOST_TIMEOUT_MS) {356// the target has not been seen for a long time357// might as well consider it as "never seen"358_current_target_state = TargetState::TARGET_NEVER_SEEN;359return;360}361362if ((dist_to_last_target_loc_xy > LANDING_TARGET_LOST_DIST_THRESH_M) || (dist_to_last_loc_xy > LANDING_TARGET_LOST_DIST_THRESH_M)) {363// the last known location of target is too far away364_current_target_state = TargetState::TARGET_NEVER_SEEN;365return;366}367}368}369}370371// Check if the landing target is supposed to be in sight based on the height of the vehicle from the ground372// This needs a valid rangefinder to work, if the min/max parameters are non zero373bool AC_PrecLand::check_if_sensor_in_range(float rangefinder_alt_m, bool rangefinder_alt_valid) const374{375if (is_zero(_sensor_max_alt) && is_zero(_sensor_min_alt)) {376// no sensor limits have been specified, assume sensor is always in range377return true;378}379380if (!rangefinder_alt_valid) {381// rangefinder isn't healthy. We might be at a very high altitude382return false;383}384385if (rangefinder_alt_m > _sensor_max_alt && !is_zero(_sensor_max_alt)) {386// this prevents triggering a retry when we are too far away from the target387return false;388}389390if (rangefinder_alt_m < _sensor_min_alt && !is_zero(_sensor_min_alt)) {391// this prevents triggering a retry when we are very close to the target392return false;393}394395// target should be in range396return true;397}398399bool AC_PrecLand::target_acquired()400{401if ((AP_HAL::millis()-_last_update_ms) > LANDING_TARGET_TIMEOUT_MS) {402if (_target_acquired) {403// just lost the landing target, inform the user. This message will only be sent once every time target is lost404GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "PrecLand: Target Lost");405}406// not had a sensor update since a long time407// probably lost the target408_estimator_initialized = false;409_target_acquired = false;410}411return _target_acquired;412}413414bool AC_PrecLand::get_target_position_cm(Vector2f& ret)415{416if (!target_acquired()) {417return false;418}419Vector2f curr_pos;420if (!AP::ahrs().get_relative_position_NE_origin(curr_pos)) {421return false;422}423ret.x = (_target_pos_rel_out_NE.x + curr_pos.x) * 100.0f; // m to cm424ret.y = (_target_pos_rel_out_NE.y + curr_pos.y) * 100.0f; // m to cm425return true;426}427428void AC_PrecLand::get_target_position_measurement_cm(Vector3f& ret)429{430ret = _target_pos_rel_meas_NED*100.0f;431return;432}433434bool AC_PrecLand::get_target_position_relative_cm(Vector2f& ret)435{436if (!target_acquired()) {437return false;438}439ret = _target_pos_rel_out_NE*100.0f;440return true;441}442443bool AC_PrecLand::get_target_velocity_relative_cms(Vector2f& ret)444{445if (!target_acquired()) {446return false;447}448ret = _target_vel_rel_out_NE*100.0f;449return true;450}451452// get the absolute velocity of the vehicle453void AC_PrecLand::get_target_velocity_cms(const Vector2f& vehicle_velocity_cms, Vector2f& target_vel_cms)454{455if (!(_options & PLND_OPTION_MOVING_TARGET)) {456// the target should not be moving457target_vel_cms.zero();458return;459}460if ((EstimatorType)_estimator_type.get() == EstimatorType::RAW_SENSOR) {461// We do not predict the velocity of the target in this case462// assume velocity to be zero463target_vel_cms.zero();464return;465}466Vector2f target_vel_rel_cms;467if (!get_target_velocity_relative_cms(target_vel_rel_cms)) {468// Don't know where the target is469// assume velocity to be zero470target_vel_cms.zero();471return;472}473// return the absolute velocity474target_vel_cms = target_vel_rel_cms + vehicle_velocity_cms;475}476477// handle_msg - Process a LANDING_TARGET mavlink message478void AC_PrecLand::handle_msg(const mavlink_landing_target_t &packet, uint32_t timestamp_ms)479{480// run backend update481if (_backend != nullptr) {482_backend->handle_msg(packet, timestamp_ms);483}484}485486//487// Private methods488//489490void AC_PrecLand::run_estimator(float rangefinder_alt_m, bool rangefinder_alt_valid)491{492_inertial_data_delayed = (*_inertial_history)[0];493494switch ((EstimatorType)_estimator_type.get()) {495case EstimatorType::RAW_SENSOR: {496// Return if there's any invalid velocity data497for (uint8_t i=0; i<_inertial_history->available(); i++) {498const struct inertial_data_frame_s *inertial_data = (*_inertial_history)[i];499if (!inertial_data->inertialNavVelocityValid) {500_target_acquired = false;501return;502}503}504505// Predict506if (target_acquired()) {507_target_pos_rel_est_NE.x -= _inertial_data_delayed->inertialNavVelocity.x * _inertial_data_delayed->dt;508_target_pos_rel_est_NE.y -= _inertial_data_delayed->inertialNavVelocity.y * _inertial_data_delayed->dt;509_target_vel_rel_est_NE.x = -_inertial_data_delayed->inertialNavVelocity.x;510_target_vel_rel_est_NE.y = -_inertial_data_delayed->inertialNavVelocity.y;511}512513// Update if a new Line-Of-Sight measurement is available514if (construct_pos_meas_using_rangefinder(rangefinder_alt_m, rangefinder_alt_valid)) {515if (!_estimator_initialized) {516GCS_SEND_TEXT(MAV_SEVERITY_INFO, "PrecLand: Target Found");517_estimator_initialized = true;518}519_target_pos_rel_est_NE.x = _target_pos_rel_meas_NED.x;520_target_pos_rel_est_NE.y = _target_pos_rel_meas_NED.y;521_target_vel_rel_est_NE.x = -_inertial_data_delayed->inertialNavVelocity.x;522_target_vel_rel_est_NE.y = -_inertial_data_delayed->inertialNavVelocity.y;523524_last_update_ms = AP_HAL::millis();525_target_acquired = true;526}527528// Output prediction529if (target_acquired()) {530run_output_prediction();531}532break;533}534case EstimatorType::KALMAN_FILTER: {535// Predict536if (target_acquired() || _estimator_initialized) {537const float& dt = _inertial_data_delayed->dt;538const Vector3f& vehicleDelVel = _inertial_data_delayed->correctedVehicleDeltaVelocityNED;539540_ekf_x.predict(dt, -vehicleDelVel.x, _accel_noise*dt);541_ekf_y.predict(dt, -vehicleDelVel.y, _accel_noise*dt);542}543544// Update if a new Line-Of-Sight measurement is available545if (construct_pos_meas_using_rangefinder(rangefinder_alt_m, rangefinder_alt_valid)) {546float xy_pos_var = sq(_target_pos_rel_meas_NED.z*(0.01f + 0.01f*AP::ahrs().get_gyro().length()) + 0.02f);547if (!_estimator_initialized) {548// Inform the user landing target has been found549GCS_SEND_TEXT(MAV_SEVERITY_INFO, "PrecLand: Target Found");550// start init of EKF. We will let the filter consume the data for a while before it available for consumption551// reset filter state552if (_inertial_data_delayed->inertialNavVelocityValid) {553_ekf_x.init(_target_pos_rel_meas_NED.x, xy_pos_var, -_inertial_data_delayed->inertialNavVelocity.x, sq(2.0f));554_ekf_y.init(_target_pos_rel_meas_NED.y, xy_pos_var, -_inertial_data_delayed->inertialNavVelocity.y, sq(2.0f));555} else {556_ekf_x.init(_target_pos_rel_meas_NED.x, xy_pos_var, 0.0f, sq(10.0f));557_ekf_y.init(_target_pos_rel_meas_NED.y, xy_pos_var, 0.0f, sq(10.0f));558}559_last_update_ms = AP_HAL::millis();560_estimator_init_ms = AP_HAL::millis();561// we have initialized the estimator but will not use the values for sometime so that EKF settles down562_estimator_initialized = true;563} else {564float NIS_x = _ekf_x.getPosNIS(_target_pos_rel_meas_NED.x, xy_pos_var);565float NIS_y = _ekf_y.getPosNIS(_target_pos_rel_meas_NED.y, xy_pos_var);566if (MAX(NIS_x, NIS_y) < 3.0f || _outlier_reject_count >= 3) {567_outlier_reject_count = 0;568_ekf_x.fusePos(_target_pos_rel_meas_NED.x, xy_pos_var);569_ekf_y.fusePos(_target_pos_rel_meas_NED.y, xy_pos_var);570_last_update_ms = AP_HAL::millis();571} else {572_outlier_reject_count++;573}574}575}576577// check EKF was properly initialized when the sensor detected a landing target578check_ekf_init_timeout();579580// Output prediction581if (target_acquired()) {582_target_pos_rel_est_NE.x = _ekf_x.getPos();583_target_pos_rel_est_NE.y = _ekf_y.getPos();584_target_vel_rel_est_NE.x = _ekf_x.getVel();585_target_vel_rel_est_NE.y = _ekf_y.getVel();586587run_output_prediction();588}589break;590}591}592}593594595// check if EKF got the time to initialize when the landing target was first detected596// Expects sensor to update within EKF_INIT_SENSOR_MIN_UPDATE_MS milliseconds till EKF_INIT_TIME_MS milliseconds have passed597// after this period landing target estimates can be used by vehicle598void AC_PrecLand::check_ekf_init_timeout()599{600if (!target_acquired() && _estimator_initialized) {601// we have just got the target in sight602if (AP_HAL::millis()-_last_update_ms > EKF_INIT_SENSOR_MIN_UPDATE_MS) {603// we have lost the target, not enough readings to initialize the EKF604_estimator_initialized = false;605GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "PrecLand: Init Failed");606} else if (AP_HAL::millis()-_estimator_init_ms > EKF_INIT_TIME_MS) {607// the target has been visible for a while, EKF should now have initialized to a good value608_target_acquired = true;609GCS_SEND_TEXT(MAV_SEVERITY_INFO, "PrecLand: Init Complete");610}611}612}613614bool AC_PrecLand::retrieve_los_meas(Vector3f& target_vec_unit_body)615{616const uint32_t los_meas_time_ms = _backend->los_meas_time_ms();617if (los_meas_time_ms != _last_backend_los_meas_ms && _backend->get_los_body(target_vec_unit_body)) {618_last_backend_los_meas_ms = los_meas_time_ms;619if (!is_zero(_yaw_align)) {620// Apply sensor yaw alignment rotation621target_vec_unit_body.rotate_xy(radians(_yaw_align*0.01f));622}623624625// rotate vector based on sensor orientation to get correct body frame vector626if (_orient != ROTATION_PITCH_270) {627// by default, the vector is constructed downwards in body frame628// hence, we do not do any rotation if the orientation is downwards629// if it is some other orientation, we first bring the vector to forward630// and then we rotate it to desired orientation631// because the rotations are measured with respect to a vector pointing towards front in body frame632// for eg, if orientation is back, i.e., ROTATION_YAW_180,633// the vector is first brought to front and then rotation by YAW 180 to take it to the back of vehicle634target_vec_unit_body.rotate(ROTATION_PITCH_90); // bring vector to front635target_vec_unit_body.rotate(_orient); // rotate it to desired orientation636}637638return true;639}640return false;641}642643bool AC_PrecLand::construct_pos_meas_using_rangefinder(float rangefinder_alt_m, bool rangefinder_alt_valid)644{645Vector3f target_vec_unit_body;646if (retrieve_los_meas(target_vec_unit_body)) {647_inertial_data_delayed = (*_inertial_history)[0];648649const bool target_vec_valid = target_vec_unit_body.projected(_approach_vector_body).dot(_approach_vector_body) > 0.0f;650const Vector3f target_vec_unit_ned = _inertial_data_delayed->Tbn * target_vec_unit_body;651const Vector3f approach_vector_NED = _inertial_data_delayed->Tbn * _approach_vector_body;652const bool alt_valid = (rangefinder_alt_valid && rangefinder_alt_m > 0.0f) || (_backend->distance_to_target() > 0.0f);653if (target_vec_valid && alt_valid) {654// distance to target and distance to target along approach vector655float dist_to_target, dist_to_target_along_av;656// figure out ned camera orientation w.r.t its offset657Vector3f cam_pos_ned;658if (!_cam_offset.get().is_zero()) {659// user has specifed offset for camera660// take its height into account while calculating distance661cam_pos_ned = _inertial_data_delayed->Tbn * _cam_offset;662}663if (_backend->distance_to_target() > 0.0f) {664// sensor has provided distance to landing target665dist_to_target = _backend->distance_to_target();666} else {667// sensor only knows the horizontal location of the landing target668// rely on rangefinder for the vertical target669dist_to_target_along_av = MAX(rangefinder_alt_m - cam_pos_ned.projected(approach_vector_NED).length(), 0.0f);670dist_to_target = dist_to_target_along_av / target_vec_unit_ned.projected(approach_vector_NED).length();671}672673// Compute camera position relative to IMU674const Vector3f accel_pos_ned = _inertial_data_delayed->Tbn * AP::ins().get_imu_pos_offset(AP::ahrs().get_primary_accel_index());675const Vector3f cam_pos_ned_rel_imu = cam_pos_ned - accel_pos_ned;676677// Compute target position relative to IMU678_target_pos_rel_meas_NED = (target_vec_unit_ned * dist_to_target) + cam_pos_ned_rel_imu;679680// store the current relative down position so that if we need to retry landing, we know at this height landing target can be found681const AP_AHRS &_ahrs = AP::ahrs();682Vector3f pos_NED;683if (_ahrs.get_relative_position_NED_origin(pos_NED)) {684_last_target_pos_rel_origin_NED.z = pos_NED.z;685_last_vehicle_pos_NED = pos_NED;686}687return true;688}689}690return false;691}692693void AC_PrecLand::run_output_prediction()694{695_target_pos_rel_out_NE = _target_pos_rel_est_NE;696_target_vel_rel_out_NE = _target_vel_rel_est_NE;697698// Predict forward from delayed time horizon699for (uint8_t i=1; i<_inertial_history->available(); i++) {700const struct inertial_data_frame_s *inertial_data = (*_inertial_history)[i];701_target_vel_rel_out_NE.x -= inertial_data->correctedVehicleDeltaVelocityNED.x;702_target_vel_rel_out_NE.y -= inertial_data->correctedVehicleDeltaVelocityNED.y;703_target_pos_rel_out_NE.x += _target_vel_rel_out_NE.x * inertial_data->dt;704_target_pos_rel_out_NE.y += _target_vel_rel_out_NE.y * inertial_data->dt;705}706707const AP_AHRS &_ahrs = AP::ahrs();708709const Matrix3f& Tbn = (*_inertial_history)[_inertial_history->available()-1]->Tbn;710Vector3f accel_body_offset = AP::ins().get_imu_pos_offset(_ahrs.get_primary_accel_index());711712// Apply position correction for CG offset from IMU713Vector3f imu_pos_ned = Tbn * accel_body_offset;714_target_pos_rel_out_NE.x += imu_pos_ned.x;715_target_pos_rel_out_NE.y += imu_pos_ned.y;716717// Apply position correction for body-frame horizontal camera offset from CG, so that vehicle lands lens-to-target718Vector3f cam_pos_horizontal_ned = Tbn * Vector3f{_cam_offset.get().x, _cam_offset.get().y, 0};719_target_pos_rel_out_NE.x -= cam_pos_horizontal_ned.x;720_target_pos_rel_out_NE.y -= cam_pos_horizontal_ned.y;721722// Apply velocity correction for IMU offset from CG723Vector3f vel_ned_rel_imu = Tbn * (_ahrs.get_gyro() % (-accel_body_offset));724_target_vel_rel_out_NE.x -= vel_ned_rel_imu.x;725_target_vel_rel_out_NE.y -= vel_ned_rel_imu.y;726727// remember vehicle velocity728UNUSED_RESULT(_ahrs.get_velocity_NED(_last_veh_velocity_NED_ms));729730// Apply land offset731Vector3f land_ofs_ned_m = _ahrs.get_rotation_body_to_ned() * Vector3f{_land_ofs_cm_x, _land_ofs_cm_y, 0} * 0.01f;732_target_pos_rel_out_NE.x += land_ofs_ned_m.x;733_target_pos_rel_out_NE.y += land_ofs_ned_m.y;734735// store the landing target as a offset from current position. This is used in landing retry736Vector2f last_target_loc_rel_origin_2d;737get_target_position_cm(last_target_loc_rel_origin_2d);738_last_target_pos_rel_origin_NED.x = last_target_loc_rel_origin_2d.x * 0.01f;739_last_target_pos_rel_origin_NED.y = last_target_loc_rel_origin_2d.y * 0.01f;740741// record the last time there was a target output742_last_valid_target_ms = AP_HAL::millis();743}744745/*746get target location lat/lon. Note that altitude in returned747location is not reliable748*/749bool AC_PrecLand::get_target_location(Location &loc)750{751if (!target_acquired()) {752return false;753}754if (!AP::ahrs().get_origin(loc)) {755return false;756}757loc.offset(_last_target_pos_rel_origin_NED.x, _last_target_pos_rel_origin_NED.y);758loc.alt -= _last_target_pos_rel_origin_NED.z*100;759return true;760}761762/*763get the absolute velocity of the target in m/s.764return false if we cannot estimate target velocity or if the target is not acquired765*/766bool AC_PrecLand::get_target_velocity(Vector2f& target_vel)767{768if (!(_options & PLND_OPTION_MOVING_TARGET)) {769// the target should not be moving770return false;771}772if ((EstimatorType)_estimator_type.get() == EstimatorType::RAW_SENSOR) {773return false;774}775Vector2f target_vel_rel_cms;776if (!get_target_velocity_relative_cms(target_vel_rel_cms)) {777return false;778}779// return the absolute velocity780target_vel = (target_vel_rel_cms*0.01) + _last_veh_velocity_NED_ms.xy();781return true;782}783784#if HAL_LOGGING_ENABLED785// Write a precision landing entry786void AC_PrecLand::Write_Precland()787{788// exit immediately if not enabled789if (!enabled()) {790return;791}792793Vector3f target_pos_meas;794Vector2f target_pos_rel;795Vector2f target_vel_rel;796get_target_position_relative_cm(target_pos_rel);797get_target_velocity_relative_cms(target_vel_rel);798get_target_position_measurement_cm(target_pos_meas);799800const struct log_Precland pkt {801LOG_PACKET_HEADER_INIT(LOG_PRECLAND_MSG),802time_us : AP_HAL::micros64(),803healthy : healthy(),804target_acquired : target_acquired(),805pos_x : target_pos_rel.x,806pos_y : target_pos_rel.y,807vel_x : target_vel_rel.x,808vel_y : target_vel_rel.y,809meas_x : target_pos_meas.x,810meas_y : target_pos_meas.y,811meas_z : target_pos_meas.z,812last_meas : last_backend_los_meas_ms(),813ekf_outcount : ekf_outlier_count(),814estimator : (uint8_t)_estimator_type815};816AP::logger().WriteBlock(&pkt, sizeof(pkt));817}818#endif819820// singleton instance821AC_PrecLand *AC_PrecLand::_singleton;822823namespace AP {824825AC_PrecLand *ac_precland()826{827return AC_PrecLand::get_singleton();828}829830}831832#endif // AC_PRECLAND_ENABLED833834835