Compare commits

...

10 Commits

Author SHA1 Message Date
Daniel Agar 153b683a0e module.h fix trivial whitespace astyle failure 2024-06-20 15:50:25 -04:00
Thomas Debrunner eba9276e6f system: never call task_delete on nuttx, never force stop tasks 2024-06-20 13:31:51 +02:00
fury1895 e4fc3022f2 gimbal - input_mavlink: return NoUpdate by default 2024-06-19 13:52:27 +02:00
Daniel Agar 741c7ab610 Update submodule GPS drivers to latest Wed Jun 19 00:38:26 UTC 2024
- GPS drivers in PX4/Firmware (e5d44cc1ba691f075bc2bce52dea7ec88af9e6cd): https://github.com/PX4/PX4-GPSDrivers/commit/0b79ec4dbe3e5ac5925c011067e7e294033a0a32
    - GPS drivers current upstream: https://github.com/PX4/PX4-GPSDrivers/commit/a41210ede8c2d22dd8e9fdcf388fca927c1fc5e1
    - Changes: https://github.com/PX4/PX4-GPSDrivers/compare/0b79ec4dbe3e5ac5925c011067e7e294033a0a32...a41210ede8c2d22dd8e9fdcf388fca927c1fc5e1

    a41210e 2024-06-18 Daniel Agar - sbf: fix code style
2024-06-18 21:03:27 -04:00
Eric Katzfey c334e488e4 Changed Serial readAtLeast timeout from microseconds to milliseconds 2024-06-18 18:48:56 -04:00
Daniel Agar e33ba810e9 boards: px4_fmu-v5x_test disable differential_drive module to fix flash overflow 2024-06-18 18:48:13 -04:00
Daniel Agar 69a4a11c7f boards: cuav/nora disable modules to fix flash overflow 2024-06-18 18:47:42 -04:00
Daniel Agar 81f26be846 Update submodule GPS drivers to latest Tue Jun 18 12:39:32 UTC 2024
- GPS drivers in PX4/Firmware (c29d189788090f6994e488f65789a8fe6b835d8d): https://github.com/PX4/PX4-GPSDrivers/commit/d92cf3a2b2704d5509b651bfca33cdfea3a7a18a
    - GPS drivers current upstream: https://github.com/PX4/PX4-GPSDrivers/commit/0b79ec4dbe3e5ac5925c011067e7e294033a0a32
    - Changes: https://github.com/PX4/PX4-GPSDrivers/compare/d92cf3a2b2704d5509b651bfca33cdfea3a7a18a...0b79ec4dbe3e5ac5925c011067e7e294033a0a32

0b79ec4 2024-04-12 Thomas Frans - sbf: fix issue with automatic base config in QGC
5810dac 2024-04-12 Thomas Frans - style: add editorconfig file for consistent style
915024c 2024-03-26 Julian Oes - sbf: fix subsequent init in QGC
3ea1d76 2024-03-04 Julian Oes - sbf: don't foget to configure RTCM
c6da592 2024-03-04 Julian Oes - sbf: don't change baudrate of USB port

Co-authored-by: PX4 BuildBot <bot@px4.io>
2024-06-18 13:55:02 -04:00
PX4 BuildBot 38956e50ce Update submodule mavlink to latest Tue Jun 18 12:39:42 UTC 2024
- mavlink in PX4/Firmware (7d9b119283b5aff3976431bd48e4308a0bce7b56): https://github.com/mavlink/mavlink/commit/9e0d01df69e2f659114070db5545a35ddf61cae8
    - mavlink current upstream: https://github.com/mavlink/mavlink/commit/da3223ff9380bfe8e496fab8df2cbb06d5f8d5c3
    - Changes: https://github.com/mavlink/mavlink/compare/9e0d01df69e2f659114070db5545a35ddf61cae8...da3223ff9380bfe8e496fab8df2cbb06d5f8d5c3

    da3223ff 2024-06-13 Thomas Frans - gps: add status and integrity information (#2110)
2024-06-18 11:48:00 -04:00
Daniel Agar 8b9900cce3 mc_pos_control: new velocity low pass and notch filter (optional, disabled by default)
- MPC_VEL_LP: new velocity first order low pass filter (off by default)
 - MPC_VEL_NF_FRQ/MPC_VEL_NF_BW: new velocity notch filter (off by default)
 - MPC_VELD_LP: existing velocity derivative low pass filter, but I've dropped the remaining controllib usage
2024-06-18 11:47:19 -04:00
16 changed files with 160 additions and 60 deletions
-4
View File
@@ -39,7 +39,6 @@ CONFIG_DRIVERS_TONE_ALARM=y
CONFIG_DRIVERS_UAVCAN=y
CONFIG_BOARD_UAVCAN_TIMER_OVERRIDE=2
CONFIG_MODULES_AIRSPEED_SELECTOR=y
CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y
CONFIG_MODULES_BATTERY_STATUS=y
CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
@@ -58,7 +57,6 @@ CONFIG_MODULES_GYRO_CALIBRATION=y
CONFIG_MODULES_LAND_DETECTOR=y
CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y
CONFIG_MODULES_LOAD_MON=y
CONFIG_MODULES_LOCAL_POSITION_ESTIMATOR=y
CONFIG_MODULES_LOGGER=y
CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y
CONFIG_MODULES_MANUAL_CONTROL=y
@@ -70,7 +68,6 @@ CONFIG_MODULES_MC_POS_CONTROL=y
CONFIG_MODULES_MC_RATE_CONTROL=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_ROVER_POS_CONTROL=y
CONFIG_MODULES_SENSORS=y
CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
@@ -98,4 +95,3 @@ CONFIG_SYSTEMCMDS_UORB=y
CONFIG_SYSTEMCMDS_USB_CONNECTED=y
CONFIG_SYSTEMCMDS_VER=y
CONFIG_SYSTEMCMDS_WORK_QUEUE=y
CONFIG_EXAMPLES_FAKE_GPS=y
+1
View File
@@ -6,6 +6,7 @@ CONFIG_DRIVERS_CAMERA_CAPTURE=n
CONFIG_DRIVERS_CAMERA_TRIGGER=n
CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16448=n
CONFIG_DRIVERS_IRLOCK=n
CONFIG_MODULES_DIFFERENTIAL_DRIVE=n
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=n
CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=n
CONFIG_MODULES_PAYLOAD_DELIVERER=n
+2 -2
View File
@@ -74,9 +74,9 @@ ssize_t Serial::read(uint8_t *buffer, size_t buffer_size)
return _impl.read(buffer, buffer_size);
}
ssize_t Serial::readAtLeast(uint8_t *buffer, size_t buffer_size, size_t character_count, uint32_t timeout_us)
ssize_t Serial::readAtLeast(uint8_t *buffer, size_t buffer_size, size_t character_count, uint32_t timeout_ms)
{
return _impl.readAtLeast(buffer, buffer_size, character_count, timeout_us);
return _impl.readAtLeast(buffer, buffer_size, character_count, timeout_ms);
}
ssize_t Serial::write(const void *buffer, size_t buffer_size)
@@ -62,7 +62,7 @@ public:
bool close();
ssize_t read(uint8_t *buffer, size_t buffer_size);
ssize_t readAtLeast(uint8_t *buffer, size_t buffer_size, size_t character_count = 1, uint32_t timeout_us = 0);
ssize_t readAtLeast(uint8_t *buffer, size_t buffer_size, size_t character_count = 1, uint32_t timeout_ms = 0);
ssize_t write(const void *buffer, size_t buffer_size);
@@ -239,21 +239,10 @@ public:
unlock_module();
px4_usleep(10000); // 10 ms
lock_module();
i++;
if (++i > 500 && _task_id != -1) { // wait at most 5 sec
PX4_ERR("timeout, forcing stop");
if (_task_id != task_id_is_work_queue) {
px4_task_delete(_task_id);
}
_task_id = -1;
delete _object.load();
_object.store(nullptr);
ret = -1;
break;
if (i % 500 == 0) {
PX4_INFO("Waiting for task to stop...");
}
} while (_task_id != -1);
@@ -251,7 +251,7 @@ ssize_t SerialImpl::read(uint8_t *buffer, size_t buffer_size)
return ret;
}
ssize_t SerialImpl::readAtLeast(uint8_t *buffer, size_t buffer_size, size_t character_count, uint32_t timeout_us)
ssize_t SerialImpl::readAtLeast(uint8_t *buffer, size_t buffer_size, size_t character_count, uint32_t timeout_ms)
{
if (!_open) {
PX4_ERR("Cannot readAtLeast from serial device until it has been opened");
@@ -264,6 +264,7 @@ ssize_t SerialImpl::readAtLeast(uint8_t *buffer, size_t buffer_size, size_t char
}
const hrt_abstime start_time_us = hrt_absolute_time();
hrt_abstime timeout_us = timeout_ms * 1000;
int total_bytes_read = 0;
while ((total_bytes_read < (int) character_count) && (hrt_elapsed_time(&start_time_us) < timeout_us)) {
+3 -1
View File
@@ -45,6 +45,7 @@
#include <nuttx/kthread.h>
#include <sys/wait.h>
#include <syslog.h>
#include <stdbool.h>
#include <stdio.h>
#include <stdlib.h>
@@ -88,7 +89,8 @@ int px4_task_spawn_cmd(const char *name, int scheduler, int priority, int stack_
int px4_task_delete(int pid)
{
return task_delete(pid);
syslog(LOG_ERR, "Ignoring force task delete on NuttX\n");
return ERROR;
}
const char *px4_get_taskname(void)
@@ -244,7 +244,7 @@ ssize_t SerialImpl::read(uint8_t *buffer, size_t buffer_size)
return ret;
}
ssize_t SerialImpl::readAtLeast(uint8_t *buffer, size_t buffer_size, size_t character_count, uint32_t timeout_us)
ssize_t SerialImpl::readAtLeast(uint8_t *buffer, size_t buffer_size, size_t character_count, uint32_t timeout_ms)
{
if (!_open) {
PX4_ERR("Cannot readAtLeast from serial device until it has been opened");
@@ -257,6 +257,7 @@ ssize_t SerialImpl::readAtLeast(uint8_t *buffer, size_t buffer_size, size_t char
}
const hrt_abstime start_time_us = hrt_absolute_time();
hrt_abstime timeout_us = timeout_ms * 1000;
int total_bytes_read = 0;
while ((total_bytes_read < (int) character_count) && (hrt_elapsed_time(&start_time_us) < timeout_us)) {
+2 -1
View File
@@ -173,7 +173,7 @@ ssize_t SerialImpl::read(uint8_t *buffer, size_t buffer_size)
return ret_read;
}
ssize_t SerialImpl::readAtLeast(uint8_t *buffer, size_t buffer_size, size_t character_count, uint32_t timeout_us)
ssize_t SerialImpl::readAtLeast(uint8_t *buffer, size_t buffer_size, size_t character_count, uint32_t timeout_ms)
{
if (!_open) {
PX4_ERR("Cannot readAtLeast from serial device until it has been opened");
@@ -186,6 +186,7 @@ ssize_t SerialImpl::readAtLeast(uint8_t *buffer, size_t buffer_size, size_t char
}
const hrt_abstime start_time_us = hrt_absolute_time();
hrt_abstime timeout_us = timeout_ms * 1000;
int total_bytes_read = 0;
while (total_bytes_read < (int) character_count) {
+5
View File
@@ -290,6 +290,11 @@ inline bool isFinite(const float &value)
return PX4_ISFINITE(value);
}
inline bool isFinite(const matrix::Vector2f &value)
{
return value.isAllFinite();
}
inline bool isFinite(const matrix::Vector3f &value)
{
return value.isAllFinite();
+1 -1
View File
@@ -518,7 +518,7 @@ InputMavlinkGimbalV2::update(unsigned int timeout_ms, ControlData &control_data,
// We can't return early instead because we need to copy all topics that triggered poll.
bool exit_loop = false;
UpdateResult update_result = already_active ? UpdateResult::UpdatedActive : UpdateResult::NoUpdate;
UpdateResult update_result = UpdateResult::NoUpdate;
while (!exit_loop && poll_timeout >= 0) {
@@ -42,14 +42,11 @@
using namespace matrix;
MulticopterPositionControl::MulticopterPositionControl(bool vtol) :
SuperBlock(nullptr, "MPC"),
ModuleParams(nullptr),
ScheduledWorkItem(MODULE_NAME, px4::wq_configurations::nav_and_controllers),
_vehicle_attitude_setpoint_pub(vtol ? ORB_ID(mc_virtual_attitude_setpoint) : ORB_ID(vehicle_attitude_setpoint)),
_vel_x_deriv(this, "VELD"),
_vel_y_deriv(this, "VELD"),
_vel_z_deriv(this, "VELD")
_vehicle_attitude_setpoint_pub(vtol ? ORB_ID(mc_virtual_attitude_setpoint) : ORB_ID(vehicle_attitude_setpoint))
{
_sample_interval_s.update(0.01f); // 100 Hz default
parameters_update(true);
_tilt_limit_slew_rate.setSlewRate(.2f);
_takeoff_status_pub.advertise();
@@ -83,7 +80,42 @@ void MulticopterPositionControl::parameters_update(bool force)
// update parameters from storage
ModuleParams::updateParams();
SuperBlock::updateParams();
float sample_freq_hz = 1.f / _sample_interval_s.mean();
// velocity notch filter
if ((_param_mpc_vel_nf_frq.get() > 0.f) && (_param_mpc_vel_nf_bw.get() > 0.f)) {
_vel_xy_notch_filter.setParameters(sample_freq_hz, _param_mpc_vel_nf_frq.get(), _param_mpc_vel_nf_bw.get());
_vel_z_notch_filter.setParameters(sample_freq_hz, _param_mpc_vel_nf_frq.get(), _param_mpc_vel_nf_bw.get());
} else {
_vel_xy_notch_filter.disable();
_vel_z_notch_filter.disable();
}
// velocity xy/z low pass filter
if (_param_mpc_vel_lp.get() > 0.f) {
_vel_xy_lp_filter.setCutoffFreq(sample_freq_hz, _param_mpc_vel_lp.get());
_vel_z_lp_filter.setCutoffFreq(sample_freq_hz, _param_mpc_vel_lp.get());
} else {
// disable filtering
_vel_xy_lp_filter.setAlpha(1.f);
_vel_z_lp_filter.setAlpha(1.f);
}
// velocity derivative xy/z low pass filter
if (_param_mpc_veld_lp.get() > 0.f) {
_vel_deriv_xy_lp_filter.setCutoffFreq(sample_freq_hz, _param_mpc_veld_lp.get());
_vel_deriv_z_lp_filter.setCutoffFreq(sample_freq_hz, _param_mpc_veld_lp.get());
} else {
// disable filtering
_vel_deriv_xy_lp_filter.setAlpha(1.f);
_vel_deriv_z_lp_filter.setAlpha(1.f);
}
int num_changed = 0;
@@ -276,7 +308,7 @@ void MulticopterPositionControl::parameters_update(bool force)
}
PositionControlStates MulticopterPositionControl::set_vehicle_states(const vehicle_local_position_s
&vehicle_local_position)
&vehicle_local_position, const float dt_s)
{
PositionControlStates states;
@@ -300,29 +332,42 @@ PositionControlStates MulticopterPositionControl::set_vehicle_states(const vehic
const Vector2f velocity_xy(vehicle_local_position.vx, vehicle_local_position.vy);
if (vehicle_local_position.v_xy_valid && velocity_xy.isAllFinite()) {
states.velocity.xy() = velocity_xy;
states.acceleration(0) = _vel_x_deriv.update(velocity_xy(0));
states.acceleration(1) = _vel_y_deriv.update(velocity_xy(1));
const Vector2f vel_xy_prev = _vel_xy_lp_filter.getState();
// vel xy notch filter, then low pass filter
states.velocity.xy() = _vel_xy_lp_filter.update(_vel_xy_notch_filter.apply(velocity_xy));
// vel xy derivative low pass filter
states.acceleration.xy() = _vel_deriv_xy_lp_filter.update((_vel_xy_lp_filter.getState() - vel_xy_prev) / dt_s);
} else {
states.velocity(0) = states.velocity(1) = NAN;
states.acceleration(0) = states.acceleration(1) = NAN;
// reset derivatives to prevent acceleration spikes when regaining velocity
_vel_x_deriv.reset();
_vel_y_deriv.reset();
// reset filters to prevent acceleration spikes when regaining velocity
_vel_xy_lp_filter.reset({});
_vel_xy_notch_filter.reset();
_vel_deriv_xy_lp_filter.reset({});
}
if (PX4_ISFINITE(vehicle_local_position.vz) && vehicle_local_position.v_z_valid) {
states.velocity(2) = vehicle_local_position.vz;
states.acceleration(2) = _vel_z_deriv.update(states.velocity(2));
const float vel_z_prev = _vel_z_lp_filter.getState();
// vel z notch filter, then low pass filter
states.velocity(2) = _vel_z_lp_filter.update(_vel_z_notch_filter.apply(vehicle_local_position.vz));
// vel z derivative low pass filter
states.acceleration(2) = _vel_deriv_z_lp_filter.update((_vel_z_lp_filter.getState() - vel_z_prev) / dt_s);
} else {
states.velocity(2) = NAN;
states.acceleration(2) = NAN;
// reset derivative to prevent acceleration spikes when regaining velocity
_vel_z_deriv.reset();
// reset filters to prevent acceleration spikes when regaining velocity
_vel_z_lp_filter.reset({});
_vel_z_notch_filter.reset();
_vel_deriv_z_lp_filter.reset({});
}
states.yaw = vehicle_local_position.heading;
@@ -351,8 +396,7 @@ void MulticopterPositionControl::Run()
math::constrain(((vehicle_local_position.timestamp_sample - _time_stamp_last_loop) * 1e-6f), 0.002f, 0.04f);
_time_stamp_last_loop = vehicle_local_position.timestamp_sample;
// set _dt in controllib Block for BlockDerivative
setDt(dt);
_sample_interval_s.update(dt);
if (_vehicle_control_mode_sub.updated()) {
const bool previous_position_control_enabled = _vehicle_control_mode.flag_multicopter_position_control_enabled;
@@ -380,7 +424,7 @@ void MulticopterPositionControl::Run()
}
}
PositionControlStates states{set_vehicle_states(vehicle_local_position)};
PositionControlStates states{set_vehicle_states(vehicle_local_position, dt)};
// if a goto setpoint available this publishes a trajectory setpoint to go there
if (_goto_control.checkForSetpoint(vehicle_local_position.timestamp_sample,
@@ -638,12 +682,13 @@ void MulticopterPositionControl::adjustSetpointForEKFResets(const vehicle_local_
}
if (vehicle_local_position.vxy_reset_counter != _vxy_reset_counter) {
_vel_x_deriv.reset();
_vel_y_deriv.reset();
_vel_xy_lp_filter.reset(_vel_xy_lp_filter.getState() + Vector2f(vehicle_local_position.delta_vxy));
_vel_xy_notch_filter.reset();
}
if (vehicle_local_position.vz_reset_counter != _vz_reset_counter) {
_vel_z_deriv.reset();
_vel_z_lp_filter.reset(_vel_z_lp_filter.getState() + vehicle_local_position.delta_vz);
_vel_z_notch_filter.reset();
}
// save latest reset counters
@@ -42,7 +42,9 @@
#include "GotoControl/GotoControl.hpp"
#include <drivers/drv_hrt.h>
#include <lib/controllib/blocks.hpp>
#include <lib/mathlib/math/filter/AlphaFilter.hpp>
#include <lib/mathlib/math/filter/NotchFilter.hpp>
#include <lib/mathlib/math/WelfordMean.hpp>
#include <lib/perf/perf_counter.h>
#include <lib/slew_rate/SlewRateYaw.hpp>
#include <lib/systemlib/mavlink_log.h>
@@ -68,8 +70,8 @@
using namespace time_literals;
class MulticopterPositionControl : public ModuleBase<MulticopterPositionControl>, public control::SuperBlock,
public ModuleParams, public px4::ScheduledWorkItem
class MulticopterPositionControl : public ModuleBase<MulticopterPositionControl>, public ModuleParams,
public px4::ScheduledWorkItem
{
public:
MulticopterPositionControl(bool vtol = false);
@@ -148,6 +150,11 @@ private:
(ParamBool<px4::params::MPC_USE_HTE>) _param_mpc_use_hte,
(ParamBool<px4::params::MPC_ACC_DECOUPLE>) _param_mpc_acc_decouple,
(ParamFloat<px4::params::MPC_VEL_LP>) _param_mpc_vel_lp,
(ParamFloat<px4::params::MPC_VEL_NF_FRQ>) _param_mpc_vel_nf_frq,
(ParamFloat<px4::params::MPC_VEL_NF_BW>) _param_mpc_vel_nf_bw,
(ParamFloat<px4::params::MPC_VELD_LP>) _param_mpc_veld_lp,
// Takeoff / Land
(ParamFloat<px4::params::COM_SPOOLUP_TIME>) _param_com_spoolup_time, /**< time to let motors spool up after arming */
(ParamBool<px4::params::COM_THROW_EN>) _param_com_throw_en, /**< throw launch enabled */
@@ -185,9 +192,16 @@ private:
(ParamFloat<px4::params::MPC_YAWRAUTO_ACC>) _param_mpc_yawrauto_acc
);
control::BlockDerivative _vel_x_deriv; /**< velocity derivative in x */
control::BlockDerivative _vel_y_deriv; /**< velocity derivative in y */
control::BlockDerivative _vel_z_deriv; /**< velocity derivative in z */
math::WelfordMean<float> _sample_interval_s{};
AlphaFilter<matrix::Vector2f> _vel_xy_lp_filter{};
AlphaFilter<float> _vel_z_lp_filter{};
math::NotchFilter<matrix::Vector2f> _vel_xy_notch_filter{};
math::NotchFilter<float> _vel_z_notch_filter{};
AlphaFilter<matrix::Vector2f> _vel_deriv_xy_lp_filter{};
AlphaFilter<float> _vel_deriv_z_lp_filter{};
GotoControl _goto_control; ///< class for handling smooth goto position setpoints
PositionControl _control; ///< class for core PID position control
@@ -224,7 +238,7 @@ private:
/**
* Check for validity of positon/velocity states.
*/
PositionControlStates set_vehicle_states(const vehicle_local_position_s &local_pos);
PositionControlStates set_vehicle_states(const vehicle_local_position_s &local_pos, const float dt_s);
/**
* Generate setpoint to bridge no executable setpoint being available.
@@ -75,11 +75,56 @@ PARAM_DEFINE_INT32(MPC_USE_HTE, 1);
PARAM_DEFINE_FLOAT(MPC_THR_XY_MARG, 0.3f);
/**
* Numerical velocity derivative low pass cutoff frequency
* Velocity low pass cutoff frequency
*
* A value of 0 disables the filter.
*
* @unit Hz
* @min 0
* @max 10
* @max 50
* @decimal 1
* @increment 0.5
* @group Multicopter Position Control
*/
PARAM_DEFINE_FLOAT(MPC_VEL_LP, 0.0f);
/**
* Velocity notch filter frequency
*
* The center frequency for the 2nd order notch filter on the velocity.
* A value of 0 disables the filter.
*
* @unit Hz
* @min 0
* @max 50
* @decimal 1
* @increment 0.5
* @group Multicopter Position Control
*/
PARAM_DEFINE_FLOAT(MPC_VEL_NF_FRQ, 0.0f);
/**
* Velocity notch filter bandwidth
*
* A value of 0 disables the filter.
*
* @unit Hz
* @min 0
* @max 50
* @decimal 1
* @increment 0.5
* @group Multicopter Position Control
*/
PARAM_DEFINE_FLOAT(MPC_VEL_NF_BW, 5.0f);
/**
* Velocity derivative low pass cutoff frequency
*
* A value of 0 disables the filter.
*
* @unit Hz
* @min 0
* @max 50
* @decimal 1
* @increment 0.5
* @group Multicopter Position Control