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/AP_Follow/AP_Follow.cpp
Views: 1798
/*1This program is free software: you can redistribute it and/or modify2it under the terms of the GNU General Public License as published by3the Free Software Foundation, either version 3 of the License, or4(at your option) any later version.56This program is distributed in the hope that it will be useful,7but WITHOUT ANY WARRANTY; without even the implied warranty of8MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the9GNU General Public License for more details.1011You should have received a copy of the GNU General Public License12along with this program. If not, see <http://www.gnu.org/licenses/>.13*/1415#include "AP_Follow_config.h"1617#if AP_FOLLOW_ENABLED1819#include <AP_HAL/AP_HAL.h>20#include "AP_Follow.h"21#include <ctype.h>22#include <stdio.h>2324#include <AP_AHRS/AP_AHRS.h>25#include <AP_Logger/AP_Logger.h>26#include <GCS_MAVLink/GCS.h>27#include <AP_Vehicle/AP_Vehicle_Type.h>2829extern const AP_HAL::HAL& hal;3031#define AP_FOLLOW_TIMEOUT_MS 3000 // position estimate timeout after 1 second32#define AP_FOLLOW_SYSID_TIMEOUT_MS 10000 // forget sysid we are following if we have not heard from them in 10 seconds3334#define AP_FOLLOW_OFFSET_TYPE_NED 0 // offsets are in north-east-down frame35#define AP_FOLLOW_OFFSET_TYPE_RELATIVE 1 // offsets are relative to lead vehicle's heading3637#define AP_FOLLOW_ALTITUDE_TYPE_RELATIVE 1 // relative altitude is used by default3839#define AP_FOLLOW_POS_P_DEFAULT 0.1f // position error gain default4041#if APM_BUILD_TYPE(APM_BUILD_ArduPlane)42#define AP_FOLLOW_ALT_TYPE_DEFAULT 043#else44#define AP_FOLLOW_ALT_TYPE_DEFAULT AP_FOLLOW_ALTITUDE_TYPE_RELATIVE45#endif4647AP_Follow *AP_Follow::_singleton;4849// table of user settable parameters50const AP_Param::GroupInfo AP_Follow::var_info[] = {5152// @Param: _ENABLE53// @DisplayName: Follow enable/disable54// @Description: Enabled/disable following a target55// @Values: 0:Disabled,1:Enabled56// @User: Standard57AP_GROUPINFO_FLAGS("_ENABLE", 1, AP_Follow, _enabled, 0, AP_PARAM_FLAG_ENABLE),5859// 2 is reserved for TYPE parameter6061// @Param: _SYSID62// @DisplayName: Follow target's mavlink system id63// @Description: Follow target's mavlink system id64// @Range: 0 25565// @User: Standard66AP_GROUPINFO("_SYSID", 3, AP_Follow, _sysid, 0),6768// 4 is reserved for MARGIN parameter6970// @Param: _DIST_MAX71// @DisplayName: Follow distance maximum72// @Description: Follow distance maximum. targets further than this will be ignored73// @Units: m74// @Range: 1 100075// @User: Standard76AP_GROUPINFO("_DIST_MAX", 5, AP_Follow, _dist_max, 100),7778// @Param: _OFS_TYPE79// @DisplayName: Follow offset type80// @Description: Follow offset type81// @Values: 0:North-East-Down, 1:Relative to lead vehicle heading82// @User: Standard83AP_GROUPINFO("_OFS_TYPE", 6, AP_Follow, _offset_type, AP_FOLLOW_OFFSET_TYPE_NED),8485// @Param: _OFS_X86// @DisplayName: Follow offsets in meters north/forward87// @Description: Follow offsets in meters north/forward. If positive, this vehicle fly ahead or north of lead vehicle. Depends on FOLL_OFS_TYPE88// @Range: -100 10089// @Units: m90// @Increment: 191// @User: Standard9293// @Param: _OFS_Y94// @DisplayName: Follow offsets in meters east/right95// @Description: Follow offsets in meters east/right. If positive, this vehicle will fly to the right or east of lead vehicle. Depends on FOLL_OFS_TYPE96// @Range: -100 10097// @Units: m98// @Increment: 199// @User: Standard100101// @Param: _OFS_Z102// @DisplayName: Follow offsets in meters down103// @Description: Follow offsets in meters down. If positive, this vehicle will fly below the lead vehicle104// @Range: -100 100105// @Units: m106// @Increment: 1107// @User: Standard108AP_GROUPINFO("_OFS", 7, AP_Follow, _offset, 0),109110#if !(APM_BUILD_TYPE(APM_BUILD_Rover))111// @Param: _YAW_BEHAVE112// @DisplayName: Follow yaw behaviour113// @Description: Follow yaw behaviour114// @Values: 0:None,1:Face Lead Vehicle,2:Same as Lead vehicle,3:Direction of Flight115// @User: Standard116AP_GROUPINFO("_YAW_BEHAVE", 8, AP_Follow, _yaw_behave, 1),117#endif118119// @Param: _POS_P120// @DisplayName: Follow position error P gain121// @Description: Follow position error P gain. Converts the difference between desired vertical speed and actual speed into a desired acceleration that is passed to the throttle acceleration controller122// @Range: 0.01 1.00123// @Increment: 0.01124// @User: Standard125AP_SUBGROUPINFO(_p_pos, "_POS_", 9, AP_Follow, AC_P),126127#if !(APM_BUILD_TYPE(APM_BUILD_Rover))128// @Param: _ALT_TYPE129// @DisplayName: Follow altitude type130// @Description: Follow altitude type131// @Values: 0:absolute, 1:relative132// @User: Standard133AP_GROUPINFO("_ALT_TYPE", 10, AP_Follow, _alt_type, AP_FOLLOW_ALT_TYPE_DEFAULT),134#endif135136// @Param: _OPTIONS137// @DisplayName: Follow options138// @Description: Follow options bitmask139// @Values: 0:None,1: Mount Follows lead vehicle on mode enter140// @User: Standard141AP_GROUPINFO("_OPTIONS", 11, AP_Follow, _options, 0),142143AP_GROUPEND144};145146/*147The constructor also initialises the proximity sensor. Note that this148constructor is not called until detect() returns true, so we149already know that we should setup the proximity sensor150*/151AP_Follow::AP_Follow() :152_p_pos(AP_FOLLOW_POS_P_DEFAULT)153{154_singleton = this;155AP_Param::setup_object_defaults(this, var_info);156}157158// restore offsets to zero if necessary, should be called when vehicle exits follow mode159void AP_Follow::clear_offsets_if_required()160{161if (_offsets_were_zero) {162_offset.set(Vector3f());163}164_offsets_were_zero = false;165}166167// get target's estimated location168bool AP_Follow::get_target_location_and_velocity(Location &loc, Vector3f &vel_ned) const169{170// exit immediately if not enabled171if (!_enabled) {172return false;173}174175// check for timeout176if ((_last_location_update_ms == 0) || (AP_HAL::millis() - _last_location_update_ms > AP_FOLLOW_TIMEOUT_MS)) {177return false;178}179180// calculate time since last actual position update181const float dt = (AP_HAL::millis() - _last_location_update_ms) * 0.001f;182183// get velocity estimate184if (!get_velocity_ned(vel_ned, dt)) {185return false;186}187188// project the vehicle position189Location last_loc = _target_location;190last_loc.offset(vel_ned.x * dt, vel_ned.y * dt);191last_loc.alt -= vel_ned.z * 100.0f * dt; // convert m/s to cm/s, multiply by dt. minus because NED192193// return latest position estimate194loc = last_loc;195return true;196}197198// get distance vector to target (in meters) and target's velocity all in NED frame199bool AP_Follow::get_target_dist_and_vel_ned(Vector3f &dist_ned, Vector3f &dist_with_offs, Vector3f &vel_ned)200{201// get our location202Location current_loc;203if (!AP::ahrs().get_location(current_loc)) {204clear_dist_and_bearing_to_target();205return false;206}207208// get target location and velocity209Location target_loc;210Vector3f veh_vel;211if (!get_target_location_and_velocity(target_loc, veh_vel)) {212clear_dist_and_bearing_to_target();213return false;214}215216// change to altitude above home217if (target_loc.relative_alt == 1) {218current_loc.change_alt_frame(Location::AltFrame::ABOVE_HOME);219}220221// calculate difference222const Vector3f dist_vec = current_loc.get_distance_NED(target_loc);223224// fail if too far225if (is_positive(_dist_max.get()) && (dist_vec.length() > _dist_max)) {226clear_dist_and_bearing_to_target();227return false;228}229230// initialise offsets from distance vector if required231init_offsets_if_required(dist_vec);232233// get offsets234Vector3f offsets;235if (!get_offsets_ned(offsets)) {236clear_dist_and_bearing_to_target();237return false;238}239240// calculate results241dist_ned = dist_vec;242dist_with_offs = dist_vec + offsets;243vel_ned = veh_vel;244245// record distance and heading for reporting purposes246if (is_zero(dist_with_offs.x) && is_zero(dist_with_offs.y)) {247clear_dist_and_bearing_to_target();248} else {249_dist_to_target = safe_sqrt(sq(dist_with_offs.x) + sq(dist_with_offs.y));250_bearing_to_target = degrees(atan2f(dist_with_offs.y, dist_with_offs.x));251}252253return true;254}255256// get target's heading in degrees (0 = north, 90 = east)257bool AP_Follow::get_target_heading_deg(float &heading) const258{259// exit immediately if not enabled260if (!_enabled) {261return false;262}263264// check for timeout265if ((_last_heading_update_ms == 0) || (AP_HAL::millis() - _last_heading_update_ms > AP_FOLLOW_TIMEOUT_MS)) {266return false;267}268269// return latest heading estimate270heading = _target_heading;271return true;272}273274// returns true if we should extract information from msg275bool AP_Follow::should_handle_message(const mavlink_message_t &msg) const276{277// exit immediately if not enabled278if (!_enabled) {279return false;280}281282// skip our own messages283if (msg.sysid == mavlink_system.sysid) {284return false;285}286287// skip message if not from our target288if (_sysid != 0 && msg.sysid != _sysid) {289return false;290}291292return true;293}294295// handle mavlink DISTANCE_SENSOR messages296void AP_Follow::handle_msg(const mavlink_message_t &msg)297{298// this method should be called from an "update()" method:299if (_automatic_sysid) {300// maybe timeout who we were following...301if ((_last_location_update_ms == 0) ||302(AP_HAL::millis() - _last_location_update_ms > AP_FOLLOW_SYSID_TIMEOUT_MS)) {303_sysid.set(0);304}305}306307if (!should_handle_message(msg)) {308return;309}310311// decode global-position-int message312bool updated = false;313314switch (msg.msgid) {315case MAVLINK_MSG_ID_GLOBAL_POSITION_INT: {316updated = handle_global_position_int_message(msg);317break;318}319case MAVLINK_MSG_ID_FOLLOW_TARGET: {320updated = handle_follow_target_message(msg);321break;322}323}324325if (updated) {326#if HAL_LOGGING_ENABLED327Log_Write_FOLL();328#endif329}330}331332bool AP_Follow::handle_global_position_int_message(const mavlink_message_t &msg)333{334// decode message335mavlink_global_position_int_t packet;336mavlink_msg_global_position_int_decode(&msg, &packet);337338// ignore message if lat and lon are (exactly) zero339if ((packet.lat == 0 && packet.lon == 0)) {340return false;341}342343_target_location.lat = packet.lat;344_target_location.lng = packet.lon;345346// select altitude source based on FOLL_ALT_TYPE param347if (_alt_type == AP_FOLLOW_ALTITUDE_TYPE_RELATIVE) {348// above home alt349_target_location.set_alt_cm(packet.relative_alt / 10, Location::AltFrame::ABOVE_HOME);350} else {351// absolute altitude352_target_location.set_alt_cm(packet.alt / 10, Location::AltFrame::ABSOLUTE);353}354355_target_velocity_ned.x = packet.vx * 0.01f; // velocity north356_target_velocity_ned.y = packet.vy * 0.01f; // velocity east357_target_velocity_ned.z = packet.vz * 0.01f; // velocity down358359// get a local timestamp with correction for transport jitter360_last_location_update_ms = _jitter.correct_offboard_timestamp_msec(packet.time_boot_ms, AP_HAL::millis());361if (packet.hdg <= 36000) { // heading (UINT16_MAX if unknown)362_target_heading = packet.hdg * 0.01f; // convert centi-degrees to degrees363_last_heading_update_ms = _last_location_update_ms;364}365// initialise _sysid if zero to sender's id366if (_sysid == 0) {367_sysid.set(msg.sysid);368_automatic_sysid = true;369}370return true;371}372373bool AP_Follow::handle_follow_target_message(const mavlink_message_t &msg)374{375// decode message376mavlink_follow_target_t packet;377mavlink_msg_follow_target_decode(&msg, &packet);378379// ignore message if lat and lon are (exactly) zero380if ((packet.lat == 0 && packet.lon == 0)) {381return false;382}383// require at least position384if ((packet.est_capabilities & (1<<0)) == 0) {385return false;386}387388Location new_loc = _target_location;389new_loc.lat = packet.lat;390new_loc.lng = packet.lon;391new_loc.set_alt_m(packet.alt, Location::AltFrame::ABSOLUTE);392393// FOLLOW_TARGET is always AMSL, change the provided alt to394// above home if we are configured for relative alt395if (_alt_type == AP_FOLLOW_ALTITUDE_TYPE_RELATIVE &&396!new_loc.change_alt_frame(Location::AltFrame::ABOVE_HOME)) {397return false;398}399_target_location = new_loc;400401if (packet.est_capabilities & (1<<1)) {402_target_velocity_ned.x = packet.vel[0]; // velocity north403_target_velocity_ned.y = packet.vel[1]; // velocity east404_target_velocity_ned.z = packet.vel[2]; // velocity down405} else {406_target_velocity_ned.zero();407}408409// get a local timestamp with correction for transport jitter410_last_location_update_ms = _jitter.correct_offboard_timestamp_msec(packet.timestamp, AP_HAL::millis());411412if (packet.est_capabilities & (1<<3)) {413Quaternion q{packet.attitude_q[0], packet.attitude_q[1], packet.attitude_q[2], packet.attitude_q[3]};414float r, p, y;415q.to_euler(r,p,y);416_target_heading = degrees(y);417_last_heading_update_ms = _last_location_update_ms;418}419420// initialise _sysid if zero to sender's id421if (_sysid == 0) {422_sysid.set(msg.sysid);423_automatic_sysid = true;424}425426return true;427}428429// write out an onboard-log message to help diagnose follow problems:430#if HAL_LOGGING_ENABLED431void AP_Follow::Log_Write_FOLL()432{433// get estimated location and velocity434Location loc_estimate{};435Vector3f vel_estimate;436UNUSED_RESULT(get_target_location_and_velocity(loc_estimate, vel_estimate));437438// log lead's estimated vs reported position439// @LoggerMessage: FOLL440// @Description: Follow library diagnostic data441// @Field: TimeUS: Time since system startup442// @Field: Lat: Target latitude443// @Field: Lon: Target longitude444// @Field: Alt: Target absolute altitude445// @Field: VelN: Target earth-frame velocity, North446// @Field: VelE: Target earth-frame velocity, East447// @Field: VelD: Target earth-frame velocity, Down448// @Field: LatE: Vehicle latitude449// @Field: LonE: Vehicle longitude450// @Field: AltE: Vehicle absolute altitude451AP::logger().WriteStreaming("FOLL",452"TimeUS,Lat,Lon,Alt,VelN,VelE,VelD,LatE,LonE,AltE", // labels453"sDUmnnnDUm", // units454"F--B000--B", // mults455"QLLifffLLi", // fmt456AP_HAL::micros64(),457_target_location.lat,458_target_location.lng,459_target_location.alt,460(double)_target_velocity_ned.x,461(double)_target_velocity_ned.y,462(double)_target_velocity_ned.z,463loc_estimate.lat,464loc_estimate.lng,465loc_estimate.alt466);467}468#endif // HAL_LOGGING_ENABLED469470// get velocity estimate in m/s in NED frame using dt since last update471bool AP_Follow::get_velocity_ned(Vector3f &vel_ned, float dt) const472{473vel_ned = _target_velocity_ned + (_target_accel_ned * dt);474return true;475}476477// initialise offsets to provided distance vector to other vehicle (in meters in NED frame) if required478void AP_Follow::init_offsets_if_required(const Vector3f &dist_vec_ned)479{480// return immediately if offsets have already been set481if (!_offset.get().is_zero()) {482return;483}484_offsets_were_zero = true;485486float target_heading_deg;487if ((_offset_type == AP_FOLLOW_OFFSET_TYPE_RELATIVE) && get_target_heading_deg(target_heading_deg)) {488// rotate offsets from north facing to vehicle's perspective489_offset.set(rotate_vector(-dist_vec_ned, -target_heading_deg));490GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Relative follow offset loaded");491} else {492// initialise offset in NED frame493_offset.set(-dist_vec_ned);494// ensure offset_type used matches frame of offsets saved495_offset_type.set(AP_FOLLOW_OFFSET_TYPE_NED);496GCS_SEND_TEXT(MAV_SEVERITY_INFO, "N-E-D follow offset loaded");497}498}499500// get offsets in meters in NED frame501bool AP_Follow::get_offsets_ned(Vector3f &offset) const502{503const Vector3f &off = _offset.get();504505// if offsets are zero or type is NED, simply return offset vector506if (off.is_zero() || (_offset_type == AP_FOLLOW_OFFSET_TYPE_NED)) {507offset = off;508return true;509}510511// offset type is relative, exit if we cannot get vehicle's heading512float target_heading_deg;513if (!get_target_heading_deg(target_heading_deg)) {514return false;515}516517// rotate offsets from vehicle's perspective to NED518offset = rotate_vector(off, target_heading_deg);519return true;520}521522// rotate 3D vector clockwise by specified angle (in degrees)523Vector3f AP_Follow::rotate_vector(const Vector3f &vec, float angle_deg) const524{525// rotate roll, pitch input from north facing to vehicle's perspective526Vector3f ret = vec;527ret.xy().rotate(radians(angle_deg));528529return ret;530}531532// set recorded distance and bearing to target to zero533void AP_Follow::clear_dist_and_bearing_to_target()534{535_dist_to_target = 0.0f;536_bearing_to_target = 0.0f;537}538539// get target's estimated location and velocity (in NED), with offsets added540bool AP_Follow::get_target_location_and_velocity_ofs(Location &loc, Vector3f &vel_ned) const541{542Vector3f ofs;543if (!get_offsets_ned(ofs) ||544!get_target_location_and_velocity(loc, vel_ned)) {545return false;546}547// apply offsets548loc.offset(ofs.x, ofs.y);549loc.alt -= ofs.z*100;550return true;551}552553// return true if we have a target554bool AP_Follow::have_target(void) const555{556if (!_enabled) {557return false;558}559560// check for timeout561if ((_last_location_update_ms == 0) || (AP_HAL::millis() - _last_location_update_ms > AP_FOLLOW_TIMEOUT_MS)) {562return false;563}564return true;565}566567namespace AP {568569AP_Follow &follow()570{571return *AP_Follow::get_singleton();572}573574}575576#endif // AP_FOLLOW_ENABLED577578579