Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/ArduSub/mode_surftrak.cpp
9484 views
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
55
if (!motors.armed()) {
56
// Forget rangefinder target
57
reset();
58
} else {
59
control_range();
60
}
61
62
run_post();
63
}
64
65
/*
66
* Set the rangefinder target, return true if successful. This may be called from scripting so run a few extra checks.
67
*/
68
bool ModeSurftrak::set_rangefinder_target_cm(float target_cm)
69
{
70
bool success = false;
71
72
#if AP_RANGEFINDER_ENABLED
73
if (sub.control_mode != Number::SURFTRAK) {
74
sub.gcs().send_text(MAV_SEVERITY_WARNING, "wrong mode, rangefinder target not set");
75
} else if (sub.inertial_nav.get_position_z_up_cm() >= sub.g.surftrak_depth) {
76
sub.gcs().send_text(MAV_SEVERITY_WARNING, "descend below %f meters to set rangefinder target", sub.g.surftrak_depth * 0.01f);
77
} else if (target_cm < sub.rangefinder_state.min*100) {
78
sub.gcs().send_text(MAV_SEVERITY_WARNING, "rangefinder target below minimum, ignored");
79
} else if (target_cm > sub.rangefinder_state.max*100) {
80
sub.gcs().send_text(MAV_SEVERITY_WARNING, "rangefinder target above maximum, ignored");
81
} else {
82
success = true;
83
}
84
85
if (success) {
86
rangefinder_target_cm = target_cm;
87
sub.gcs().send_text(MAV_SEVERITY_INFO, "rangefinder target is %.2f meters", rangefinder_target_cm * 0.01f);
88
89
// Initialize the terrain offset
90
auto terrain_offset_cm = sub.inertial_nav.get_position_z_up_cm() - rangefinder_target_cm;
91
sub.pos_control.init_pos_terrain_U_cm(terrain_offset_cm);
92
93
} else {
94
reset();
95
}
96
#endif
97
98
return success;
99
}
100
101
void ModeSurftrak::reset()
102
{
103
rangefinder_target_cm = INVALID_TARGET;
104
105
// Reset the terrain offset
106
sub.pos_control.init_pos_terrain_U_cm(0);
107
}
108
109
/*
110
* Main controller, call at 100hz+
111
*/
112
void ModeSurftrak::control_range() {
113
float target_climb_rate_cms = sub.get_pilot_desired_climb_rate(channel_throttle->get_control_in());
114
target_climb_rate_cms = constrain_float(target_climb_rate_cms, -sub.get_pilot_speed_dn(), g.pilot_speed_up);
115
116
// Desired_climb_rate returns 0 when within the deadzone
117
if (fabsf(target_climb_rate_cms) < 0.05f) {
118
if (pilot_in_control) {
119
// Pilot has released control; apply the delta to the rangefinder target
120
set_rangefinder_target_cm(rangefinder_target_cm + inertial_nav.get_position_z_up_cm() - pilot_control_start_z_cm);
121
pilot_in_control = false;
122
}
123
if (sub.ap.at_surface) {
124
// Set target depth to 5 cm below SURFACE_DEPTH and reset
125
position_control->set_pos_desired_U_cm(MIN(position_control->get_pos_desired_U_cm(), g.surface_depth - 5.0f));
126
reset();
127
} else if (sub.ap.at_bottom) {
128
// Set target depth to 10 cm above bottom and reset
129
position_control->set_pos_desired_U_cm(MAX(inertial_nav.get_position_z_up_cm() + 10.0f, position_control->get_pos_desired_U_cm()));
130
reset();
131
} else {
132
// Typical operation
133
update_surface_offset();
134
}
135
} else if (HAS_VALID_TARGET && !pilot_in_control) {
136
// Pilot has taken control; note the current depth
137
pilot_control_start_z_cm = inertial_nav.get_position_z_up_cm();
138
pilot_in_control = true;
139
}
140
141
// Set the target altitude from the climb rate and the terrain offset
142
position_control->D_set_pos_target_from_climb_rate_cms(target_climb_rate_cms);
143
144
// Run the PID controllers
145
position_control->D_update_controller();
146
}
147
148
/*
149
* Update the AC_PosControl terrain offset if we have a good rangefinder reading
150
*/
151
void ModeSurftrak::update_surface_offset()
152
{
153
#if AP_RANGEFINDER_ENABLED
154
if (sub.rangefinder_alt_ok()) {
155
// Get the latest terrain offset
156
float rangefinder_terrain_offset_cm = sub.rangefinder_state.rangefinder_terrain_offset_cm;
157
158
// Handle the first reading or a reset
159
if (!HAS_VALID_TARGET && sub.rangefinder_state.inertial_alt_cm < sub.g.surftrak_depth) {
160
set_rangefinder_target_cm(sub.rangefinder_state.inertial_alt_cm - rangefinder_terrain_offset_cm);
161
}
162
163
if (HAS_VALID_TARGET) {
164
// Will the new offset target cause the sub to ascend above SURFTRAK_DEPTH?
165
float desired_z_cm = rangefinder_terrain_offset_cm + rangefinder_target_cm;
166
if (desired_z_cm >= sub.g.surftrak_depth) {
167
// Adjust the terrain offset to stay below SURFTRAK_DEPTH, this should avoid "at_surface" events
168
rangefinder_terrain_offset_cm += sub.g.surftrak_depth - desired_z_cm;
169
}
170
171
// Set the offset target, AC_PosControl will do the rest
172
sub.pos_control.set_pos_terrain_target_U_cm(rangefinder_terrain_offset_cm);
173
}
174
}
175
#endif // AP_RANGEFINDER_ENABLED
176
}
177
178