mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-06-15 18:51:31 +08:00
Compare commits
1 Commits
v1.12.0-be
...
pr-angular
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
779229a41c |
@ -82,7 +82,7 @@ CONFIG_I2C_RESET=y
|
||||
CONFIG_IDLETHREAD_STACKSIZE=750
|
||||
CONFIG_LIBC_FLOATINGPOINT=y
|
||||
CONFIG_LIBC_LONG_LONG=y
|
||||
CONFIG_LIBC_STRERROR=n
|
||||
CONFIG_LIBC_STRERROR=y
|
||||
CONFIG_LIBC_STRERROR_SHORT=y
|
||||
CONFIG_MEMSET_64BIT=y
|
||||
CONFIG_MEMSET_OPTSPEED=y
|
||||
|
||||
@ -1 +1 @@
|
||||
Subproject commit 3a3aea8fe57c9f14d215b8769f9b77bca8b7c750
|
||||
Subproject commit 826b4ba68b83fa4e7a30636d2d97a9d6f1105122
|
||||
@ -1 +1 @@
|
||||
Subproject commit adb88ade443523e1ae28c14a2d6410977f4e3dd8
|
||||
Subproject commit bf06434168d1b60474e90b277ff117975e250e6a
|
||||
@ -530,27 +530,11 @@ bool DShot::updateOutputs(bool stop_motors, uint16_t outputs[MAX_ACTUATORS],
|
||||
|
||||
} else {
|
||||
for (int i = 0; i < (int)num_outputs; i++) {
|
||||
|
||||
uint16_t output = outputs[i];
|
||||
|
||||
// DShot 3D splits the throttle ranges in two.
|
||||
// This is in terms of DShot values, code below is in terms of actuator_output
|
||||
// Direction 1) 48 is the slowest, 1047 is the fastest.
|
||||
// Direction 2) 1049 is the slowest, 2047 is the fastest.
|
||||
if (_param_dshot_3d_enable.get()) {
|
||||
if (output >= _param_dshot_3d_dead_l.get() && output <= _param_dshot_3d_dead_h.get()) {
|
||||
output = DSHOT_DISARM_VALUE;
|
||||
|
||||
} else if (output < 1000 && output > 0) { //Todo: allow actuator 0 or dshot 48 to be used
|
||||
output = 999 - output;
|
||||
}
|
||||
}
|
||||
|
||||
if (output == DSHOT_DISARM_VALUE) {
|
||||
if (outputs[i] == DSHOT_DISARM_VALUE) {
|
||||
up_dshot_motor_command(i, DShot_cmd_motor_stop, i == requested_telemetry_index);
|
||||
|
||||
} else {
|
||||
up_dshot_motor_data_set(i, math::min(output, static_cast<uint16_t>(DSHOT_MAX_THROTTLE)),
|
||||
up_dshot_motor_data_set(i, math::min(outputs[i], static_cast<uint16_t>(DSHOT_MAX_THROTTLE)),
|
||||
i == requested_telemetry_index);
|
||||
}
|
||||
}
|
||||
|
||||
@ -231,9 +231,6 @@ private:
|
||||
DEFINE_PARAMETERS(
|
||||
(ParamInt<px4::params::DSHOT_CONFIG>) _param_dshot_config,
|
||||
(ParamFloat<px4::params::DSHOT_MIN>) _param_dshot_min,
|
||||
(ParamBool<px4::params::DSHOT_3D_ENABLE>) _param_dshot_3d_enable,
|
||||
(ParamInt<px4::params::DSHOT_3D_DEAD_H>) _param_dshot_3d_dead_h,
|
||||
(ParamInt<px4::params::DSHOT_3D_DEAD_L>) _param_dshot_3d_dead_l,
|
||||
(ParamInt<px4::params::MOT_POLE_COUNT>) _param_mot_pole_count
|
||||
)
|
||||
};
|
||||
|
||||
@ -14,7 +14,7 @@ parameters:
|
||||
long: |
|
||||
This enables/disables DShot. The different modes define different
|
||||
speeds, for example DShot150 = 150kb/s. Not all ESCs support all modes.
|
||||
|
||||
|
||||
Note: this enables DShot on the FMU outputs. For boards with an IO it is the
|
||||
AUX outputs.
|
||||
type: enum
|
||||
@ -40,37 +40,6 @@ parameters:
|
||||
decimal: 2
|
||||
increment: 0.01
|
||||
default: 0.055
|
||||
DSHOT_3D_ENABLE:
|
||||
description:
|
||||
short: Allows for 3d mode when using DShot and suitable mixer
|
||||
long: |
|
||||
WARNING: ESC must be configured for 3D mode, and DSHOT_MIN set to 0.
|
||||
This splits the throttle ranges in two.
|
||||
Direction 1) 48 is the slowest, 1047 is the fastest.
|
||||
Direction 2) 1049 is the slowest, 2047 is the fastest.
|
||||
When mixer outputs 1000 or value inside DSHOT 3D deadband, DShot 0 is sent.
|
||||
type: boolean
|
||||
default: 0
|
||||
DSHOT_3D_DEAD_H:
|
||||
description:
|
||||
short: DSHOT 3D deadband high
|
||||
long: |
|
||||
When the actuator_output is between DSHOT_3D_DEAD_L and DSHOT_3D_DEAD_H, motor will not spin.
|
||||
This value is with respect to the mixer_module range (0-1999), not the DSHOT values.
|
||||
type: int32
|
||||
min: 1000
|
||||
max: 1999
|
||||
default: 1000
|
||||
DSHOT_3D_DEAD_L:
|
||||
description:
|
||||
short: DSHOT 3D deadband low
|
||||
long: |
|
||||
When the actuator_output is between DSHOT_3D_DEAD_L and DSHOT_3D_DEAD_H, motor will not spin.
|
||||
This value is with respect to the mixer_module range (0-1999), not the DSHOT values.
|
||||
type: int32
|
||||
min: 0
|
||||
max: 1000
|
||||
default: 1000
|
||||
MOT_POLE_COUNT: # only used by dshot so far, so keep it under the dshot group
|
||||
description:
|
||||
short: Number of magnetic poles of the motors
|
||||
@ -82,3 +51,4 @@ parameters:
|
||||
Typical motors for 5 inch props have 14 poles.
|
||||
type: int32
|
||||
default: 14
|
||||
|
||||
|
||||
@ -84,6 +84,8 @@ int PAW3902::init()
|
||||
return PX4_ERROR;
|
||||
}
|
||||
|
||||
Reset();
|
||||
|
||||
// force to low light mode (1) initially
|
||||
ChangeMode(Mode::LowLight, true);
|
||||
|
||||
@ -148,6 +150,24 @@ bool PAW3902::DataReadyInterruptDisable()
|
||||
return px4_arch_gpiosetevent(_drdy_gpio, false, false, false, nullptr, nullptr) == 0;
|
||||
}
|
||||
|
||||
bool PAW3902::Reset()
|
||||
{
|
||||
DataReadyInterruptDisable();
|
||||
|
||||
// Power on reset
|
||||
RegisterWrite(Register::Power_Up_Reset, 0x5A);
|
||||
usleep(1000);
|
||||
|
||||
// Read from registers 0x02, 0x03, 0x04, 0x05 and 0x06 one time regardless of the motion state
|
||||
RegisterRead(Register::Motion);
|
||||
RegisterRead(Register::Delta_X_L);
|
||||
RegisterRead(Register::Delta_X_H);
|
||||
RegisterRead(Register::Delta_Y_L);
|
||||
RegisterRead(Register::Delta_Y_H);
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
void PAW3902::exit_and_cleanup()
|
||||
{
|
||||
DataReadyInterruptDisable();
|
||||
@ -163,7 +183,6 @@ bool PAW3902::ChangeMode(Mode newMode, bool force)
|
||||
|
||||
// Issue a soft reset
|
||||
RegisterWrite(Register::Power_Up_Reset, 0x5A);
|
||||
px4_usleep(1000);
|
||||
|
||||
uint32_t interval_us = 0;
|
||||
|
||||
@ -187,10 +206,6 @@ bool PAW3902::ChangeMode(Mode newMode, bool force)
|
||||
break;
|
||||
}
|
||||
|
||||
EnableLed();
|
||||
|
||||
_discard_reading = 3;
|
||||
|
||||
if (DataReadyInterruptConfigure()) {
|
||||
// backup schedule as a watchdog timeout
|
||||
ScheduleDelayed(500_ms);
|
||||
@ -199,6 +214,17 @@ bool PAW3902::ChangeMode(Mode newMode, bool force)
|
||||
ScheduleOnInterval(interval_us);
|
||||
}
|
||||
|
||||
// Discard the first three motion data.
|
||||
for (int i = 0; i < 3; i++) {
|
||||
RegisterRead(Register::Motion);
|
||||
RegisterRead(Register::Delta_X_L);
|
||||
RegisterRead(Register::Delta_X_H);
|
||||
RegisterRead(Register::Delta_Y_L);
|
||||
RegisterRead(Register::Delta_Y_H);
|
||||
}
|
||||
|
||||
EnableLed();
|
||||
|
||||
_mode = newMode;
|
||||
}
|
||||
|
||||
@ -206,6 +232,11 @@ bool PAW3902::ChangeMode(Mode newMode, bool force)
|
||||
_low_to_superlow_counter = 0;
|
||||
_low_to_bright_counter = 0;
|
||||
_superlow_to_low_counter = 0;
|
||||
// Approximate Resolution = (Register Value + 1) * (50 / 8450) ≈ 0.6% of data point in Figure 19
|
||||
// The maximum register value is 0xA8. The minimum register value is 0.
|
||||
uint8_t resolution = RegisterRead(Register::Resolution);
|
||||
PX4_DEBUG("Resolution: %X", resolution);
|
||||
PX4_DEBUG("Resolution is approx: %.3f", (double)((resolution + 1.0f) * (50.0f / 8450.0f)));
|
||||
|
||||
return true;
|
||||
}
|
||||
@ -551,9 +582,9 @@ void PAW3902::ModeSuperLowLight()
|
||||
void PAW3902::EnableLed()
|
||||
{
|
||||
// Enable LED_N controls
|
||||
RegisterWrite(0x7F, 0x14);
|
||||
RegisterWrite(0x6F, 0x1c);
|
||||
RegisterWrite(0x7F, 0x00);
|
||||
RegisterWriteVerified(0x7F, 0x14);
|
||||
RegisterWriteVerified(0x6F, 0x1c);
|
||||
RegisterWriteVerified(0x7F, 0x00);
|
||||
}
|
||||
|
||||
uint8_t PAW3902::RegisterRead(uint8_t reg, int retries)
|
||||
@ -632,17 +663,11 @@ void PAW3902::RunImpl()
|
||||
// update for next iteration
|
||||
_previous_collect_timestamp = timestamp_sample;
|
||||
|
||||
if (_discard_reading > 0) {
|
||||
_discard_reading--;
|
||||
ResetAccumulatedData();
|
||||
return;
|
||||
}
|
||||
|
||||
// check SQUAL & Shutter values
|
||||
// To suppress false motion reports, discard Delta X and Delta Y values if the SQUAL and Shutter values meet the condition
|
||||
// Bright Mode, SQUAL < 0x19, Shutter ≥ 0x1FF0
|
||||
// Low Light Mode, SQUAL < 0x46, Shutter ≥ 0x1FF0
|
||||
// Super Low Light Mode, SQUAL < 0x55, Shutter ≥ 0x0BC0
|
||||
// Bright Mode, SQUAL < 0x19, Shutter ≥ 0x1FF0
|
||||
// Low Light Mode, SQUAL < 0x46, Shutter ≥ 0x1FF0
|
||||
// Super Low Light Mode, SQUAL < 0x55, Shutter ≥ 0x0BC0
|
||||
const uint16_t shutter = (buf.data.Shutter_Upper << 8) | buf.data.Shutter_Lower;
|
||||
|
||||
bool data_valid = true;
|
||||
@ -652,6 +677,7 @@ void PAW3902::RunImpl()
|
||||
if ((buf.data.SQUAL < 0x19) && (shutter >= 0x1FF0)) {
|
||||
// false motion report, discarding
|
||||
perf_count(_false_motion_perf);
|
||||
ResetAccumulatedData();
|
||||
data_valid = false;
|
||||
}
|
||||
|
||||
@ -673,6 +699,7 @@ void PAW3902::RunImpl()
|
||||
if ((buf.data.SQUAL < 0x46) && (shutter >= 0x1FF0)) {
|
||||
// false motion report, discarding
|
||||
perf_count(_false_motion_perf);
|
||||
ResetAccumulatedData();
|
||||
data_valid = false;
|
||||
}
|
||||
|
||||
@ -705,14 +732,11 @@ void PAW3902::RunImpl()
|
||||
if ((buf.data.SQUAL < 0x55) && (shutter >= 0x0BC0)) {
|
||||
// false motion report, discarding
|
||||
perf_count(_false_motion_perf);
|
||||
ResetAccumulatedData();
|
||||
data_valid = false;
|
||||
}
|
||||
|
||||
if (shutter < 0x01F4) {
|
||||
// should not operate with Shutter < 0x01F4 in Mode 2
|
||||
ChangeMode(Mode::LowLight);
|
||||
|
||||
} else if (shutter < 0x03E8) {
|
||||
if (shutter < 0x03E8) {
|
||||
// SuperLowLight -> LowLight
|
||||
_superlow_to_low_counter++;
|
||||
|
||||
|
||||
@ -90,6 +90,8 @@ private:
|
||||
void RegisterWrite(uint8_t reg, uint8_t data);
|
||||
bool RegisterWriteVerified(uint8_t reg, uint8_t data, int retries = 5);
|
||||
|
||||
bool Reset();
|
||||
|
||||
void EnableLed();
|
||||
|
||||
void ModeBright();
|
||||
@ -122,8 +124,6 @@ private:
|
||||
|
||||
matrix::Dcmf _rotation;
|
||||
|
||||
int _discard_reading{3};
|
||||
|
||||
int _flow_sum_x{0};
|
||||
int _flow_sum_y{0};
|
||||
|
||||
|
||||
@ -1 +1 @@
|
||||
Subproject commit 29243ac5cbb5d27ac71744e88afcd786df6f748d
|
||||
Subproject commit a7b8afe420f438554ad90bcba0f1f4872325e75b
|
||||
@ -65,12 +65,7 @@ bool PreFlightCheck::accelerometerCheck(orb_advert_t *mavlink_log_pub, vehicle_s
|
||||
|
||||
device_id = accel.get().device_id;
|
||||
|
||||
if (status.hil_state == vehicle_status_s::HIL_STATE_ON) {
|
||||
calibration_valid = true;
|
||||
|
||||
} else {
|
||||
calibration_valid = (calibration::FindCalibrationIndex("ACC", device_id) >= 0);
|
||||
}
|
||||
calibration_valid = (calibration::FindCalibrationIndex("ACC", device_id) >= 0);
|
||||
|
||||
if (!calibration_valid) {
|
||||
if (report_fail) {
|
||||
|
||||
@ -64,12 +64,7 @@ bool PreFlightCheck::gyroCheck(orb_advert_t *mavlink_log_pub, vehicle_status_s &
|
||||
|
||||
device_id = gyro.get().device_id;
|
||||
|
||||
if (status.hil_state == vehicle_status_s::HIL_STATE_ON) {
|
||||
calibration_valid = true;
|
||||
|
||||
} else {
|
||||
calibration_valid = (calibration::FindCalibrationIndex("GYRO", device_id) >= 0);
|
||||
}
|
||||
calibration_valid = (calibration::FindCalibrationIndex("GYRO", device_id) >= 0);
|
||||
|
||||
if (!calibration_valid) {
|
||||
if (report_fail) {
|
||||
|
||||
@ -66,12 +66,7 @@ bool PreFlightCheck::magnetometerCheck(orb_advert_t *mavlink_log_pub, vehicle_st
|
||||
|
||||
device_id = magnetometer.get().device_id;
|
||||
|
||||
if (status.hil_state == vehicle_status_s::HIL_STATE_ON) {
|
||||
calibration_valid = true;
|
||||
|
||||
} else {
|
||||
calibration_valid = (calibration::FindCalibrationIndex("MAG", device_id) >= 0);
|
||||
}
|
||||
calibration_valid = (calibration::FindCalibrationIndex("MAG", device_id) >= 0);
|
||||
|
||||
if (!calibration_valid) {
|
||||
if (report_fail) {
|
||||
|
||||
@ -63,11 +63,6 @@ bool PreFlightCheck::powerCheck(orb_advert_t *mavlink_log_pub, const vehicle_sta
|
||||
return true;
|
||||
}
|
||||
|
||||
if (status.hil_state == vehicle_status_s::HIL_STATE_ON) {
|
||||
// Ignore power check in HITL.
|
||||
return true;
|
||||
}
|
||||
|
||||
uORB::SubscriptionData<system_power_s> system_power_sub{ORB_ID(system_power)};
|
||||
system_power_sub.update();
|
||||
const system_power_s &system_power = system_power_sub.get();
|
||||
|
||||
@ -199,7 +199,7 @@ int do_airspeed_calibration(orb_advert_t *mavlink_log_pub)
|
||||
/* wait 500 ms to ensure parameter propagated through the system */
|
||||
px4_usleep(500 * 1000);
|
||||
|
||||
calibration_log_critical(mavlink_log_pub, "[cal] Blow into front of pitot without touching");
|
||||
calibration_log_critical(mavlink_log_pub, "[cal] Blow across front of pitot without touching");
|
||||
|
||||
calibration_counter = 0;
|
||||
|
||||
|
||||
@ -1742,8 +1742,7 @@ int EKF2::task_spawn(int argc, char *argv[])
|
||||
|
||||
while ((multi_instances_allocated < multi_instances)
|
||||
&& (vehicle_status_sub.get().arming_state != vehicle_status_s::ARMING_STATE_ARMED)
|
||||
&& ((hrt_elapsed_time(&time_started) < 30_s)
|
||||
|| (vehicle_status_sub.get().hil_state == vehicle_status_s::HIL_STATE_ON))) {
|
||||
&& (hrt_elapsed_time(&time_started) < 30_s)) {
|
||||
|
||||
vehicle_status_sub.update();
|
||||
|
||||
|
||||
@ -1,6 +1,6 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2020-2021 PX4 Development Team. All rights reserved.
|
||||
* 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
|
||||
@ -37,6 +37,7 @@ using namespace time_literals;
|
||||
using matrix::Quatf;
|
||||
using matrix::Vector2f;
|
||||
using math::constrain;
|
||||
using math::max;
|
||||
using math::radians;
|
||||
|
||||
EKF2Selector::EKF2Selector() :
|
||||
@ -117,6 +118,12 @@ bool EKF2Selector::SelectInstance(uint8_t ekf_instance)
|
||||
_instance[i].relative_test_ratio = 0;
|
||||
}
|
||||
|
||||
// publish new data immediately with resets
|
||||
PublishVehicleAttitude(true);
|
||||
PublishVehicleLocalPosition(true);
|
||||
PublishVehicleGlobalPosition(true);
|
||||
PublishWindEstimate(true);
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
@ -315,11 +322,6 @@ bool EKF2Selector::UpdateErrorScores()
|
||||
if (error_delta > 0 || error_delta < -threshold) {
|
||||
_instance[i].relative_test_ratio += error_delta;
|
||||
_instance[i].relative_test_ratio = constrain(_instance[i].relative_test_ratio, -_rel_err_score_lim, _rel_err_score_lim);
|
||||
|
||||
if ((error_delta < -threshold) && (_instance[i].relative_test_ratio < 1.f)) {
|
||||
// increase status publication rate if there's movement towards a potential instance change
|
||||
_selector_status_publish = true;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
@ -328,152 +330,104 @@ bool EKF2Selector::UpdateErrorScores()
|
||||
return (primary_updated || updated);
|
||||
}
|
||||
|
||||
void EKF2Selector::PublishVehicleAttitude()
|
||||
void EKF2Selector::PublishVehicleAttitude(bool reset)
|
||||
{
|
||||
// selected estimator_attitude -> vehicle_attitude
|
||||
vehicle_attitude_s attitude;
|
||||
|
||||
if (_instance[_selected_instance].estimator_attitude_sub.update(&attitude)) {
|
||||
bool instance_change = false;
|
||||
if (_instance[_selected_instance].estimator_attitude_sub.copy(&attitude)) {
|
||||
if (reset) {
|
||||
// on reset compute deltas from last published data
|
||||
++_quat_reset_counter;
|
||||
|
||||
if (_instance[_selected_instance].estimator_attitude_sub.get_instance() != _attitude_instance_prev) {
|
||||
_attitude_instance_prev = _instance[_selected_instance].estimator_attitude_sub.get_instance();
|
||||
instance_change = true;
|
||||
}
|
||||
_delta_q_reset = (Quatf(attitude.q) * Quatf(_attitude_last.q).inversed()).normalized();
|
||||
|
||||
if (_attitude_last.timestamp != 0) {
|
||||
if (!instance_change && (attitude.quat_reset_counter == _attitude_last.quat_reset_counter + 1)) {
|
||||
// propogate deltas from estimator data while maintaining the overall reset counts
|
||||
++_quat_reset_counter;
|
||||
_delta_q_reset = Quatf{attitude.delta_q_reset};
|
||||
|
||||
} else if (instance_change || (attitude.quat_reset_counter != _attitude_last.quat_reset_counter)) {
|
||||
// on reset compute deltas from last published data
|
||||
++_quat_reset_counter;
|
||||
_delta_q_reset = (Quatf(attitude.q) * Quatf(_attitude_last.q).inversed()).normalized();
|
||||
}
|
||||
// ensure monotonically increasing timestamp_sample through reset
|
||||
attitude.timestamp_sample = max(attitude.timestamp_sample, _attitude_last.timestamp_sample);
|
||||
|
||||
} else {
|
||||
_quat_reset_counter = attitude.quat_reset_counter;
|
||||
_delta_q_reset = Quatf{attitude.delta_q_reset};
|
||||
// otherwise propogate deltas from estimator data while maintaining the overall reset counts
|
||||
if (attitude.quat_reset_counter > _attitude_last.quat_reset_counter) {
|
||||
++_quat_reset_counter;
|
||||
_delta_q_reset = Quatf{attitude.delta_q_reset};
|
||||
}
|
||||
}
|
||||
|
||||
bool publish = true;
|
||||
|
||||
// ensure monotonically increasing timestamp_sample through reset, don't publish
|
||||
// estimator's attitude for system (vehicle_attitude) if it's stale
|
||||
if ((attitude.timestamp_sample <= _attitude_last.timestamp_sample)
|
||||
|| (attitude.timestamp_sample < _instance[_selected_instance].timestamp_sample_last)) {
|
||||
|
||||
publish = false;
|
||||
}
|
||||
|
||||
// save last primary estimator_attitude as published with original resets
|
||||
// save last primary estimator_attitude
|
||||
_attitude_last = attitude;
|
||||
|
||||
if (publish) {
|
||||
// republish with total reset count and current timestamp
|
||||
attitude.quat_reset_counter = _quat_reset_counter;
|
||||
_delta_q_reset.copyTo(attitude.delta_q_reset);
|
||||
// republish with total reset count and current timestamp
|
||||
attitude.quat_reset_counter = _quat_reset_counter;
|
||||
_delta_q_reset.copyTo(attitude.delta_q_reset);
|
||||
|
||||
attitude.timestamp = hrt_absolute_time();
|
||||
_vehicle_attitude_pub.publish(attitude);
|
||||
}
|
||||
attitude.timestamp = hrt_absolute_time();
|
||||
_vehicle_attitude_pub.publish(attitude);
|
||||
|
||||
_instance[_selected_instance].timestamp_sample_last = attitude.timestamp_sample;
|
||||
}
|
||||
}
|
||||
|
||||
void EKF2Selector::PublishVehicleLocalPosition()
|
||||
void EKF2Selector::PublishVehicleLocalPosition(bool reset)
|
||||
{
|
||||
// selected estimator_local_position -> vehicle_local_position
|
||||
// vehicle_local_position
|
||||
vehicle_local_position_s local_position;
|
||||
|
||||
if (_instance[_selected_instance].estimator_local_position_sub.update(&local_position)) {
|
||||
bool instance_change = false;
|
||||
if (_instance[_selected_instance].estimator_local_position_sub.copy(&local_position)) {
|
||||
if (reset) {
|
||||
// on reset compute deltas from last published data
|
||||
++_xy_reset_counter;
|
||||
++_z_reset_counter;
|
||||
++_vxy_reset_counter;
|
||||
++_vz_reset_counter;
|
||||
++_heading_reset_counter;
|
||||
|
||||
if (_instance[_selected_instance].estimator_local_position_sub.get_instance() != _local_position_instance_prev) {
|
||||
_local_position_instance_prev = _instance[_selected_instance].estimator_local_position_sub.get_instance();
|
||||
instance_change = true;
|
||||
}
|
||||
_delta_xy_reset = Vector2f{local_position.x, local_position.y} - Vector2f{_local_position_last.x, _local_position_last.y};
|
||||
_delta_z_reset = local_position.z - _local_position_last.z;
|
||||
_delta_vxy_reset = Vector2f{local_position.vx, local_position.vy} - Vector2f{_local_position_last.vx, _local_position_last.vy};
|
||||
_delta_vz_reset = local_position.vz - _local_position_last.vz;
|
||||
_delta_heading_reset = matrix::wrap_2pi(local_position.heading - _local_position_last.heading);
|
||||
|
||||
// ensure monotonically increasing timestamp_sample through reset
|
||||
local_position.timestamp_sample = max(local_position.timestamp_sample, _local_position_last.timestamp_sample);
|
||||
|
||||
} else {
|
||||
// otherwise propogate deltas from estimator data while maintaining the overall reset counts
|
||||
|
||||
if (_local_position_last.timestamp != 0) {
|
||||
// XY reset
|
||||
if (!instance_change && (local_position.xy_reset_counter == _local_position_last.xy_reset_counter + 1)) {
|
||||
if (local_position.xy_reset_counter > _local_position_last.xy_reset_counter) {
|
||||
++_xy_reset_counter;
|
||||
_delta_xy_reset = Vector2f{local_position.delta_xy};
|
||||
|
||||
} else if (instance_change || (local_position.xy_reset_counter != _local_position_last.xy_reset_counter)) {
|
||||
++_xy_reset_counter;
|
||||
_delta_xy_reset = Vector2f{local_position.x, local_position.y} - Vector2f{_local_position_last.x, _local_position_last.y};
|
||||
}
|
||||
|
||||
// Z reset
|
||||
if (!instance_change && (local_position.z_reset_counter == _local_position_last.z_reset_counter + 1)) {
|
||||
if (local_position.z_reset_counter > _local_position_last.z_reset_counter) {
|
||||
++_z_reset_counter;
|
||||
_delta_z_reset = local_position.delta_z;
|
||||
|
||||
} else if (instance_change || (local_position.z_reset_counter != _local_position_last.z_reset_counter)) {
|
||||
++_z_reset_counter;
|
||||
_delta_z_reset = local_position.z - _local_position_last.z;
|
||||
}
|
||||
|
||||
// VXY reset
|
||||
if (!instance_change && (local_position.vxy_reset_counter == _local_position_last.vxy_reset_counter + 1)) {
|
||||
if (local_position.vxy_reset_counter > _local_position_last.vxy_reset_counter) {
|
||||
++_vxy_reset_counter;
|
||||
_delta_vxy_reset = Vector2f{local_position.delta_vxy};
|
||||
|
||||
} else if (instance_change || (local_position.vxy_reset_counter != _local_position_last.vxy_reset_counter)) {
|
||||
++_vxy_reset_counter;
|
||||
_delta_vxy_reset = Vector2f{local_position.vx, local_position.vy} - Vector2f{_local_position_last.vx, _local_position_last.vy};
|
||||
}
|
||||
|
||||
// VZ reset
|
||||
if (!instance_change && (local_position.vz_reset_counter == _local_position_last.vz_reset_counter + 1)) {
|
||||
if (local_position.vz_reset_counter > _local_position_last.vz_reset_counter) {
|
||||
++_vz_reset_counter;
|
||||
_delta_vz_reset = local_position.delta_vz;
|
||||
|
||||
} else if (instance_change || (local_position.vz_reset_counter != _local_position_last.vz_reset_counter)) {
|
||||
++_vz_reset_counter;
|
||||
_delta_vz_reset = local_position.vz - _local_position_last.vz;
|
||||
}
|
||||
|
||||
// heading reset
|
||||
if (!instance_change && (local_position.heading_reset_counter == _local_position_last.heading_reset_counter + 1)) {
|
||||
if (local_position.heading_reset_counter > _local_position_last.heading_reset_counter) {
|
||||
++_heading_reset_counter;
|
||||
_delta_heading_reset = local_position.delta_heading;
|
||||
|
||||
} else if (instance_change || (local_position.heading_reset_counter != _local_position_last.heading_reset_counter)) {
|
||||
++_heading_reset_counter;
|
||||
_delta_heading_reset = matrix::wrap_pi(local_position.heading - _local_position_last.heading);
|
||||
}
|
||||
|
||||
} else {
|
||||
_xy_reset_counter = local_position.xy_reset_counter;
|
||||
_z_reset_counter = local_position.z_reset_counter;
|
||||
_vxy_reset_counter = local_position.vxy_reset_counter;
|
||||
_vz_reset_counter = local_position.vz_reset_counter;
|
||||
_heading_reset_counter = local_position.heading_reset_counter;
|
||||
|
||||
_delta_xy_reset = Vector2f{local_position.delta_xy};
|
||||
_delta_z_reset = local_position.delta_z;
|
||||
_delta_vxy_reset = Vector2f{local_position.delta_vxy};
|
||||
_delta_vz_reset = local_position.delta_vz;
|
||||
_delta_heading_reset = local_position.delta_heading;
|
||||
}
|
||||
|
||||
bool publish = true;
|
||||
|
||||
// ensure monotonically increasing timestamp_sample through reset, don't publish
|
||||
// estimator's local position for system (vehicle_local_position) if it's stale
|
||||
if ((local_position.timestamp_sample <= _local_position_last.timestamp_sample)
|
||||
|| (local_position.timestamp_sample < _instance[_selected_instance].timestamp_sample_last)) {
|
||||
|
||||
publish = false;
|
||||
}
|
||||
|
||||
// save last primary estimator_local_position as published with original resets
|
||||
// save last primary estimator_local_position
|
||||
_local_position_last = local_position;
|
||||
|
||||
if (publish) {
|
||||
// publish estimator's local position for system (vehicle_local_position) unless it's stale
|
||||
if (local_position.timestamp_sample >= _instance[_selected_instance].timestamp_sample_last) {
|
||||
// republish with total reset count and current timestamp
|
||||
local_position.xy_reset_counter = _xy_reset_counter;
|
||||
local_position.z_reset_counter = _z_reset_counter;
|
||||
@ -493,92 +447,47 @@ void EKF2Selector::PublishVehicleLocalPosition()
|
||||
}
|
||||
}
|
||||
|
||||
void EKF2Selector::PublishVehicleOdometry()
|
||||
void EKF2Selector::PublishVehicleGlobalPosition(bool reset)
|
||||
{
|
||||
// selected estimator_odometry -> vehicle_odometry
|
||||
vehicle_odometry_s odometry;
|
||||
|
||||
if (_instance[_selected_instance].estimator_odometry_sub.update(&odometry)) {
|
||||
bool publish = true;
|
||||
|
||||
// ensure monotonically increasing timestamp_sample through reset, don't publish
|
||||
// estimator's odometry for system (vehicle_odometry) if it's stale
|
||||
if ((odometry.timestamp_sample <= _odometry_last.timestamp_sample)
|
||||
|| (odometry.timestamp_sample < _instance[_selected_instance].timestamp_sample_last)) {
|
||||
|
||||
publish = false;
|
||||
}
|
||||
|
||||
// save last primary estimator_odometry
|
||||
_odometry_last = odometry;
|
||||
|
||||
if (publish) {
|
||||
odometry.timestamp = hrt_absolute_time();
|
||||
_vehicle_odometry_pub.publish(odometry);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void EKF2Selector::PublishVehicleGlobalPosition()
|
||||
{
|
||||
// selected estimator_global_position -> vehicle_global_position
|
||||
vehicle_global_position_s global_position;
|
||||
|
||||
if (_instance[_selected_instance].estimator_global_position_sub.update(&global_position)) {
|
||||
bool instance_change = false;
|
||||
if (_instance[_selected_instance].estimator_global_position_sub.copy(&global_position)) {
|
||||
if (reset) {
|
||||
// on reset compute deltas from last published data
|
||||
++_lat_lon_reset_counter;
|
||||
++_alt_reset_counter;
|
||||
|
||||
if (_instance[_selected_instance].estimator_global_position_sub.get_instance() != _global_position_instance_prev) {
|
||||
_global_position_instance_prev = _instance[_selected_instance].estimator_global_position_sub.get_instance();
|
||||
instance_change = true;
|
||||
}
|
||||
_delta_lat_reset = global_position.lat - _global_position_last.lat;
|
||||
_delta_lon_reset = global_position.lon - _global_position_last.lon;
|
||||
_delta_alt_reset = global_position.delta_alt - _global_position_last.delta_alt;
|
||||
|
||||
// ensure monotonically increasing timestamp_sample through reset
|
||||
global_position.timestamp_sample = max(global_position.timestamp_sample, _global_position_last.timestamp_sample);
|
||||
|
||||
} else {
|
||||
// otherwise propogate deltas from estimator data while maintaining the overall reset counts
|
||||
|
||||
if (_global_position_last.timestamp != 0) {
|
||||
// lat/lon reset
|
||||
if (!instance_change && (global_position.lat_lon_reset_counter == _global_position_last.lat_lon_reset_counter + 1)) {
|
||||
if (global_position.lat_lon_reset_counter > _global_position_last.lat_lon_reset_counter) {
|
||||
++_lat_lon_reset_counter;
|
||||
|
||||
// TODO: delta latitude/longitude
|
||||
_delta_lat_reset = global_position.lat - _global_position_last.lat;
|
||||
_delta_lon_reset = global_position.lon - _global_position_last.lon;
|
||||
|
||||
} else if (instance_change || (global_position.lat_lon_reset_counter != _global_position_last.lat_lon_reset_counter)) {
|
||||
++_lat_lon_reset_counter;
|
||||
|
||||
_delta_lat_reset = global_position.lat - _global_position_last.lat;
|
||||
_delta_lon_reset = global_position.lon - _global_position_last.lon;
|
||||
//_delta_lat_reset = global_position.delta_lat;
|
||||
//_delta_lon_reset = global_position.delta_lon;
|
||||
}
|
||||
|
||||
// alt reset
|
||||
if (!instance_change && (global_position.alt_reset_counter == _global_position_last.alt_reset_counter + 1)) {
|
||||
if (global_position.alt_reset_counter > _global_position_last.alt_reset_counter) {
|
||||
++_alt_reset_counter;
|
||||
_delta_alt_reset = global_position.delta_alt;
|
||||
|
||||
} else if (instance_change || (global_position.alt_reset_counter != _global_position_last.alt_reset_counter)) {
|
||||
++_alt_reset_counter;
|
||||
_delta_alt_reset = global_position.delta_alt - _global_position_last.delta_alt;
|
||||
}
|
||||
|
||||
} else {
|
||||
_lat_lon_reset_counter = global_position.lat_lon_reset_counter;
|
||||
_alt_reset_counter = global_position.alt_reset_counter;
|
||||
|
||||
_delta_alt_reset = global_position.delta_alt;
|
||||
}
|
||||
|
||||
bool publish = true;
|
||||
|
||||
// ensure monotonically increasing timestamp_sample through reset, don't publish
|
||||
// estimator's global position for system (vehicle_global_position) if it's stale
|
||||
if ((global_position.timestamp_sample <= _global_position_last.timestamp_sample)
|
||||
|| (global_position.timestamp_sample < _instance[_selected_instance].timestamp_sample_last)) {
|
||||
|
||||
publish = false;
|
||||
}
|
||||
|
||||
// save last primary estimator_global_position as published with original resets
|
||||
// save last primary estimator_global_position
|
||||
_global_position_last = global_position;
|
||||
|
||||
if (publish) {
|
||||
// publish estimator's global position for system (vehicle_global_position) unless it's stale
|
||||
if (global_position.timestamp_sample >= _instance[_selected_instance].timestamp_sample_last) {
|
||||
// republish with total reset count and current timestamp
|
||||
global_position.lat_lon_reset_counter = _lat_lon_reset_counter;
|
||||
global_position.alt_reset_counter = _alt_reset_counter;
|
||||
@ -590,31 +499,22 @@ void EKF2Selector::PublishVehicleGlobalPosition()
|
||||
}
|
||||
}
|
||||
|
||||
void EKF2Selector::PublishWindEstimate()
|
||||
void EKF2Selector::PublishWindEstimate(bool reset)
|
||||
{
|
||||
// selected estimator_wind -> wind
|
||||
wind_s wind;
|
||||
|
||||
if (_instance[_selected_instance].estimator_wind_sub.update(&wind)) {
|
||||
bool publish = true;
|
||||
|
||||
// ensure monotonically increasing timestamp_sample through reset, don't publish
|
||||
// estimator's wind for system (wind) if it's stale
|
||||
if ((wind.timestamp_sample <= _wind_last.timestamp_sample)
|
||||
|| (wind.timestamp_sample < _instance[_selected_instance].timestamp_sample_last)) {
|
||||
|
||||
publish = false;
|
||||
if (_instance[_selected_instance].estimator_wind_sub.copy(&wind)) {
|
||||
if (reset) {
|
||||
// ensure monotonically increasing timestamp_sample through reset
|
||||
wind.timestamp_sample = max(wind.timestamp_sample, _wind_last.timestamp_sample);
|
||||
}
|
||||
|
||||
// save last primary wind
|
||||
_wind_last = wind;
|
||||
|
||||
// publish estimator's wind for system unless it's stale
|
||||
if (publish) {
|
||||
// republish with current timestamp
|
||||
wind.timestamp = hrt_absolute_time();
|
||||
_wind_pub.publish(wind);
|
||||
}
|
||||
// republish with current timestamp
|
||||
wind.timestamp = hrt_absolute_time();
|
||||
_wind_pub.publish(wind);
|
||||
}
|
||||
}
|
||||
|
||||
@ -655,6 +555,7 @@ void EKF2Selector::Run()
|
||||
}
|
||||
|
||||
if (updated) {
|
||||
|
||||
const uint8_t available_instances_prev = _available_instances;
|
||||
const uint8_t selected_instance_prev = _selected_instance;
|
||||
const uint32_t instance_changed_count_prev = _instance_changed_count;
|
||||
@ -723,47 +624,69 @@ void EKF2Selector::Run()
|
||||
|| (last_instance_change_prev != _last_instance_change)
|
||||
|| _accel_fault_detected || _gyro_fault_detected) {
|
||||
|
||||
PublishEstimatorSelectorStatus();
|
||||
estimator_selector_status_s selector_status{};
|
||||
selector_status.primary_instance = _selected_instance;
|
||||
selector_status.instances_available = _available_instances;
|
||||
selector_status.instance_changed_count = _instance_changed_count;
|
||||
selector_status.last_instance_change = _last_instance_change;
|
||||
selector_status.accel_device_id = _instance[_selected_instance].accel_device_id;
|
||||
selector_status.baro_device_id = _instance[_selected_instance].baro_device_id;
|
||||
selector_status.gyro_device_id = _instance[_selected_instance].gyro_device_id;
|
||||
selector_status.mag_device_id = _instance[_selected_instance].mag_device_id;
|
||||
selector_status.gyro_fault_detected = _gyro_fault_detected;
|
||||
selector_status.accel_fault_detected = _accel_fault_detected;
|
||||
|
||||
for (int i = 0; i < EKF2_MAX_INSTANCES; i++) {
|
||||
selector_status.combined_test_ratio[i] = _instance[i].combined_test_ratio;
|
||||
selector_status.relative_test_ratio[i] = _instance[i].relative_test_ratio;
|
||||
selector_status.healthy[i] = _instance[i].healthy;
|
||||
}
|
||||
|
||||
for (int i = 0; i < IMU_STATUS_SIZE; i++) {
|
||||
selector_status.accumulated_gyro_error[i] = _accumulated_gyro_error[i];
|
||||
selector_status.accumulated_accel_error[i] = _accumulated_accel_error[i];
|
||||
}
|
||||
|
||||
selector_status.timestamp = hrt_absolute_time();
|
||||
_estimator_selector_status_pub.publish(selector_status);
|
||||
_last_status_publish = selector_status.timestamp;
|
||||
_selector_status_publish = false;
|
||||
}
|
||||
}
|
||||
|
||||
// republish selected estimator data for system
|
||||
PublishVehicleAttitude();
|
||||
PublishVehicleLocalPosition();
|
||||
PublishVehicleGlobalPosition();
|
||||
PublishVehicleOdometry();
|
||||
PublishWindEstimate();
|
||||
}
|
||||
|
||||
void EKF2Selector::PublishEstimatorSelectorStatus()
|
||||
{
|
||||
estimator_selector_status_s selector_status{};
|
||||
selector_status.primary_instance = _selected_instance;
|
||||
selector_status.instances_available = _available_instances;
|
||||
selector_status.instance_changed_count = _instance_changed_count;
|
||||
selector_status.last_instance_change = _last_instance_change;
|
||||
selector_status.accel_device_id = _instance[_selected_instance].accel_device_id;
|
||||
selector_status.baro_device_id = _instance[_selected_instance].baro_device_id;
|
||||
selector_status.gyro_device_id = _instance[_selected_instance].gyro_device_id;
|
||||
selector_status.mag_device_id = _instance[_selected_instance].mag_device_id;
|
||||
selector_status.gyro_fault_detected = _gyro_fault_detected;
|
||||
selector_status.accel_fault_detected = _accel_fault_detected;
|
||||
|
||||
for (int i = 0; i < EKF2_MAX_INSTANCES; i++) {
|
||||
selector_status.combined_test_ratio[i] = _instance[i].combined_test_ratio;
|
||||
selector_status.relative_test_ratio[i] = _instance[i].relative_test_ratio;
|
||||
selector_status.healthy[i] = _instance[i].healthy;
|
||||
// selected estimator_attitude -> vehicle_attitude
|
||||
if (_instance[_selected_instance].estimator_attitude_sub.updated()) {
|
||||
PublishVehicleAttitude();
|
||||
}
|
||||
|
||||
for (int i = 0; i < IMU_STATUS_SIZE; i++) {
|
||||
selector_status.accumulated_gyro_error[i] = _accumulated_gyro_error[i];
|
||||
selector_status.accumulated_accel_error[i] = _accumulated_accel_error[i];
|
||||
// selected estimator_local_position -> vehicle_local_position
|
||||
if (_instance[_selected_instance].estimator_local_position_sub.updated()) {
|
||||
PublishVehicleLocalPosition();
|
||||
}
|
||||
|
||||
selector_status.timestamp = hrt_absolute_time();
|
||||
_estimator_selector_status_pub.publish(selector_status);
|
||||
_last_status_publish = selector_status.timestamp;
|
||||
// selected estimator_global_position -> vehicle_global_position
|
||||
if (_instance[_selected_instance].estimator_global_position_sub.updated()) {
|
||||
PublishVehicleGlobalPosition();
|
||||
}
|
||||
|
||||
// selected estimator_wind -> wind
|
||||
if (_instance[_selected_instance].estimator_wind_sub.updated()) {
|
||||
PublishWindEstimate();
|
||||
}
|
||||
|
||||
// selected estimator_odometry -> vehicle_odometry
|
||||
if (_instance[_selected_instance].estimator_odometry_sub.updated()) {
|
||||
vehicle_odometry_s vehicle_odometry;
|
||||
|
||||
if (_instance[_selected_instance].estimator_odometry_sub.update(&vehicle_odometry)) {
|
||||
if (vehicle_odometry.timestamp_sample >= _instance[_selected_instance].timestamp_sample_last) {
|
||||
vehicle_odometry.timestamp = hrt_absolute_time();
|
||||
_vehicle_odometry_pub.publish(vehicle_odometry);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void EKF2Selector::PrintStatus()
|
||||
|
||||
@ -1,6 +1,6 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2020-2021 PX4 Development Team. All rights reserved.
|
||||
* 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
|
||||
@ -78,12 +78,10 @@ private:
|
||||
static constexpr uint64_t FILTER_UPDATE_PERIOD{10_ms};
|
||||
|
||||
void Run() override;
|
||||
void PublishEstimatorSelectorStatus();
|
||||
void PublishVehicleAttitude();
|
||||
void PublishVehicleLocalPosition();
|
||||
void PublishVehicleGlobalPosition();
|
||||
void PublishVehicleOdometry();
|
||||
void PublishWindEstimate();
|
||||
void PublishVehicleAttitude(bool reset = false);
|
||||
void PublishVehicleLocalPosition(bool reset = false);
|
||||
void PublishVehicleGlobalPosition(bool reset = false);
|
||||
void PublishWindEstimate(bool reset = false);
|
||||
bool SelectInstance(uint8_t instance);
|
||||
|
||||
// Update the error scores for all available instances
|
||||
@ -193,9 +191,6 @@ private:
|
||||
uint8_t _vz_reset_counter{0};
|
||||
uint8_t _heading_reset_counter{0};
|
||||
|
||||
// vehicle_odometry
|
||||
vehicle_odometry_s _odometry_last{};
|
||||
|
||||
// vehicle_global_position: reset counters
|
||||
vehicle_global_position_s _global_position_last{};
|
||||
double _delta_lat_reset{0};
|
||||
@ -207,10 +202,6 @@ private:
|
||||
// wind estimate
|
||||
wind_s _wind_last{};
|
||||
|
||||
uint8_t _attitude_instance_prev{INVALID_INSTANCE};
|
||||
uint8_t _local_position_instance_prev{INVALID_INSTANCE};
|
||||
uint8_t _global_position_instance_prev{INVALID_INSTANCE};
|
||||
|
||||
uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s};
|
||||
uORB::Subscription _sensors_status_imu{ORB_ID(sensors_status_imu)};
|
||||
|
||||
|
||||
@ -148,22 +148,23 @@ void VehicleAngularVelocity::ResetFilters(float new_scale)
|
||||
{
|
||||
if ((_filter_sample_rate_hz > 0) && PX4_ISFINITE(_filter_sample_rate_hz)) {
|
||||
|
||||
const Vector3f angular_velocity{GetResetAngularVelocity(new_scale)};
|
||||
const Vector3f angular_acceleration{GetResetAngularAcceleration(new_scale)};
|
||||
const Vector3f angular_velocity_raw{GetResetAngularVelocity(_angular_velocity, new_scale)};
|
||||
const Vector3f angular_velocity_raw_prev{GetResetAngularVelocity(_angular_velocity_prev, new_scale)};
|
||||
const Vector3f angular_acceleration_raw{GetResetAngularAcceleration(new_scale)};
|
||||
|
||||
for (int axis = 0; axis < 3; axis++) {
|
||||
// angular velocity low pass
|
||||
_lp_filter_velocity[axis].set_cutoff_frequency(_filter_sample_rate_hz, _param_imu_gyro_cutoff.get());
|
||||
_lp_filter_velocity[axis].reset(angular_velocity(axis));
|
||||
_lp_filter_velocity[axis].reset(angular_velocity_raw(axis));
|
||||
|
||||
// angular velocity notch
|
||||
_notch_filter_velocity[axis].setParameters(_filter_sample_rate_hz, _param_imu_gyro_nf_freq.get(),
|
||||
_param_imu_gyro_nf_bw.get());
|
||||
_notch_filter_velocity[axis].reset(angular_velocity(axis));
|
||||
_notch_filter_velocity[axis].reset(angular_velocity_raw(axis));
|
||||
|
||||
// angular acceleration low pass
|
||||
_lp_filter_acceleration[axis].set_cutoff_frequency(_filter_sample_rate_hz, _param_imu_dgyro_cutoff.get());
|
||||
_lp_filter_acceleration[axis].reset(angular_acceleration(axis));
|
||||
_lp_filter_acceleration[axis].reset(angular_acceleration_raw(axis));
|
||||
}
|
||||
|
||||
// dynamic notch filters, first disable, then force update (if available)
|
||||
@ -173,7 +174,8 @@ void VehicleAngularVelocity::ResetFilters(float new_scale)
|
||||
UpdateDynamicNotchEscRpm(new_scale, true);
|
||||
UpdateDynamicNotchFFT(new_scale, true);
|
||||
|
||||
_angular_velocity_prev = angular_velocity;
|
||||
_angular_velocity_raw_prev = angular_velocity_raw;
|
||||
_angular_velocity_raw_prev_prev = angular_velocity_raw_prev;
|
||||
_last_scale = new_scale;
|
||||
|
||||
_reset_filters = false;
|
||||
@ -350,18 +352,18 @@ void VehicleAngularVelocity::ParametersUpdate(bool force)
|
||||
}
|
||||
}
|
||||
|
||||
Vector3f VehicleAngularVelocity::GetResetAngularVelocity(float new_scale) const
|
||||
Vector3f VehicleAngularVelocity::GetResetAngularVelocity(const Vector3f &angular_velocity, float new_scale) const
|
||||
{
|
||||
if ((_last_publish != 0) && (new_scale > 0.f)) {
|
||||
// angular velocity filtering is performed on raw unscaled data
|
||||
// start with last valid vehicle body frame angular velocity and compute equivalent raw data (for current sensor selection)
|
||||
Vector3f angular_velocity{_calibration.Uncorrect(_angular_velocity + _bias) / new_scale};
|
||||
Vector3f angular_velocity_raw{_calibration.Uncorrect(angular_velocity + _bias) / new_scale};
|
||||
|
||||
if (PX4_ISFINITE(angular_velocity(0))
|
||||
&& PX4_ISFINITE(angular_velocity(1))
|
||||
&& PX4_ISFINITE(angular_velocity(2))) {
|
||||
if (PX4_ISFINITE(angular_velocity_raw(0))
|
||||
&& PX4_ISFINITE(angular_velocity_raw(1))
|
||||
&& PX4_ISFINITE(angular_velocity_raw(2))) {
|
||||
|
||||
return angular_velocity;
|
||||
return angular_velocity_raw;
|
||||
}
|
||||
}
|
||||
|
||||
@ -373,13 +375,13 @@ Vector3f VehicleAngularVelocity::GetResetAngularAcceleration(float new_scale) co
|
||||
if ((_last_publish != 0) && (new_scale > 0.f)) {
|
||||
// angular acceleration filtering is performed on unscaled angular velocity data
|
||||
// start with last valid vehicle body frame angular acceleration and compute equivalent raw data (for current sensor selection)
|
||||
Vector3f angular_acceleration{_calibration.rotation().I() *_angular_acceleration / new_scale};
|
||||
Vector3f angular_acceleration_raw{_calibration.rotation().I() *_angular_acceleration / new_scale};
|
||||
|
||||
if (PX4_ISFINITE(angular_acceleration(0))
|
||||
&& PX4_ISFINITE(angular_acceleration(1))
|
||||
&& PX4_ISFINITE(angular_acceleration(2))) {
|
||||
if (PX4_ISFINITE(angular_acceleration_raw(0))
|
||||
&& PX4_ISFINITE(angular_acceleration_raw(1))
|
||||
&& PX4_ISFINITE(angular_acceleration_raw(2))) {
|
||||
|
||||
return angular_acceleration;
|
||||
return angular_acceleration_raw;
|
||||
}
|
||||
}
|
||||
|
||||
@ -452,7 +454,7 @@ void VehicleAngularVelocity::UpdateDynamicNotchEscRpm(float new_scale, bool forc
|
||||
|
||||
// only reset if there's sufficient change (> 1%)
|
||||
if (force || (change_percent > 0.01f)) {
|
||||
const Vector3f reset_angular_velocity{GetResetAngularVelocity(new_scale)};
|
||||
const Vector3f reset_angular_velocity{GetResetAngularVelocity(_angular_velocity, new_scale)};
|
||||
|
||||
for (int axis = 0; axis < 3; axis++) {
|
||||
auto &dnf = _dynamic_notch_filter_esc_rpm[i][harmonic][axis];
|
||||
@ -511,7 +513,7 @@ void VehicleAngularVelocity::UpdateDynamicNotchFFT(float new_scale, bool force)
|
||||
|
||||
// only reset if there's sufficient change
|
||||
if (peak_diff_abs > sensor_gyro_fft.resolution_hz) {
|
||||
dnf.reset(GetResetAngularVelocity(new_scale)(axis));
|
||||
dnf.reset(GetResetAngularVelocity(_angular_velocity, new_scale)(axis));
|
||||
}
|
||||
|
||||
perf_count(_dynamic_notch_filter_fft_update_perf);
|
||||
@ -583,20 +585,6 @@ float VehicleAngularVelocity::FilterAngularVelocity(int axis, float data[], int
|
||||
return data[N - 1];
|
||||
}
|
||||
|
||||
float VehicleAngularVelocity::FilterAngularAcceleration(int axis, float dt_s, float data[], int N)
|
||||
{
|
||||
// angular acceleration: Differentiate & apply specific angular acceleration (D-term) low-pass (IMU_DGYRO_CUTOFF)
|
||||
float angular_acceleration_filtered = 0.f;
|
||||
|
||||
for (int n = 0; n < N; n++) {
|
||||
const float angular_acceleration = (data[n] - _angular_velocity_prev(axis)) / dt_s;
|
||||
angular_acceleration_filtered = _lp_filter_acceleration[axis].apply(angular_acceleration);
|
||||
_angular_velocity_prev(axis) = data[n];
|
||||
}
|
||||
|
||||
return angular_acceleration_filtered;
|
||||
}
|
||||
|
||||
void VehicleAngularVelocity::Run()
|
||||
{
|
||||
// backup schedule
|
||||
@ -656,7 +644,18 @@ void VehicleAngularVelocity::Run()
|
||||
|
||||
// save last filtered sample
|
||||
angular_velocity_unscaled(axis) = FilterAngularVelocity(axis, data, N);
|
||||
angular_acceleration_unscaled(axis) = FilterAngularAcceleration(axis, dt_s, data, N);
|
||||
|
||||
// angular acceleration: Differentiate & apply specific angular acceleration (D-term) low-pass (IMU_DGYRO_CUTOFF)
|
||||
for (int n = 0; n < N; n++) {
|
||||
// Backward finite difference (1st derivative 3 coffecients [1/2, -2, 3/2])
|
||||
const float angular_acceleration = (+ 0.5f * _angular_velocity_raw_prev_prev(axis)
|
||||
- 2.0f * _angular_velocity_raw_prev(axis)
|
||||
+ 1.5f * data[n]) / dt_s;
|
||||
_angular_velocity_raw_prev_prev(axis) = _angular_velocity_raw_prev(axis);
|
||||
_angular_velocity_raw_prev(axis) = data[n];
|
||||
|
||||
angular_acceleration_unscaled(axis) = _lp_filter_acceleration[axis].apply(angular_acceleration);
|
||||
}
|
||||
}
|
||||
|
||||
// Publish
|
||||
@ -699,7 +698,11 @@ void VehicleAngularVelocity::Run()
|
||||
|
||||
// save last filtered sample
|
||||
angular_velocity(axis) = FilterAngularVelocity(axis, data);
|
||||
angular_acceleration(axis) = FilterAngularAcceleration(axis, dt_s, data);
|
||||
|
||||
angular_acceleration(axis) = _lp_filter_acceleration[axis].apply((raw_data_array[axis]
|
||||
- _angular_velocity_raw_prev(axis)) / dt_s);
|
||||
_angular_velocity_raw_prev_prev(axis) = _angular_velocity_raw_prev(axis);
|
||||
_angular_velocity_raw_prev(axis) = raw_data_array[axis];
|
||||
}
|
||||
|
||||
// Publish
|
||||
@ -712,6 +715,7 @@ void VehicleAngularVelocity::CalibrateAndPublish(bool publish, const hrt_abstime
|
||||
const Vector3f &angular_velocity_unscaled, const Vector3f &angular_acceleration_unscaled, float scale)
|
||||
{
|
||||
// Angular velocity: rotate sensor frame to board, scale raw data to SI, apply calibration, and remove in-run estimated bias
|
||||
_angular_velocity_prev = _angular_velocity;
|
||||
_angular_velocity = _calibration.Correct(angular_velocity_unscaled * scale) - _bias;
|
||||
|
||||
// Angular acceleration: rotate sensor frame to board, scale raw data to SI, apply any additional configured rotation
|
||||
|
||||
@ -79,7 +79,6 @@ private:
|
||||
const matrix::Vector3f &angular_acceleration, float scale = 1.f);
|
||||
|
||||
float FilterAngularVelocity(int axis, float data[], int N = 1);
|
||||
float FilterAngularAcceleration(int axis, float dt_s, float data[], int N = 1);
|
||||
|
||||
void DisableDynamicNotchEscRpm();
|
||||
void DisableDynamicNotchFFT();
|
||||
@ -93,7 +92,7 @@ private:
|
||||
bool UpdateSampleRate();
|
||||
|
||||
// scaled appropriately for current FIFO mode
|
||||
matrix::Vector3f GetResetAngularVelocity(float new_scale = 1.f) const;
|
||||
matrix::Vector3f GetResetAngularVelocity(const matrix::Vector3f &angular_velocity, float new_scale = 1.f) const;
|
||||
matrix::Vector3f GetResetAngularAcceleration(float new_scale = 1.f) const;
|
||||
|
||||
static constexpr int MAX_SENSOR_COUNT = 4;
|
||||
@ -119,9 +118,11 @@ private:
|
||||
matrix::Vector3f _bias{};
|
||||
|
||||
matrix::Vector3f _angular_velocity{};
|
||||
matrix::Vector3f _angular_velocity_prev{};
|
||||
matrix::Vector3f _angular_acceleration{};
|
||||
|
||||
matrix::Vector3f _angular_velocity_prev{};
|
||||
matrix::Vector3f _angular_velocity_raw_prev{};
|
||||
matrix::Vector3f _angular_velocity_raw_prev_prev{};
|
||||
hrt_abstime _timestamp_sample_last{0};
|
||||
|
||||
hrt_abstime _publish_interval_min_us{0};
|
||||
|
||||
@ -332,7 +332,7 @@ bool VtolType::set_idle_fw()
|
||||
|
||||
for (int i = 0; i < num_outputs_max; i++) {
|
||||
if (is_channel_set(i, generate_bitmap_from_channel_numbers(_params->vtol_motor_id))) {
|
||||
pwm_values.values[i] = PWM_DEFAULT_MIN;
|
||||
pwm_values.values[i] = PWM_MOTOR_OFF;
|
||||
|
||||
} else {
|
||||
pwm_values.values[i] = _min_mc_pwm_values.values[i];
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user