CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/ArduPlane/mode_loiter.cpp
Views: 1798
1
#include "mode.h"
2
#include "Plane.h"
3
4
bool ModeLoiter::_enter()
5
{
6
plane.do_loiter_at_location();
7
plane.setup_terrain_target_alt(plane.next_WP_loc);
8
9
// make sure the local target altitude is the same as the nav target used for loiter nav
10
// this allows us to do FBWB style stick control
11
/*IGNORE_RETURN(plane.next_WP_loc.get_alt_cm(Location::AltFrame::ABSOLUTE, plane.target_altitude.amsl_cm));*/
12
if (plane.stick_mixing_enabled() && (plane.flight_option_enabled(FlightOptions::ENABLE_LOITER_ALT_CONTROL))) {
13
plane.set_target_altitude_current();
14
}
15
16
plane.loiter_angle_reset();
17
18
return true;
19
}
20
21
void ModeLoiter::update()
22
{
23
plane.calc_nav_roll();
24
if (plane.stick_mixing_enabled() && plane.flight_option_enabled(FlightOptions::ENABLE_LOITER_ALT_CONTROL)) {
25
plane.update_fbwb_speed_height();
26
} else {
27
plane.calc_nav_pitch();
28
plane.calc_throttle();
29
}
30
31
#if AP_SCRIPTING_ENABLED
32
if (plane.nav_scripting_active()) {
33
// while a trick is running we reset altitude
34
plane.set_target_altitude_current();
35
plane.next_WP_loc.set_alt_cm(plane.target_altitude.amsl_cm, Location::AltFrame::ABSOLUTE);
36
}
37
#endif
38
}
39
40
bool ModeLoiter::isHeadingLinedUp(const Location loiterCenterLoc, const Location targetLoc)
41
{
42
// Return true if current heading is aligned to vector to targetLoc.
43
// Tolerance is initially 10 degrees and grows at 10 degrees for each loiter circle completed.
44
45
// Corrected radius for altitude
46
const float loiter_radius = plane.nav_controller->loiter_radius(fabsf(plane.loiter.radius));
47
if (!is_positive(loiter_radius)) {
48
// Zero is invalid, protect against divide by zero for destination inside loiter radius case
49
return true;
50
}
51
52
// Calculate relative position of the vehicle relative to loiter center projected onto the closest point of the loiter circle
53
// This removes error due to radial position as the nav controller attempts to track the circle
54
const Vector2f projected_pos = loiterCenterLoc.get_distance_NE(plane.current_loc).normalized() * loiter_radius;
55
56
// Target position relative to loiter center
57
const Vector2f target_pos = loiterCenterLoc.get_distance_NE(targetLoc);
58
59
// Distance between loiter circle and target
60
const float target_dist = target_pos.length();
61
if (!is_positive(target_dist)) {
62
// Target is coincident with loiter center, no heading will be closer than any other
63
return true;
64
}
65
66
// Target bearing in centi-degrees
67
int32_t target_bearing_cd;
68
69
if (target_dist >= loiter_radius) {
70
// Destination outside loiter radius, heading will always line up with destination
71
72
// Vector from between projected vehicle position and target postion
73
const Vector2f pos_to_target = target_pos - projected_pos;
74
target_bearing_cd = degrees(pos_to_target.angle()) * 100;
75
76
} else {
77
// Destination is inside loiter, heading will never line up with destination
78
79
// Advance turn point by the angle of a segment with chord "a"
80
// This results in turning earlier as the target point approaches the center
81
// If target is on radius angle of 0 and angle of 60 deg if target is on center
82
const float a = loiter_radius - target_dist;
83
const float segment_angle = 2.0 * asinf(a / (2.0 * loiter_radius));
84
85
// Pick the intersection point that will be hit first for the current loiter direction, add 90 deg to get the tangent angle
86
target_bearing_cd = degrees(wrap_PI(target_pos.angle() + (M_PI_2 - segment_angle) * plane.loiter.direction)) * 100;
87
88
}
89
90
// Ideal heading in centi-degrees, +- 90 to get tangent to loiter circle at closest point
91
const int32_t current_heading_cd = degrees(wrap_PI(projected_pos.angle() + M_PI_2 * plane.loiter.direction)) * 100;
92
93
return isHeadingLinedUp_cd(target_bearing_cd, current_heading_cd);
94
}
95
96
97
bool ModeLoiter::isHeadingLinedUp_cd(const int32_t bearing_cd) {
98
99
// get current heading.
100
const int32_t heading_cd = (wrap_360(degrees(ahrs.groundspeed_vector().angle())))*100;
101
102
return isHeadingLinedUp_cd(bearing_cd, heading_cd);
103
}
104
105
106
bool ModeLoiter::isHeadingLinedUp_cd(const int32_t bearing_cd, const int32_t heading_cd)
107
{
108
// Return true if current heading is aligned to bearing_cd.
109
// Tolerance is initially 10 degrees and grows at 10 degrees for each loiter circle completed.
110
const int32_t heading_err_cd = wrap_180_cd(bearing_cd - heading_cd);
111
112
/*
113
Check to see if the the plane is heading toward the land
114
waypoint. We use 20 degrees (+/-10 deg) of margin so that
115
we can handle 200 degrees/second of yaw.
116
117
After every full circle, extend acceptance criteria to ensure
118
aircraft will not loop forever in case high winds are forcing
119
it beyond 200 deg/sec when passing the desired exit course
120
*/
121
122
// Use integer division to get discrete steps
123
const int32_t expanded_acceptance = 1000 * (labs(plane.loiter.sum_cd) / 36000);
124
125
if (labs(heading_err_cd) <= 1000 + expanded_acceptance) {
126
// Want to head in a straight line from _here_ to the next waypoint instead of center of loiter wp
127
128
// 0 to xtrack from center of waypoint, 1 to xtrack from tangent exit location
129
if (plane.next_WP_loc.loiter_xtrack) {
130
plane.next_WP_loc = plane.current_loc;
131
}
132
return true;
133
}
134
return false;
135
}
136
137
void ModeLoiter::navigate()
138
{
139
if (plane.flight_option_enabled(FlightOptions::ENABLE_LOITER_ALT_CONTROL)) {
140
// update the WP alt from the global target adjusted by update_fbwb_speed_height
141
plane.next_WP_loc.set_alt_cm(plane.target_altitude.amsl_cm, Location::AltFrame::ABSOLUTE);
142
}
143
144
#if AP_SCRIPTING_ENABLED
145
if (plane.nav_scripting_active()) {
146
// don't try to navigate while running trick
147
return;
148
}
149
#endif
150
151
// Zero indicates to use WP_LOITER_RAD
152
plane.update_loiter(0);
153
}
154
155
void ModeLoiter::update_target_altitude()
156
{
157
if (plane.stick_mixing_enabled() && (plane.flight_option_enabled(FlightOptions::ENABLE_LOITER_ALT_CONTROL))) {
158
return;
159
}
160
Mode::update_target_altitude();
161
}
162
163