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/ArduPlane/mode_loiter.cpp
Views: 1798
#include "mode.h"1#include "Plane.h"23bool ModeLoiter::_enter()4{5plane.do_loiter_at_location();6plane.setup_terrain_target_alt(plane.next_WP_loc);78// make sure the local target altitude is the same as the nav target used for loiter nav9// this allows us to do FBWB style stick control10/*IGNORE_RETURN(plane.next_WP_loc.get_alt_cm(Location::AltFrame::ABSOLUTE, plane.target_altitude.amsl_cm));*/11if (plane.stick_mixing_enabled() && (plane.flight_option_enabled(FlightOptions::ENABLE_LOITER_ALT_CONTROL))) {12plane.set_target_altitude_current();13}1415plane.loiter_angle_reset();1617return true;18}1920void ModeLoiter::update()21{22plane.calc_nav_roll();23if (plane.stick_mixing_enabled() && plane.flight_option_enabled(FlightOptions::ENABLE_LOITER_ALT_CONTROL)) {24plane.update_fbwb_speed_height();25} else {26plane.calc_nav_pitch();27plane.calc_throttle();28}2930#if AP_SCRIPTING_ENABLED31if (plane.nav_scripting_active()) {32// while a trick is running we reset altitude33plane.set_target_altitude_current();34plane.next_WP_loc.set_alt_cm(plane.target_altitude.amsl_cm, Location::AltFrame::ABSOLUTE);35}36#endif37}3839bool ModeLoiter::isHeadingLinedUp(const Location loiterCenterLoc, const Location targetLoc)40{41// Return true if current heading is aligned to vector to targetLoc.42// Tolerance is initially 10 degrees and grows at 10 degrees for each loiter circle completed.4344// Corrected radius for altitude45const float loiter_radius = plane.nav_controller->loiter_radius(fabsf(plane.loiter.radius));46if (!is_positive(loiter_radius)) {47// Zero is invalid, protect against divide by zero for destination inside loiter radius case48return true;49}5051// Calculate relative position of the vehicle relative to loiter center projected onto the closest point of the loiter circle52// This removes error due to radial position as the nav controller attempts to track the circle53const Vector2f projected_pos = loiterCenterLoc.get_distance_NE(plane.current_loc).normalized() * loiter_radius;5455// Target position relative to loiter center56const Vector2f target_pos = loiterCenterLoc.get_distance_NE(targetLoc);5758// Distance between loiter circle and target59const float target_dist = target_pos.length();60if (!is_positive(target_dist)) {61// Target is coincident with loiter center, no heading will be closer than any other62return true;63}6465// Target bearing in centi-degrees66int32_t target_bearing_cd;6768if (target_dist >= loiter_radius) {69// Destination outside loiter radius, heading will always line up with destination7071// Vector from between projected vehicle position and target postion72const Vector2f pos_to_target = target_pos - projected_pos;73target_bearing_cd = degrees(pos_to_target.angle()) * 100;7475} else {76// Destination is inside loiter, heading will never line up with destination7778// Advance turn point by the angle of a segment with chord "a"79// This results in turning earlier as the target point approaches the center80// If target is on radius angle of 0 and angle of 60 deg if target is on center81const float a = loiter_radius - target_dist;82const float segment_angle = 2.0 * asinf(a / (2.0 * loiter_radius));8384// Pick the intersection point that will be hit first for the current loiter direction, add 90 deg to get the tangent angle85target_bearing_cd = degrees(wrap_PI(target_pos.angle() + (M_PI_2 - segment_angle) * plane.loiter.direction)) * 100;8687}8889// Ideal heading in centi-degrees, +- 90 to get tangent to loiter circle at closest point90const int32_t current_heading_cd = degrees(wrap_PI(projected_pos.angle() + M_PI_2 * plane.loiter.direction)) * 100;9192return isHeadingLinedUp_cd(target_bearing_cd, current_heading_cd);93}949596bool ModeLoiter::isHeadingLinedUp_cd(const int32_t bearing_cd) {9798// get current heading.99const int32_t heading_cd = (wrap_360(degrees(ahrs.groundspeed_vector().angle())))*100;100101return isHeadingLinedUp_cd(bearing_cd, heading_cd);102}103104105bool ModeLoiter::isHeadingLinedUp_cd(const int32_t bearing_cd, const int32_t heading_cd)106{107// Return true if current heading is aligned to bearing_cd.108// Tolerance is initially 10 degrees and grows at 10 degrees for each loiter circle completed.109const int32_t heading_err_cd = wrap_180_cd(bearing_cd - heading_cd);110111/*112Check to see if the the plane is heading toward the land113waypoint. We use 20 degrees (+/-10 deg) of margin so that114we can handle 200 degrees/second of yaw.115116After every full circle, extend acceptance criteria to ensure117aircraft will not loop forever in case high winds are forcing118it beyond 200 deg/sec when passing the desired exit course119*/120121// Use integer division to get discrete steps122const int32_t expanded_acceptance = 1000 * (labs(plane.loiter.sum_cd) / 36000);123124if (labs(heading_err_cd) <= 1000 + expanded_acceptance) {125// Want to head in a straight line from _here_ to the next waypoint instead of center of loiter wp126127// 0 to xtrack from center of waypoint, 1 to xtrack from tangent exit location128if (plane.next_WP_loc.loiter_xtrack) {129plane.next_WP_loc = plane.current_loc;130}131return true;132}133return false;134}135136void ModeLoiter::navigate()137{138if (plane.flight_option_enabled(FlightOptions::ENABLE_LOITER_ALT_CONTROL)) {139// update the WP alt from the global target adjusted by update_fbwb_speed_height140plane.next_WP_loc.set_alt_cm(plane.target_altitude.amsl_cm, Location::AltFrame::ABSOLUTE);141}142143#if AP_SCRIPTING_ENABLED144if (plane.nav_scripting_active()) {145// don't try to navigate while running trick146return;147}148#endif149150// Zero indicates to use WP_LOITER_RAD151plane.update_loiter(0);152}153154void ModeLoiter::update_target_altitude()155{156if (plane.stick_mixing_enabled() && (plane.flight_option_enabled(FlightOptions::ENABLE_LOITER_ALT_CONTROL))) {157return;158}159Mode::update_target_altitude();160}161162163