Compare commits

..

1 Commits

Author SHA1 Message Date
Daniel Agar e389d6ffbb commander: cleanup mavlink system present and validity checks
- try to handle mavlink system validity and present checks more consistently
 - telemetry_status unify heartbeats and healthy flags across MAV_TYPE and MAV_COMPONENT (once it's outside of mavlink we don't care about the difference)
 - add gimbal
2021-12-22 09:38:43 +01:00
129 changed files with 762 additions and 856 deletions
+4 -5
View File
@@ -410,8 +410,10 @@ pipeline {
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "sd_bench -u -v"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "sd_stress"'
// test dataman
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "tests dataman"'
// test dataman (stop mavlink & navigator first)
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "mavlink stop-all"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "navigator stop"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "tests dataman" || true'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "tests file" || true'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "uorb_tests"'
@@ -495,9 +497,6 @@ pipeline {
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "work_queue status"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "uorb_tests"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "uorb_tests latency_test" || true'
// test dataman
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "tests dataman"'
}
}
stage("status") {
+4 -4
View File
@@ -15,10 +15,10 @@ jobs:
fail-fast: false
matrix:
config:
- {model: "iris", latitude: "59.617693", longitude: "-151.145316", altitude: "48", build_type: "RelWithDebInfo" } # Alaska
- {model: "standard_vtol", latitude: "-38.071235", longitude: "145.281220", altitude: "31", build_type: "AddressSanitizer" } # Australia
- {model: "tailsitter" , latitude: "29.660316", longitude: "-82.316658", altitude: "30", build_type: "RelWithDebInfo" } # Florida
- {model: "standard_vtol", latitude: "47.397742", longitude: "8.545594", altitude: "488", build_type: "Coverage" } # Zurich
- {latitude: "59.617693", longitude: "-151.145316", altitude: "48", build_type: "RelWithDebInfo", model: "iris" } # Alaska
- {latitude: "-38.071235", longitude: "145.281220", altitude: "31", build_type: "AddressSanitizer", model: "standard_vtol" } # Australia
- {latitude: "29.660316", longitude: "-82.316658", altitude: "30", build_type: "RelWithDebInfo", model: "tailsitter" } # Florida
- {latitude: "47.397742", longitude: "8.545594", altitude: "488", build_type: "Coverage", model: "standard_vtol" } # Zurich
container:
image: px4io/px4-dev-simulation-focal:2021-09-08
+4 -1
View File
@@ -111,7 +111,7 @@ def parse_yaml_parameters_config(yaml_config, ethernet_supported):
for key in param['values']:
tags += '\n * @value {:} {:}'.format(key, param['values'][key])
elif param['type'] == 'boolean':
param_type = 'BOOL'
param_type = 'INT32'
tags += '\n * @boolean'
elif param['type'] == 'int32':
param_type = 'INT32'
@@ -136,6 +136,9 @@ def parse_yaml_parameters_config(yaml_config, ethernet_supported):
else:
default_value = param['default']
if type(default_value) == bool:
default_value = int(default_value)
# output the existing C-style format
ret += '''
/**
+1 -2
View File
@@ -14,7 +14,6 @@ CONFIG_DRIVERS_GPS=y
CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16448=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20948=y
CONFIG_DRIVERS_IMU_INVENSENSE_MPU9250=y
CONFIG_DRIVERS_LINUX_PWM_OUT=y
CONFIG_DRIVERS_MAGNETOMETER_HMC5883=y
CONFIG_DRIVERS_PWM_OUT_SIM=y
CONFIG_DRIVERS_RC_INPUT=y
@@ -24,7 +23,6 @@ CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y
CONFIG_MODULES_BATTERY_STATUS=y
CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_EKF2=y
CONFIG_MODULES_ESC_BATTERY=y
@@ -48,6 +46,7 @@ CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
CONFIG_MODULES_MC_POS_CONTROL=y
CONFIG_MODULES_MC_RATE_CONTROL=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_ROVER_POS_CONTROL=y
+1 -3
View File
@@ -14,8 +14,6 @@ CONFIG_DRIVERS_GPS=y
CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16448=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20948=y
CONFIG_DRIVERS_IMU_INVENSENSE_MPU9250=y
CONFIG_DRIVERS_IMU_ST_LSM9DS1=y
CONFIG_DRIVERS_LINUX_PWM_OUT=y
CONFIG_DRIVERS_MAGNETOMETER_HMC5883=y
CONFIG_DRIVERS_MAGNETOMETER_LSM9DS1_MAG=y
CONFIG_DRIVERS_PWM_OUT_SIM=y
@@ -26,7 +24,6 @@ CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y
CONFIG_MODULES_BATTERY_STATUS=y
CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_EKF2=y
CONFIG_MODULES_ESC_BATTERY=y
@@ -50,6 +47,7 @@ CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
CONFIG_MODULES_MC_POS_CONTROL=y
CONFIG_MODULES_MC_RATE_CONTROL=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_ROVER_POS_CONTROL=y
+1 -5
View File
@@ -49,11 +49,7 @@ add_custom_target(metadata_airframes
set(generated_params_dir ${PX4_BINARY_DIR}/generated_params_metadata)
file(GLOB_RECURSE yaml_config_files ${PX4_SOURCE_DIR}/src/modules/*.yaml
${PX4_SOURCE_DIR}/src/drivers/*.yaml ${PX4_SOURCE_DIR}/src/lib/*.yaml)
# avoid param duplicates
list(FILTER yaml_config_files EXCLUDE REGEX ".*/pwm_out_sim/")
list(FILTER yaml_config_files EXCLUDE REGEX ".*/linux_pwm_out/")
list(FILTER yaml_config_files EXCLUDE REGEX ".*/pwm_out_sim/") # avoid param duplicates
add_custom_target(metadata_parameters
COMMAND ${CMAKE_COMMAND} -E make_directory ${PX4_BINARY_DIR}/docs
COMMAND ${CMAKE_COMMAND} -E make_directory ${generated_params_dir}
+34 -21
View File
@@ -37,25 +37,38 @@ float32 rx_message_lost_rate
uint64 HEARTBEAT_TIMEOUT_US = 1500000 # Heartbeat timeout 1.5 seconds
# Heartbeats per type
bool heartbeat_type_antenna_tracker # MAV_TYPE_ANTENNA_TRACKER
bool heartbeat_type_gcs # MAV_TYPE_GCS
bool heartbeat_type_onboard_controller # MAV_TYPE_ONBOARD_CONTROLLER
bool heartbeat_type_gimbal # MAV_TYPE_GIMBAL
bool heartbeat_type_adsb # MAV_TYPE_ADSB
bool heartbeat_type_camera # MAV_TYPE_CAMERA
bool heartbeat_type_parachute # MAV_TYPE_PARACHUTE
# Heartbeats
bool heartbeat_adsb # MAV_TYPE_ADSB
bool heartbeat_antenna_tracker # MAV_TYPE_ANTENNA_TRACKER
bool heartbeat_battery # MAV_TYPE_BATTERY
bool heartbeat_camera # MAV_TYPE_CAMERA
bool heartbeat_gcs # MAV_TYPE_GCS
bool heartbeat_gimbal # MAV_TYPE_GIMBAL
bool heartbeat_log # MAV_COMP_ID_LOG
bool heartbeat_obstacle_avoidance # MAV_COMP_ID_OBSTACLE_AVOIDANCE
bool heartbeat_onboard_controller # MAV_TYPE_ONBOARD_CONTROLLER
bool heartbeat_osd # MAV_COMP_ID_OSD
bool heartbeat_pairing_manager # MAV_COMP_ID_PAIRING_MANAGER
bool heartbeat_parachute # MAV_TYPE_PARACHUTE
bool heartbeat_telemetry_radio # MAV_COMP_ID_TELEMETRY_RADIO
bool heartbeat_uart_bridge # MAV_COMP_ID_UART_BRIDGE
bool heartbeat_udp_bridge # MAV_COMP_ID_UDP_BRIDGE
bool heartbeat_vio # MAV_COMP_ID_VISUAL_INERTIAL_ODOMETRY
# Heartbeats per component
bool heartbeat_component_telemetry_radio # MAV_COMP_ID_TELEMETRY_RADIO
bool heartbeat_component_log # MAV_COMP_ID_LOG
bool heartbeat_component_osd # MAV_COMP_ID_OSD
bool heartbeat_component_obstacle_avoidance # MAV_COMP_ID_OBSTACLE_AVOIDANCE
bool heartbeat_component_vio # MAV_COMP_ID_VISUAL_INERTIAL_ODOMETRY
bool heartbeat_component_pairing_manager # MAV_COMP_ID_PAIRING_MANAGER
bool heartbeat_component_udp_bridge # MAV_COMP_ID_UDP_BRIDGE
bool heartbeat_component_uart_bridge # MAV_COMP_ID_UART_BRIDGE
# Misc component health
bool avoidance_system_healthy
bool parachute_system_healthy
# system status healthy
bool system_healthy_adsb
bool system_healthy_antenna_tracker
bool system_healthy_battery
bool system_healthy_camera
bool system_healthy_gcs
bool system_healthy_gimbal
bool system_healthy_log
bool system_healthy_obstacle_avoidance
bool system_healthy_onboard_controller
bool system_healthy_osd
bool system_healthy_pairing_manager
bool system_healthy_parachute
bool system_healthy_telemetry_radio
bool system_healthy_uart_bridge
bool system_healthy_udp_bridge
bool system_healthy_vio
+13 -5
View File
@@ -30,14 +30,22 @@ bool circuit_breaker_vtol_fw_arming_check # set to true if for VTOLs arming in
bool offboard_control_signal_lost
bool rc_signal_found_once
bool rc_calibration_in_progress
bool rc_input_blocked # set if RC input should be ignored temporarily
bool rc_calibration_valid # set if RC calibration is valid
bool vtol_transition_failure # Set to true if vtol transition failed
bool usb_connected # status of the USB power supply
bool sd_card_detected_once # set to true if the SD card was detected
bool avoidance_system_required # Set to true if avoidance system is enabled via COM_OBS_AVOID parameter
bool avoidance_system_valid # Status of the obstacle avoidance system
bool system_required_obstacle_avoidance # Set to true if avoidance system is enabled via COM_OBS_AVOID parameter
bool parachute_system_present
bool parachute_system_healthy
bool system_present_gcs
bool system_present_gimbal
bool system_present_obstacle_avoidance
bool system_present_onboard_controller
bool system_present_parachute
bool system_valid_gcs
bool system_valid_gimbal
bool system_valid_obstacle_avoidance
bool system_valid_onboard_controller
bool system_valid_parachute
@@ -261,7 +261,7 @@ private:
int32_t _val;
};
// external version
//external version
template<px4::params p>
class Param<int32_t &, p>
{
@@ -318,7 +318,7 @@ class Param<bool, p>
{
public:
// static type-check
static_assert(px4::parameters_type[(int)p] == PARAM_TYPE_BOOL, "parameter type must be bool");
static_assert(px4::parameters_type[(int)p] == PARAM_TYPE_INT32, "parameter type must be int32_t");
Param()
{
@@ -331,10 +331,18 @@ public:
const bool &reference() const { return _val; }
/// Store the parameter value to the parameter storage (@see param_set())
bool commit() const { return param_set(handle(), &_val) == 0; }
bool commit() const
{
int32_t value_int = (int32_t)_val;
return param_set(handle(), &value_int) == 0;
}
/// Store the parameter value to the parameter storage, w/o notifying the system (@see param_set_no_notification())
bool commit_no_notification() const { return param_set_no_notification(handle(), &_val) == 0; }
bool commit_no_notification() const
{
int32_t value_int = (int32_t)_val;
return param_set_no_notification(handle(), &value_int) == 0;
}
/// Set and commit a new value. Returns true if the value changed.
bool commit_no_notification(bool val)
@@ -356,83 +364,38 @@ public:
update();
}
bool update() { return param_get(handle(), &_val) == 0; }
bool update()
{
int32_t value_int;
int ret = param_get(handle(), &value_int);
if (ret == 0) {
_val = value_int != 0;
return true;
}
return false;
}
param_t handle() const { return param_handle(p); }
private:
bool _val;
};
// external version
template<px4::params p>
class Param<bool &, p>
{
public:
// static type-check
static_assert(px4::parameters_type[(int)p] == PARAM_TYPE_BOOL, "parameter type must be bool");
Param(bool &external_val)
: _val(external_val)
{
param_set_used(handle());
update();
}
bool get() const { return _val; }
const bool &reference() const { return _val; }
/// Store the parameter value to the parameter storage (@see param_set())
bool commit() const { return param_set(handle(), &_val) == 0; }
/// Store the parameter value to the parameter storage, w/o notifying the system (@see param_set_no_notification())
bool commit_no_notification() const { return param_set_no_notification(handle(), &_val) == 0; }
/// Set and commit a new value. Returns true if the value changed.
bool commit_no_notification(bool val)
{
if (val != _val) {
set(val);
commit_no_notification();
return true;
}
return false;
}
void set(bool val) { _val = val; }
void reset()
{
param_reset_no_notification(handle());
update();
}
bool update() { return param_get(handle(), &_val) == 0; }
param_t handle() const { return param_handle(p); }
private:
bool &_val;
};
template <px4::params p>
using ParamBool = Param<bool, p>;
using ParamFloat = Param<float, p>;
template <px4::params p>
using ParamInt = Param<int32_t, p>;
template <px4::params p>
using ParamFloat = Param<float, p>;
template <px4::params p>
using ParamExtBool = Param<bool &, p>;
using ParamExtFloat = Param<float &, p>;
template <px4::params p>
using ParamExtInt = Param<int32_t &, p>;
template <px4::params p>
using ParamExtFloat = Param<float &, p>;
using ParamBool = Param<bool, p>;
} /* namespace do_not_explicitly_use_this_namespace */
@@ -268,7 +268,7 @@ WorkQueueManagerRun(int, char **)
// On posix system , the desired stacksize round to the nearest multiplier of the system pagesize
// It is a requirement of the pthread_attr_setstacksize* function
const unsigned int page_size = sysconf(_SC_PAGESIZE);
const size_t stacksize_adj = math::max((int)PTHREAD_STACK_MIN, PX4_STACK_ADJUSTED(wq->stacksize));
const size_t stacksize_adj = math::max(PTHREAD_STACK_MIN, PX4_STACK_ADJUSTED(wq->stacksize));
const size_t stacksize = (stacksize_adj + page_size - (stacksize_adj % page_size));
#endif
@@ -114,7 +114,7 @@ public:
ArchPX4IOSerial();
ArchPX4IOSerial(ArchPX4IOSerial &) = delete;
ArchPX4IOSerial &operator = (const ArchPX4IOSerial &) = delete;
virtual ~ArchPX4IOSerial();
~ArchPX4IOSerial();
virtual int init();
virtual int ioctl(unsigned operation, unsigned &arg);
@@ -159,6 +159,7 @@ private:
/**
* Performance counters.
*/
perf_counter_t _pc_dmasetup;
perf_counter_t _pc_dmaerrs;
/**
@@ -58,7 +58,13 @@ ArchPX4IOSerial::ArchPX4IOSerial() :
_current_packet(nullptr),
_rx_dma_status(_dma_status_inactive),
_completion_semaphore(SEM_INITIALIZER(0)),
_pc_dmaerrs(perf_alloc(PC_COUNT, MODULE_NAME": DMA errors"))
#if 0
_pc_dmasetup(perf_alloc(PC_ELAPSED, "io_dmasetup ")),
_pc_dmaerrs(perf_alloc(PC_COUNT, "io_dmaerrs "))
#else
_pc_dmasetup(nullptr),
_pc_dmaerrs(nullptr)
#endif
{
}
@@ -93,6 +99,7 @@ ArchPX4IOSerial::~ArchPX4IOSerial()
/* and kill our semaphores */
px4_sem_destroy(&_completion_semaphore);
perf_free(_pc_dmasetup);
perf_free(_pc_dmaerrs);
}
@@ -195,6 +202,7 @@ ArchPX4IOSerial::ioctl(unsigned operation, unsigned &arg)
if (count >= 5000) {
syslog(LOG_INFO, "==== test 1 : %u failures ====\n", fails);
perf_print_counter(_pc_txns);
perf_print_counter(_pc_dmasetup);
perf_print_counter(_pc_retries);
perf_print_counter(_pc_timeouts);
perf_print_counter(_pc_crcerrs);
@@ -233,6 +241,7 @@ ArchPX4IOSerial::_bus_exchange(IOPacket *_packet)
/* start RX DMA */
perf_begin(_pc_txns);
perf_begin(_pc_dmasetup);
/* DMA setup time ~3µs */
_rx_dma_status = _dma_status_waiting;
@@ -279,6 +288,8 @@ ArchPX4IOSerial::_bus_exchange(IOPacket *_packet)
//rCR1 |= USART_CR1_TE;
rCR3 |= USART_CR3_DMAT;
perf_end(_pc_dmasetup);
/* compute the deadline for a 10ms timeout */
struct timespec abstime;
clock_gettime(CLOCK_REALTIME, &abstime);
@@ -298,8 +309,6 @@ ArchPX4IOSerial::_bus_exchange(IOPacket *_packet)
if (ret == OK) {
/* check for DMA errors */
if (_rx_dma_status & DMA_STATUS_TEIF) {
// stream transfer error, ensure all DMA is also stopped before exiting early
_abort_dma();
perf_count(_pc_dmaerrs);
ret = -EIO;
break;
@@ -310,7 +319,6 @@ ArchPX4IOSerial::_bus_exchange(IOPacket *_packet)
_current_packet->crc = 0;
if ((crc != crc_packet(_current_packet)) || (PKT_CODE(*_current_packet) == PKT_CODE_CORRUPT)) {
_abort_dma();
perf_count(_pc_crcerrs);
ret = -EIO;
break;
@@ -68,7 +68,13 @@ ArchPX4IOSerial::ArchPX4IOSerial() :
_current_packet(nullptr),
_rx_dma_status(_dma_status_inactive),
_completion_semaphore(SEM_INITIALIZER(0)),
_pc_dmaerrs(perf_alloc(PC_COUNT, MODULE_NAME": DMA errors"))
#if 0
_pc_dmasetup(perf_alloc(PC_ELAPSED, "io_dmasetup ")),
_pc_dmaerrs(perf_alloc(PC_COUNT, "io_dmaerrs "))
#else
_pc_dmasetup(nullptr),
_pc_dmaerrs(nullptr)
#endif
{
}
@@ -103,6 +109,7 @@ ArchPX4IOSerial::~ArchPX4IOSerial()
/* and kill our semaphores */
px4_sem_destroy(&_completion_semaphore);
perf_free(_pc_dmasetup);
perf_free(_pc_dmaerrs);
}
@@ -207,6 +214,7 @@ ArchPX4IOSerial::ioctl(unsigned operation, unsigned &arg)
if (count >= 5000) {
syslog(LOG_INFO, "==== test 1 : %u failures ====\n", fails);
perf_print_counter(_pc_txns);
perf_print_counter(_pc_dmasetup);
perf_print_counter(_pc_retries);
perf_print_counter(_pc_timeouts);
perf_print_counter(_pc_crcerrs);
@@ -248,6 +256,7 @@ ArchPX4IOSerial::_bus_exchange(IOPacket *_packet)
/* start RX DMA */
perf_begin(_pc_txns);
perf_begin(_pc_dmasetup);
/* DMA setup time ~3µs */
_rx_dma_status = _dma_status_waiting;
@@ -298,6 +307,8 @@ ArchPX4IOSerial::_bus_exchange(IOPacket *_packet)
//rCR1 &= ~USART_CR1_TE;
//rCR1 |= USART_CR1_TE;
perf_end(_pc_dmasetup);
/* compute the deadline for a 10ms timeout */
struct timespec abstime;
clock_gettime(CLOCK_REALTIME, &abstime);
@@ -317,8 +328,8 @@ ArchPX4IOSerial::_bus_exchange(IOPacket *_packet)
if (ret == OK) {
/* check for DMA errors */
if (_rx_dma_status & DMA_STATUS_TEIF) {
// stream transfer error, ensure all DMA is also stopped before exiting early
_abort_dma();
// stream transfer error, ensure TX DMA is also stopped before exiting early
stm32_dmastop(_tx_dma);
perf_count(_pc_dmaerrs);
ret = -EIO;
break;
@@ -329,7 +340,6 @@ ArchPX4IOSerial::_bus_exchange(IOPacket *_packet)
_current_packet->crc = 0;
if ((crc != crc_packet(_current_packet)) || (PKT_CODE(*_current_packet) == PKT_CODE_CORRUPT)) {
_abort_dma();
perf_count(_pc_crcerrs);
ret = -EIO;
break;
@@ -106,7 +106,13 @@ ArchPX4IOSerial::ArchPX4IOSerial() :
_current_packet(nullptr),
_rx_dma_status(_dma_status_inactive),
_completion_semaphore(SEM_INITIALIZER(0)),
_pc_dmaerrs(perf_alloc(PC_COUNT, MODULE_NAME": DMA errors"))
#if 0
_pc_dmasetup(perf_alloc(PC_ELAPSED, "io_dmasetup ")),
_pc_dmaerrs(perf_alloc(PC_COUNT, "io_dmaerrs "))
#else
_pc_dmasetup(nullptr),
_pc_dmaerrs(nullptr)
#endif
{
}
@@ -141,6 +147,7 @@ ArchPX4IOSerial::~ArchPX4IOSerial()
/* and kill our semaphores */
px4_sem_destroy(&_completion_semaphore);
perf_free(_pc_dmasetup);
perf_free(_pc_dmaerrs);
}
@@ -245,6 +252,7 @@ ArchPX4IOSerial::ioctl(unsigned operation, unsigned &arg)
if (count >= 5000) {
syslog(LOG_INFO, "==== test 1 : %u failures ====\n", fails);
perf_print_counter(_pc_txns);
perf_print_counter(_pc_dmasetup);
perf_print_counter(_pc_retries);
perf_print_counter(_pc_timeouts);
perf_print_counter(_pc_crcerrs);
@@ -286,6 +294,7 @@ ArchPX4IOSerial::_bus_exchange(IOPacket *_packet)
/* start RX DMA */
perf_begin(_pc_txns);
perf_begin(_pc_dmasetup);
/* DMA setup time ~3µs */
_rx_dma_status = _dma_status_waiting;
@@ -345,6 +354,8 @@ ArchPX4IOSerial::_bus_exchange(IOPacket *_packet)
//rCR1 &= ~USART_CR1_TE;
//rCR1 |= USART_CR1_TE;
perf_end(_pc_dmasetup);
/* compute the deadline for a 10ms timeout */
struct timespec abstime;
clock_gettime(CLOCK_REALTIME, &abstime);
@@ -364,8 +375,8 @@ ArchPX4IOSerial::_bus_exchange(IOPacket *_packet)
if (ret == OK) {
/* check for DMA errors */
if (_rx_dma_status & DMA_STATUS_TEIF) {
// stream transfer error, ensure all DMA is also stopped before exiting early
_abort_dma();
// stream transfer error, ensure TX DMA is also stopped before exiting early
stm32_dmastop(_tx_dma);
perf_count(_pc_dmaerrs);
ret = -EIO;
break;
@@ -376,7 +387,6 @@ ArchPX4IOSerial::_bus_exchange(IOPacket *_packet)
_current_packet->crc = 0;
if ((crc != crc_packet(_current_packet)) || (PKT_CODE(*_current_packet) == PKT_CODE_CORRUPT)) {
_abort_dma();
perf_count(_pc_crcerrs);
ret = -EIO;
break;
+1 -2
View File
@@ -6,8 +6,7 @@
# config for a quad
# modified from ../rpi/px4.config
param select eeprom/parameters
param import
param load
param set CBRK_SUPPLY_CHK 894281
+1 -2
View File
@@ -6,8 +6,7 @@
# config for fixed wing (FW)
# modified from ./px4.config, switch att/pos_control & mixer
param select eeprom/parameters
param import
param load
param set CBRK_SUPPLY_CHK 894281
+4 -2
View File
@@ -3,8 +3,10 @@
# (px4-alias.sh is expected to be in the PATH)
. px4-alias.sh
param select eeprom/parameters
param import
if [ -f eeprom/parameters ]
then
param load
fi
# system_power not implemented
param set CBRK_SUPPLY_CHK 894281
+4 -2
View File
@@ -3,8 +3,10 @@
# (px4-alias.sh is expected to be in the PATH)
. px4-alias.sh
param select eeprom/parameters
param import
if [ -f eeprom/parameters ]
then
param load
fi
# system_power not implemented
param set CBRK_SUPPLY_CHK 894281
+4 -3
View File
@@ -5,9 +5,10 @@
# navio config for a quad
param select eeprom/parameters
param import
if [ -f eeprom/parameters ]
then
param load
fi
param set CBRK_SUPPLY_CHK 894281
param set SYS_AUTOSTART 4001
param set MAV_TYPE 2
+4 -3
View File
@@ -5,9 +5,10 @@
# navio config for FW
param select eeprom/parameters
param import
if [ -f eeprom/parameters ]
then
param load
fi
param set CBRK_SUPPLY_CHK 894281
param set SYS_AUTOSTART 2100
param set MAV_TYPE 1
+4 -3
View File
@@ -7,9 +7,10 @@
# connect to it with jMAVSim:
# ./Tools/jmavsim_run.sh -q -i <IP> -p 14577 -r 250
param select eeprom/parameters
param import
if [ -f eeprom/parameters ]
then
param load
fi
param set CBRK_SUPPLY_CHK 894281
param set SYS_AUTOSTART 1001
param set MAV_TYPE 2
+4 -3
View File
@@ -5,9 +5,10 @@
# navio config for simple testing
param select eeprom/parameters
param import
if [ -f eeprom/parameters ]
then
param load
fi
param set CBRK_SUPPLY_CHK 894281
param set SYS_AUTOSTART 4001
param set MAV_TYPE 2
+1 -1
View File
@@ -39,7 +39,7 @@
* @boolean
* @group Sensors
*/
PARAM_DEFINE_BOOL(SENS_EN_BATT, 0);
PARAM_DEFINE_INT32(SENS_EN_BATT, 0);
/**
* Capacity/current multiplier for high-current capable SMBUS battery
@@ -70,13 +70,13 @@ CameraCapture::CameraCapture() :
// get the capture channel from function configuration params
param_t p_ctrl_alloc = param_find("SYS_CTRL_ALLOC");
bool ctrl_alloc = false;
int32_t ctrl_alloc = 0;
if (p_ctrl_alloc != PARAM_INVALID) {
param_get(p_ctrl_alloc, &ctrl_alloc);
}
if (ctrl_alloc) {
if (ctrl_alloc == 1) {
_capture_channel = -1;
for (unsigned i = 0; i < 16 && _capture_channel == -1; ++i) {
@@ -59,7 +59,7 @@ PARAM_DEFINE_FLOAT(CAM_CAP_DELAY, 0.0f);
* @group Camera Control
* @reboot_required true
*/
PARAM_DEFINE_BOOL(CAM_CAP_FBACK, 0);
PARAM_DEFINE_INT32(CAM_CAP_FBACK, 0);
/**
* Camera capture timestamping mode
@@ -84,4 +84,4 @@ PARAM_DEFINE_INT32(CAM_CAP_MODE, 0);
* @group Camera Control
* @reboot_required true
*/
PARAM_DEFINE_INT32(CAM_CAP_EDGE, 0);
PARAM_DEFINE_INT32(CAM_CAP_EDGE, 0);
@@ -43,13 +43,14 @@ void CameraInterface::get_pins()
}
param_t p_ctrl_alloc = param_find("SYS_CTRL_ALLOC");
bool ctrl_alloc = false;
int32_t ctrl_alloc = 0;
if (p_ctrl_alloc != PARAM_INVALID) {
param_get(p_ctrl_alloc, &ctrl_alloc);
}
if (ctrl_alloc) {
if (ctrl_alloc == 1) {
unsigned pin_index = 0;
for (unsigned i = 0; i < 16 && pin_index < arraySize(_pins); ++i) {
@@ -38,4 +38,4 @@
* @group Sensors
* @boolean
*/
PARAM_DEFINE_BOOL(SENS_EN_ETSASPD, 0);
PARAM_DEFINE_INT32(SENS_EN_ETSASPD, 0);
@@ -38,4 +38,4 @@
* @group Sensors
* @boolean
*/
PARAM_DEFINE_BOOL(SENS_EN_MS4525, 0);
PARAM_DEFINE_INT32(SENS_EN_MS4525, 0);
@@ -37,5 +37,5 @@
* @reboot_required true
* @group Sensors
* @boolean
**/
PARAM_DEFINE_BOOL(SENS_EN_MS5525, 0);
*/
PARAM_DEFINE_INT32(SENS_EN_MS5525, 0);
@@ -37,5 +37,5 @@
* @reboot_required true
* @group Sensors
* @boolean
**/
PARAM_DEFINE_BOOL(SENS_EN_SDP3X, 0);
*/
PARAM_DEFINE_INT32(SENS_EN_SDP3X, 0);
@@ -157,7 +157,7 @@ private:
perf_counter_t _sample_perf{perf_alloc(PC_COUNT, "mb12xx_sample_perf")};
DEFINE_PARAMETERS(
(ParamBool<px4::params::SENS_EN_MB12XX>) _p_sensor_enabled,
(ParamInt<px4::params::SENS_EN_MB12XX>) _p_sensor_enabled,
(ParamInt<px4::params::SENS_MB12_0_ROT>) _p_sensor0_rot,
(ParamInt<px4::params::SENS_MB12_1_ROT>) _p_sensor1_rot,
(ParamInt<px4::params::SENS_MB12_2_ROT>) _p_sensor2_rot,
@@ -39,7 +39,7 @@
* @boolean
* @group Sensors
*/
PARAM_DEFINE_BOOL(SENS_EN_MB12XX, 0);
PARAM_DEFINE_INT32(SENS_EN_MB12XX, 0);
/**
* MaxBotix MB12XX Sensor 0 Rotation
@@ -291,4 +291,4 @@ PARAM_DEFINE_INT32(SENS_MB12_10_ROT, 0);
* @value 6 Yaw 270°
* @value 7 Yaw 315°
*/
PARAM_DEFINE_INT32(SENS_MB12_11_ROT, 0);
PARAM_DEFINE_INT32(SENS_MB12_11_ROT, 0);
@@ -39,4 +39,4 @@
* @boolean
* @group Sensors
*/
PARAM_DEFINE_BOOL(SENS_EN_PGA460, 0);
PARAM_DEFINE_INT32(SENS_EN_PGA460, 0);
@@ -38,4 +38,4 @@
* @group Sensors
* @boolean
*/
PARAM_DEFINE_BOOL(SENS_EN_SR05, 0);
PARAM_DEFINE_INT32(SENS_EN_SR05, 0);
+1 -1
View File
@@ -39,4 +39,4 @@
* @boolean
* @group Sensors
*/
PARAM_DEFINE_BOOL(SENS_EN_VL53L1X, 0);
PARAM_DEFINE_INT32(SENS_EN_VL53L1X, 0);
+43
View File
@@ -0,0 +1,43 @@
############################################################################
#
# Copyright (c) 2017 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.
#
############################################################################
add_subdirectory(adis16477)
add_subdirectory(adis16497)
add_subdirectory(analog_devices)
add_subdirectory(bosch)
add_subdirectory(fxas21002c)
add_subdirectory(fxos8701cq)
add_subdirectory(invensense)
add_subdirectory(l3gd20)
add_subdirectory(lsm303d)
add_subdirectory(st)
+44
View File
@@ -0,0 +1,44 @@
############################################################################
#
# Copyright (c) 2020 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
add_subdirectory(icm20602)
add_subdirectory(icm20608g)
add_subdirectory(icm20649)
add_subdirectory(icm20689)
add_subdirectory(icm40609d)
add_subdirectory(icm42605)
add_subdirectory(icm42688p)
add_subdirectory(icm42670p)
add_subdirectory(mpu6000)
add_subdirectory(mpu6500)
add_subdirectory(mpu9250)
+34
View File
@@ -0,0 +1,34 @@
############################################################################
#
# Copyright (c) 2020 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
add_subdirectory(lsm9ds1)
+5 -3
View File
@@ -1,3 +1,5 @@
menu "ST"
rsource "*/Kconfig"
endmenu #Invensense
menuconfig DRIVERS_IMU_ST
bool "st"
default n
---help---
Enable support for st
-5
View File
@@ -1,5 +0,0 @@
menuconfig DRIVERS_IMU_ST_LSM9DS1
bool "lsm9ds1"
default n
---help---
Enable support for lsm9ds1
+1 -1
View File
@@ -268,7 +268,7 @@ void LinuxPWMOut::update_params()
// PWM_MAIN_REVx
{
sprintf(str, "%s_REV%u", prefix, i + 1);
bool pwm_rev = false;
int32_t pwm_rev = 0;
if (param_get(param_find(str), &pwm_rev) == PX4_OK) {
uint16_t &reverse_pwm_mask = _mixing_output.reverseOutputMask();
+1 -1
View File
@@ -85,7 +85,7 @@ private:
void update_params();
MixingOutput _mixing_output{"PWM_MAIN", MAX_ACTUATORS, *this, MixingOutput::SchedulingPolicy::Auto, false};
MixingOutput _mixing_output{"PWM", MAX_ACTUATORS, *this, MixingOutput::SchedulingPolicy::Auto, false};
uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s};
+1 -1
View File
@@ -1,7 +1,7 @@
module_name: PWM Output
actuator_output:
output_groups:
- param_prefix: PWM_MAIN
- param_prefix: PWM
channel_label: 'Channel'
standard_params:
disarmed: { min: 800, max: 2200, default: 900 }
@@ -39,4 +39,4 @@
* @boolean
* @group Sensors
*/
PARAM_DEFINE_BOOL(SENS_EN_PAW3902, 0);
PARAM_DEFINE_INT32(SENS_EN_PAW3902, 0);
@@ -39,4 +39,4 @@
* @boolean
* @group Sensors
*/
PARAM_DEFINE_BOOL(SENS_EN_PMW3901, 0);
PARAM_DEFINE_INT32(SENS_EN_PMW3901, 0);
@@ -39,4 +39,4 @@
* @boolean
* @group Sensors
*/
PARAM_DEFINE_BOOL(SENS_EN_PX4FLOW, 0);
PARAM_DEFINE_INT32(SENS_EN_PX4FLOW, 0);
+1 -1
View File
@@ -314,7 +314,7 @@ void PCA9685Wrapper::updatePWMParams()
if (param_h != PARAM_INVALID) {
uint16_t &reverse_pwm_mask = _mixing_output.reverseOutputMask();
bool pval = false;
int32_t pval = 0;
param_get(param_h, &pval);
reverse_pwm_mask &= (0xfffe << i); // clear this bit
reverse_pwm_mask |= (((uint16_t)(pval != 0)) << i); // set to new val
@@ -40,7 +40,7 @@
* @boolean
* @reboot_required true
*/
PARAM_DEFINE_BOOL(SENS_EN_INA226, 0);
PARAM_DEFINE_INT32(SENS_EN_INA226, 0);
/**
* INA226 Power Monitor Config
@@ -40,7 +40,7 @@
* @boolean
* @reboot_required true
*/
PARAM_DEFINE_BOOL(SENS_EN_INA228, 0);
PARAM_DEFINE_INT32(SENS_EN_INA228, 0);
/**
* INA228 Power Monitor Config
@@ -40,7 +40,7 @@
* @boolean
* @reboot_required true
*/
PARAM_DEFINE_BOOL(SENS_EN_INA238, 0);
PARAM_DEFINE_INT32(SENS_EN_INA238, 0);
/**
* INA238 Power Monitor Max Current
+1 -1
View File
@@ -655,7 +655,7 @@ void PWMOut::update_params()
// PWM_MAIN_REVx
{
sprintf(str, "%s_REV%u", prefix, i + 1);
bool pwm_rev = false;
int32_t pwm_rev = 0;
if (param_get(param_find(str), &pwm_rev) == PX4_OK) {
uint16_t &reverse_pwm_mask = _mixing_output.reverseOutputMask();
+1 -1
View File
@@ -902,7 +902,7 @@ void PX4IO::update_params()
for (unsigned i = 0; i < _max_actuators; i++) {
sprintf(str, "%s_REV%u", prefix, i + 1);
bool pwm_rev = false;
int32_t pwm_rev = -1;
if (param_get(param_find(str), &pwm_rev) == PX4_OK) {
if (pwm_rev >= 1) {
+1 -1
View File
@@ -40,4 +40,4 @@
* @reboot_required true
* @group Telemetry
*/
PARAM_DEFINE_BOOL(TEL_BST_EN, 0);
PARAM_DEFINE_INT32(TEL_BST_EN, 0);
+11 -11
View File
@@ -57,18 +57,18 @@
void IUavcanSensorBridge::make_all(uavcan::INode &node, List<IUavcanSensorBridge *> &list)
{
// airspeed
bool uavcan_sub_aspd = true;
int32_t uavcan_sub_aspd = 1;
param_get(param_find("UAVCAN_SUB_ASPD"), &uavcan_sub_aspd);
if (uavcan_sub_aspd) {
if (uavcan_sub_aspd != 0) {
list.add(new UavcanAirspeedBridge(node));
}
// baro
bool uavcan_sub_baro = true;
int32_t uavcan_sub_baro = 1;
param_get(param_find("UAVCAN_SUB_BARO"), &uavcan_sub_baro);
if (uavcan_sub_baro) {
if (uavcan_sub_baro != 0) {
list.add(new UavcanBarometerBridge(node));
}
@@ -84,7 +84,7 @@ void IUavcanSensorBridge::make_all(uavcan::INode &node, List<IUavcanSensorBridge
}
// differential pressure
bool uavcan_sub_dpres = true;
int32_t uavcan_sub_dpres = 1;
param_get(param_find("UAVCAN_SUB_DPRES"), &uavcan_sub_dpres);
if (uavcan_sub_dpres != 0) {
@@ -92,7 +92,7 @@ void IUavcanSensorBridge::make_all(uavcan::INode &node, List<IUavcanSensorBridge
}
// flow
bool uavcan_sub_flow = true;
int32_t uavcan_sub_flow = 1;
param_get(param_find("UAVCAN_SUB_FLOW"), &uavcan_sub_flow);
if (uavcan_sub_flow != 0) {
@@ -100,7 +100,7 @@ void IUavcanSensorBridge::make_all(uavcan::INode &node, List<IUavcanSensorBridge
}
// GPS
bool uavcan_sub_gps = true;
int32_t uavcan_sub_gps = 1;
param_get(param_find("UAVCAN_SUB_GPS"), &uavcan_sub_gps);
if (uavcan_sub_gps != 0) {
@@ -108,7 +108,7 @@ void IUavcanSensorBridge::make_all(uavcan::INode &node, List<IUavcanSensorBridge
}
// ice (internal combustion engine)
bool uavcan_sub_ice = true;
int32_t uavcan_sub_ice = 1;
param_get(param_find("UAVCAN_SUB_ICE"), &uavcan_sub_ice);
if (uavcan_sub_ice != 0) {
@@ -116,7 +116,7 @@ void IUavcanSensorBridge::make_all(uavcan::INode &node, List<IUavcanSensorBridge
}
// IMU
bool uavcan_sub_imu = true;
int32_t uavcan_sub_imu = 1;
param_get(param_find("UAVCAN_SUB_IMU"), &uavcan_sub_imu);
if (uavcan_sub_imu != 0) {
@@ -125,7 +125,7 @@ void IUavcanSensorBridge::make_all(uavcan::INode &node, List<IUavcanSensorBridge
}
// magnetometer
bool uavcan_sub_mag = true;
int32_t uavcan_sub_mag = 1;
param_get(param_find("UAVCAN_SUB_MAG"), &uavcan_sub_mag);
if (uavcan_sub_mag != 0) {
@@ -133,7 +133,7 @@ void IUavcanSensorBridge::make_all(uavcan::INode &node, List<IUavcanSensorBridge
}
// range finder
bool uavcan_sub_rng = true;
int32_t uavcan_sub_rng = 1;
param_get(param_find("UAVCAN_SUB_RNG"), &uavcan_sub_rng);
if (uavcan_sub_rng != 0) {
+9 -9
View File
@@ -206,7 +206,7 @@ PARAM_DEFINE_INT32(UAVCAN_LGT_LAND, 0);
* @reboot_required true
* @group UAVCAN
*/
PARAM_DEFINE_BOOL(UAVCAN_SUB_ASPD, 0);
PARAM_DEFINE_INT32(UAVCAN_SUB_ASPD, 0);
/**
* subscription barometer
@@ -219,7 +219,7 @@ PARAM_DEFINE_BOOL(UAVCAN_SUB_ASPD, 0);
* @reboot_required true
* @group UAVCAN
*/
PARAM_DEFINE_BOOL(UAVCAN_SUB_BARO, 0);
PARAM_DEFINE_INT32(UAVCAN_SUB_BARO, 0);
/**
* subscription battery
@@ -248,7 +248,7 @@ PARAM_DEFINE_INT32(UAVCAN_SUB_BAT, 0);
* @reboot_required true
* @group UAVCAN
*/
PARAM_DEFINE_BOOL(UAVCAN_SUB_DPRES, 0);
PARAM_DEFINE_INT32(UAVCAN_SUB_DPRES, 0);
/**
* subscription flow
@@ -259,7 +259,7 @@ PARAM_DEFINE_BOOL(UAVCAN_SUB_DPRES, 0);
* @reboot_required true
* @group UAVCAN
*/
PARAM_DEFINE_BOOL(UAVCAN_SUB_FLOW, 0);
PARAM_DEFINE_INT32(UAVCAN_SUB_FLOW, 0);
/**
* subscription GPS
@@ -273,7 +273,7 @@ PARAM_DEFINE_BOOL(UAVCAN_SUB_FLOW, 0);
* @reboot_required true
* @group UAVCAN
*/
PARAM_DEFINE_BOOL(UAVCAN_SUB_GPS, 1);
PARAM_DEFINE_INT32(UAVCAN_SUB_GPS, 1);
/**
* subscription ICE
@@ -285,7 +285,7 @@ PARAM_DEFINE_BOOL(UAVCAN_SUB_GPS, 1);
* @reboot_required true
* @group UAVCAN
*/
PARAM_DEFINE_BOOL(UAVCAN_SUB_ICE, 0);
PARAM_DEFINE_INT32(UAVCAN_SUB_ICE, 0);
/**
* subscription IMU
@@ -297,7 +297,7 @@ PARAM_DEFINE_BOOL(UAVCAN_SUB_ICE, 0);
* @reboot_required true
* @group UAVCAN
*/
PARAM_DEFINE_BOOL(UAVCAN_SUB_IMU, 0);
PARAM_DEFINE_INT32(UAVCAN_SUB_IMU, 0);
/**
* subscription magnetometer
@@ -310,7 +310,7 @@ PARAM_DEFINE_BOOL(UAVCAN_SUB_IMU, 0);
* @reboot_required true
* @group UAVCAN
*/
PARAM_DEFINE_BOOL(UAVCAN_SUB_MAG, 1);
PARAM_DEFINE_INT32(UAVCAN_SUB_MAG, 1);
/**
* subscription range finder
@@ -322,4 +322,4 @@ PARAM_DEFINE_BOOL(UAVCAN_SUB_MAG, 1);
* @reboot_required true
* @group UAVCAN
*/
PARAM_DEFINE_BOOL(UAVCAN_SUB_RNG, 0);
PARAM_DEFINE_INT32(UAVCAN_SUB_RNG, 0);
+1 -1
View File
@@ -178,7 +178,7 @@ private:
CanardTransferID _uavcan_node_heartbeat_transfer_id{0};
DEFINE_PARAMETERS(
(ParamBool<px4::params::UAVCAN_V1_ENABLE>) _param_uavcan_v1_enable,
(ParamInt<px4::params::UAVCAN_V1_ENABLE>) _param_uavcan_v1_enable,
(ParamInt<px4::params::UAVCAN_V1_ID>) _param_uavcan_v1_id,
(ParamInt<px4::params::UAVCAN_V1_BAUD>) _param_uavcan_v1_baud
)
+1 -1
View File
@@ -41,7 +41,7 @@
* @reboot_required true
* @group UAVCAN v1
*/
PARAM_DEFINE_BOOL(UAVCAN_V1_ENABLE, 0);
PARAM_DEFINE_INT32(UAVCAN_V1_ENABLE, 0);
/**
* UAVCAN v1 Node ID.
+1 -1
View File
@@ -58,7 +58,7 @@ PARAM_DEFINE_INT32(CANNODE_BITRATE, 1000000);
* @max 1
* @group UAVCAN
*/
PARAM_DEFINE_BOOL(CANNODE_TERM, 0);
PARAM_DEFINE_INT32(CANNODE_TERM, 0);
/**
* Cannode flow board rotation
@@ -317,7 +317,7 @@ TEST_F(CollisionPreventionTest, testPurgeOldData)
//at iteration 8 change the CP_GO_NO_DATA to True
if (i == 8) {
param_t param_allow = param_handle(px4::params::CP_GO_NO_DATA);
bool value_allow = true;
float value_allow = 1;
param_set(param_allow, &value_allow);
cp.paramsChanged();
}
@@ -555,7 +555,7 @@ TEST_F(CollisionPreventionTest, goNoData)
//WHEN: we change the parameter CP_GO_NO_DATA to allow flying ouside the FOV
param_t param_allow = param_handle(px4::params::CP_GO_NO_DATA);
bool value_allow = true;
float value_allow = 1;
param_set(param_allow, &value_allow);
cp.paramsChanged();
@@ -83,4 +83,4 @@ PARAM_DEFINE_FLOAT(CP_GUIDE_ANG, 30.f);
* @boolean
* @group Multicopter Position Control
*/
PARAM_DEFINE_BOOL(CP_GO_NO_DATA, 0);
PARAM_DEFINE_INT32(CP_GO_NO_DATA, 0);
+1 -1
View File
@@ -331,7 +331,7 @@ private:
perf_counter_t _control_latency_perf;
/* SYS_CTRL_ALLOC */
/* SYS_CTRL_ALLOC == 1 */
FunctionProviderBase *_function_allocated[MAX_ACTUATORS] {}; ///< unique allocated functions
FunctionProviderBase *_functions[MAX_ACTUATORS] {}; ///< currently assigned functions
OutputFunction _function_assignment[MAX_ACTUATORS] {};
+1 -25
View File
@@ -94,7 +94,6 @@ param_export_internal(bool only_unsaved, param_filter_func filter)
while ((s = (struct param_wbuf_s *)utarray_next(param_values, s)) != nullptr) {
bool b;
int32_t i;
float f;
@@ -115,16 +114,6 @@ param_export_internal(bool only_unsaved, param_filter_func filter)
/* append the appropriate BSON type object */
switch (param_type(s->param)) {
case PARAM_TYPE_BOOL:
b = s->val.b;
if (bson_encoder_append_bool(&encoder, param_name(s->param), b)) {
debug("BSON append failed for '%s'", param_name(s->param));
goto out;
}
break;
case PARAM_TYPE_INT32:
i = s->val.i;
@@ -216,10 +205,8 @@ struct param_import_state {
static int
param_import_callback(bson_decoder_t decoder, void *priv, bson_node_t node)
{
bool b;
int32_t i;
float f;
int32_t i;
void *v = nullptr;
int result = -1;
struct param_import_state *state = (struct param_import_state *)priv;
@@ -251,17 +238,6 @@ param_import_callback(bson_decoder_t decoder, void *priv, bson_node_t node)
*/
switch (node->type) {
case BSON_BOOL:
if (param_type(param) != PARAM_TYPE_BOOL) {
PX4_WARN("unexpected type for %s", node->name);
result = 1; // just skip this entry
goto out;
}
b = node->b;
v = &b;
break;
case BSON_INT32:
if (param_type(param) != PARAM_TYPE_INT32) {
PX4_WARN("unexpected type for %s", node->name);
+11 -20
View File
@@ -57,10 +57,9 @@ __BEGIN_DECLS
/**
* Parameter types.
*/
#define PARAM_TYPE_UNKNOWN 0
#define PARAM_TYPE_BOOL 1
#define PARAM_TYPE_INT32 2
#define PARAM_TYPE_FLOAT 3
#define PARAM_TYPE_UNKNOWN 0
#define PARAM_TYPE_INT32 1
#define PARAM_TYPE_FLOAT 2
typedef uint8_t param_type_t;
@@ -453,10 +452,9 @@ __EXPORT void param_control_autosave(bool enable);
* Parameter value union.
*/
union param_value_u {
void *p;
bool b;
int32_t i;
float f;
void *p;
int32_t i;
float f;
};
/**
@@ -495,23 +493,16 @@ __END_DECLS
// param is a C-interface. This means there is no overloading, and thus no type-safety for param_get().
// So for C++ code we redefine param_get() to inlined overloaded versions, which gives us type-safety
// w/o having to use a different interface
static inline int param_get_cplusplus(param_t param, bool *val)
{
CHECK_PARAM_TYPE(param, PARAM_TYPE_BOOL);
return param_get(param, (void *)val);
}
static inline int param_get_cplusplus(param_t param, int32_t *val)
{
CHECK_PARAM_TYPE(param, PARAM_TYPE_INT32);
return param_get(param, (void *)val);
}
static inline int param_get_cplusplus(param_t param, float *val)
{
CHECK_PARAM_TYPE(param, PARAM_TYPE_FLOAT);
return param_get(param, (void *)val);
}
static inline int param_get_cplusplus(param_t param, int32_t *val)
{
CHECK_PARAM_TYPE(param, PARAM_TYPE_INT32);
return param_get(param, (void *)val);
}
#undef CHECK_PARAM_TYPE
#define param_get(param, val) param_get_cplusplus(param, val)
-8
View File
@@ -163,13 +163,5 @@ bool param_modify_on_import(bson_node_t node)
}
}
// 2021-11-15 migrate INT32 parameters that are now BOOL
if ((node->type == BSON_INT32) && (param_type(param_find(node->name)) == PARAM_TYPE_BOOL)) {
int32_t old_value = node->i32;
node->type = BSON_BOOL;
node->b = (old_value != 0);
}
return false;
}
+3 -93
View File
@@ -425,9 +425,6 @@ size_t param_size(param_t param)
{
if (handle_in_range(param)) {
switch (param_type(param)) {
case PARAM_TYPE_BOOL:
return 1;
case PARAM_TYPE_INT32:
case PARAM_TYPE_FLOAT:
return 4;
@@ -473,9 +470,6 @@ param_get_value_ptr(param_t param)
// otherwise return static default value
switch (param_type(param)) {
case PARAM_TYPE_BOOL:
return &px4::parameters[param].val.b;
case PARAM_TYPE_INT32:
return &px4::parameters[param].val.i;
@@ -543,10 +537,6 @@ param_get_default_value_internal(param_t param, void *default_val)
// otherwise return static default value
switch (param_type(param)) {
case PARAM_TYPE_BOOL:
memcpy(default_val, &px4::parameters[param].val.b, param_size(param));
return PX4_OK;
case PARAM_TYPE_INT32:
memcpy(default_val, &px4::parameters[param].val.i, param_size(param));
return PX4_OK;
@@ -575,25 +565,6 @@ bool param_value_is_default(param_t param)
// back to default, so we don't rely on the params_changed bitset here
if (handle_in_range(param)) {
switch (param_type(param)) {
case PARAM_TYPE_BOOL: {
param_lock_reader();
bool default_value = false;
if (param_get_default_value_internal(param, &default_value) == PX4_OK) {
const void *v = param_get_value_ptr(param);
if (v) {
bool current_value;
memcpy(&current_value, v, param_size(param));
param_unlock_reader();
return (current_value == default_value);
}
}
param_unlock_reader();
}
break;
case PARAM_TYPE_INT32: {
param_lock_reader();
int32_t default_value = 0;
@@ -647,10 +618,6 @@ param_get_system_default_value(param_t param, void *default_val)
int ret = PX4_OK;
switch (param_type(param)) {
case PARAM_TYPE_BOOL:
memcpy(default_val, &px4::parameters[param].val.b, param_size(param));
break;
case PARAM_TYPE_INT32:
memcpy(default_val, &px4::parameters[param].val.i, param_size(param));
break;
@@ -804,14 +771,6 @@ param_set_internal(param_t param, const void *val, bool mark_saved, bool notify_
if (s != nullptr) {
/* update the changed value */
switch (param_type(param)) {
case PARAM_TYPE_BOOL:
param_changed = param_changed || s->val.b != *(bool *)val;
s->val.b = *(bool *)val;
s->unsaved = !mark_saved;
params_changed.set(param, true);
result = PX4_OK;
break;
case PARAM_TYPE_INT32:
param_changed = param_changed || s->val.i != *(int32_t *)val;
s->val.i = *(int32_t *)val;
@@ -926,10 +885,6 @@ int param_set_default_value(param_t param, const void *val)
bool setting_to_static_default = false;
switch (param_type(param)) {
case PARAM_TYPE_BOOL:
setting_to_static_default = (px4::parameters[param].val.b == *(bool *)val);
break;
case PARAM_TYPE_INT32:
setting_to_static_default = (px4::parameters[param].val.i == *(int32_t *)val);
break;
@@ -976,12 +931,6 @@ int param_set_default_value(param_t param, const void *val)
if (s != nullptr) {
// update the default value
switch (param_type(param)) {
case PARAM_TYPE_BOOL:
s->val.b = *(bool *)val;
params_custom_default.set(param, true);
result = PX4_OK;
break;
case PARAM_TYPE_INT32:
s->val.i = *(int32_t *)val;
params_custom_default.set(param, true);
@@ -1336,17 +1285,6 @@ param_export(int fd, bool only_unsaved, param_filter_func filter)
// don't export default values
switch (param_type(s->param)) {
case PARAM_TYPE_BOOL: {
bool default_value = false;
param_get_default_value_internal(s->param, &default_value);
if (s->val.b == default_value) {
PX4_DEBUG("skipping %s %d export", param_name(s->param), default_value);
continue;
}
}
break;
case PARAM_TYPE_INT32: {
int32_t default_value = 0;
param_get_default_value_internal(s->param, &default_value);
@@ -1377,17 +1315,6 @@ param_export(int fd, bool only_unsaved, param_filter_func filter)
/* append the appropriate BSON type object */
switch (param_type(s->param)) {
case PARAM_TYPE_BOOL: {
const bool b = s->val.b;
PX4_DEBUG("exporting: %s (%d) size: %lu val: %d", name, s->param, (long unsigned int)size, b);
if (bson_encoder_append_bool(&encoder, name, b) != 0) {
PX4_ERR("BSON append failed for '%s'", name);
goto out;
}
}
break;
case PARAM_TYPE_INT32: {
const int32_t i = s->val.i;
PX4_DEBUG("exporting: %s (%d) size: %lu val: %d", name, s->param, (long unsigned int)size, i);
@@ -1446,10 +1373,8 @@ struct param_import_state {
static int
param_import_callback(bson_decoder_t decoder, void *priv, bson_node_t node)
{
bool b = false;
int32_t i = 0;
float f = 0.0f;
int32_t i = 0;
void *v = nullptr;
int result = -1;
param_import_state *state = (param_import_state *)priv;
@@ -1481,20 +1406,6 @@ param_import_callback(bson_decoder_t decoder, void *priv, bson_node_t node)
*/
switch (node->type) {
case BSON_BOOL: {
if (param_type(param) != PARAM_TYPE_BOOL) {
PX4_WARN("unexpected type for %s", node->name);
result = 1; // just skip this entry
goto out;
}
b = node->b;
v = &b;
PX4_DEBUG("Imported %s with value %d", param_name(param), b);
}
break;
case BSON_INT32: {
if (param_type(param) != PARAM_TYPE_INT32) {
PX4_WARN("unexpected type for %s", node->name);
@@ -1591,10 +1502,9 @@ param_import_internal(int fd, bool mark_saved)
} while (result > 0);
if (result == 0) {
PX4_INFO("BSON document size %" PRId32 " bytes, decoded %" PRId32 " bytes, bool:%" PRIu16 ", int32:%" PRIu16
", double:%" PRIu16,
PX4_INFO("BSON document size %" PRId32 " bytes, decoded %" PRId32 " bytes (INT32:%" PRIu16 ", FLOAT:%" PRIu16 ")",
decoder.total_document_size, decoder.total_decoded_size,
decoder.count_node_bool, decoder.count_node_int32, decoder.count_node_double);
decoder.count_node_int32, decoder.count_node_double);
return 0;
+2 -3
View File
@@ -25,7 +25,7 @@ class JsonOutput():
"reboot_required": ("rebootRequired", bool),
"decimal": ("decimalPlaces", int),
}
allowed_types = { "Bool", "Uint8", "Int8", "Uint16", "Int16", "Uint32", "Int32", "Float"}
allowed_types = { "Uint8", "Int8", "Uint16", "Int16", "Uint32", "Int32", "Float"}
last_param_name = ""
board_specific_param_set = False
@@ -33,9 +33,8 @@ class JsonOutput():
group_name=group.GetName()
def get_typed_value(value: str, type_name: str):
if type_name == 'Bool': return bool(value)
if type_name == 'Int32': return int(value)
if type_name == 'Float': return float(value)
if type_name == 'Int32': return int(value)
return value
for param in group.GetParams():
+1 -4
View File
@@ -381,7 +381,6 @@ class SourceParser(object):
seenParamNames.append(name_plus_board)
# Validate values
default = param.GetDefault()
type = param.GetType()
min = param.GetFieldValue("min")
max = param.GetFieldValue("max")
units = param.GetFieldValue("unit")
@@ -389,11 +388,9 @@ class SourceParser(object):
sys.stderr.write("Invalid unit in {0}: {1}\n".format(name, units))
return False
#sys.stderr.write("{0} default:{1} min:{2} max:{3}\n".format(name, default, min, max))
if type != "BOOL" and default != "" and not self.IsNumber(default):
if default != "" and not self.IsNumber(default):
sys.stderr.write("Default value not number: {0} {1}\n".format(name, default))
return False
# if default != "" and "." not in default:
# sys.stderr.write("Default value does not contain dot (e.g. 10 needs to be written as 10.0): {0} {1}\n".format(name, default))
# return False
@@ -24,12 +24,10 @@ static constexpr param_info_s parameters[] = {
{% for param in params %}
{
"{{ param.attrib["name"] }}",
{%- if param.attrib["type"] == "BOOL" %}
.val = {{ "{" }} .b = {{ param.attrib["default"] }}{{ "}" }},
{%- if param.attrib["type"] == "FLOAT" %}
.val = {{ "{" }} .f = {{ param.attrib["default"] }} {{ "}" }},
{%- elif param.attrib["type"] == "INT32" %}
.val = {{ "{" }} .i = {{ param.attrib["default"] }}{{ "}" }},
{%- elif param.attrib["type"] == "FLOAT" %}
.val = {{ "{" }} .f = {{ param.attrib["default"] }} {{ "}" }},
{%- endif %}
},
{% endfor %}
+7 -6
View File
@@ -187,7 +187,7 @@ PARAM_DEFINE_INT32(SYS_CAL_TMAX, 10);
*
* @group System
*/
PARAM_DEFINE_BOOL(SYS_HAS_GPS, 1);
PARAM_DEFINE_INT32(SYS_HAS_GPS, 1);
/**
* Control if the vehicle has a magnetometer
@@ -201,7 +201,7 @@ PARAM_DEFINE_BOOL(SYS_HAS_GPS, 1);
*
* @group System
*/
PARAM_DEFINE_BOOL(SYS_HAS_MAG, 1);
PARAM_DEFINE_INT32(SYS_HAS_MAG, 1);
/**
* Control if the vehicle has a barometer
@@ -216,7 +216,7 @@ PARAM_DEFINE_BOOL(SYS_HAS_MAG, 1);
*
* @group System
*/
PARAM_DEFINE_BOOL(SYS_HAS_BARO, 1);
PARAM_DEFINE_INT32(SYS_HAS_BARO, 1);
/**
* Enable factory calibration mode
@@ -229,7 +229,7 @@ PARAM_DEFINE_BOOL(SYS_HAS_BARO, 1);
* @boolean
* @group System
*/
PARAM_DEFINE_BOOL(SYS_FAC_CAL_MODE, 0);
PARAM_DEFINE_INT32(SYS_FAC_CAL_MODE, 0);
/**
* Bootloader update
@@ -251,7 +251,7 @@ PARAM_DEFINE_BOOL(SYS_FAC_CAL_MODE, 0);
*
* @group System
*/
PARAM_DEFINE_BOOL(SYS_BL_UPDATE, 0);
PARAM_DEFINE_INT32(SYS_BL_UPDATE, 0);
/**
* Enable failure injection
@@ -266,6 +266,7 @@ PARAM_DEFINE_BOOL(SYS_BL_UPDATE, 0);
*/
PARAM_DEFINE_INT32(SYS_FAILURE_EN, 0);
/**
* Enable Dynamic Control Allocation
*
@@ -279,4 +280,4 @@ PARAM_DEFINE_INT32(SYS_FAILURE_EN, 0);
* @reboot_required true
* @group System
*/
PARAM_DEFINE_BOOL(SYS_CTRL_ALLOC, 0);
PARAM_DEFINE_INT32(SYS_CTRL_ALLOC, 0);
+2 -2
View File
@@ -45,7 +45,7 @@
* @boolean
* @group Multicopter Position Control
*/
PARAM_DEFINE_BOOL(WV_EN, 0);
PARAM_DEFINE_INT32(WV_EN, 0);
/**
* Weather-vane roll angle to yawrate.
@@ -79,4 +79,4 @@ PARAM_DEFINE_FLOAT(WV_ROLL_MIN, 1.0f);
* @unit deg/s
* @group Multicopter Position Control
*/
PARAM_DEFINE_FLOAT(WV_YRATE_MAX, 90.0f);
PARAM_DEFINE_FLOAT(WV_YRATE_MAX, 90.0f);
@@ -177,7 +177,7 @@ private:
(ParamFloat<px4::params::ASPD_SCALE_3>) _param_airspeed_scale_3,
(ParamInt<px4::params::ASPD_PRIMARY>) _param_airspeed_primary_index,
(ParamInt<px4::params::ASPD_DO_CHECKS>) _param_airspeed_checks_on,
(ParamBool<px4::params::ASPD_FALLBACK_GW>) _param_airspeed_fallback_gw,
(ParamInt<px4::params::ASPD_FALLBACK_GW>) _param_airspeed_fallback_gw,
(ParamFloat<px4::params::ASPD_FS_INNOV>) _tas_innov_threshold, /**< innovation check threshold */
(ParamFloat<px4::params::ASPD_FS_INTEG>) _tas_innov_integ_threshold, /**< innovation check integrator threshold */
@@ -169,7 +169,7 @@ PARAM_DEFINE_INT32(ASPD_DO_CHECKS, 7);
* @boolean
* @group Airspeed Validator
*/
PARAM_DEFINE_BOOL(ASPD_FALLBACK_GW, 0);
PARAM_DEFINE_INT32(ASPD_FALLBACK_GW, 0);
/**
* Airspeed failure innovation threshold
@@ -148,11 +148,11 @@ private:
(ParamFloat<px4::params::ATT_W_EXT_HDG>) _param_att_w_ext_hdg,
(ParamFloat<px4::params::ATT_W_GYRO_BIAS>) _param_att_w_gyro_bias,
(ParamFloat<px4::params::ATT_MAG_DECL>) _param_att_mag_decl,
(ParamBool<px4::params::ATT_MAG_DECL_A>) _param_att_mag_decl_a,
(ParamInt<px4::params::ATT_MAG_DECL_A>) _param_att_mag_decl_a,
(ParamInt<px4::params::ATT_EXT_HDG_M>) _param_att_ext_hdg_m,
(ParamBool<px4::params::ATT_ACC_COMP>) _param_att_acc_comp,
(ParamInt<px4::params::ATT_ACC_COMP>) _param_att_acc_comp,
(ParamFloat<px4::params::ATT_BIAS_MAX>) _param_att_bias_mas,
(ParamBool<px4::params::SYS_HAS_MAG>) _param_sys_has_mag
(ParamInt<px4::params::SYS_HAS_MAG>) _param_sys_has_mag
)
};
@@ -99,7 +99,7 @@ PARAM_DEFINE_FLOAT(ATT_MAG_DECL, 0.0f);
* @group Attitude Q estimator
* @boolean
*/
PARAM_DEFINE_BOOL(ATT_MAG_DECL_A, 1);
PARAM_DEFINE_INT32(ATT_MAG_DECL_A, 1);
/**
* External heading usage mode (from Motion capture/Vision)
@@ -122,7 +122,7 @@ PARAM_DEFINE_INT32(ATT_EXT_HDG_M, 0);
* @group Attitude Q estimator
* @boolean
*/
PARAM_DEFINE_BOOL(ATT_ACC_COMP, 1);
PARAM_DEFINE_INT32(ATT_ACC_COMP, 1);
/**
* Gyro bias limit
@@ -68,10 +68,11 @@ bool PreFlightCheck::preflightCheck(orb_advert_t *mavlink_log_pub, vehicle_statu
/* ---- MAG ---- */
{
bool sys_has_mag = true;
int32_t sys_has_mag = 1;
param_get(param_find("SYS_HAS_MAG"), &sys_has_mag);
if (sys_has_mag) {
if (sys_has_mag == 1) {
/* check all sensors individually, but fail only for mandatory ones */
for (unsigned i = 0; i < max_optional_mag_count; i++) {
const bool required = (i < max_mandatory_mag_count) && (sys_has_mag == 1);
@@ -141,14 +142,14 @@ bool PreFlightCheck::preflightCheck(orb_advert_t *mavlink_log_pub, vehicle_statu
/* ---- BARO ---- */
{
bool sys_has_baro = true;
int32_t sys_has_baro = 1;
param_get(param_find("SYS_HAS_BARO"), &sys_has_baro);
bool baro_fail_reported = false;
/* check all sensors, but fail only for mandatory ones */
for (unsigned i = 0; i < max_optional_baro_count; i++) {
const bool required = (i < max_mandatory_baro_count) && sys_has_baro;
const bool required = (i < max_mandatory_baro_count) && (sys_has_baro == 1);
bool report_fail = (required && report_failures && !baro_fail_reported);
int32_t device_id = -1;
@@ -64,10 +64,10 @@ bool PreFlightCheck::ekf2Check(orb_advert_t *mavlink_log_pub, vehicle_status_s &
float mag_test_ratio_limit = 1.f;
param_get(param_find("COM_ARM_EKF_YAW"), &mag_test_ratio_limit);
bool arm_without_gps = 0;
int32_t arm_without_gps = 0;
param_get(param_find("COM_ARM_WO_GPS"), &arm_without_gps);
bool sys_has_gps = 1;
int32_t sys_has_gps = 1;
param_get(param_find("SYS_HAS_GPS"), &sys_has_gps);
bool gps_success = false;
@@ -48,14 +48,14 @@ bool PreFlightCheck::parachuteCheck(orb_advert_t *mavlink_log_pub, const bool re
const bool parachute_required = param_com_parachute != 0;
if (parachute_required) {
if (!status_flags.parachute_system_present) {
if (!status_flags.system_present_parachute) {
success = false;
if (report_fail) {
mavlink_log_critical(mavlink_log_pub, "Fail: Parachute system missing");
}
} else if (!status_flags.parachute_system_healthy) {
} else if (!status_flags.system_valid_parachute) {
success = false;
if (report_fail) {
@@ -123,7 +123,7 @@ bool PreFlightCheck::preArmCheck(orb_advert_t *mavlink_log_pub, const vehicle_st
prearm_ok = false;
}
if (status_flags.avoidance_system_required && !status_flags.avoidance_system_valid) {
if (status_flags.system_required_obstacle_avoidance && !status_flags.system_valid_obstacle_avoidance) {
if (prearm_ok) {
if (report_fail) { mavlink_log_critical(mavlink_log_pub, "Arming denied! Avoidance system not ready"); }
}
+168 -154
View File
@@ -572,6 +572,7 @@ transition_result_t Commander::arm(arm_disarm_reason_t calling_reason, bool run_
"Arming denied: throttle above center");
tune_negative(true);
return TRANSITION_DENIED;
}
if (!_vehicle_control_mode.flag_control_climb_rate_enabled &&
@@ -944,12 +945,47 @@ Commander::handle_command(const vehicle_command_s &cmd)
break;
case vehicle_command_s::VEHICLE_CMD_DO_SET_HOME: {
if (_param_com_home_en.get()) {
bool use_current = cmd.param1 > 0.5f;
bool use_current = cmd.param1 > 0.5f;
if (use_current) {
/* use current position */
if (set_home_position()) {
cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED;
} else {
cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
}
} else {
float yaw = matrix::wrap_2pi(math::radians(cmd.param4));
yaw = PX4_ISFINITE(yaw) ? yaw : (float)NAN;
const double lat = cmd.param5;
const double lon = cmd.param6;
const float alt = cmd.param7;
if (PX4_ISFINITE(lat) && PX4_ISFINITE(lon) && PX4_ISFINITE(alt)) {
const vehicle_local_position_s &local_pos = _local_position_sub.get();
if (local_pos.xy_global && local_pos.z_global) {
/* use specified position */
home_position_s home{};
home.timestamp = hrt_absolute_time();
fillGlobalHomePos(home, lat, lon, alt);
home.manual_home = true;
// update local projection reference including altitude
MapProjection ref_pos{local_pos.ref_lat, local_pos.ref_lon};
float home_x;
float home_y;
ref_pos.project(lat, lon, home_x, home_y);
const float home_z = -(alt - local_pos.ref_alt);
fillLocalHomePos(home, home_x, home_y, home_z, yaw);
/* mark home position as set */
_status_flags.condition_home_position_valid = _home_pub.update(home);
if (use_current) {
/* use current position */
if (set_home_position()) {
cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED;
} else {
@@ -957,49 +993,8 @@ Commander::handle_command(const vehicle_command_s &cmd)
}
} else {
float yaw = matrix::wrap_2pi(math::radians(cmd.param4));
yaw = PX4_ISFINITE(yaw) ? yaw : (float)NAN;
const double lat = cmd.param5;
const double lon = cmd.param6;
const float alt = cmd.param7;
if (PX4_ISFINITE(lat) && PX4_ISFINITE(lon) && PX4_ISFINITE(alt)) {
const vehicle_local_position_s &local_pos = _local_position_sub.get();
if (local_pos.xy_global && local_pos.z_global) {
/* use specified position */
home_position_s home{};
home.timestamp = hrt_absolute_time();
fillGlobalHomePos(home, lat, lon, alt);
home.manual_home = true;
// update local projection reference including altitude
MapProjection ref_pos{local_pos.ref_lat, local_pos.ref_lon};
float home_x;
float home_y;
ref_pos.project(lat, lon, home_x, home_y);
const float home_z = -(alt - local_pos.ref_alt);
fillLocalHomePos(home, home_x, home_y, home_z, yaw);
/* mark home position as set */
_status_flags.condition_home_position_valid = _home_pub.update(home);
cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED;
} else {
cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
}
} else {
cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_DENIED;
}
cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_DENIED;
}
} else {
// COM_HOME_EN disabled
cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_DENIED;
}
}
break;
@@ -1262,7 +1257,7 @@ Commander::handle_command(const vehicle_command_s &cmd)
/* RC calibration */
answer_command(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED);
/* disable RC control input completely */
_status_flags.rc_calibration_in_progress = true;
_status_flags.rc_input_blocked = true;
mavlink_log_info(&_mavlink_log_pub, "Calibration: Disabling RC input\t");
events::send(events::ID("commander_calib_rc_off"), events::Log::Info,
"Calibration: Disabling RC input");
@@ -1312,9 +1307,9 @@ Commander::handle_command(const vehicle_command_s &cmd)
} else if ((int)(cmd.param4) == 0) {
/* RC calibration ended - have we been in one worth confirming? */
if (_status_flags.rc_calibration_in_progress) {
if (_status_flags.rc_input_blocked) {
/* enable RC control input */
_status_flags.rc_calibration_in_progress = false;
_status_flags.rc_input_blocked = false;
mavlink_log_info(&_mavlink_log_pub, "Calibration: Restoring RC input\t");
events::send(events::ID("commander_calib_rc_on"), events::Log::Info,
"Calibration: Restoring RC input");
@@ -1460,7 +1455,7 @@ Commander::handle_command_motor_test(const vehicle_command_s &cmd)
return vehicle_command_s::VEHICLE_CMD_RESULT_DENIED;
}
if (!_param_com_mot_test_en.get()) {
if (_param_com_mot_test_en.get() != 1) {
return vehicle_command_s::VEHICLE_CMD_RESULT_DENIED;
}
@@ -1557,15 +1552,6 @@ void Commander::executeActionRequest(const action_request_s &action_request)
{
arm_disarm_reason_t arm_disarm_reason{};
// Silently ignore RC actions during RC calibration
if (_status_flags.rc_calibration_in_progress
&& (action_request.source == action_request_s::SOURCE_RC_STICK_GESTURE
|| action_request.source == action_request_s::SOURCE_RC_SWITCH
|| action_request.source == action_request_s::SOURCE_RC_BUTTON
|| action_request.source == action_request_s::SOURCE_RC_MODE_SLOT)) {
return;
}
switch (action_request.source) {
case action_request_s::SOURCE_RC_STICK_GESTURE: arm_disarm_reason = arm_disarm_reason_t::rc_stick; break;
@@ -1683,8 +1669,7 @@ Commander::set_home_position()
bool
Commander::set_in_air_home_position()
{
if (_param_com_home_en.get()
&& _status_flags.condition_local_position_valid
if (_status_flags.condition_local_position_valid
&& _status_flags.condition_global_position_valid) {
const vehicle_global_position_s &gpos = _global_position_sub.get();
@@ -1775,7 +1760,7 @@ Commander::set_home_position_alt_only()
{
const vehicle_local_position_s &lpos = _local_position_sub.get();
if (_param_com_home_en.get() && !_home_pub.get().valid_alt && lpos.z_global) {
if (!_home_pub.get().valid_alt && lpos.z_global) {
// handle special case where we are setting only altitude using local position reference
home_position_s home{};
home.alt = lpos.ref_alt;
@@ -1792,14 +1777,12 @@ Commander::set_home_position_alt_only()
void
Commander::updateHomePositionYaw(float yaw)
{
if (_param_com_home_en.get()) {
home_position_s home = _home_pub.get();
home_position_s home = _home_pub.get();
home.yaw = yaw;
home.timestamp = hrt_absolute_time();
home.yaw = yaw;
home.timestamp = hrt_absolute_time();
_home_pub.update(home);
}
_home_pub.update(home);
}
void
@@ -1918,7 +1901,7 @@ Commander::run()
_status_changed = true;
}
_status_flags.avoidance_system_required = _param_com_obs_avoid.get();
_status_flags.system_required_obstacle_avoidance = _param_com_obs_avoid.get();
_arm_requirements.arm_authorization = _param_arm_auth_required.get();
_arm_requirements.esc_check = _param_escs_checks_required.get();
@@ -1970,7 +1953,7 @@ Commander::run()
}
/* Update OA parameter */
_status_flags.avoidance_system_required = _param_com_obs_avoid.get();
_status_flags.system_required_obstacle_avoidance = _param_com_obs_avoid.get();
#if defined(BOARD_HAS_POWER_CONTROL)
@@ -2037,7 +2020,7 @@ Commander::run()
}
// automatically set or update home position
if (_param_com_home_en.get() && !_home_pub.get().manual_home) {
if (!_home_pub.get().manual_home) {
// set the home position when taking off, but only if we were previously disarmed
// and at least 500 ms from commander start spent to avoid setting home on in-air restart
if (_should_set_home_on_takeoff && !_land_detector.landed &&
@@ -2465,7 +2448,8 @@ Commander::run()
_last_valid_manual_control_setpoint = manual_control_setpoint.timestamp;
} else {
if (_status_flags.rc_signal_found_once && !_status.rc_signal_lost) {
if (_status_flags.rc_signal_found_once && !_status.rc_signal_lost
&& !_status_flags.condition_calibration_enabled && !_status_flags.rc_input_blocked) {
mavlink_log_critical(&_mavlink_log_pub, "Manual control lost\t");
events::send(events::ID("commander_rc_lost"), {events::Log::Critical, events::LogInternal::Info},
"Manual control lost");
@@ -2488,7 +2472,7 @@ Commander::run()
if ((_status.vehicle_type == vehicle_status_s::VEHICLE_TYPE_ROTARY_WING)
&& !in_low_battery_failsafe && !_geofence_warning_action_on
&& _armed.armed
&& !_status_flags.rc_calibration_in_progress
&& !_status_flags.rc_input_blocked
&& manual_control_setpoint.valid
&& manual_control_setpoint.sticks_moving
&& override_enabled) {
@@ -2679,7 +2663,7 @@ Commander::run()
const hrt_abstime now = hrt_absolute_time();
// automatically set or update home position
if (_param_com_home_en.get() && !_home_pub.get().manual_home) {
if (!_home_pub.get().manual_home) {
const vehicle_local_position_s &local_position = _local_position_sub.get();
if (!_armed.armed) {
@@ -3452,124 +3436,152 @@ void Commander::data_link_check()
}
}
if (telemetry.heartbeat_type_gcs) {
// Initial connection or recovery from data link lost
if (_status.data_link_lost) {
_status.data_link_lost = false;
if (telemetry.heartbeat_gcs) {
if (!_status_flags.system_present_gcs && (_datalink_last_heartbeat_gcs != 0)) {
_status_changed = true;
if (_datalink_last_heartbeat_gcs != 0) {
mavlink_log_info(&_mavlink_log_pub, "Data link regained\t");
events::send(events::ID("commander_dl_regained"), events::Log::Info, "Data link regained");
}
if (!_armed.armed && !_status_flags.condition_calibration_enabled) {
// make sure to report preflight check failures to a connecting GCS
PreFlightCheck::preflightCheck(&_mavlink_log_pub, _status, _status_flags, true, false,
hrt_elapsed_time(&_boot_timestamp));
}
mavlink_log_info(&_mavlink_log_pub, "Data link regained\t");
events::send(events::ID("commander_dl_regained"), events::Log::Info, "Data link regained");
}
_datalink_last_heartbeat_gcs = telemetry.timestamp;
_status_flags.system_valid_gcs = telemetry.system_healthy_onboard_controller;
_status_flags.system_present_gcs = true;
// Initial connection or recovery from data link lost
if (_status.data_link_lost) {
_status.data_link_lost = false;
}
if (!_armed.armed && !_status_flags.condition_calibration_enabled) {
// make sure to report preflight check failures to a connecting GCS
PreFlightCheck::preflightCheck(&_mavlink_log_pub, _status, _status_flags, true, false,
hrt_elapsed_time(&_boot_timestamp));
}
}
if (telemetry.heartbeat_type_onboard_controller) {
if (_onboard_controller_lost) {
_onboard_controller_lost = false;
if (telemetry.heartbeat_onboard_controller) {
if (!_status_flags.system_present_onboard_controller && (_datalink_last_heartbeat_onboard_controller != 0)) {
_status_changed = true;
if (_datalink_last_heartbeat_onboard_controller != 0) {
mavlink_log_info(&_mavlink_log_pub, "Onboard controller regained\t");
events::send(events::ID("commander_onboard_ctrl_regained"), events::Log::Info, "Onboard controller regained");
}
mavlink_log_info(&_mavlink_log_pub, "Onboard controller regained\t");
events::send(events::ID("commander_onboard_ctrl_regained"), events::Log::Info, "Onboard controller regained");
}
_datalink_last_heartbeat_onboard_controller = telemetry.timestamp;
_status_flags.system_valid_onboard_controller = telemetry.system_healthy_onboard_controller;
_status_flags.system_present_onboard_controller = true;
}
if (telemetry.heartbeat_type_parachute) {
if (_parachute_system_lost) {
_parachute_system_lost = false;
if (_datalink_last_heartbeat_parachute_system != 0) {
mavlink_log_info(&_mavlink_log_pub, "Parachute system regained\t");
events::send(events::ID("commander_parachute_regained"), events::Log::Info, "Parachute system regained");
}
if (telemetry.heartbeat_gimbal) {
if (!_status_flags.system_present_gimbal && (_datalink_last_heartbeat_gimbal != 0)) {
_status_changed = true;
mavlink_log_info(&_mavlink_log_pub, "Gimbal regained\t");
events::send(events::ID("commander_gimbal_regained"), events::Log::Info, "Gimbal regained");
}
bool healthy = telemetry.parachute_system_healthy;
_datalink_last_heartbeat_gimbal = telemetry.timestamp;
_status_flags.system_valid_gimbal = telemetry.system_healthy_gimbal;
_status_flags.system_present_gimbal = true;
}
if (telemetry.heartbeat_parachute) {
if (!_status_flags.system_present_parachute && (_datalink_last_heartbeat_parachute_system != 0)) {
_status_changed = true;
mavlink_log_info(&_mavlink_log_pub, "Parachute system regained\t");
events::send(events::ID("commander_parachute_regained"), events::Log::Info, "Parachute system regained");
}
const bool healthy = telemetry.system_healthy_parachute;
_datalink_last_heartbeat_parachute_system = telemetry.timestamp;
_status_flags.parachute_system_present = true;
_status_flags.parachute_system_healthy = healthy;
_status_flags.system_present_parachute = true;
_status_flags.system_valid_parachute = healthy;
set_health_flags(subsystem_info_s::SUBSYSTEM_TYPE_PARACHUTE, true, true, healthy, _status);
}
if (telemetry.heartbeat_component_obstacle_avoidance) {
if (_avoidance_system_lost) {
_avoidance_system_lost = false;
if (telemetry.heartbeat_obstacle_avoidance) {
if (!_status_flags.system_present_obstacle_avoidance && (_datalink_last_heartbeat_obstacle_avoidance_system != 0)) {
_status_changed = true;
mavlink_log_info(&_mavlink_log_pub, "Obstacle avoidance system regained\t");
events::send(events::ID("commander_obstacle_avoidance_regained"), events::Log::Info,
"Obstacle avoidance system regained");
}
_datalink_last_heartbeat_avoidance_system = telemetry.timestamp;
_status_flags.avoidance_system_valid = telemetry.avoidance_system_healthy;
_datalink_last_heartbeat_obstacle_avoidance_system = telemetry.timestamp;
_status_flags.system_valid_obstacle_avoidance = telemetry.system_healthy_obstacle_avoidance;
_status_flags.system_present_obstacle_avoidance = true;
}
}
}
static constexpr uint64_t TIMEOUT_DEFAULT = 3_s;
// GCS data link loss failsafe
if (!_status.data_link_lost) {
if ((_datalink_last_heartbeat_gcs != 0)
&& hrt_elapsed_time(&_datalink_last_heartbeat_gcs) > (_param_com_dl_loss_t.get() * 1_s)) {
_status.data_link_lost = true;
_status.data_link_lost_counter++;
// GCS (data link loss failsafe)
if (_status_flags.system_present_gcs
&& hrt_elapsed_time(&_datalink_last_heartbeat_gcs) > (_param_com_dl_loss_t.get() * 1_s)) {
mavlink_log_info(&_mavlink_log_pub, "Connection to ground station lost\t");
events::send(events::ID("commander_gcs_lost"), {events::Log::Warning, events::LogInternal::Info},
"Connection to ground station lost");
_status_flags.system_present_gcs = false;
_status_flags.system_valid_gcs = false;
_status_changed = true;
mavlink_log_info(&_mavlink_log_pub, "Connection to ground station lost\t");
events::send(events::ID("commander_gcs_lost"), {events::Log::Warning, events::LogInternal::Info},
"Connection to ground station lost");
_status_changed = true;
}
_status.data_link_lost = true;
_status.data_link_lost_counter++;
}
// ONBOARD CONTROLLER data link loss failsafe
if ((_datalink_last_heartbeat_onboard_controller > 0)
&& (hrt_elapsed_time(&_datalink_last_heartbeat_onboard_controller) > (_param_com_obc_loss_t.get() * 1_s))
&& !_onboard_controller_lost) {
// gimbal
if (_status_flags.system_present_gimbal
&& (hrt_elapsed_time(&_datalink_last_heartbeat_gimbal) > TIMEOUT_DEFAULT)) {
_status_flags.system_present_gimbal = false;
_status_flags.system_valid_gimbal = false;
_status_changed = true;
mavlink_log_critical(&_mavlink_log_pub, "Connection to gimbal lost\t");
events::send(events::ID("commander_gimbal_lost"), events::Log::Critical, "Connection to gimbal lost");
}
// obstacle avoidance
if (_status_flags.system_present_obstacle_avoidance
&& (hrt_elapsed_time(&_datalink_last_heartbeat_obstacle_avoidance_system) > TIMEOUT_DEFAULT)) {
_status_flags.system_present_obstacle_avoidance = false;
_status_flags.system_valid_obstacle_avoidance = false;
_status_changed = true;
mavlink_log_critical(&_mavlink_log_pub, "Connection to obstacle avoidance lost\t");
events::send(events::ID("commander_obstacle_avoidance_lost"), events::Log::Critical,
"Connection to obstacle avoidance lost");
}
// onboard controller
if (_status_flags.system_present_onboard_controller
&& (hrt_elapsed_time(&_datalink_last_heartbeat_onboard_controller) > (_param_com_obc_loss_t.get() * 1_s))) {
_status_flags.system_present_onboard_controller = false;
_status_flags.system_valid_onboard_controller = false;
_status_changed = true;
mavlink_log_critical(&_mavlink_log_pub, "Connection to mission computer lost\t");
events::send(events::ID("commander_mission_comp_lost"), events::Log::Critical, "Connection to mission computer lost");
_onboard_controller_lost = true;
_status_changed = true;
}
// Parachute system
if ((hrt_elapsed_time(&_datalink_last_heartbeat_parachute_system) > 3_s)
&& !_parachute_system_lost) {
mavlink_log_critical(&_mavlink_log_pub, "Parachute system lost");
_status_flags.parachute_system_present = false;
_status_flags.parachute_system_healthy = false;
_parachute_system_lost = true;
// parachute
if (_status_flags.system_present_parachute
&& (hrt_elapsed_time(&_datalink_last_heartbeat_parachute_system) > TIMEOUT_DEFAULT)) {
_status_flags.system_present_parachute = false;
_status_flags.system_valid_parachute = false;
_status_changed = true;
set_health_flags(subsystem_info_s::SUBSYSTEM_TYPE_PARACHUTE, false, true, false, _status);
}
// AVOIDANCE SYSTEM state check (only if it is enabled)
if (_status_flags.avoidance_system_required && !_onboard_controller_lost) {
// if heartbeats stop
if (!_avoidance_system_lost && (_datalink_last_heartbeat_avoidance_system > 0)
&& (hrt_elapsed_time(&_datalink_last_heartbeat_avoidance_system) > 5_s)) {
_avoidance_system_lost = true;
_status_flags.avoidance_system_valid = false;
}
mavlink_log_critical(&_mavlink_log_pub, "Connection to parachute lost\t");
events::send(events::ID("commander_parachute_lost"), events::Log::Critical, "Connection to parachute lost");
}
// high latency data link loss failsafe
if (_high_latency_datalink_heartbeat > 0
if ((_high_latency_datalink_heartbeat != 0)
&& hrt_elapsed_time(&_high_latency_datalink_heartbeat) > (_param_com_hldl_loss_t.get() * 1_s)) {
_high_latency_datalink_lost = hrt_absolute_time();
if (!_status.high_latency_data_link_lost) {
@@ -3598,16 +3610,18 @@ void Commander::avoidance_check()
const bool cp_enabled = _param_cp_dist.get() > 0.f;
const bool distance_sensor_valid = hrt_elapsed_time(&_valid_distance_sensor_time_us) < 500_ms;
const bool cp_healthy = _status_flags.avoidance_system_valid || distance_sensor_valid;
const bool cp_healthy = _status_flags.system_valid_obstacle_avoidance || distance_sensor_valid;
const bool sensor_oa_present = cp_healthy || _status_flags.avoidance_system_required || cp_enabled;
const bool sensor_oa_present = cp_healthy || _status_flags.system_required_obstacle_avoidance || cp_enabled;
const bool auto_mode = _vehicle_control_mode.flag_control_auto_enabled;
const bool pos_ctl_mode = (_vehicle_control_mode.flag_control_manual_enabled
&& _vehicle_control_mode.flag_control_position_enabled);
const bool sensor_oa_enabled = ((auto_mode && _status_flags.avoidance_system_required) || (pos_ctl_mode && cp_enabled));
const bool sensor_oa_healthy = ((auto_mode && _status_flags.avoidance_system_valid) || (pos_ctl_mode && cp_healthy));
const bool sensor_oa_enabled = ((auto_mode && _status_flags.system_required_obstacle_avoidance) || (pos_ctl_mode
&& cp_enabled));
const bool sensor_oa_healthy = ((auto_mode && _status_flags.system_valid_obstacle_avoidance) || (pos_ctl_mode
&& cp_healthy));
set_health_flags(subsystem_info_s::SUBSYSTEM_TYPE_OBSTACLE_AVOIDANCE, sensor_oa_present, sensor_oa_enabled,
sensor_oa_healthy, _status);
+2 -5
View File
@@ -196,7 +196,6 @@ private:
(ParamFloat<px4::params::COM_RCL_ACT_T>) _param_com_rcl_act_t,
(ParamInt<px4::params::COM_RCL_EXCEPT>) _param_com_rcl_except,
(ParamBool<px4::params::COM_HOME_EN>) _param_com_home_en,
(ParamFloat<px4::params::COM_HOME_H_T>) _param_com_home_h_t,
(ParamFloat<px4::params::COM_HOME_V_T>) _param_com_home_v_t,
(ParamBool<px4::params::COM_HOME_IN_AIR>) _param_com_home_in_air,
@@ -328,12 +327,10 @@ private:
hrt_abstime _datalink_last_heartbeat_gcs{0};
hrt_abstime _datalink_last_heartbeat_avoidance_system{0};
hrt_abstime _datalink_last_heartbeat_gimbal{0};
hrt_abstime _datalink_last_heartbeat_obstacle_avoidance_system{0};
hrt_abstime _datalink_last_heartbeat_onboard_controller{0};
hrt_abstime _datalink_last_heartbeat_parachute_system{0};
bool _onboard_controller_lost{false};
bool _avoidance_system_lost{false};
bool _parachute_system_lost{true};
hrt_abstime _high_latency_datalink_heartbeat{0};
hrt_abstime _high_latency_datalink_lost{0};
+9 -20
View File
@@ -202,17 +202,6 @@ PARAM_DEFINE_FLOAT(COM_RC_LOSS_T, 0.5f);
*/
PARAM_DEFINE_FLOAT(COM_RCL_ACT_T, 15.0f);
/**
* Home position enabled
*
* Set home position automatically if possible.
*
* @group Commander
* @reboot_required true
* @boolean
*/
PARAM_DEFINE_INT32(COM_HOME_EN, 1);
/**
* Home set horizontal threshold
*
@@ -251,7 +240,7 @@ PARAM_DEFINE_FLOAT(COM_HOME_V_T, 10.0f);
* @boolean
* @group Commander
*/
PARAM_DEFINE_BOOL(COM_HOME_IN_AIR, 0);
PARAM_DEFINE_INT32(COM_HOME_IN_AIR, 0);
/**
* RC control input mode
@@ -323,7 +312,7 @@ PARAM_DEFINE_FLOAT(COM_DISARM_PRFLT, 10.0f);
* @value 0 Require GPS lock to arm
* @value 1 Allow arming without GPS
*/
PARAM_DEFINE_BOOL(COM_ARM_WO_GPS, 1);
PARAM_DEFINE_INT32(COM_ARM_WO_GPS, 1);
/**
* Arm switch is a momentary button
@@ -335,7 +324,7 @@ PARAM_DEFINE_BOOL(COM_ARM_WO_GPS, 1);
* @group Commander
* @boolean
*/
PARAM_DEFINE_BOOL(COM_ARM_SWISBTN, 0);
PARAM_DEFINE_INT32(COM_ARM_SWISBTN, 0);
/**
* Battery failsafe mode
@@ -669,7 +658,7 @@ PARAM_DEFINE_INT32(COM_ARM_MAG_STR, 2);
* @group Commander
* @boolean
*/
PARAM_DEFINE_BOOL(COM_REARM_GRACE, 1);
PARAM_DEFINE_INT32(COM_REARM_GRACE, 1);
/**
* Enable RC stick override of auto and/or offboard modes
@@ -713,7 +702,7 @@ PARAM_DEFINE_FLOAT(COM_RC_STICK_OV, 30.0f);
* @group Commander
* @boolean
*/
PARAM_DEFINE_BOOL(COM_ARM_MIS_REQ, 0);
PARAM_DEFINE_INT32(COM_ARM_MIS_REQ, 0);
/**
* Position control navigation loss response.
@@ -736,7 +725,7 @@ PARAM_DEFINE_INT32(COM_POSCTL_NAVL, 0);
* @group Commander
* @boolean
*/
PARAM_DEFINE_BOOL(COM_ARM_AUTH_REQ, 0);
PARAM_DEFINE_INT32(COM_ARM_AUTH_REQ, 0);
/**
* Arm authorizer system id
@@ -930,7 +919,7 @@ PARAM_DEFINE_INT32(COM_RCL_EXCEPT, 0);
* @boolean
* @group Commander
*/
PARAM_DEFINE_BOOL(COM_OBS_AVOID, 0);
PARAM_DEFINE_INT32(COM_OBS_AVOID, 0);
/**
* Expect and require a healthy MAVLink parachute system
@@ -965,7 +954,7 @@ PARAM_DEFINE_INT32(COM_FLT_PROFILE, 0);
* @group Commander
* @boolean
*/
PARAM_DEFINE_BOOL(COM_ARM_CHK_ESCS, 0);
PARAM_DEFINE_INT32(COM_ARM_CHK_ESCS, 0);
/**
* Condition to enter prearmed mode
@@ -990,7 +979,7 @@ PARAM_DEFINE_INT32(COM_PREARM_MODE, 0);
* @boolean
* @group Commander
*/
PARAM_DEFINE_BOOL(COM_MOT_TEST_EN, 1);
PARAM_DEFINE_INT32(COM_MOT_TEST_EN, 1);
/**
* Timeout value for disarming when kill switch is engaged
@@ -117,7 +117,7 @@ private:
(ParamFloat<px4::params::FD_FAIL_P_TTRI>) _param_fd_fail_p_ttri,
(ParamBool<px4::params::FD_EXT_ATS_EN>) _param_fd_ext_ats_en,
(ParamInt<px4::params::FD_EXT_ATS_TRIG>) _param_fd_ext_ats_trig,
(ParamBool<px4::params::FD_ESCS_EN>) _param_escs_en,
(ParamInt<px4::params::FD_ESCS_EN>) _param_escs_en,
(ParamInt<px4::params::FD_IMB_PROP_THR>) _param_fd_imb_prop_thr
)
};
@@ -116,7 +116,7 @@ PARAM_DEFINE_FLOAT(FD_FAIL_P_TTRI, 0.3);
* @reboot_required true
* @group Failure Detector
*/
PARAM_DEFINE_BOOL(FD_EXT_ATS_EN, 0);
PARAM_DEFINE_INT32(FD_EXT_ATS_EN, 0);
/**
* The PWM threshold from external automatic trigger system for engaging failsafe.
@@ -140,7 +140,7 @@ PARAM_DEFINE_INT32(FD_EXT_ATS_TRIG, 1900);
*
* @group Failure Detector
*/
PARAM_DEFINE_BOOL(FD_ESCS_EN, 1);
PARAM_DEFINE_INT32(FD_ESCS_EN, 1);
/**
* Imbalanced propeller check threshold
+2 -2
View File
@@ -373,8 +373,8 @@ struct parameters {
float is_moving_scaler{1.0f}; ///< gain scaler used to adjust the threshold for the on-ground movement detection. Larger values make the test less sensitive.
// compute synthetic magnetomter Z value if possible
bool synthesize_mag_z{0};
bool check_mag_strength{0};
int32_t synthesize_mag_z{0};
int32_t check_mag_strength{0};
// Parameters used to control when yaw is reset to the EKF-GSF yaw estimator value
float EKFGSF_tas_default{15.0f}; ///< default airspeed value assumed during fixed wing flight if no airspeed measurement available (m/s)
+4 -4
View File
@@ -440,7 +440,7 @@ private:
_param_ekf2_rng_qlty_t, ///< Minimum duration during which the reported range finder signal quality needs to be non-zero in order to be declared valid (s)
// vision estimate fusion
(ParamBool<px4::params::EKF2_EV_NOISE_MD>)
(ParamInt<px4::params::EKF2_EV_NOISE_MD>)
_param_ekf2_ev_noise_md, ///< determine source of vision observation noise
(ParamFloat<px4::params::EKF2_EVP_NOISE>)
_param_ekf2_evp_noise, ///< default position observation noise for exernal vision measurements (m)
@@ -489,7 +489,7 @@ private:
// control of airspeed and sideslip fusion
(ParamExtFloat<px4::params::EKF2_ARSP_THR>)
_param_ekf2_arsp_thr, ///< A value of zero will disabled airspeed fusion. Any positive value sets the minimum airspeed which will be used (m/sec)
(ParamBool<px4::params::EKF2_FUSE_BETA>)
(ParamInt<px4::params::EKF2_FUSE_BETA>)
_param_ekf2_fuse_beta, ///< Controls synthetic sideslip fusion, 0 disables, 1 enables
// output predictor filter time constants
@@ -542,8 +542,8 @@ private:
_param_ekf2_move_test, ///< scaling applied to IMU data thresholds used to determine if the vehicle is static or moving.
(ParamFloat<px4::params::EKF2_REQ_GPS_H>) _param_ekf2_req_gps_h, ///< Required GPS health time
(ParamExtBool<px4::params::EKF2_MAG_CHECK>) _param_ekf2_mag_check, ///< Mag field strength check
(ParamExtBool<px4::params::EKF2_SYNT_MAG_Z>)
(ParamExtInt<px4::params::EKF2_MAG_CHECK>) _param_ekf2_mag_check, ///< Mag field strength check
(ParamExtInt<px4::params::EKF2_SYNT_MAG_Z>)
_param_ekf2_synthetic_mag_z, ///< Enables the use of a synthetic value for the Z axis of the magnetometer calculated from the 3D magnetic field vector at the location of the drone.
// Used by EKF-GSF experimental yaw estimator
+4 -4
View File
@@ -717,7 +717,7 @@ PARAM_DEFINE_FLOAT(EKF2_MIN_RNG, 0.1f);
* @boolean
* @group EKF2
*/
PARAM_DEFINE_BOOL(EKF2_EV_NOISE_MD, 0);
PARAM_DEFINE_INT32(EKF2_EV_NOISE_MD, 0);
/**
* Measurement noise for vision position observations used to lower bound or replace the uncertainty included in the message
@@ -973,7 +973,7 @@ PARAM_DEFINE_FLOAT(EKF2_ARSP_THR, 0.0f);
* @group EKF2
* @boolean
*/
PARAM_DEFINE_BOOL(EKF2_FUSE_BETA, 0);
PARAM_DEFINE_INT32(EKF2_FUSE_BETA, 0);
/**
@@ -1358,7 +1358,7 @@ PARAM_DEFINE_FLOAT(EKF2_REQ_GPS_H, 10.0f);
* @group EKF2
* @boolean
*/
PARAM_DEFINE_BOOL(EKF2_MAG_CHECK, 1);
PARAM_DEFINE_INT32(EKF2_MAG_CHECK, 1);
/**
* Enable synthetic magnetometer Z component measurement.
@@ -1372,7 +1372,7 @@ PARAM_DEFINE_BOOL(EKF2_MAG_CHECK, 1);
* @group EKF2
* @boolean
*/
PARAM_DEFINE_BOOL(EKF2_SYNT_MAG_Z, 0);
PARAM_DEFINE_INT32(EKF2_SYNT_MAG_Z, 0);
/**
* Default value of true airspeed used in EKF-GSF AHRS calculation.
+2 -2
View File
@@ -53,7 +53,7 @@
* @boolean
* @reboot_required true
*/
PARAM_DEFINE_BOOL(EV_TSK_STAT_DIS, 0);
PARAM_DEFINE_INT32(EV_TSK_STAT_DIS, 0);
/**
* RC Loss Alarm
@@ -68,4 +68,4 @@ PARAM_DEFINE_BOOL(EV_TSK_STAT_DIS, 0);
* @boolean
* @reboot_required true
*/
PARAM_DEFINE_BOOL(EV_TSK_RC_LOSS, 0);
PARAM_DEFINE_INT32(EV_TSK_RC_LOSS, 0);
@@ -160,7 +160,7 @@ protected:
(ParamFloat<px4::params::NAV_MC_ALT_RAD>)
_param_nav_mc_alt_rad, //vertical acceptance radius at which waypoints are updated
(ParamInt<px4::params::MPC_YAW_MODE>) _param_mpc_yaw_mode, // defines how heading is executed,
(ParamBool<px4::params::COM_OBS_AVOID>) _param_com_obs_avoid, // obstacle avoidance active
(ParamInt<px4::params::COM_OBS_AVOID>) _param_com_obs_avoid, // obstacle avoidance active
(ParamFloat<px4::params::MPC_YAWRAUTO_MAX>) _param_mpc_yawrauto_max,
(ParamFloat<px4::params::MIS_YAW_ERR>) _param_mis_yaw_err, // yaw-error threshold
(ParamBool<px4::params::WV_EN>) _param_wv_en, // enable/disable weather vane (VTOL)
@@ -159,7 +159,7 @@ private:
(ParamFloat<px4::params::FW_AIRSPD_TRIM>) _param_fw_airspd_trim,
(ParamInt<px4::params::FW_ARSP_MODE>) _param_fw_arsp_mode,
(ParamBool<px4::params::FW_ARSP_SCALE_EN>) _param_fw_arsp_scale_en,
(ParamInt<px4::params::FW_ARSP_SCALE_EN>) _param_fw_arsp_scale_en,
(ParamBool<px4::params::FW_BAT_SCALE_EN>) _param_fw_bat_scale_en,
@@ -293,7 +293,8 @@ PARAM_DEFINE_FLOAT(FW_RLL_TO_YAW_FF, 0.0f);
* @boolean
* @group FW Attitude Control
*/
PARAM_DEFINE_BOOL(FW_W_EN, 0);
PARAM_DEFINE_INT32(FW_W_EN, 0);
/**
* Wheel steering rate proportional gain
@@ -533,7 +534,7 @@ PARAM_DEFINE_INT32(FW_ARSP_MODE, 0);
* @boolean
* @group FW Attitude Control
*/
PARAM_DEFINE_BOOL(FW_ARSP_SCALE_EN, 1);
PARAM_DEFINE_INT32(FW_ARSP_SCALE_EN, 1);
/**
* Manual roll scale
@@ -590,7 +591,7 @@ PARAM_DEFINE_FLOAT(FW_MAN_Y_SC, 1.0f);
* @boolean
* @group FW Attitude Control
*/
PARAM_DEFINE_BOOL(FW_BAT_SCALE_EN, 0);
PARAM_DEFINE_INT32(FW_BAT_SCALE_EN, 0);
/**
* Acro body x max rate.
@@ -56,7 +56,7 @@
* @boolean
* @group Autotune
*/
PARAM_DEFINE_BOOL(FW_AT_START, 0);
PARAM_DEFINE_INT32(FW_AT_START, 0);
/**
* Amplitude of the injected signal
@@ -420,7 +420,7 @@ private:
(ParamFloat<px4::params::FW_THR_MIN>) _param_fw_thr_min,
(ParamFloat<px4::params::FW_THR_SLEW_MAX>) _param_fw_thr_slew_max,
(ParamInt<px4::params::FW_POSCTL_INV_ST>) _param_fw_posctl_inv_st,
(ParamBool<px4::params::FW_POSCTL_INV_ST>) _param_fw_posctl_inv_st,
(ParamInt<px4::params::FW_GPSF_LT>) _param_nav_gpsf_lt,
@@ -342,7 +342,7 @@ PARAM_DEFINE_FLOAT(FW_LND_HHDIST, 15.0f);
* @boolean
* @group FW L1 Control
*/
PARAM_DEFINE_BOOL(FW_LND_USETER, 0);
PARAM_DEFINE_INT32(FW_LND_USETER, 0);
/**
* Early landing configuration deployment
@@ -358,7 +358,7 @@ PARAM_DEFINE_BOOL(FW_LND_USETER, 0);
*
* @group FW L1 Control
*/
PARAM_DEFINE_BOOL(FW_LND_EARLYCFG, 0);
PARAM_DEFINE_INT32(FW_LND_EARLYCFG, 0);
/**
* Flare, minimum pitch
@@ -50,7 +50,7 @@
* @boolean
* @group FW Launch detection
*/
PARAM_DEFINE_BOOL(LAUN_ALL_ON, 0);
PARAM_DEFINE_INT32(LAUN_ALL_ON, 0);
/**
* Catapult accelerometer threshold.
@@ -45,7 +45,7 @@
* @boolean
* @group Runway Takeoff
*/
PARAM_DEFINE_BOOL(RWTO_TKOFF, 0);
PARAM_DEFINE_INT32(RWTO_TKOFF, 0);
/**
* Specifies which heading should be held during runnway takeoff.
+1 -1
View File
@@ -38,4 +38,4 @@
* @reboot_required true
* @group Sensors
*/
PARAM_DEFINE_BOOL(IMU_GYRO_CAL_EN, 1);
PARAM_DEFINE_INT32(IMU_GYRO_CAL_EN, 1);
+1 -1
View File
@@ -38,7 +38,7 @@
* @reboot_required true
* @group Sensors
*/
PARAM_DEFINE_BOOL(IMU_GYRO_FFT_EN, 0);
PARAM_DEFINE_INT32(IMU_GYRO_FFT_EN, 0);
/**
* IMU gyro FFT minimum frequency.
@@ -128,7 +128,7 @@ void MulticopterLandDetector::_update_params()
_param_lndmc_z_vel_max.commit_no_notification();
}
bool use_hover_thrust_estimate = false;
int32_t use_hover_thrust_estimate = 0;
param_get(_paramHandle.useHoverThrustEstimate, &use_hover_thrust_estimate);
_params.useHoverThrustEstimate = (use_hover_thrust_estimate == 1);
+1 -1
View File
@@ -37,4 +37,4 @@
* @boolean
* @group System
*/
PARAM_DEFINE_BOOL(SYS_STCK_EN, 1);
PARAM_DEFINE_INT32(SYS_STCK_EN, 1);

Some files were not shown because too many files have changed in this diff Show More