Skip to content

Commit 0a9f9f7

Browse files
committed
Add new auto-trim feature for fixed-wings
Estimates the torque trim values while flying
1 parent 6c4fa8d commit 0a9f9f7

File tree

13 files changed

+712
-76
lines changed

13 files changed

+712
-76
lines changed

msg/AutoTrimStatus.msg

Lines changed: 17 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,17 @@
1+
uint64 timestamp # Time since system start (microseconds)
2+
uint64 timestamp_sample
3+
4+
float32[3] trim_estimate # Roll/pitch/yaw trim value obtained from torque setpoints averaged over several seconds
5+
float32[3] trim_estimate_var
6+
float32[3] trim_test # Same as trim_estimate but done on a shorter period. Used to validate the trim estimate.
7+
float32[3] trim_test_var
8+
float32[3] trim_validated # Final roll/pitch/yaw trim estimate, verified by trim_test
9+
10+
uint8 STATE_IDLE = 0
11+
uint8 STATE_SAMPLING = 1
12+
uint8 STATE_SAMPLING_TEST = 2
13+
uint8 STATE_VERIFICATION = 3
14+
uint8 STATE_COMPLETE = 4
15+
uint8 STATE_FAIL = 5
16+
17+
uint8 state

msg/CMakeLists.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -52,6 +52,7 @@ set(msg_files
5252
ArmingCheckReply.msg
5353
ArmingCheckRequest.msg
5454
AutotuneAttitudeControlStatus.msg
55+
AutoTrimStatus.msg
5556
BatteryStatus.msg
5657
Buffer128.msg
5758
ButtonEvent.msg

src/lib/slew_rate/SlewRate.hpp

Lines changed: 14 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -56,13 +56,13 @@ class SlewRate
5656
* Set maximum rate of change for the value
5757
* @param slew_rate maximum rate of change
5858
*/
59-
void setSlewRate(const Type slew_rate) { _slew_rate = slew_rate; }
59+
void setSlewRate(const Type &slew_rate) { _slew_rate = slew_rate; }
6060

6161
/**
6262
* Set value ignoring slew rate for initialization purpose
6363
* @param value new applied value
6464
*/
65-
void setForcedValue(const Type value) { _value = value; }
65+
void setForcedValue(const Type &value) { _value = value; }
6666

6767
/**
6868
* Get value from last update of the slew rate
@@ -76,7 +76,7 @@ class SlewRate
7676
* @param deltatime time in seconds since last update
7777
* @return actual value that complies with the slew rate
7878
*/
79-
Type update(const Type new_value, const float deltatime)
79+
Type update(const Type &new_value, const float deltatime)
8080
{
8181
// Limit the rate of change of the value
8282
const Type dvalue_desired = new_value - _value;
@@ -90,3 +90,14 @@ class SlewRate
9090
Type _slew_rate{}; ///< maximum rate of change for the value
9191
Type _value{}; ///< state to keep last value of the slew rate
9292
};
93+
94+
template<>
95+
inline matrix::Vector3f SlewRate<matrix::Vector3f>::update(const matrix::Vector3f &new_value, const float deltatime)
96+
{
97+
// Limit the rate of change of the value
98+
const matrix::Vector3f dvalue_desired = new_value - _value;
99+
const matrix::Vector3f dvalue_max = _slew_rate * deltatime;
100+
const matrix::Vector3f dvalue = matrix::constrain(dvalue_desired, -dvalue_max, dvalue_max);
101+
_value += dvalue;
102+
return _value;
103+
}

src/modules/fw_rate_control/CMakeLists.txt

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -30,6 +30,7 @@
3030
# POSSIBILITY OF SUCH DAMAGE.
3131
#
3232
############################################################################
33+
add_subdirectory(fw_trim)
3334

3435
px4_add_module(
3536
MODULE modules__fw_rate_control
@@ -38,6 +39,7 @@ px4_add_module(
3839
FixedwingRateControl.cpp
3940
FixedwingRateControl.hpp
4041
DEPENDS
42+
FwTrim
4143
px4_work_queue
4244
RateControl
4345
SlewRate

src/modules/fw_rate_control/FixedwingRateControl.cpp

Lines changed: 57 additions & 62 deletions
Original file line numberDiff line numberDiff line change
@@ -37,7 +37,6 @@ using namespace time_literals;
3737
using namespace matrix;
3838

3939
using math::constrain;
40-
using math::interpolate;
4140
using math::radians;
4241

4342
FixedwingRateControl::FixedwingRateControl(bool vtol) :
@@ -54,6 +53,7 @@ FixedwingRateControl::FixedwingRateControl(bool vtol) :
5453
parameters_update();
5554

5655
_rate_ctrl_status_pub.advertise();
56+
_trim_slew.setSlewRate(Vector3f(0.01f, 0.01f, 0.01f));
5757
}
5858

5959
FixedwingRateControl::~FixedwingRateControl()
@@ -96,6 +96,12 @@ FixedwingRateControl::parameters_update()
9696
return PX4_OK;
9797
}
9898

99+
void
100+
FixedwingRateControl::save_params()
101+
{
102+
_trim.saveParams();
103+
}
104+
99105
void
100106
FixedwingRateControl::vehicle_manual_poll()
101107
{
@@ -127,13 +133,14 @@ FixedwingRateControl::vehicle_manual_poll()
127133

128134
} else {
129135
// Manual/direct control, filled in FW-frame. Note that setpoints will get transformed to body frame prior publishing.
136+
const Vector3f trim = _trim_slew.getState();
130137

131138
_vehicle_torque_setpoint.xyz[0] = math::constrain(_manual_control_setpoint.roll * _param_fw_man_r_sc.get() +
132-
_param_trim_roll.get(), -1.f, 1.f);
139+
trim(0), -1.f, 1.f);
133140
_vehicle_torque_setpoint.xyz[1] = math::constrain(-_manual_control_setpoint.pitch * _param_fw_man_p_sc.get() +
134-
_param_trim_pitch.get(), -1.f, 1.f);
141+
trim(1), -1.f, 1.f);
135142
_vehicle_torque_setpoint.xyz[2] = math::constrain(_manual_control_setpoint.yaw * _param_fw_man_y_sc.get() +
136-
_param_trim_yaw.get(), -1.f, 1.f);
143+
trim(2), -1.f, 1.f);
137144

138145
_vehicle_thrust_setpoint.xyz[0] = math::constrain((_manual_control_setpoint.throttle + 1.f) * .5f, 0.f, 1.f);
139146
}
@@ -256,7 +263,14 @@ void FixedwingRateControl::Run()
256263
const bool is_fixed_wing = _vehicle_status.vehicle_type == vehicle_status_s::VEHICLE_TYPE_FIXED_WING;
257264
_in_fw_or_transition_wo_tailsitter_transition = is_fixed_wing || is_in_transition_except_tailsitter;
258265

259-
_vehicle_control_mode_sub.update(&_vcontrol_mode);
266+
{
267+
const bool armed_prev = _vcontrol_mode.flag_armed;
268+
_vehicle_control_mode_sub.update(&_vcontrol_mode);
269+
270+
if (!_vcontrol_mode.flag_armed && armed_prev) {
271+
save_params();
272+
}
273+
}
260274

261275
vehicle_land_detected_poll();
262276

@@ -321,78 +335,56 @@ void FixedwingRateControl::Run()
321335
}
322336
}
323337

324-
/* bi-linear interpolation over airspeed for actuator trim scheduling */
325-
Vector3f trim(_param_trim_roll.get(), _param_trim_pitch.get(), _param_trim_yaw.get());
326-
327-
if (airspeed < _param_fw_airspd_trim.get()) {
328-
trim(0) += interpolate(airspeed, _param_fw_airspd_min.get(), _param_fw_airspd_trim.get(),
329-
_param_fw_dtrim_r_vmin.get(),
330-
0.0f);
331-
trim(1) += interpolate(airspeed, _param_fw_airspd_min.get(), _param_fw_airspd_trim.get(),
332-
_param_fw_dtrim_p_vmin.get(),
333-
0.0f);
334-
trim(2) += interpolate(airspeed, _param_fw_airspd_min.get(), _param_fw_airspd_trim.get(),
335-
_param_fw_dtrim_y_vmin.get(),
336-
0.0f);
337-
338-
} else {
339-
trim(0) += interpolate(airspeed, _param_fw_airspd_trim.get(), _param_fw_airspd_max.get(), 0.0f,
340-
_param_fw_dtrim_r_vmax.get());
341-
trim(1) += interpolate(airspeed, _param_fw_airspd_trim.get(), _param_fw_airspd_max.get(), 0.0f,
342-
_param_fw_dtrim_p_vmax.get());
343-
trim(2) += interpolate(airspeed, _param_fw_airspd_trim.get(), _param_fw_airspd_max.get(), 0.0f,
344-
_param_fw_dtrim_y_vmax.get());
345-
}
338+
_trim.setAirspeed(airspeed);
339+
_trim_slew.update(_trim.getTrim(), dt);
346340

347-
if (_vcontrol_mode.flag_control_rates_enabled) {
348-
_rates_sp_sub.update(&_rates_sp);
341+
_rates_sp_sub.update(&_rates_sp);
349342

350-
Vector3f body_rates_setpoint = Vector3f(_rates_sp.roll, _rates_sp.pitch, _rates_sp.yaw);
343+
Vector3f body_rates_setpoint = Vector3f(_rates_sp.roll, _rates_sp.pitch, _rates_sp.yaw);
351344

352-
// Tailsitter: rotate setpoint from hover to fixed-wing frame (controller is in fixed-wing frame, interface in hover)
353-
if (_vehicle_status.is_vtol_tailsitter) {
354-
body_rates_setpoint = Vector3f(-_rates_sp.yaw, _rates_sp.pitch, _rates_sp.roll);
355-
}
345+
// Tailsitter: rotate setpoint from hover to fixed-wing frame (controller is in fixed-wing frame, interface in hover)
346+
if (_vehicle_status.is_vtol_tailsitter) {
347+
body_rates_setpoint = Vector3f(-_rates_sp.yaw, _rates_sp.pitch, _rates_sp.roll);
348+
}
356349

357-
// Run attitude RATE controllers which need the desired attitudes from above, add trim.
358-
const Vector3f angular_acceleration_setpoint = _rate_control.update(rates, body_rates_setpoint, angular_accel, dt,
359-
_landed);
350+
// Run attitude RATE controllers which need the desired attitudes from above, add trim.
351+
const Vector3f angular_acceleration_setpoint = _rate_control.update(rates, body_rates_setpoint, angular_accel, dt,
352+
_landed);
360353

361-
const Vector3f gain_ff(_param_fw_rr_ff.get(), _param_fw_pr_ff.get(), _param_fw_yr_ff.get());
362-
const Vector3f feedforward = gain_ff.emult(body_rates_setpoint) * _airspeed_scaling;
354+
const Vector3f gain_ff(_param_fw_rr_ff.get(), _param_fw_pr_ff.get(), _param_fw_yr_ff.get());
355+
const Vector3f feedforward = gain_ff.emult(body_rates_setpoint) * _airspeed_scaling;
363356

364-
Vector3f control_u = angular_acceleration_setpoint * _airspeed_scaling * _airspeed_scaling + feedforward;
357+
Vector3f control_u = angular_acceleration_setpoint * _airspeed_scaling * _airspeed_scaling + feedforward;
365358

366-
// Special case yaw in Acro: if the parameter FW_ACRO_YAW_CTL is not set then don't control yaw
367-
if (!_vcontrol_mode.flag_control_attitude_enabled && !_param_fw_acro_yaw_en.get()) {
368-
control_u(2) = _manual_control_setpoint.yaw * _param_fw_man_y_sc.get();
369-
_rate_control.resetIntegral(2);
370-
}
359+
// Special case yaw in Acro: if the parameter FW_ACRO_YAW_CTL is not set then don't control yaw
360+
if (!_vcontrol_mode.flag_control_attitude_enabled && !_param_fw_acro_yaw_en.get()) {
361+
control_u(2) = _manual_control_setpoint.yaw * _param_fw_man_y_sc.get();
362+
_rate_control.resetIntegral(2);
363+
}
371364

372-
if (control_u.isAllFinite()) {
373-
matrix::constrain(control_u + trim, -1.f, 1.f).copyTo(_vehicle_torque_setpoint.xyz);
365+
if (control_u.isAllFinite()) {
366+
matrix::constrain(control_u + _trim_slew.getState(), -1.f, 1.f).copyTo(_vehicle_torque_setpoint.xyz);
374367

375-
} else {
376-
_rate_control.resetIntegral();
377-
trim.copyTo(_vehicle_torque_setpoint.xyz);
378-
}
368+
} else {
369+
_rate_control.resetIntegral();
370+
_trim_slew.getState().copyTo(_vehicle_torque_setpoint.xyz);
371+
}
379372

380-
/* throttle passed through if it is finite */
381-
_vehicle_thrust_setpoint.xyz[0] = PX4_ISFINITE(_rates_sp.thrust_body[0]) ? _rates_sp.thrust_body[0] : 0.0f;
373+
/* throttle passed through if it is finite */
374+
_vehicle_thrust_setpoint.xyz[0] = PX4_ISFINITE(_rates_sp.thrust_body[0]) ? _rates_sp.thrust_body[0] : 0.0f;
382375

383-
/* scale effort by battery status */
384-
if (_param_fw_bat_scale_en.get() && _vehicle_thrust_setpoint.xyz[0] > 0.1f) {
376+
/* scale effort by battery status */
377+
if (_param_fw_bat_scale_en.get() && _vehicle_thrust_setpoint.xyz[0] > 0.1f) {
385378

386-
if (_battery_status_sub.updated()) {
387-
battery_status_s battery_status{};
379+
if (_battery_status_sub.updated()) {
380+
battery_status_s battery_status{};
388381

389-
if (_battery_status_sub.copy(&battery_status) && battery_status.connected && battery_status.scale > 0.f) {
390-
_battery_scale = battery_status.scale;
391-
}
382+
if (_battery_status_sub.copy(&battery_status) && battery_status.connected && battery_status.scale > 0.f) {
383+
_battery_scale = battery_status.scale;
392384
}
393-
394-
_vehicle_thrust_setpoint.xyz[0] *= _battery_scale;
395385
}
386+
387+
_vehicle_thrust_setpoint.xyz[0] *= _battery_scale;
396388
}
397389

398390
// publish rate controller status
@@ -405,6 +397,7 @@ void FixedwingRateControl::Run()
405397
} else {
406398
// full manual
407399
_rate_control.resetIntegral();
400+
_trim.reset();
408401
}
409402

410403
// Add feed-forward from roll control output to yaw control output
@@ -432,6 +425,8 @@ void FixedwingRateControl::Run()
432425
_vehicle_torque_setpoint.timestamp_sample = angular_velocity.timestamp_sample;
433426
_vehicle_torque_setpoint_pub.publish(_vehicle_torque_setpoint);
434427
}
428+
429+
_trim.updateAutoTrim(Vector3f(_vehicle_torque_setpoint.xyz), dt);
435430
}
436431

437432
updateActuatorControlsStatus(dt);

src/modules/fw_rate_control/FixedwingRateControl.hpp

Lines changed: 7 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -69,6 +69,8 @@
6969
#include <uORB/topics/vehicle_thrust_setpoint.h>
7070
#include <uORB/topics/vehicle_torque_setpoint.h>
7171

72+
#include "fw_trim/FwTrim.hpp"
73+
7274
using matrix::Eulerf;
7375
using matrix::Quatf;
7476

@@ -170,13 +172,6 @@ class FixedwingRateControl final : public ModuleBase<FixedwingRateControl>, publ
170172

171173
(ParamBool<px4::params::FW_BAT_SCALE_EN>) _param_fw_bat_scale_en,
172174

173-
(ParamFloat<px4::params::FW_DTRIM_P_VMAX>) _param_fw_dtrim_p_vmax,
174-
(ParamFloat<px4::params::FW_DTRIM_P_VMIN>) _param_fw_dtrim_p_vmin,
175-
(ParamFloat<px4::params::FW_DTRIM_R_VMAX>) _param_fw_dtrim_r_vmax,
176-
(ParamFloat<px4::params::FW_DTRIM_R_VMIN>) _param_fw_dtrim_r_vmin,
177-
(ParamFloat<px4::params::FW_DTRIM_Y_VMAX>) _param_fw_dtrim_y_vmax,
178-
(ParamFloat<px4::params::FW_DTRIM_Y_VMIN>) _param_fw_dtrim_y_vmin,
179-
180175
(ParamFloat<px4::params::FW_MAN_P_SC>) _param_fw_man_p_sc,
181176
(ParamFloat<px4::params::FW_MAN_R_SC>) _param_fw_man_r_sc,
182177
(ParamFloat<px4::params::FW_MAN_Y_SC>) _param_fw_man_y_sc,
@@ -200,22 +195,23 @@ class FixedwingRateControl final : public ModuleBase<FixedwingRateControl>, publ
200195
(ParamFloat<px4::params::FW_YR_P>) _param_fw_yr_p,
201196
(ParamFloat<px4::params::FW_YR_D>) _param_fw_yr_d,
202197

203-
(ParamFloat<px4::params::TRIM_PITCH>) _param_trim_pitch,
204-
(ParamFloat<px4::params::TRIM_ROLL>) _param_trim_roll,
205-
(ParamFloat<px4::params::TRIM_YAW>) _param_trim_yaw,
206-
207198
(ParamInt<px4::params::FW_SPOILERS_MAN>) _param_fw_spoilers_man
208199
)
209200

210201
RateControl _rate_control; ///< class for rate control calculations
211202

203+
FwTrim _trim{this};
204+
SlewRate<matrix::Vector3f> _trim_slew{}; ///< prevents large trim changes
205+
212206
void updateActuatorControlsStatus(float dt);
213207

214208
/**
215209
* Update our local parameter cache.
216210
*/
217211
int parameters_update();
218212

213+
void save_params();
214+
219215
void vehicle_manual_poll();
220216
void vehicle_land_detected_poll();
221217

src/modules/fw_rate_control/fw_rate_control_params.c

Lines changed: 15 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -295,6 +295,21 @@ PARAM_DEFINE_INT32(FW_BAT_SCALE_EN, 0);
295295
*/
296296
PARAM_DEFINE_INT32(FW_ARSP_SCALE_EN, 1);
297297

298+
/**
299+
* Auto-Trim mode
300+
*
301+
* In calibration mode, the estimated trim is used to set the TRIM_ROLL/PITCH/YAW
302+
* parameters after landing. The parameter is then changed to continuous mode.
303+
* In continuous mode, part of the auto-trim estimated
304+
* during flight is used to update the exitsting trim.
305+
*
306+
* @group FW Rate Control
307+
* @value 0 Disabled
308+
* @value 1 Calibration
309+
* @value 2 Continuous
310+
*/
311+
PARAM_DEFINE_INT32(FW_ATRIM_MODE, 1);
312+
298313
/**
299314
* Roll trim increment at minimum airspeed
300315
*
Lines changed: 39 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,39 @@
1+
############################################################################
2+
#
3+
# Copyright (c) 2024 PX4 Development Team. All rights reserved.
4+
#
5+
# Redistribution and use in source and binary forms, with or without
6+
# modification, are permitted provided that the following conditions
7+
# are met:
8+
#
9+
# 1. Redistributions of source code must retain the above copyright
10+
# notice, this list of conditions and the following disclaimer.
11+
# 2. Redistributions in binary form must reproduce the above copyright
12+
# notice, this list of conditions and the following disclaimer in
13+
# the documentation and/or other materials provided with the
14+
# distribution.
15+
# 3. Neither the name PX4 nor the names of its contributors may be
16+
# used to endorse or promote products derived from this software
17+
# without specific prior written permission.
18+
#
19+
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
20+
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
21+
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
22+
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
23+
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
24+
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
25+
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
26+
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
27+
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
28+
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
29+
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30+
# POSSIBILITY OF SUCH DAMAGE.
31+
#
32+
############################################################################
33+
px4_add_library(FwTrim
34+
FwTrim.cpp
35+
FwAutoTrim.cpp
36+
)
37+
38+
# target_link_libraries(FwTrim)
39+
target_include_directories(FwTrim PUBLIC ${CMAKE_CURRENT_SOURCE_DIR})

0 commit comments

Comments
 (0)