MulticopterHoverThrustEstimator.cpp
8.17 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
/****************************************************************************
*
* Copyright (c) 2020 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file hover_thrust_estimator.cpp
*
* @author Mathieu Bresciani <brescianimathieu@gmail.com>
*/
#include "MulticopterHoverThrustEstimator.hpp"
#include <mathlib/mathlib.h>
using namespace time_literals;
MulticopterHoverThrustEstimator::MulticopterHoverThrustEstimator() :
ModuleParams(nullptr),
WorkItem(MODULE_NAME, px4::wq_configurations::nav_and_controllers)
{
_valid_hysteresis.set_hysteresis_time_from(false, 2_s);
updateParams();
reset();
}
MulticopterHoverThrustEstimator::~MulticopterHoverThrustEstimator()
{
perf_free(_cycle_perf);
}
bool MulticopterHoverThrustEstimator::init()
{
if (!_vehicle_local_position_sub.registerCallback()) {
PX4_ERR("vehicle_local_position_setpoint callback registration failed!");
return false;
}
return true;
}
void MulticopterHoverThrustEstimator::reset()
{
_hover_thrust_ekf.setHoverThrust(_param_mpc_thr_hover.get());
_hover_thrust_ekf.setHoverThrustStdDev(_param_hte_ht_err_init.get());
_hover_thrust_ekf.resetAccelNoise();
}
void MulticopterHoverThrustEstimator::updateParams()
{
const float ht_err_init_prev = _param_hte_ht_err_init.get();
ModuleParams::updateParams();
_hover_thrust_ekf.setProcessNoiseStdDev(_param_hte_ht_noise.get());
if (fabsf(_param_hte_ht_err_init.get() - ht_err_init_prev) > FLT_EPSILON) {
_hover_thrust_ekf.setHoverThrustStdDev(_param_hte_ht_err_init.get());
}
_hover_thrust_ekf.setAccelInnovGate(_param_hte_acc_gate.get());
}
void MulticopterHoverThrustEstimator::Run()
{
if (should_exit()) {
_vehicle_local_position_sub.unregisterCallback();
exit_and_cleanup();
return;
}
if (_vehicle_land_detected_sub.updated()) {
vehicle_land_detected_s vehicle_land_detected;
if (_vehicle_land_detected_sub.copy(&vehicle_land_detected)) {
_landed = vehicle_land_detected.landed;
if (_landed) {
_in_air = false;
}
}
}
if (!_vehicle_local_position_sub.updated()) {
return;
}
vehicle_local_position_s local_pos{};
if (_vehicle_local_position_sub.copy(&local_pos)) {
// This is only necessary because the landed
// flag of the land detector does not guarantee that
// the vehicle does not touch the ground anymore.
// There is no check for the dist_bottom validity as
// this value is always good enough after takeoff for
// this use case.
// TODO: improve the landed flag
if (!_landed) {
if (local_pos.dist_bottom > 1.f) {
_in_air = true;
}
}
}
// new local position setpoint needed every iteration
if (!_vehicle_local_position_setpoint_sub.updated()) {
return;
}
// check for parameter updates
if (_parameter_update_sub.updated()) {
// clear update
parameter_update_s pupdate;
_parameter_update_sub.copy(&pupdate);
// update parameters from storage
updateParams();
}
perf_begin(_cycle_perf);
if (_vehicle_status_sub.updated()) {
vehicle_status_s vehicle_status;
if (_vehicle_status_sub.copy(&vehicle_status)) {
_armed = (vehicle_status.arming_state == vehicle_status_s::ARMING_STATE_ARMED);
}
}
const float dt = (local_pos.timestamp - _timestamp_last) * 1e-6f;
_timestamp_last = local_pos.timestamp;
if (_armed && _in_air && (dt > 0.001f) && (dt < 1.f) && PX4_ISFINITE(local_pos.az)) {
_hover_thrust_ekf.predict(dt);
vehicle_local_position_setpoint_s local_pos_sp;
if (_vehicle_local_position_setpoint_sub.copy(&local_pos_sp)) {
if (PX4_ISFINITE(local_pos_sp.thrust[2])) {
// Inform the hover thrust estimator about the measured vertical
// acceleration (positive acceleration is up) and the current thrust (positive thrust is up)
// Guard against fast up and down motions biasing the estimator due to large drag and prop wash effects
if (fabsf(local_pos.vz) < 2.f) {
_hover_thrust_ekf.fuseAccZ(-local_pos.az, -local_pos_sp.thrust[2]);
}
const bool valid = (_hover_thrust_ekf.getHoverThrustEstimateVar() < 0.001f)
&& (_hover_thrust_ekf.getInnovationTestRatio() < 1.f);
_valid_hysteresis.set_state_and_update(valid, local_pos.timestamp);
_valid = _valid_hysteresis.get_state();
publishStatus(local_pos.timestamp);
}
}
} else {
_valid_hysteresis.set_state_and_update(false, hrt_absolute_time());
if (!_armed) {
reset();
}
if (_valid) {
// only publish a single message to invalidate
publishInvalidStatus();
_valid = false;
}
}
perf_end(_cycle_perf);
}
void MulticopterHoverThrustEstimator::publishStatus(const hrt_abstime ×tamp_sample)
{
hover_thrust_estimate_s status_msg{};
status_msg.timestamp_sample = timestamp_sample;
status_msg.hover_thrust = _hover_thrust_ekf.getHoverThrustEstimate();
status_msg.hover_thrust_var = _hover_thrust_ekf.getHoverThrustEstimateVar();
status_msg.accel_innov = _hover_thrust_ekf.getInnovation();
status_msg.accel_innov_var = _hover_thrust_ekf.getInnovationVar();
status_msg.accel_innov_test_ratio = _hover_thrust_ekf.getInnovationTestRatio();
status_msg.accel_noise_var = _hover_thrust_ekf.getAccelNoiseVar();
status_msg.valid = _valid;
status_msg.timestamp = hrt_absolute_time();
_hover_thrust_ekf_pub.publish(status_msg);
}
void MulticopterHoverThrustEstimator::publishInvalidStatus()
{
hover_thrust_estimate_s status_msg{};
status_msg.hover_thrust = NAN;
status_msg.hover_thrust_var = NAN;
status_msg.accel_innov = NAN;
status_msg.accel_innov_var = NAN;
status_msg.accel_innov_test_ratio = NAN;
status_msg.accel_noise_var = NAN;
status_msg.timestamp = hrt_absolute_time();
_hover_thrust_ekf_pub.publish(status_msg);
}
int MulticopterHoverThrustEstimator::task_spawn(int argc, char *argv[])
{
MulticopterHoverThrustEstimator *instance = new MulticopterHoverThrustEstimator();
if (instance) {
_object.store(instance);
_task_id = task_id_is_work_queue;
if (instance->init()) {
return PX4_OK;
}
} else {
PX4_ERR("alloc failed");
}
delete instance;
_object.store(nullptr);
_task_id = -1;
return PX4_ERROR;
}
int MulticopterHoverThrustEstimator::custom_command(int argc, char *argv[])
{
return print_usage("unknown command");
}
int MulticopterHoverThrustEstimator::print_status()
{
perf_print_counter(_cycle_perf);
return 0;
}
int MulticopterHoverThrustEstimator::print_usage(const char *reason)
{
if (reason) {
PX4_WARN("%s\n", reason);
}
PRINT_MODULE_DESCRIPTION(
R"DESCR_STR(
### Description
)DESCR_STR");
PRINT_MODULE_USAGE_NAME("mc_hover_thrust_estimator", "estimator");
PRINT_MODULE_USAGE_COMMAND("start");
PRINT_MODULE_USAGE_DEFAULT_COMMANDS();
return 0;
}
extern "C" __EXPORT int mc_hover_thrust_estimator_main(int argc, char *argv[])
{
return MulticopterHoverThrustEstimator::main(argc, argv);
}