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/Rover/mode_smart_rtl.cpp
Views: 1798
1
#include "Rover.h"
2
3
bool ModeSmartRTL::_enter()
4
{
5
// SmartRTL requires EKF (not DCM)
6
Location ekf_origin;
7
if (!ahrs.get_origin(ekf_origin)) {
8
return false;
9
}
10
11
// refuse to enter SmartRTL if smart RTL's home has not been set
12
if (!g2.smart_rtl.is_active()) {
13
return false;
14
}
15
16
// initialise waypoint navigation library
17
g2.wp_nav.init(MAX(0, g2.rtl_speed));
18
19
// set desired location to reasonable stopping point
20
if (!g2.wp_nav.set_desired_location_to_stopping_location()) {
21
return false;
22
}
23
24
// init state
25
smart_rtl_state = SmartRTLState::WaitForPathCleanup;
26
_loitering = false;
27
28
return true;
29
}
30
31
void ModeSmartRTL::update()
32
{
33
switch (smart_rtl_state) {
34
case SmartRTLState::WaitForPathCleanup:
35
// check if return path is computed and if yes, begin journey home
36
if (g2.smart_rtl.request_thorough_cleanup()) {
37
smart_rtl_state = SmartRTLState::PathFollow;
38
_load_point = true;
39
}
40
// Note: this may lead to an unnecessary 20ms slow down of the vehicle (but it is unlikely)
41
stop_vehicle();
42
break;
43
44
case SmartRTLState::PathFollow:
45
// load point if required
46
if (_load_point) {
47
Vector3f dest_NED;
48
if (!g2.smart_rtl.pop_point(dest_NED)) {
49
// if not more points, we have reached home
50
gcs().send_text(MAV_SEVERITY_INFO, "Reached destination");
51
smart_rtl_state = SmartRTLState::StopAtHome;
52
break;
53
} else {
54
// peek at the next point. this can fail if the IO task currently has the path semaphore
55
Vector3f next_dest_NED;
56
if (g2.smart_rtl.peek_point(next_dest_NED)) {
57
if (!g2.wp_nav.set_desired_location_NED(dest_NED, next_dest_NED)) {
58
// this should never happen because the EKF origin should already be set
59
gcs().send_text(MAV_SEVERITY_INFO, "SmartRTL: failed to set destination");
60
smart_rtl_state = SmartRTLState::Failure;
61
INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);
62
}
63
} else {
64
// no next point so add only immediate point
65
if (!g2.wp_nav.set_desired_location_NED(dest_NED)) {
66
// this should never happen because the EKF origin should already be set
67
gcs().send_text(MAV_SEVERITY_INFO, "SmartRTL: failed to set destination");
68
smart_rtl_state = SmartRTLState::Failure;
69
INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);
70
}
71
}
72
}
73
_load_point = false;
74
}
75
// update navigation controller
76
navigate_to_waypoint();
77
78
// check if we've reached the next point
79
if (g2.wp_nav.reached_destination()) {
80
_load_point = true;
81
}
82
break;
83
84
case SmartRTLState::StopAtHome:
85
case SmartRTLState::Failure:
86
_reached_destination = true;
87
// we have reached the destination
88
// boats loiters, rovers stop
89
if (!rover.is_boat()) {
90
stop_vehicle();
91
} else {
92
// if not loitering yet, start loitering
93
if (!_loitering) {
94
_loitering = rover.mode_loiter.enter();
95
}
96
if (_loitering) {
97
rover.mode_loiter.update();
98
} else {
99
stop_vehicle();
100
}
101
}
102
break;
103
}
104
}
105
106
// get desired location
107
bool ModeSmartRTL::get_desired_location(Location& destination) const
108
{
109
switch (smart_rtl_state) {
110
case SmartRTLState::WaitForPathCleanup:
111
return false;
112
case SmartRTLState::PathFollow:
113
if (g2.wp_nav.is_destination_valid()) {
114
destination = g2.wp_nav.get_destination();
115
return true;
116
}
117
return false;
118
case SmartRTLState::StopAtHome:
119
case SmartRTLState::Failure:
120
return false;
121
}
122
// should never reach here but just in case
123
return false;
124
}
125
126
// set desired speed in m/s
127
bool ModeSmartRTL::set_desired_speed(float speed)
128
{
129
return g2.wp_nav.set_speed_max(speed);
130
}
131
132
// save current position for use by the smart_rtl flight mode
133
void ModeSmartRTL::save_position()
134
{
135
const bool save_pos = (rover.control_mode != &rover.mode_smartrtl);
136
g2.smart_rtl.update(true, save_pos);
137
}
138
139