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/ArduSub/mode_surftrak.cpp
Views: 1798
1
#include "Sub.h"
2
3
/*
4
* SURFTRAK (surface tracking) -- a variation on ALT_HOLD (depth hold)
5
*
6
* SURFTRAK starts in the "reset" state (rangefinder_target_cm < 0). SURFTRAK exits the reset state when these
7
* conditions are met:
8
* -- There is a good rangefinder reading (the rangefinder is healthy, the reading is between min and max, etc.)
9
* -- The sub is below SURFTRAK_DEPTH
10
*
11
* During normal operation, SURFTRAK sets the offset target to the current terrain altitude estimate and calls
12
* AC_PosControl to do the rest.
13
*
14
* We generally do not want to reset SURFTRAK if the rangefinder glitches, since that will result in a new rangefinder
15
* target. E.g., if a pilot is running 1m above the seafloor, there is a glitch, and the next rangefinder reading shows
16
* 1.1m, the desired behavior is to move 10cm closer to the seafloor, vs setting a new target of 1.1m above the
17
* seafloor.
18
*
19
* If the pilot takes control, SURFTRAK uses the change in depth readings to adjust the rangefinder target. This
20
* minimizes the "bounce back" that can happen as the slower rangefinder catches up to the quicker barometer.
21
*/
22
23
#define INVALID_TARGET (-1)
24
#define HAS_VALID_TARGET (rangefinder_target_cm > 0)
25
26
ModeSurftrak::ModeSurftrak() :
27
rangefinder_target_cm(INVALID_TARGET),
28
pilot_in_control(false),
29
pilot_control_start_z_cm(0)
30
{ }
31
32
bool ModeSurftrak::init(bool ignore_checks)
33
{
34
if (!ModeAlthold::init(ignore_checks)) {
35
return false;
36
}
37
38
reset();
39
40
if (!sub.rangefinder_alt_ok()) {
41
sub.gcs().send_text(MAV_SEVERITY_INFO, "waiting for a rangefinder reading");
42
#if AP_RANGEFINDER_ENABLED
43
} else if (sub.inertial_nav.get_position_z_up_cm() >= sub.g.surftrak_depth) {
44
sub.gcs().send_text(MAV_SEVERITY_WARNING, "descend below %f meters to hold range", sub.g.surftrak_depth * 0.01f);
45
#endif
46
}
47
48
return true;
49
}
50
51
void ModeSurftrak::run()
52
{
53
run_pre();
54
control_range();
55
run_post();
56
}
57
58
/*
59
* Set the rangefinder target, return true if successful. This may be called from scripting so run a few extra checks.
60
*/
61
bool ModeSurftrak::set_rangefinder_target_cm(float target_cm)
62
{
63
bool success = false;
64
65
#if AP_RANGEFINDER_ENABLED
66
if (sub.control_mode != Number::SURFTRAK) {
67
sub.gcs().send_text(MAV_SEVERITY_WARNING, "wrong mode, rangefinder target not set");
68
} else if (sub.inertial_nav.get_position_z_up_cm() >= sub.g.surftrak_depth) {
69
sub.gcs().send_text(MAV_SEVERITY_WARNING, "descend below %f meters to set rangefinder target", sub.g.surftrak_depth * 0.01f);
70
} else if (target_cm < (float)sub.rangefinder_state.min_cm) {
71
sub.gcs().send_text(MAV_SEVERITY_WARNING, "rangefinder target below minimum, ignored");
72
} else if (target_cm > (float)sub.rangefinder_state.max_cm) {
73
sub.gcs().send_text(MAV_SEVERITY_WARNING, "rangefinder target above maximum, ignored");
74
} else {
75
success = true;
76
}
77
78
if (success) {
79
rangefinder_target_cm = target_cm;
80
sub.gcs().send_text(MAV_SEVERITY_INFO, "rangefinder target is %.2f meters", rangefinder_target_cm * 0.01f);
81
82
// Initialize the terrain offset
83
auto terrain_offset_cm = sub.inertial_nav.get_position_z_up_cm() - rangefinder_target_cm;
84
sub.pos_control.init_pos_terrain_cm(terrain_offset_cm);
85
86
} else {
87
reset();
88
}
89
#endif
90
91
return success;
92
}
93
94
void ModeSurftrak::reset()
95
{
96
rangefinder_target_cm = INVALID_TARGET;
97
98
// Reset the terrain offset
99
sub.pos_control.init_pos_terrain_cm(0);
100
}
101
102
/*
103
* Main controller, call at 100hz+
104
*/
105
void ModeSurftrak::control_range() {
106
float target_climb_rate_cm_s = sub.get_pilot_desired_climb_rate(channel_throttle->get_control_in());
107
target_climb_rate_cm_s = constrain_float(target_climb_rate_cm_s, -sub.get_pilot_speed_dn(), g.pilot_speed_up);
108
109
// Desired_climb_rate returns 0 when within the deadzone
110
if (fabsf(target_climb_rate_cm_s) < 0.05f) {
111
if (pilot_in_control) {
112
// Pilot has released control; apply the delta to the rangefinder target
113
set_rangefinder_target_cm(rangefinder_target_cm + inertial_nav.get_position_z_up_cm() - pilot_control_start_z_cm);
114
pilot_in_control = false;
115
}
116
if (sub.ap.at_surface) {
117
// Set target depth to 5 cm below SURFACE_DEPTH and reset
118
position_control->set_pos_desired_z_cm(MIN(position_control->get_pos_desired_z_cm(), g.surface_depth - 5.0f));
119
reset();
120
} else if (sub.ap.at_bottom) {
121
// Set target depth to 10 cm above bottom and reset
122
position_control->set_pos_desired_z_cm(MAX(inertial_nav.get_position_z_up_cm() + 10.0f, position_control->get_pos_desired_z_cm()));
123
reset();
124
} else {
125
// Typical operation
126
update_surface_offset();
127
}
128
} else if (HAS_VALID_TARGET && !pilot_in_control) {
129
// Pilot has taken control; note the current depth
130
pilot_control_start_z_cm = inertial_nav.get_position_z_up_cm();
131
pilot_in_control = true;
132
}
133
134
// Set the target altitude from the climb rate and the terrain offset
135
position_control->set_pos_target_z_from_climb_rate_cm(target_climb_rate_cm_s);
136
137
// Run the PID controllers
138
position_control->update_z_controller();
139
}
140
141
/*
142
* Update the AC_PosControl terrain offset if we have a good rangefinder reading
143
*/
144
void ModeSurftrak::update_surface_offset()
145
{
146
#if AP_RANGEFINDER_ENABLED
147
if (sub.rangefinder_alt_ok()) {
148
// Get the latest terrain offset
149
float rangefinder_terrain_offset_cm = sub.rangefinder_state.rangefinder_terrain_offset_cm;
150
151
// Handle the first reading or a reset
152
if (!HAS_VALID_TARGET && sub.rangefinder_state.inertial_alt_cm < sub.g.surftrak_depth) {
153
set_rangefinder_target_cm(sub.rangefinder_state.inertial_alt_cm - rangefinder_terrain_offset_cm);
154
}
155
156
if (HAS_VALID_TARGET) {
157
// Will the new offset target cause the sub to ascend above SURFTRAK_DEPTH?
158
float desired_z_cm = rangefinder_terrain_offset_cm + rangefinder_target_cm;
159
if (desired_z_cm >= sub.g.surftrak_depth) {
160
// Adjust the terrain offset to stay below SURFTRAK_DEPTH, this should avoid "at_surface" events
161
rangefinder_terrain_offset_cm += sub.g.surftrak_depth - desired_z_cm;
162
}
163
164
// Set the offset target, AC_PosControl will do the rest
165
sub.pos_control.set_pos_terrain_target_cm(rangefinder_terrain_offset_cm);
166
}
167
}
168
#endif // AP_RANGEFINDER_ENABLED
169
}
170
171