mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-06-19 07:00:35 +08:00
Compare commits
1 Commits
| Author | SHA1 | Date | |
|---|---|---|---|
| 779229a41c |
@@ -468,27 +468,26 @@ validate_module_configs:
|
||||
.PHONY: clean submodulesclean submodulesupdate gazeboclean distclean
|
||||
|
||||
clean:
|
||||
@find "$(SRC_DIR)/build" -mindepth 1 -maxdepth 1 -type d -exec sh -c "echo {}; cmake --build {} -- clean || rm -rf {}" \; # use generated build system to clean, wipe build directory if it fails
|
||||
@git submodule foreach git clean -dX --force # some submodules generate build artifacts in source
|
||||
@rm -rf "$(SRC_DIR)"/build
|
||||
@git submodule foreach git clean -df
|
||||
|
||||
submodulesclean:
|
||||
@git submodule foreach --quiet --recursive git clean -ff -x -d
|
||||
@git submodule update --quiet --init --recursive --force || true
|
||||
@git submodule sync --recursive
|
||||
@git submodule update --init --recursive --force --jobs 4
|
||||
@git submodule update --init --recursive --force
|
||||
|
||||
submodulesupdate:
|
||||
@git submodule update --quiet --init --recursive --jobs 4 || true
|
||||
@git submodule update --quiet --init --recursive || true
|
||||
@git submodule sync --recursive
|
||||
@git submodule update --init --recursive --jobs 4
|
||||
@git submodule update --init --recursive
|
||||
|
||||
gazeboclean:
|
||||
@rm -rf ~/.gazebo/*
|
||||
|
||||
distclean: gazeboclean
|
||||
@git submodule deinit --force $(SRC_DIR)
|
||||
@rm -rf "$(SRC_DIR)/build"
|
||||
@git clean --force -X "$(SRC_DIR)/msg/" "$(SRC_DIR)/platforms/" "$(SRC_DIR)/posix-configs/" "$(SRC_DIR)/ROMFS/" "$(SRC_DIR)/src/" "$(SRC_DIR)/test/" "$(SRC_DIR)/Tools/"
|
||||
@git submodule deinit -f .
|
||||
@git clean -ff -x -d -e ".cproject" -e ".idea" -e ".project" -e ".settings" -e ".vscode"
|
||||
|
||||
# Help / Error
|
||||
# --------------------------------------------------------------------
|
||||
|
||||
@@ -63,7 +63,7 @@ CONFIG_HAVE_CXXINITIALIZE=y
|
||||
CONFIG_I2C_RESET=y
|
||||
CONFIG_IDLETHREAD_STACKSIZE=750
|
||||
CONFIG_IOB_NBUFFERS=48
|
||||
CONFIG_IOB_NCHAINS=18
|
||||
CONFIG_IOB_NCHAINS=16
|
||||
CONFIG_KINETIS_ADC0=y
|
||||
CONFIG_KINETIS_ADC1=y
|
||||
CONFIG_KINETIS_CRC=y
|
||||
|
||||
@@ -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
|
||||
|
||||
Submodule mavlink/include/mavlink/v2.0 updated: 3a3aea8fe5...826b4ba68b
Submodule platforms/nuttx/NuttX/nuttx updated: adb88ade44...bf06434168
@@ -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};
|
||||
|
||||
|
||||
@@ -126,7 +126,7 @@ int16_t CanardNuttXCDev::receive(CanardFrame *received_frame)
|
||||
// Any recieved CAN messages will cause the poll statement to unblock and run
|
||||
// This way CAN read runs with minimal latency.
|
||||
// Note that multiple messages may be received in a short time, so this will try to read any availible in a loop
|
||||
::poll(&fds, 1, 0);
|
||||
::poll(&fds, 1, 10);
|
||||
|
||||
// Only execute this part if can0 is changed.
|
||||
if (fds.revents & POLLIN) {
|
||||
|
||||
@@ -162,12 +162,12 @@ int16_t CanardSocketCAN::transmit(const CanardFrame &txf, int timeout_ms)
|
||||
_send_tv->tv_usec = txf.timestamp_usec % 1000000ULL;
|
||||
_send_tv->tv_sec = (txf.timestamp_usec - _send_tv->tv_usec) / 1000000ULL;
|
||||
|
||||
return sendmsg(_fd, &_send_msg, 0);
|
||||
return sendmsg(_fd, &_send_msg, 1000);
|
||||
}
|
||||
|
||||
int16_t CanardSocketCAN::receive(CanardFrame *rxf)
|
||||
{
|
||||
int32_t result = recvmsg(_fd, &_recv_msg, MSG_DONTWAIT);
|
||||
int32_t result = recvmsg(_fd, &_recv_msg, 1000);
|
||||
|
||||
if (result < 0) {
|
||||
return result;
|
||||
|
||||
@@ -39,20 +39,16 @@
|
||||
* @author Peter van der Perk <peter.vanderperk@nxp.com>
|
||||
*/
|
||||
|
||||
#define RETRY_COUNT 10
|
||||
|
||||
#include "NodeManager.hpp"
|
||||
|
||||
bool NodeManager::HandleNodeIDRequest(uavcan_pnp_NodeIDAllocationData_1_0 &msg)
|
||||
{
|
||||
if (msg.allocated_node_id.count == 0) {
|
||||
uint32_t i;
|
||||
|
||||
msg.allocated_node_id.count = 1;
|
||||
msg.allocated_node_id.elements[0].value = CANARD_NODE_ID_UNSET;
|
||||
|
||||
/* Search for an available NodeID to assign */
|
||||
for (i = 1; i < sizeof(nodeid_registry) / sizeof(nodeid_registry[0]); i++) {
|
||||
for (uint32_t i = 1; i < sizeof(nodeid_registry) / sizeof(nodeid_registry[0]); i++) {
|
||||
if (i == _canard_instance.node_id) {
|
||||
continue; // Don't give our NodeID to a node
|
||||
|
||||
@@ -67,10 +63,6 @@ bool NodeManager::HandleNodeIDRequest(uavcan_pnp_NodeIDAllocationData_1_0 &msg)
|
||||
}
|
||||
}
|
||||
|
||||
nodeid_registry[i].register_setup = false; // Re-instantiate register setup
|
||||
nodeid_registry[i].register_index = 0;
|
||||
nodeid_registry[i].retry_count = 0;
|
||||
|
||||
if (msg.allocated_node_id.elements[0].value != CANARD_NODE_ID_UNSET) {
|
||||
|
||||
PX4_INFO("Received NodeID allocation request assigning %i", msg.allocated_node_id.elements[0].value);
|
||||
@@ -128,15 +120,17 @@ void NodeManager::HandleListResponse(CanardNodeID node_id, uavcan_register_List_
|
||||
if (nodeid_registry[i].node_id == node_id) {
|
||||
nodeid_registry[i].register_index++; // Increment index counter for next update()
|
||||
nodeid_registry[i].register_setup = false;
|
||||
nodeid_registry[i].retry_count = 0;
|
||||
}
|
||||
}
|
||||
|
||||
if (_access_request.setPortId(node_id, msg.name)) {
|
||||
PX4_INFO("Set portID succesfull");
|
||||
|
||||
} else {
|
||||
PX4_INFO("Register not found %.*s", msg.name.name.count, msg.name.name.elements);
|
||||
if (strncmp((char *)msg.name.name.elements, gps_uorb_register_name,
|
||||
msg.name.name.count) == 0) {
|
||||
_access_request.setPortId(node_id, gps_uorb_register_name, 1235); //TODO configurable and combine with ParamManager.
|
||||
|
||||
} else if (strncmp((char *)msg.name.name.elements, bms_status_register_name,
|
||||
msg.name.name.count) == 0) { //Battery status publisher
|
||||
_access_request.setPortId(node_id, bms_status_register_name, 1234); //TODO configurable and combine with ParamManager.
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -148,11 +142,7 @@ void NodeManager::update()
|
||||
if (nodeid_registry[i].node_id != 0 && nodeid_registry[i].register_setup == false) {
|
||||
//Setting up registers
|
||||
_list_request.request(nodeid_registry[i].node_id, nodeid_registry[i].register_index);
|
||||
nodeid_registry[i].retry_count++;
|
||||
|
||||
if (nodeid_registry[i].retry_count > RETRY_COUNT) {
|
||||
nodeid_registry[i].register_setup = true; // Don't update anymore
|
||||
}
|
||||
nodeid_registry[i].register_setup = true;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
@@ -63,14 +63,12 @@ typedef struct {
|
||||
uint8_t unique_id[16];
|
||||
bool register_setup;
|
||||
uint16_t register_index;
|
||||
uint16_t retry_count;
|
||||
} UavcanNodeEntry;
|
||||
|
||||
class NodeManager
|
||||
{
|
||||
public:
|
||||
NodeManager(CanardInstance &ins, UavcanParamManager &pmgr) : _canard_instance(ins), _access_request(ins, pmgr),
|
||||
_list_request(ins) { };
|
||||
NodeManager(CanardInstance &ins) : _canard_instance(ins), _access_request(ins), _list_request(ins) { };
|
||||
|
||||
bool HandleNodeIDRequest(uavcan_pnp_NodeIDAllocationData_1_0 &msg);
|
||||
bool HandleNodeIDRequest(uavcan_pnp_NodeIDAllocationData_2_0 &msg);
|
||||
@@ -91,4 +89,8 @@ private:
|
||||
bool nodeRegisterSetup = 0;
|
||||
|
||||
hrt_abstime _register_request_last{0};
|
||||
|
||||
//TODO work this out
|
||||
const char *gps_uorb_register_name = "uavcan.pub.gnss_uorb.id";
|
||||
const char *bms_status_register_name = "uavcan.pub.battery_status.id";
|
||||
};
|
||||
|
||||
@@ -40,7 +40,6 @@
|
||||
*/
|
||||
|
||||
#include "ParamManager.hpp"
|
||||
#include <px4_platform_common/defines.h>
|
||||
|
||||
bool UavcanParamManager::GetParamByName(const char *param_name, uavcan_register_Value_1_0 &value)
|
||||
{
|
||||
@@ -57,16 +56,8 @@ bool UavcanParamManager::GetParamByName(const char *param_name, uavcan_register_
|
||||
case PARAM_TYPE_INT32: {
|
||||
int32_t out_val {};
|
||||
param_get(param_handle, &out_val);
|
||||
|
||||
if (uavcan_register_Value_1_0_is_natural16_(&value)) { //FIXME param rewrite
|
||||
value.natural16.value.elements[0] = (uint16_t)out_val;
|
||||
uavcan_register_Value_1_0_select_natural16_(&value);
|
||||
|
||||
} else {
|
||||
value.integer32.value.elements[0] = out_val;
|
||||
uavcan_register_Value_1_0_select_integer32_(&value);
|
||||
}
|
||||
|
||||
value.integer32.value.elements[0] = out_val;
|
||||
uavcan_register_Value_1_0_select_integer32_(&value);
|
||||
break;
|
||||
}
|
||||
|
||||
@@ -100,23 +91,15 @@ bool UavcanParamManager::GetParamByName(const uavcan_register_Name_1_0 &name, ua
|
||||
switch (param_type(param_handle)) {
|
||||
case PARAM_TYPE_INT32: {
|
||||
int32_t out_val {};
|
||||
param_get(param_handle, &out_val);
|
||||
|
||||
if (uavcan_register_Value_1_0_is_natural16_(&value)) { //FIXME param rewrite
|
||||
value.natural16.value.elements[0] = (uint16_t)out_val;
|
||||
uavcan_register_Value_1_0_select_natural16_(&value);
|
||||
|
||||
} else {
|
||||
value.integer32.value.elements[0] = out_val;
|
||||
uavcan_register_Value_1_0_select_integer32_(&value);
|
||||
}
|
||||
|
||||
param_set(param_handle, &out_val);
|
||||
value.integer32.value.elements[0] = out_val;
|
||||
uavcan_register_Value_1_0_select_integer32_(&value);
|
||||
break;
|
||||
}
|
||||
|
||||
case PARAM_TYPE_FLOAT: {
|
||||
float out_val {};
|
||||
param_get(param_handle, &out_val);
|
||||
param_set(param_handle, &out_val);
|
||||
value.real32.value.elements[0] = out_val;
|
||||
uavcan_register_Value_1_0_select_real32_(&value);
|
||||
break;
|
||||
|
||||
@@ -63,7 +63,7 @@ public:
|
||||
|
||||
private:
|
||||
|
||||
const UavcanParamBinder _uavcan_params[11] {
|
||||
const UavcanParamBinder _uavcan_params[10] {
|
||||
{"uavcan.pub.esc.0.id", "UCAN1_ESC_PUB"},
|
||||
{"uavcan.pub.servo.0.id", "UCAN1_SERVO_PUB"},
|
||||
{"uavcan.pub.gps.0.id", "UCAN1_GPS_PUB"},
|
||||
@@ -74,7 +74,6 @@ private:
|
||||
{"uavcan.sub.battery_status.0.id", "UCAN1_BMS_BS_PID"},
|
||||
{"uavcan.sub.battery_parameters.0.id", "UCAN1_BMS_BP_PID"},
|
||||
{"uavcan.sub.legacy_bms.0.id", "UCAN1_LG_BMS_PID"},
|
||||
{"uavcan.sub.uorb.sensor_gps.0.id", "UCAN1_UORB_GPS"},
|
||||
//{"uavcan.sub.bms.0.id", "UCAN1_BMS0_PID"}, //FIXME instancing
|
||||
//{"uavcan.sub.bms.1.id", "UCAN1_BMS1_PID"},
|
||||
};
|
||||
|
||||
@@ -1,84 +0,0 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2021 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 sensor_gps.hpp
|
||||
*
|
||||
* Defines uORB over UAVCANv1 sensor_gps publisher
|
||||
*
|
||||
* @author Peter van der Perk <peter.vanderperk@nxp.com>
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <uORB/topics/sensor_gps.h>
|
||||
|
||||
#include "../Publisher.hpp"
|
||||
|
||||
class UORB_over_UAVCAN_sensor_gps_Publisher : public UavcanPublisher
|
||||
{
|
||||
public:
|
||||
UORB_over_UAVCAN_sensor_gps_Publisher(CanardInstance &ins, UavcanParamManager &pmgr, uint8_t instance = 0) :
|
||||
UavcanPublisher(ins, pmgr, "sensor_gps", instance)
|
||||
{};
|
||||
|
||||
// Update the uORB Subscription and broadcast a UAVCAN message
|
||||
virtual void update() override
|
||||
{
|
||||
// Not sure if actuator_armed is a good indication of readiness but seems close to it
|
||||
if (_sensor_gps_sub.updated() && _port_id != CANARD_PORT_ID_UNSET && _port_id != 0) {
|
||||
sensor_gps_s gps_msg {};
|
||||
_sensor_gps_sub.update(&gps_msg);
|
||||
|
||||
CanardTransfer transfer = {
|
||||
.timestamp_usec = hrt_absolute_time() + PUBLISHER_DEFAULT_TIMEOUT_USEC,
|
||||
.priority = CanardPriorityNominal,
|
||||
.transfer_kind = CanardTransferKindMessage,
|
||||
.port_id = _port_id, // This is the subject-ID.
|
||||
.remote_node_id = CANARD_NODE_ID_UNSET,
|
||||
.transfer_id = _transfer_id,
|
||||
.payload_size = sizeof(struct sensor_gps_s),
|
||||
.payload = &gps_msg,
|
||||
};
|
||||
|
||||
if (result == 0) {
|
||||
// set the data ready in the buffer and chop if needed
|
||||
++_transfer_id; // The transfer-ID shall be incremented after every transmission on this subject.
|
||||
result = canardTxPush(&_canard_instance, &transfer);
|
||||
}
|
||||
}
|
||||
};
|
||||
|
||||
private:
|
||||
uORB::Subscription _sensor_gps_sub{ORB_ID(sensor_gps)};
|
||||
};
|
||||
@@ -52,55 +52,45 @@
|
||||
class UavcanAccessServiceRequest
|
||||
{
|
||||
public:
|
||||
UavcanAccessServiceRequest(CanardInstance &ins, UavcanParamManager &pmgr) :
|
||||
_canard_instance(ins), _param_manager(pmgr) { };
|
||||
UavcanAccessServiceRequest(CanardInstance &ins) :
|
||||
_canard_instance(ins) { };
|
||||
|
||||
bool setPortId(CanardNodeID node_id, uavcan_register_Name_1_0 &name)
|
||||
void setPortId(CanardNodeID node_id, const char *register_name, uint16_t port_id)
|
||||
{
|
||||
int result {0};
|
||||
|
||||
uavcan_register_Access_Request_1_0 request_msg;
|
||||
strncpy((char *)&request_msg.name.name.elements[0], register_name, sizeof(uavcan_register_Name_1_0));
|
||||
request_msg.name.name.count = strlen(register_name);
|
||||
|
||||
uavcan_register_Value_1_0_select_natural16_(&request_msg.value);
|
||||
request_msg.value.natural16.value.count = 1;
|
||||
uavcan_register_Value_1_0_select_natural16_(&request_msg.value); // Set to natural16 so that ParamManager casts type
|
||||
request_msg.value.natural16.value.elements[0] = port_id;
|
||||
|
||||
//FIXME ParamManager only has notion of being either sub/pub have to find a portable way to address trhis
|
||||
name.name.elements[7] = 's'; //HACK Change pub into sub
|
||||
uint8_t request_payload_buffer[uavcan_register_Access_Request_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_];
|
||||
|
||||
if (_param_manager.GetParamByName(name, request_msg.value)) {
|
||||
name.name.elements[7] = 'p'; //HACK Change sub into pub
|
||||
memcpy(&request_msg.name, &name, sizeof(request_msg.name));
|
||||
CanardTransfer transfer = {
|
||||
.timestamp_usec = hrt_absolute_time() + PUBLISHER_DEFAULT_TIMEOUT_USEC,
|
||||
.priority = CanardPriorityNominal,
|
||||
.transfer_kind = CanardTransferKindRequest,
|
||||
.port_id = uavcan_register_Access_1_0_FIXED_PORT_ID_, // This is the subject-ID.
|
||||
.remote_node_id = node_id, // Messages cannot be unicast, so use UNSET.
|
||||
.transfer_id = access_request_transfer_id,
|
||||
.payload_size = uavcan_register_Access_Request_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_,
|
||||
.payload = &request_payload_buffer,
|
||||
};
|
||||
|
||||
uint8_t request_payload_buffer[uavcan_register_Access_Request_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_];
|
||||
result = uavcan_register_Access_Request_1_0_serialize_(&request_msg, request_payload_buffer, &transfer.payload_size);
|
||||
|
||||
CanardTransfer transfer = {
|
||||
.timestamp_usec = hrt_absolute_time() + PUBLISHER_DEFAULT_TIMEOUT_USEC,
|
||||
.priority = CanardPriorityNominal,
|
||||
.transfer_kind = CanardTransferKindRequest,
|
||||
.port_id = uavcan_register_Access_1_0_FIXED_PORT_ID_, // This is the subject-ID.
|
||||
.remote_node_id = node_id, // Messages cannot be unicast, so use UNSET.
|
||||
.transfer_id = access_request_transfer_id,
|
||||
.payload_size = uavcan_register_Access_Request_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_,
|
||||
.payload = &request_payload_buffer,
|
||||
};
|
||||
|
||||
result = uavcan_register_Access_Request_1_0_serialize_(&request_msg, request_payload_buffer, &transfer.payload_size);
|
||||
|
||||
if (result == 0) {
|
||||
// set the data ready in the buffer and chop if needed
|
||||
++access_request_transfer_id; // The transfer-ID shall be incremented after every transmission on this subject.
|
||||
result = canardTxPush(&_canard_instance, &transfer);
|
||||
}
|
||||
|
||||
return result > 0;
|
||||
|
||||
} else {
|
||||
return false;
|
||||
if (result == 0) {
|
||||
// set the data ready in the buffer and chop if needed
|
||||
++access_request_transfer_id; // The transfer-ID shall be incremented after every transmission on this subject.
|
||||
result = canardTxPush(&_canard_instance, &transfer);
|
||||
}
|
||||
};
|
||||
|
||||
private:
|
||||
CanardInstance &_canard_instance;
|
||||
CanardTransferID access_request_transfer_id = 0;
|
||||
UavcanParamManager &_param_manager;
|
||||
|
||||
};
|
||||
|
||||
@@ -68,27 +68,25 @@ public:
|
||||
|
||||
// Set _port_id from _uavcan_param
|
||||
uavcan_register_Value_1_0 value;
|
||||
_param_manager.GetParamByName(uavcan_param, value);
|
||||
int32_t new_id = value.integer32.value.elements[0];
|
||||
|
||||
if (_param_manager.GetParamByName(uavcan_param, value)) {
|
||||
int32_t new_id = value.integer32.value.elements[0];
|
||||
/* FIXME how about partial subscribing */
|
||||
if (curSubj->_canard_sub._port_id != new_id) {
|
||||
if (new_id == CANARD_PORT_ID_UNSET) {
|
||||
// Cancel subscription
|
||||
unsubscribe();
|
||||
|
||||
/* FIXME how about partial subscribing */
|
||||
if (curSubj->_canard_sub._port_id != new_id) {
|
||||
if (new_id == CANARD_PORT_ID_UNSET) {
|
||||
// Cancel subscription
|
||||
} else {
|
||||
if (curSubj->_canard_sub._port_id != CANARD_PORT_ID_UNSET) {
|
||||
// Already active; unsubscribe first
|
||||
unsubscribe();
|
||||
|
||||
} else {
|
||||
if (curSubj->_canard_sub._port_id != CANARD_PORT_ID_UNSET) {
|
||||
// Already active; unsubscribe first
|
||||
unsubscribe();
|
||||
}
|
||||
|
||||
// Subscribe on the new port ID
|
||||
curSubj->_canard_sub._port_id = (CanardPortID)new_id;
|
||||
PX4_INFO("Subscribing %s.%d on port %d", curSubj->_subject_name, _instance, curSubj->_canard_sub._port_id);
|
||||
subscribe();
|
||||
}
|
||||
|
||||
// Subscribe on the new port ID
|
||||
curSubj->_canard_sub._port_id = (CanardPortID)new_id;
|
||||
PX4_INFO("Subscribing %s.%d on port %d", curSubj->_subject_name, _instance, curSubj->_canard_sub._port_id);
|
||||
subscribe();
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
@@ -1,83 +0,0 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2021 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 sensor_gps.hpp
|
||||
*
|
||||
* Defines uORB over UAVCANv1 sensor_gps subscriber
|
||||
*
|
||||
* @author Peter van der Perk <peter.vanderperk@nxp.com>
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <uORB/topics/sensor_gps.h>
|
||||
#include <uORB/PublicationMulti.hpp>
|
||||
|
||||
#include "../DynamicPortSubscriber.hpp"
|
||||
|
||||
class UORB_over_UAVCAN_sensor_gps_Subscriber : public UavcanDynamicPortSubscriber
|
||||
{
|
||||
public:
|
||||
UORB_over_UAVCAN_sensor_gps_Subscriber(CanardInstance &ins, UavcanParamManager &pmgr, uint8_t instance = 0) :
|
||||
UavcanDynamicPortSubscriber(ins, pmgr, "uorb.sensor_gps", instance) { };
|
||||
|
||||
void subscribe() override
|
||||
{
|
||||
// Subscribe to messages uORB sensor_gps payload over UAVCAN
|
||||
canardRxSubscribe(&_canard_instance,
|
||||
CanardTransferKindMessage,
|
||||
_subj_sub._canard_sub._port_id,
|
||||
sizeof(struct sensor_gps_s),
|
||||
CANARD_DEFAULT_TRANSFER_ID_TIMEOUT_USEC * 10000,
|
||||
&_subj_sub._canard_sub);
|
||||
};
|
||||
|
||||
void callback(const CanardTransfer &receive) override
|
||||
{
|
||||
//PX4_INFO("uORB sensor_gps Callback");
|
||||
|
||||
if (receive.payload_size == sizeof(struct sensor_gps_s)) {
|
||||
sensor_gps_s *gps_msg = (sensor_gps_s *)receive.payload;
|
||||
_sensor_gps_pub.publish(*gps_msg);
|
||||
|
||||
} else {
|
||||
PX4_ERR("uORB over UAVCAN %s playload size mismatch got %d expected %d",
|
||||
_subj_sub._subject_name, receive.payload_size, sizeof(struct sensor_gps_s));
|
||||
}
|
||||
};
|
||||
|
||||
private:
|
||||
uORB::PublicationMulti<sensor_gps_s> _sensor_gps_pub{ORB_ID(sensor_gps)};
|
||||
|
||||
};
|
||||
@@ -56,7 +56,8 @@ static void memFree(CanardInstance *const ins, void *const pointer) { o1heapFree
|
||||
UavcanNode::UavcanNode(CanardInterface *interface, uint32_t node_id) :
|
||||
ModuleParams(nullptr),
|
||||
ScheduledWorkItem(MODULE_NAME, px4::wq_configurations::uavcan),
|
||||
_can_interface(interface)
|
||||
_can_interface(interface)//,
|
||||
// _subscribers{&_gps0_sub, &_gps1_sub, &_bms0_sub, &_bms1_sub}
|
||||
{
|
||||
pthread_mutex_init(&_node_mutex, nullptr);
|
||||
|
||||
@@ -167,6 +168,13 @@ void UavcanNode::init()
|
||||
CANARD_DEFAULT_TRANSFER_ID_TIMEOUT_USEC,
|
||||
&_heartbeat_subscription);
|
||||
|
||||
canardRxSubscribe(&_canard_instance, // uORB over UAVCAN GPS message
|
||||
CanardTransferKindMessage,
|
||||
gps_port_id,
|
||||
sizeof(struct sensor_gps_s),
|
||||
CANARD_DEFAULT_TRANSFER_ID_TIMEOUT_USEC,
|
||||
&_drone_srv_gps_subscription);
|
||||
|
||||
for (auto &subscriber : _subscribers) {
|
||||
subscriber->subscribe();
|
||||
}
|
||||
@@ -230,69 +238,7 @@ void UavcanNode::Run()
|
||||
|
||||
_node_manager.update();
|
||||
|
||||
transmit();
|
||||
|
||||
/* Process received messages */
|
||||
|
||||
uint8_t data[64] {};
|
||||
CanardFrame received_frame{};
|
||||
received_frame.payload = &data;
|
||||
|
||||
while (_can_interface->receive(&received_frame) > 0) {
|
||||
CanardTransfer receive{};
|
||||
int32_t result = canardRxAccept(&_canard_instance, &received_frame, 0, &receive);
|
||||
|
||||
if (result < 0) {
|
||||
// An error has occurred: either an argument is invalid or we've ran out of memory.
|
||||
// It is possible to statically prove that an out-of-memory will never occur for a given application if
|
||||
// the heap is sized correctly; for background, refer to the Robson's Proof and the documentation for O1Heap.
|
||||
// Reception of an invalid frame is NOT an error.
|
||||
PX4_ERR("Receive error %d\n", result);
|
||||
|
||||
} else if (result == 1) {
|
||||
// A transfer has been received, process it.
|
||||
// PX4_INFO("received Port ID: %d", receive.port_id);
|
||||
|
||||
if (receive.port_id > 0) {
|
||||
// If not a fixed port ID, check any subscribers which may have registered it
|
||||
for (auto &subscriber : _subscribers) {
|
||||
if (subscriber->hasPortID(receive.port_id)) {
|
||||
subscriber->callback(receive);
|
||||
}
|
||||
}
|
||||
|
||||
for (auto &subscriber : _dynsubscribers) {
|
||||
if (subscriber->hasPortID(receive.port_id)) {
|
||||
subscriber->callback(receive);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// Deallocate the dynamic memory afterwards.
|
||||
_canard_instance.memory_free(&_canard_instance, (void *)receive.payload);
|
||||
|
||||
} else {
|
||||
//PX4_INFO("RX canard %d", result);
|
||||
}
|
||||
}
|
||||
|
||||
// Pop canardTx queue to send out responses to requets
|
||||
transmit();
|
||||
|
||||
perf_end(_cycle_perf);
|
||||
|
||||
if (_task_should_exit.load()) {
|
||||
_can_interface->close();
|
||||
|
||||
ScheduleClear();
|
||||
_instance = nullptr;
|
||||
}
|
||||
|
||||
pthread_mutex_unlock(&_node_mutex);
|
||||
}
|
||||
|
||||
void UavcanNode::transmit()
|
||||
{
|
||||
// Transmitting
|
||||
// Look at the top of the TX queue.
|
||||
for (const CanardFrame *txf = nullptr; (txf = canardTxPeek(&_canard_instance)) != nullptr;) {
|
||||
// Attempt transmission only if the frame is not yet timed out while waiting in the TX queue.
|
||||
@@ -322,6 +268,67 @@ void UavcanNode::transmit()
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/* Process received messages */
|
||||
|
||||
uint8_t data[64] {};
|
||||
CanardFrame received_frame{};
|
||||
received_frame.payload = &data;
|
||||
|
||||
/* FIXME this flawed we've to go through the whole loop to get the next frame in the buffer */
|
||||
|
||||
if (_can_interface->receive(&received_frame) > 0) {
|
||||
|
||||
CanardTransfer receive{};
|
||||
int32_t result = canardRxAccept(&_canard_instance, &received_frame, 0, &receive);
|
||||
|
||||
if (result < 0) {
|
||||
// An error has occurred: either an argument is invalid or we've ran out of memory.
|
||||
// It is possible to statically prove that an out-of-memory will never occur for a given application if
|
||||
// the heap is sized correctly; for background, refer to the Robson's Proof and the documentation for O1Heap.
|
||||
// Reception of an invalid frame is NOT an error.
|
||||
PX4_ERR("Receive error %d\n", result);
|
||||
|
||||
} else if (result == 1) {
|
||||
// A transfer has been received, process it.
|
||||
// PX4_INFO("received Port ID: %d", receive.port_id);
|
||||
|
||||
if (receive.port_id == gps_port_id) {
|
||||
result = handleUORBSensorGPS(receive);
|
||||
|
||||
} else if (receive.port_id > 0) {
|
||||
// If not a fixed port ID, check any subscribers which may have registered it
|
||||
for (auto &subscriber : _subscribers) {
|
||||
if (subscriber->hasPortID(receive.port_id)) {
|
||||
subscriber->callback(receive);
|
||||
}
|
||||
}
|
||||
|
||||
for (auto &subscriber : _dynsubscribers) {
|
||||
if (subscriber->hasPortID(receive.port_id)) {
|
||||
subscriber->callback(receive);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// Deallocate the dynamic memory afterwards.
|
||||
_canard_instance.memory_free(&_canard_instance, (void *)receive.payload);
|
||||
|
||||
} else {
|
||||
//PX4_INFO("RX canard %d\r\n", result);
|
||||
}
|
||||
}
|
||||
|
||||
perf_end(_cycle_perf);
|
||||
|
||||
if (_task_should_exit.load()) {
|
||||
_can_interface->close();
|
||||
|
||||
ScheduleClear();
|
||||
_instance = nullptr;
|
||||
}
|
||||
|
||||
pthread_mutex_unlock(&_node_mutex);
|
||||
}
|
||||
|
||||
void UavcanNode::print_info()
|
||||
@@ -331,13 +338,6 @@ void UavcanNode::print_info()
|
||||
perf_print_counter(_cycle_perf);
|
||||
perf_print_counter(_interval_perf);
|
||||
|
||||
O1HeapDiagnostics heap_diagnostics = o1heapGetDiagnostics(uavcan_allocator);
|
||||
|
||||
PX4_INFO("Heap status %zu/%zu Peak alloc %zu Peak req %zu OOM count %" PRIu64,
|
||||
heap_diagnostics.allocated, heap_diagnostics.capacity,
|
||||
heap_diagnostics.peak_allocated, heap_diagnostics.peak_request_size,
|
||||
heap_diagnostics.oom_count);
|
||||
|
||||
for (auto &publisher : _publishers) {
|
||||
publisher->printInfo();
|
||||
}
|
||||
@@ -346,10 +346,6 @@ void UavcanNode::print_info()
|
||||
subscriber->printInfo();
|
||||
}
|
||||
|
||||
for (auto &subscriber : _dynsubscribers) {
|
||||
subscriber->printInfo();
|
||||
}
|
||||
|
||||
_mixing_output.printInfo();
|
||||
_esc_controller.printInfo();
|
||||
|
||||
@@ -446,6 +442,16 @@ void UavcanNode::sendHeartbeat()
|
||||
}
|
||||
}
|
||||
|
||||
int UavcanNode::handleUORBSensorGPS(const CanardTransfer &receive)
|
||||
{
|
||||
PX4_INFO("NodeID %i GPS sensor msg", receive.remote_node_id);
|
||||
|
||||
sensor_gps_s *gps_msg = (sensor_gps_s *)receive.payload;
|
||||
|
||||
return _sensor_gps_pub.publish(*gps_msg) ? 0 : -1;
|
||||
}
|
||||
|
||||
|
||||
bool UavcanMixingInterface::updateOutputs(bool stop_motors, uint16_t outputs[MAX_ACTUATORS], unsigned num_outputs,
|
||||
unsigned num_control_groups_updated)
|
||||
{
|
||||
|
||||
@@ -78,9 +78,6 @@
|
||||
#include "Subscribers/NodeIDAllocationData.hpp"
|
||||
#include "Subscribers/LegacyBatteryInfo.hpp"
|
||||
|
||||
// uORB over UAVCAN subscribers
|
||||
#include "Subscribers/uORB/sensor_gps.hpp"
|
||||
|
||||
#include "ServiceClients/GetInfo.hpp"
|
||||
#include "ServiceClients/Access.hpp"
|
||||
|
||||
@@ -165,11 +162,14 @@ private:
|
||||
void Run() override;
|
||||
void fill_node_info();
|
||||
|
||||
void transmit();
|
||||
|
||||
// Sends a heartbeat at 1s intervals
|
||||
void sendHeartbeat();
|
||||
|
||||
int handlePnpNodeIDAllocationData(const CanardTransfer &receive);
|
||||
int handleRegisterList(const CanardTransfer &receive);
|
||||
int handleRegisterAccess(const CanardTransfer &receive);
|
||||
int handleUORBSensorGPS(const CanardTransfer &receive);
|
||||
|
||||
void *_uavcan_heap{nullptr};
|
||||
|
||||
CanardInterface *const _can_interface;
|
||||
@@ -185,9 +185,14 @@ private:
|
||||
pthread_mutex_t _node_mutex;
|
||||
|
||||
CanardRxSubscription _heartbeat_subscription;
|
||||
CanardRxSubscription _drone_srv_gps_subscription;
|
||||
|
||||
uORB::Subscription _battery_status_sub{ORB_ID(battery_status)};
|
||||
uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)};
|
||||
|
||||
uORB::Publication<battery_status_s> _battery_status_pub{ORB_ID(battery_status)};
|
||||
uORB::Publication<sensor_gps_s> _sensor_gps_pub{ORB_ID(sensor_gps)};
|
||||
|
||||
perf_counter_t _cycle_perf{perf_alloc(PC_ELAPSED, MODULE_NAME": cycle time")};
|
||||
perf_counter_t _interval_perf{perf_alloc(PC_INTERVAL, MODULE_NAME": cycle interval")};
|
||||
|
||||
@@ -196,6 +201,15 @@ private:
|
||||
hrt_abstime _uavcan_node_heartbeat_last{0};
|
||||
CanardTransferID _uavcan_node_heartbeat_transfer_id{0};
|
||||
|
||||
/* Temporary hardcoded port IDs used by the register interface
|
||||
* for demo purposes untill we have nice interface (QGC or latter)
|
||||
* to configure the nodes
|
||||
*/
|
||||
const uint16_t gps_port_id = 1235;
|
||||
|
||||
CanardTransferID _uavcan_register_list_request_transfer_id{0};
|
||||
CanardTransferID _uavcan_register_access_request_transfer_id{0};
|
||||
|
||||
DEFINE_PARAMETERS(
|
||||
(ParamInt<px4::params::UAVCAN_V1_ENABLE>) _param_uavcan_v1_enable,
|
||||
(ParamInt<px4::params::UAVCAN_V1_ID>) _param_uavcan_v1_id,
|
||||
@@ -206,7 +220,7 @@ private:
|
||||
|
||||
UavcanParamManager _param_manager;
|
||||
|
||||
NodeManager _node_manager {_canard_instance, _param_manager};
|
||||
NodeManager _node_manager {_canard_instance};
|
||||
|
||||
UavcanGnssPublisher _gps_pub {_canard_instance, _param_manager};
|
||||
|
||||
@@ -224,8 +238,6 @@ private:
|
||||
UavcanLegacyBatteryInfoSubscriber _legacybms_sub {_canard_instance, _param_manager, 0};
|
||||
UavcanNodeIDAllocationDataSubscriber _nodeid_sub {_canard_instance, _node_manager};
|
||||
|
||||
UORB_over_UAVCAN_sensor_gps_Subscriber _sensor_gps_sub {_canard_instance, _param_manager, 0};
|
||||
|
||||
UavcanGetInfoResponse _getinfo_rsp {_canard_instance};
|
||||
UavcanAccessResponse _access_rsp {_canard_instance, _param_manager};
|
||||
|
||||
@@ -233,7 +245,7 @@ private:
|
||||
UavcanListServiceReply _list_service {_canard_instance, _node_manager};
|
||||
|
||||
// Subscriber objects: Any object used to bridge a UAVCAN message to a uORB message
|
||||
UavcanDynamicPortSubscriber *_dynsubscribers[6] {&_gps0_sub, &_gps1_sub, &_bms0_sub, &_esc_sub, &_legacybms_sub, &_sensor_gps_sub}; /// TODO: turn into List<UavcanSubscription*>
|
||||
UavcanDynamicPortSubscriber *_dynsubscribers[5] {&_gps0_sub, &_gps1_sub, &_bms0_sub, &_esc_sub, &_legacybms_sub}; /// TODO: turn into List<UavcanSubscription*>
|
||||
UavcanBaseSubscriber *_subscribers[5] {&_nodeid_sub, &_getinfo_rsp, &_access_rsp, &_access_service, &_list_service}; /// TODO: turn into List<UavcanSubscription*>
|
||||
|
||||
UavcanMixingInterface _mixing_output {_node_mutex, _esc_controller};
|
||||
|
||||
@@ -103,6 +103,3 @@ PARAM_DEFINE_INT32(UCAN1_LG_BMS_PID, 0);
|
||||
PARAM_DEFINE_INT32(UCAN1_ESC_PUB, 0);
|
||||
PARAM_DEFINE_INT32(UCAN1_GPS_PUB, 0);
|
||||
PARAM_DEFINE_INT32(UCAN1_SERVO_PUB, 0);
|
||||
|
||||
// uORB over UAVCAN
|
||||
PARAM_DEFINE_INT32(UCAN1_UORB_GPS, 0);
|
||||
|
||||
@@ -381,7 +381,7 @@ static int canard_daemon(int argc, char *argv[])
|
||||
/* Init UAVCAN register interfaces */
|
||||
uavcan_node_GetInfo_Response_1_0 node_information; // TODO ADD INFO
|
||||
uavcan_register_interface_init(&ins, &node_information);
|
||||
uavcan_register_interface_add_entry("uorb.sensor_gps.0", set_gps_uorb_port_id, get_gps_uorb_port_id);
|
||||
uavcan_register_interface_add_entry("gnss_uorb", set_gps_uorb_port_id, get_gps_uorb_port_id);
|
||||
uavcan_register_interface_add_entry("gnss_fix", set_gps_fix_port_id, get_gps_fix_port_id);
|
||||
uavcan_register_interface_add_entry("gnss_aux", set_gps_aux_port_id, get_gps_aux_port_id);
|
||||
|
||||
|
||||
@@ -238,13 +238,10 @@ int32_t uavcan_register_interface_list_response(CanardInstance *ins, CanardTrans
|
||||
|
||||
// Reponse magic start
|
||||
|
||||
if (msg.index < register_list_size) {
|
||||
if (msg.index <= register_list_size) {
|
||||
response_msg.name.name.count = sprintf(response_msg.name.name.elements,
|
||||
"uavcan.pub.%s.id",
|
||||
register_list[msg.index].name);
|
||||
|
||||
} else {
|
||||
response_msg.name.name.count = 0;
|
||||
}
|
||||
|
||||
//TODO more option then pub (sub rate
|
||||
|
||||
+1
-1
Submodule src/lib/ecl updated: 29243ac5cb...a7b8afe420
@@ -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;
|
||||
|
||||
|
||||
@@ -467,18 +467,6 @@ static calibrate_return mag_calibration_worker(detect_orientation_return orienta
|
||||
|
||||
calibrate_return mag_calibrate_all(orb_advert_t *mavlink_log_pub, int32_t cal_mask)
|
||||
{
|
||||
// We should not try to subscribe if the topic doesn't actually exist and can be counted.
|
||||
const unsigned orb_mag_count = orb_group_count(ORB_ID(sensor_mag));
|
||||
|
||||
// Warn that we will not calibrate more than MAX_GYROS gyroscopes
|
||||
if (orb_mag_count > MAX_MAGS) {
|
||||
calibration_log_critical(mavlink_log_pub, "Detected %u mags, but will calibrate only %u", orb_mag_count, MAX_MAGS);
|
||||
|
||||
} else if (orb_mag_count < 1) {
|
||||
calibration_log_critical(mavlink_log_pub, "No mags found");
|
||||
return calibrate_return_error;
|
||||
}
|
||||
|
||||
calibrate_return result = calibrate_return_ok;
|
||||
|
||||
mag_worker_data_t worker_data{};
|
||||
|
||||
@@ -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();
|
||||
|
||||
|
||||
+142
-219
@@ -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)};
|
||||
|
||||
|
||||
@@ -141,26 +141,19 @@ FixedwingPositionControl::parameters_update()
|
||||
|
||||
landing_status_publish();
|
||||
|
||||
int check_ret = PX4_OK;
|
||||
|
||||
// sanity check parameters
|
||||
if (_param_fw_airspd_max.get() < _param_fw_airspd_min.get()) {
|
||||
mavlink_log_critical(&_mavlink_log_pub, "Config invalid: Airspeed max smaller than min");
|
||||
check_ret = PX4_ERROR;
|
||||
if ((_param_fw_airspd_max.get() < _param_fw_airspd_min.get()) ||
|
||||
(_param_fw_airspd_max.get() < 5.0f) ||
|
||||
(_param_fw_airspd_min.get() > 100.0f) ||
|
||||
(_param_fw_airspd_trim.get() < _param_fw_airspd_min.get()) ||
|
||||
(_param_fw_airspd_trim.get() > _param_fw_airspd_max.get())) {
|
||||
|
||||
mavlink_log_critical(&_mavlink_log_pub, "Airspeed parameters invalid");
|
||||
|
||||
return PX4_ERROR;
|
||||
}
|
||||
|
||||
if (_param_fw_airspd_max.get() < 5.0f || _param_fw_airspd_min.get() > 100.0f) {
|
||||
mavlink_log_critical(&_mavlink_log_pub, "Config invalid: Airspeed max < 5 m/s or min > 100 m/s");
|
||||
check_ret = PX4_ERROR;
|
||||
}
|
||||
|
||||
if (_param_fw_airspd_trim.get() < _param_fw_airspd_min.get() ||
|
||||
_param_fw_airspd_trim.get() > _param_fw_airspd_max.get()) {
|
||||
mavlink_log_critical(&_mavlink_log_pub, "Config invalid: Airspeed cruise out of min or max bounds");
|
||||
check_ret = PX4_ERROR;
|
||||
}
|
||||
|
||||
return check_ret;
|
||||
return PX4_OK;
|
||||
}
|
||||
|
||||
void
|
||||
|
||||
@@ -461,12 +461,11 @@ PARAM_DEFINE_FLOAT(FW_AIRSPD_MIN, 10.0f);
|
||||
PARAM_DEFINE_FLOAT(FW_AIRSPD_MAX, 20.0f);
|
||||
|
||||
/**
|
||||
* Trim/ Cruise Airspeed (CAS)
|
||||
* Cruise Airspeed (CAS)
|
||||
*
|
||||
* This is the default cruise airspeed setpoint (calibrated airspeed) used by the system in assisted
|
||||
* and autonomous control modes if no other airspeed setpoint is given.
|
||||
* It is also used for control surface effectiveness scaling.
|
||||
* (scaling = FW_AIRSPD_TRIM / calibrated_airspeed).
|
||||
* The trim CAS (calibrated airspeed) of the vehicle. If an airspeed controller is active,
|
||||
* this is the default airspeed setpoint that the controller will try to achieve if
|
||||
* no other airspeed setpoint sources are present (e.g. through non-centered RC sticks).
|
||||
*
|
||||
* @unit m/s
|
||||
* @min 0.5
|
||||
|
||||
@@ -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];
|
||||
|
||||
Reference in New Issue
Block a user