mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-06-18 05:51:28 +08:00
Compare commits
7 Commits
pr-replay_
...
pr-uorb_qu
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
f8a8675e2d | ||
|
|
600b0e6704 | ||
|
|
dd67766f6c | ||
|
|
4a043a80f1 | ||
|
|
bb617a1a56 | ||
|
|
01de368616 | ||
|
|
76352765b6 |
@ -813,6 +813,7 @@ void printTopics() {
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener commander_state" || true'
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener cpuload" || true'
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener distance_sensor" || true'
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener ekf2_timestamps" || true'
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener esc_status" || true'
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener estimator_aid_src_fake_pos" || true'
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener estimator_aid_src_gnss_pos" || true'
|
||||
|
||||
7
Makefile
7
Makefile
@ -122,6 +122,13 @@ endif
|
||||
|
||||
SRC_DIR := $(shell dirname "$(realpath $(lastword $(MAKEFILE_LIST)))")
|
||||
|
||||
# check if replay env variable is set & set build dir accordingly
|
||||
ifdef replay
|
||||
BUILD_DIR_SUFFIX := _replay
|
||||
else
|
||||
BUILD_DIR_SUFFIX :=
|
||||
endif
|
||||
|
||||
CMAKE_ARGS ?=
|
||||
|
||||
# additional config parameters passed to cmake
|
||||
|
||||
@ -37,12 +37,6 @@ px4_add_romfs_files(
|
||||
px4-rc.mavlink
|
||||
px4-rc.params
|
||||
px4-rc.simulator
|
||||
|
||||
rc.replay_ekf2
|
||||
rc.replay_mc_hover_thrust_estimator
|
||||
rc.replay_mixing
|
||||
rc.replay_sensor_calibration
|
||||
rc.replay_sensor_filtering
|
||||
|
||||
rc.replay
|
||||
rcS
|
||||
)
|
||||
|
||||
@ -6,36 +6,35 @@ param set-default IMU_INTEG_RATE 250
|
||||
|
||||
if [ "$PX4_SIMULATOR" = "sihsim" ] || [ "$(param show -q SYS_AUTOSTART)" -eq "0" ]; then
|
||||
|
||||
|
||||
echo "INFO [init] SIH simulator"
|
||||
|
||||
# if [ -n "${PX4_HOME_LAT}" ]; then
|
||||
# param set SIH_LOC_LAT0 ${PX4_HOME_LAT}
|
||||
# fi
|
||||
if [ -n "${PX4_HOME_LAT}" ]; then
|
||||
param set SIH_LOC_LAT0 ${PX4_HOME_LAT}
|
||||
fi
|
||||
|
||||
# if [ -n "${PX4_HOME_LON}" ]; then
|
||||
# param set SIH_LOC_LON0 ${PX4_HOME_LON}
|
||||
# fi
|
||||
if [ -n "${PX4_HOME_LON}" ]; then
|
||||
param set SIH_LOC_LON0 ${PX4_HOME_LON}
|
||||
fi
|
||||
|
||||
# if simulator_sih start; then
|
||||
if simulator_sih start; then
|
||||
|
||||
# if param compare -s SENS_EN_BAROSIM 1
|
||||
# then
|
||||
# sensor_baro_sim start
|
||||
# fi
|
||||
# if param compare -s SENS_EN_GPSSIM 1
|
||||
# then
|
||||
# sensor_gps_sim start
|
||||
# fi
|
||||
# if param compare -s SENS_EN_MAGSIM 1
|
||||
# then
|
||||
# sensor_mag_sim start
|
||||
# fi
|
||||
if param compare -s SENS_EN_BAROSIM 1
|
||||
then
|
||||
sensor_baro_sim start
|
||||
fi
|
||||
if param compare -s SENS_EN_GPSSIM 1
|
||||
then
|
||||
sensor_gps_sim start
|
||||
fi
|
||||
if param compare -s SENS_EN_MAGSIM 1
|
||||
then
|
||||
sensor_mag_sim start
|
||||
fi
|
||||
|
||||
# else
|
||||
# echo "ERROR [init] simulator_sih failed to start"
|
||||
# exit 1
|
||||
# fi
|
||||
else
|
||||
echo "ERROR [init] simulator_sih failed to start"
|
||||
exit 1
|
||||
fi
|
||||
|
||||
elif [ "$PX4_SIMULATOR" = "gz" ] || [ "$(param show -q SIM_GZ_EN)" = "1" ]; then
|
||||
# Use Gazebo
|
||||
@ -191,7 +190,7 @@ else
|
||||
|
||||
else
|
||||
echo "INFO [init] PX4_SIM_HOSTNAME: ${PX4_SIM_HOSTNAME}"
|
||||
#simulator_mavlink start -h "${PX4_SIM_HOSTNAME}" "${simulator_tcp_port}"
|
||||
simulator_mavlink start -h "${PX4_SIM_HOSTNAME}" "${simulator_tcp_port}"
|
||||
fi
|
||||
|
||||
fi
|
||||
|
||||
@ -13,14 +13,18 @@ if [ ! -f replay_params.txt ]; then
|
||||
ulog_params -i "${replay}" -l ' ' | grep -e '^EKF2' > replay_params.txt
|
||||
fi
|
||||
|
||||
param set SDLOG_DIRS_MAX 7
|
||||
publisher_rules_file="orb_publisher.rules"
|
||||
cat <<EOF > "$publisher_rules_file"
|
||||
restrict_topics: sensor_combined, vehicle_gps_position, vehicle_land_detected
|
||||
module: replay
|
||||
ignore_others: false
|
||||
EOF
|
||||
|
||||
# TODO:
|
||||
# input: vehicle_local_position, vehicle_local_position_setpoint
|
||||
# output: hover_thrust_estimate
|
||||
param set SDLOG_DIRS_MAX 7
|
||||
param set SDLOG_PROFILE 3
|
||||
|
||||
# apply all params before ekf starts, as some params cannot be changed after startup
|
||||
#replay tryapplyparams
|
||||
mc_hover_thrust_estimator start
|
||||
replay tryapplyparams
|
||||
ekf2 start -r
|
||||
logger start -f -t -b 1000 -p vehicle_attitude
|
||||
replay start
|
||||
@ -1,54 +0,0 @@
|
||||
#!/bin/sh
|
||||
|
||||
# EKF2 replay script
|
||||
|
||||
# shellcheck disable=SC2154
|
||||
if [ ! -f ${replay_file} ]; then
|
||||
echo "Invalid replay log file ${replay}"
|
||||
exit 1
|
||||
fi
|
||||
|
||||
echo "replay file: ${replay_file}"
|
||||
|
||||
if [ ! -f replay_params.txt ]; then
|
||||
echo "Creating $(pwd)/replay_params.txt"
|
||||
ulog_params -i "${replay_file}" -l ' ' | grep -e '^EKF2' > replay_params.txt
|
||||
fi
|
||||
|
||||
param set SDLOG_DIRS_MAX 7
|
||||
|
||||
# TODO:
|
||||
# input: vehicle_imu, vehicle_magnetometer, distance_sensor
|
||||
# output: estimator_status
|
||||
|
||||
|
||||
# replay start --ignore=estimator_status,
|
||||
# TODO: replay file?
|
||||
|
||||
# apply all params before ekf starts, as some params cannot be changed after startup
|
||||
replay tryapplyparams
|
||||
|
||||
#param set SENS_IMU_MODE 0
|
||||
#param set EKF2_MULTI_IMU 3
|
||||
|
||||
ekf2 start &
|
||||
ekf2 status
|
||||
logger start -f -t -b 1000 -p vehicle_attitude
|
||||
logger status
|
||||
replay start
|
||||
|
||||
# ekf2 status
|
||||
# logger status
|
||||
# logger stop
|
||||
|
||||
# TODO: easy debug from gdb (and vscode)
|
||||
# TODO
|
||||
# loop through parameter changes? (noise, sensor delays, etc)
|
||||
# - create log files with appropriate names (logger custom logfile name?)
|
||||
|
||||
# TODO
|
||||
# - work queue lockstep handling
|
||||
# - parameter defaults
|
||||
# - progress (percentage, time in seconds, etc)
|
||||
# - realtime vs execute as fast as possible
|
||||
# - controls (pause, reset, etc)
|
||||
@ -1,29 +0,0 @@
|
||||
#!/bin/sh
|
||||
|
||||
# EKF2 replay script
|
||||
|
||||
# shellcheck disable=SC2154
|
||||
if [ ! -f ${replay} ]; then
|
||||
echo "Invalid replay log file ${replay}"
|
||||
exit 1
|
||||
fi
|
||||
|
||||
if [ ! -f replay_params.txt ]; then
|
||||
echo "Creating $(pwd)/replay_params.txt"
|
||||
ulog_params -i "${replay}" -l ' ' | grep -e '^EKF2' > replay_params.txt
|
||||
fi
|
||||
|
||||
param set SDLOG_DIRS_MAX 7
|
||||
|
||||
# TODO:
|
||||
# input: actuator_controls_0
|
||||
# output:
|
||||
|
||||
# apply all params before ekf starts, as some params cannot be changed after startup
|
||||
#replay tryapplyparams
|
||||
|
||||
pwm_out_sim start
|
||||
mixer load /dev/pwm_output0 etc/mixers/quad_x.main.mix
|
||||
|
||||
logger start -f -t -b 1000 -p vehicle_attitude
|
||||
replay start
|
||||
@ -1,30 +0,0 @@
|
||||
#!/bin/sh
|
||||
|
||||
# EKF2 replay script
|
||||
|
||||
# shellcheck disable=SC2154
|
||||
if [ ! -f ${replay} ]; then
|
||||
echo "Invalid replay log file ${replay}"
|
||||
exit 1
|
||||
fi
|
||||
|
||||
if [ ! -f replay_params.txt ]; then
|
||||
echo "Creating $(pwd)/replay_params.txt"
|
||||
ulog_params -i "${replay}" -l ' ' | grep -e '^EKF2' > replay_params.txt
|
||||
fi
|
||||
|
||||
param set SDLOG_DIRS_MAX 7
|
||||
|
||||
# TODO:
|
||||
# input: sensor_accel, sensor_gyro, sensor_mag, ?
|
||||
# output: mag_worker_data
|
||||
|
||||
# apply all params before ekf starts, as some params cannot be changed after startup
|
||||
#replay tryapplyparams
|
||||
|
||||
commander start
|
||||
gyro_calibration start
|
||||
temperature_compensatoin start
|
||||
|
||||
logger start -f -t -b 1000 -p vehicle_attitude
|
||||
replay start
|
||||
@ -1,28 +0,0 @@
|
||||
#!/bin/sh
|
||||
|
||||
# EKF2 replay script
|
||||
|
||||
# shellcheck disable=SC2154
|
||||
if [ ! -f ${replay} ]; then
|
||||
echo "Invalid replay log file ${replay}"
|
||||
exit 1
|
||||
fi
|
||||
|
||||
if [ ! -f replay_params.txt ]; then
|
||||
echo "Creating $(pwd)/replay_params.txt"
|
||||
ulog_params -i "${replay}" -l ' ' | grep -e '^EKF2' > replay_params.txt
|
||||
fi
|
||||
|
||||
param set SDLOG_DIRS_MAX 7
|
||||
|
||||
# TODO:
|
||||
# input: sensor_accel, sensor_gyro, sensor_mag, ?
|
||||
# output: mag_worker_data
|
||||
|
||||
# apply all params before ekf starts, as some params cannot be changed after startup
|
||||
#replay tryapplyparams
|
||||
|
||||
sensors start
|
||||
|
||||
logger start -f -t -b 1000 -p vehicle_angular_velocity
|
||||
replay start
|
||||
@ -17,10 +17,11 @@ PATH="$PATH:${R}etc/init.d-posix"
|
||||
# Main SITL startup script
|
||||
#
|
||||
|
||||
# check for replay
|
||||
if [ ! -z ${replay_mode+x} ]; then
|
||||
echo "Replay Mode: ${replay_mode}"
|
||||
. ${R}etc/init.d-posix/rc.replay_${replay_mode}
|
||||
# check for ekf2 replay
|
||||
# shellcheck disable=SC2154
|
||||
if [ "$replay_mode" = "ekf2" ]
|
||||
then
|
||||
. ${R}etc/init.d-posix/rc.replay
|
||||
exit 0
|
||||
fi
|
||||
|
||||
@ -329,7 +330,12 @@ fi
|
||||
[ -e "$autostart_file".post ] && . "$autostart_file".post
|
||||
|
||||
# Run script to start logging
|
||||
set LOGGER_ARGS "-p vehicle_attitude"
|
||||
if param compare SYS_MC_EST_GROUP 2
|
||||
then
|
||||
set LOGGER_ARGS "-p ekf2_timestamps"
|
||||
else
|
||||
set LOGGER_ARGS "-p vehicle_attitude"
|
||||
fi
|
||||
. ${R}etc/init.d/rc.logging
|
||||
|
||||
mavlink boot_complete
|
||||
|
||||
@ -4,7 +4,7 @@
|
||||
"description": "Firmware for the ARK flow board",
|
||||
"image": "",
|
||||
"build_time": 0,
|
||||
"summary": "ARKFLOW",
|
||||
"summary": "ARFFLOW",
|
||||
"version": "0.1",
|
||||
"image_size": 0,
|
||||
"image_maxsize": 2080768,
|
||||
|
||||
@ -20,7 +20,6 @@ CONFIG_UAVCANNODE_RTK_DATA=y
|
||||
CONFIG_UAVCANNODE_SAFETY_BUTTON=y
|
||||
CONFIG_UAVCANNODE_STATIC_PRESSURE=y
|
||||
CONFIG_UAVCANNODE_STATIC_TEMPERATURE=y
|
||||
CONFIG_MODULES_EKF2=y
|
||||
CONFIG_MODULES_GYRO_CALIBRATION=y
|
||||
CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y
|
||||
CONFIG_MODULES_SENSORS=y
|
||||
|
||||
@ -11,5 +11,3 @@ param set-default SENS_IMU_CLPNOTI 0
|
||||
|
||||
safety_button start
|
||||
tone_alarm start
|
||||
|
||||
ekf2 start
|
||||
|
||||
@ -50,7 +50,6 @@ CONFIG_STACK_COLORATION=y
|
||||
CONFIG_START_DAY=30
|
||||
CONFIG_START_MONTH=11
|
||||
CONFIG_STDIO_DISABLE_BUFFERING=y
|
||||
CONFIG_STM32_FLASH_CONFIG_G=y
|
||||
CONFIG_STM32_NOEXT_VECTORS=y
|
||||
CONFIG_STM32_TIM8=y
|
||||
CONFIG_TASK_NAME_SIZE=0
|
||||
|
||||
@ -123,7 +123,6 @@ CONFIG_STM32_ADC1=y
|
||||
CONFIG_STM32_DISABLE_IDLE_SLEEP_DURING_DEBUG=y
|
||||
CONFIG_STM32_DMA1=y
|
||||
CONFIG_STM32_DMA2=y
|
||||
CONFIG_STM32_FLASH_CONFIG_G=y
|
||||
CONFIG_STM32_FLASH_PREFETCH=y
|
||||
CONFIG_STM32_FLOWCONTROL_BROKEN=y
|
||||
CONFIG_STM32_I2C1=y
|
||||
|
||||
@ -33,7 +33,7 @@
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/* The STM32F412 has 1M of FLASH beginning at address 0x0800:0000 and
|
||||
/* The STM32F412 has 512Kb of FLASH beginning at address 0x0800:0000 and
|
||||
* 256Kb of SRAM. SRAM is split up into three blocks:
|
||||
*
|
||||
* 1) 112Kb of SRAM beginning at address 0x2000:0000
|
||||
|
||||
@ -33,7 +33,7 @@
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/* The STM32F412 has 1M of FLASH beginning at address 0x0800:0000 and
|
||||
/* The STM32F412 has 512Kb of FLASH beginning at address 0x0800:0000 and
|
||||
* 256Kb of SRAM. SRAM is split up into three blocks:
|
||||
*
|
||||
* 1) 112Kb of SRAM beginning at address 0x2000:0000
|
||||
|
||||
@ -30,4 +30,3 @@ CONFIG_MODULES_SIMULATION_PWM_OUT_SIM=y
|
||||
CONFIG_SYSTEMCMDS_UORB=y
|
||||
CONFIG_SYSTEMCMDS_PARAM=y
|
||||
CONFIG_ORB_COMMUNICATOR=y
|
||||
CONFIG_PARAM_REMOTE=y
|
||||
|
||||
@ -62,8 +62,6 @@
|
||||
#include <uORB/topics/vehicle_odometry.h>
|
||||
#include <uORB/topics/sensor_baro.h>
|
||||
#include <uORB/topics/esc_status.h>
|
||||
#include <uORB/topics/distance_sensor.h>
|
||||
#include <uORB/topics/sensor_optical_flow.h>
|
||||
|
||||
#include <lib/drivers/accelerometer/PX4Accelerometer.hpp>
|
||||
#include <lib/drivers/gyroscope/PX4Gyroscope.hpp>
|
||||
@ -90,22 +88,21 @@ static bool _is_running = false;
|
||||
volatile bool _task_should_exit = false;
|
||||
static px4_task_t _task_handle = -1;
|
||||
int _uart_fd = -1;
|
||||
bool _debug = false;
|
||||
bool debug = false;
|
||||
std::string port = "2";
|
||||
int baudrate = 921600;
|
||||
const unsigned mode_flag_custom = 1;
|
||||
const unsigned mode_flag_armed = 128;
|
||||
bool _send_gps = false;
|
||||
bool _send_mag = false;
|
||||
bool _send_distance = false;
|
||||
|
||||
uORB::Publication<battery_status_s> _battery_pub{ORB_ID(battery_status)};
|
||||
uORB::PublicationMulti<sensor_gps_s> _sensor_gps_pub{ORB_ID(sensor_gps)};
|
||||
uORB::Publication<differential_pressure_s> _differential_pressure_pub{ORB_ID(differential_pressure)};
|
||||
uORB::Publication<vehicle_odometry_s> _visual_odometry_pub{ORB_ID(vehicle_visual_odometry)};
|
||||
uORB::Publication<vehicle_odometry_s> _mocap_odometry_pub{ORB_ID(vehicle_mocap_odometry)};
|
||||
uORB::PublicationMulti<sensor_baro_s> _sensor_baro_pub{ORB_ID(sensor_baro)};
|
||||
uORB::Publication<esc_status_s> _esc_status_pub{ORB_ID(esc_status)};
|
||||
uORB::Publication<distance_sensor_s> _distance_sensor_pub{ORB_ID(distance_sensor)};
|
||||
uORB::Publication<sensor_optical_flow_s> _sensor_optical_flow_pub{ORB_ID(sensor_optical_flow)};
|
||||
uORB::Subscription _battery_status_sub{ORB_ID(battery_status)};
|
||||
|
||||
int32_t _output_functions[actuator_outputs_s::NUM_ACTUATOR_OUTPUTS] {};
|
||||
@ -131,42 +128,13 @@ float x_gyro = 0;
|
||||
float y_gyro = 0;
|
||||
float z_gyro = 0;
|
||||
uint64_t gyro_accel_time = 0;
|
||||
bool _use_software_mav_throttling{false};
|
||||
|
||||
// Status counters
|
||||
uint32_t heartbeat_received_counter = 0;
|
||||
uint32_t heartbeat_sent_counter = 0;
|
||||
uint32_t imu_counter = 0;
|
||||
uint32_t hil_sensor_counter = 0;
|
||||
uint32_t mag_counter = 0;
|
||||
uint32_t baro_counter = 0;
|
||||
uint32_t actuator_sent_counter = 0;
|
||||
uint32_t odometry_received_counter = 0;
|
||||
uint32_t odometry_sent_counter = 0;
|
||||
uint32_t gps_received_counter = 0;
|
||||
uint32_t gps_sent_counter = 0;
|
||||
uint32_t distance_received_counter = 0;
|
||||
uint32_t distance_sent_counter = 0;
|
||||
uint32_t flow_received_counter = 0;
|
||||
uint32_t flow_sent_counter = 0;
|
||||
uint32_t unknown_msg_received_counter = 0;
|
||||
|
||||
enum class position_source {GPS, VIO, FLOW, NUM_POSITION_SOURCES};
|
||||
|
||||
struct position_source_data_s {
|
||||
char label[8];
|
||||
bool send;
|
||||
bool fail;
|
||||
uint32_t failure_duration;
|
||||
uint64_t failure_duration_start;
|
||||
} position_source_data[(int) position_source::NUM_POSITION_SOURCES] = {
|
||||
{"GPS", false, false, 0, 0},
|
||||
{"VIO", false, false, 0, 0},
|
||||
{"FLOW", false, false, 0, 0}
|
||||
};
|
||||
|
||||
uint64_t first_sensor_msg_timestamp = 0;
|
||||
uint64_t first_sensor_report_timestamp = 0;
|
||||
uint64_t last_sensor_report_timestamp = 0;
|
||||
int heartbeat_counter = 0;
|
||||
int imu_counter = 0;
|
||||
int hil_sensor_counter = 0;
|
||||
int vision_msg_counter = 0;
|
||||
int gps_counter = 0;
|
||||
|
||||
vehicle_status_s _vehicle_status{};
|
||||
vehicle_control_mode_s _control_mode{};
|
||||
@ -176,6 +144,7 @@ battery_status_s _battery_status{};
|
||||
sensor_accel_fifo_s accel_fifo{};
|
||||
sensor_gyro_fifo_s gyro_fifo{};
|
||||
|
||||
|
||||
int openPort(const char *dev, speed_t speed);
|
||||
int closePort();
|
||||
|
||||
@ -184,8 +153,7 @@ int writeResponse(void *buf, size_t len);
|
||||
|
||||
int start(int argc, char *argv[]);
|
||||
int stop();
|
||||
void print_status();
|
||||
void clear_status_counters();
|
||||
int get_status();
|
||||
bool isOpen() { return _uart_fd >= 0; };
|
||||
|
||||
void usage();
|
||||
@ -195,65 +163,50 @@ void *send_actuator(void *);
|
||||
void send_actuator_data();
|
||||
|
||||
void handle_message_hil_sensor_dsp(mavlink_message_t *msg);
|
||||
void handle_message_hil_optical_flow(mavlink_message_t *msg);
|
||||
void handle_message_distance_sensor(mavlink_message_t *msg);
|
||||
void handle_message_hil_gps_dsp(mavlink_message_t *msg);
|
||||
void handle_message_odometry_dsp(mavlink_message_t *msg);
|
||||
void handle_message_vision_position_estimate_dsp(mavlink_message_t *msg);
|
||||
void handle_message_command_long_dsp(mavlink_message_t *msg);
|
||||
|
||||
void handle_message_dsp(mavlink_message_t *msg);
|
||||
void actuator_controls_from_outputs_dsp(mavlink_hil_actuator_controls_t *msg);
|
||||
void send_esc_status(mavlink_hil_actuator_controls_t hil_act_control);
|
||||
void send_esc_telemetry_dsp(mavlink_hil_actuator_controls_t hil_act_control);
|
||||
|
||||
void
|
||||
handle_message_dsp(mavlink_message_t *msg)
|
||||
{
|
||||
switch (msg->msgid) {
|
||||
case MAVLINK_MSG_ID_HIL_SENSOR:
|
||||
hil_sensor_counter++;
|
||||
handle_message_hil_sensor_dsp(msg);
|
||||
break;
|
||||
|
||||
case MAVLINK_MSG_ID_HIL_GPS:
|
||||
gps_received_counter++;
|
||||
if (_send_gps) { handle_message_hil_gps_dsp(msg); }
|
||||
|
||||
if (position_source_data[(int) position_source::GPS].send) { handle_message_hil_gps_dsp(msg); }
|
||||
break;
|
||||
|
||||
case MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE:
|
||||
handle_message_vision_position_estimate_dsp(msg);
|
||||
break;
|
||||
|
||||
case MAVLINK_MSG_ID_ODOMETRY:
|
||||
odometry_received_counter++;
|
||||
|
||||
if (position_source_data[(int) position_source::VIO].send) { handle_message_odometry_dsp(msg); }
|
||||
handle_message_odometry_dsp(msg);
|
||||
break;
|
||||
|
||||
case MAVLINK_MSG_ID_COMMAND_LONG:
|
||||
handle_message_command_long_dsp(msg);
|
||||
break;
|
||||
|
||||
case MAVLINK_MSG_ID_HEARTBEAT:
|
||||
heartbeat_received_counter++;
|
||||
|
||||
if (_debug) { PX4_INFO("Heartbeat msg received"); }
|
||||
|
||||
PX4_DEBUG("Heartbeat msg received");
|
||||
break;
|
||||
|
||||
case MAVLINK_MSG_ID_HIL_OPTICAL_FLOW:
|
||||
flow_received_counter++;
|
||||
|
||||
if (position_source_data[(int) position_source::FLOW].send) { handle_message_hil_optical_flow(msg); }
|
||||
|
||||
break;
|
||||
|
||||
case MAVLINK_MSG_ID_DISTANCE_SENSOR:
|
||||
distance_received_counter++;
|
||||
|
||||
if (_send_distance) { handle_message_distance_sensor(msg); }
|
||||
|
||||
case MAVLINK_MSG_ID_SYSTEM_TIME:
|
||||
PX4_DEBUG("MAVLINK SYSTEM TIME");
|
||||
break;
|
||||
|
||||
default:
|
||||
unknown_msg_received_counter++;
|
||||
|
||||
if (_debug) { PX4_INFO("Unknown msg ID: %d", msg->msgid); }
|
||||
|
||||
PX4_DEBUG("Unknown msg ID: %d", msg->msgid);
|
||||
break;
|
||||
}
|
||||
}
|
||||
@ -275,6 +228,7 @@ void send_actuator_data()
|
||||
bool first_sent = false;
|
||||
|
||||
while (true) {
|
||||
|
||||
bool controls_updated = false;
|
||||
(void) orb_check(_vehicle_control_mode_sub_, &controls_updated);
|
||||
|
||||
@ -285,50 +239,45 @@ void send_actuator_data()
|
||||
bool actuator_updated = false;
|
||||
(void) orb_check(_actuator_outputs_sub, &actuator_updated);
|
||||
|
||||
uint8_t newBuf[512];
|
||||
uint16_t newBufLen = 0;
|
||||
|
||||
mavlink_hil_actuator_controls_t hil_act_control;
|
||||
actuator_controls_from_outputs_dsp(&hil_act_control);
|
||||
|
||||
mavlink_message_t message{};
|
||||
mavlink_msg_hil_actuator_controls_encode(1, 1, &message, &hil_act_control);
|
||||
|
||||
if (actuator_updated) {
|
||||
orb_copy(ORB_ID(actuator_outputs), _actuator_outputs_sub, &_actuator_outputs);
|
||||
px4_lockstep_wait_for_components();
|
||||
|
||||
if (_actuator_outputs.timestamp > 0) {
|
||||
mavlink_hil_actuator_controls_t hil_act_control;
|
||||
actuator_controls_from_outputs_dsp(&hil_act_control);
|
||||
|
||||
mavlink_message_t message{};
|
||||
mavlink_msg_hil_actuator_controls_encode(1, 1, &message, &hil_act_control);
|
||||
previous_timestamp = _actuator_outputs.timestamp;
|
||||
previous_uorb_timestamp = _actuator_outputs.timestamp;
|
||||
|
||||
uint8_t newBuf[512];
|
||||
uint16_t newBufLen = 0;
|
||||
newBufLen = mavlink_msg_to_send_buffer(newBuf, &message);
|
||||
int writeRetval = writeResponse(&newBuf, newBufLen);
|
||||
|
||||
actuator_sent_counter++;
|
||||
|
||||
if (_debug) { PX4_INFO("Succesful write of actuator back to jMAVSim: %d at %llu", writeRetval, hrt_absolute_time()); }
|
||||
|
||||
PX4_DEBUG("Succesful write of actuator back to jMAVSim: %d at %llu", writeRetval, hrt_absolute_time());
|
||||
first_sent = true;
|
||||
|
||||
send_esc_status(hil_act_control);
|
||||
send_esc_telemetry_dsp(hil_act_control);
|
||||
}
|
||||
|
||||
} else if (! actuator_updated && first_sent && differential > 4000) {
|
||||
} else if (!actuator_updated && first_sent && differential > 4000) {
|
||||
mavlink_hil_actuator_controls_t hil_act_control;
|
||||
actuator_controls_from_outputs_dsp(&hil_act_control);
|
||||
previous_timestamp = hrt_absolute_time();
|
||||
|
||||
mavlink_message_t message{};
|
||||
mavlink_msg_hil_actuator_controls_encode(1, 1, &message, &hil_act_control);
|
||||
uint8_t newBuf[512];
|
||||
uint16_t newBufLen = 0;
|
||||
newBufLen = mavlink_msg_to_send_buffer(newBuf, &message);
|
||||
int writeRetval = writeResponse(&newBuf, newBufLen);
|
||||
//PX4_INFO("Sending from NOT UPDTE AND TIMEOUT: %i", differential);
|
||||
|
||||
actuator_sent_counter++;
|
||||
|
||||
if (_debug) { PX4_INFO("Succesful write of actuator back to jMAVSim: %d at %llu", writeRetval, hrt_absolute_time()); }
|
||||
|
||||
send_esc_status(hil_act_control);
|
||||
PX4_DEBUG("Succesful write of actuator back to jMAVSim: %d at %llu", writeRetval, hrt_absolute_time());
|
||||
send_esc_telemetry_dsp(hil_act_control);
|
||||
}
|
||||
|
||||
differential = hrt_absolute_time() - previous_timestamp;
|
||||
|
||||
px4_usleep(1000);
|
||||
}
|
||||
}
|
||||
|
||||
@ -338,10 +287,14 @@ void task_main(int argc, char *argv[])
|
||||
int myoptind = 1;
|
||||
const char *myoptarg = nullptr;
|
||||
|
||||
while ((ch = px4_getopt(argc, argv, "odmghfp:b:", &myoptind, &myoptarg)) != EOF) {
|
||||
while ((ch = px4_getopt(argc, argv, "vsdcmgp:b:", &myoptind, &myoptarg)) != EOF) {
|
||||
switch (ch) {
|
||||
case 's':
|
||||
_use_software_mav_throttling = true;
|
||||
break;
|
||||
|
||||
case 'd':
|
||||
_debug = true;
|
||||
debug = true;
|
||||
break;
|
||||
|
||||
case 'p':
|
||||
@ -357,19 +310,7 @@ void task_main(int argc, char *argv[])
|
||||
break;
|
||||
|
||||
case 'g':
|
||||
position_source_data[(int) position_source::GPS].send = true;
|
||||
break;
|
||||
|
||||
case 'o':
|
||||
position_source_data[(int) position_source::VIO].send = true;
|
||||
break;
|
||||
|
||||
case 'h':
|
||||
_send_distance = true;
|
||||
break;
|
||||
|
||||
case 'f':
|
||||
position_source_data[(int) position_source::FLOW].send = true;
|
||||
_send_gps = true;
|
||||
break;
|
||||
|
||||
default:
|
||||
@ -378,13 +319,11 @@ void task_main(int argc, char *argv[])
|
||||
}
|
||||
|
||||
const char *charport = port.c_str();
|
||||
(void) openPort(charport, (speed_t) baudrate);
|
||||
int openRetval = openPort(charport, (speed_t) baudrate);
|
||||
int open = isOpen();
|
||||
|
||||
if ((_debug) && (isOpen())) { PX4_INFO("DSP HITL serial port initialized. Baudrate: %d", baudrate); }
|
||||
|
||||
if (! isOpen()) {
|
||||
PX4_ERR("DSP HITL failed to open serial port");
|
||||
return;
|
||||
if (open) {
|
||||
PX4_ERR("Port is open: %d", openRetval);
|
||||
}
|
||||
|
||||
uint64_t last_heartbeat_timestamp = hrt_absolute_time();
|
||||
@ -403,11 +342,14 @@ void task_main(int argc, char *argv[])
|
||||
pthread_attr_destroy(&sender_thread_attr);
|
||||
|
||||
int _vehicle_status_sub = orb_subscribe(ORB_ID(vehicle_status));
|
||||
PX4_INFO("Got %d from orb_subscribe", _vehicle_status_sub);
|
||||
|
||||
_is_running = true;
|
||||
|
||||
while (!_task_should_exit) {
|
||||
|
||||
uint8_t rx_buf[1024];
|
||||
//rx_buf[511] = '\0';
|
||||
|
||||
uint64_t timestamp = hrt_absolute_time();
|
||||
|
||||
@ -415,8 +357,8 @@ void task_main(int argc, char *argv[])
|
||||
if (got_first_sensor_msg) {
|
||||
uint64_t delta_time = timestamp - last_imu_update_timestamp;
|
||||
|
||||
if ((imu_counter) && (delta_time > 15000)) {
|
||||
PX4_WARN("Sending updates at %llu, delta %llu", timestamp, delta_time);
|
||||
if (delta_time > 15000) {
|
||||
PX4_ERR("Sending updates at %llu, delta %llu", timestamp, delta_time);
|
||||
}
|
||||
|
||||
uint64_t _px4_gyro_accel_timestamp = hrt_absolute_time();
|
||||
@ -454,7 +396,7 @@ void task_main(int argc, char *argv[])
|
||||
hb_newBufLen = mavlink_msg_to_send_buffer(hb_newBuf, &hb_message);
|
||||
(void) writeResponse(&hb_newBuf, hb_newBufLen);
|
||||
last_heartbeat_timestamp = timestamp;
|
||||
heartbeat_sent_counter++;
|
||||
heartbeat_counter++;
|
||||
}
|
||||
|
||||
bool vehicle_updated = false;
|
||||
@ -474,7 +416,7 @@ void task_main(int argc, char *argv[])
|
||||
_is_running = false;
|
||||
}
|
||||
|
||||
void send_esc_status(mavlink_hil_actuator_controls_t hil_act_control)
|
||||
void send_esc_telemetry_dsp(mavlink_hil_actuator_controls_t hil_act_control)
|
||||
{
|
||||
esc_status_s esc_status{};
|
||||
esc_status.timestamp = hrt_absolute_time();
|
||||
@ -506,13 +448,17 @@ void send_esc_status(mavlink_hil_actuator_controls_t hil_act_control)
|
||||
_esc_status_pub.publish(esc_status);
|
||||
}
|
||||
|
||||
|
||||
void
|
||||
handle_message_command_long_dsp(mavlink_message_t *msg)
|
||||
{
|
||||
/* command */
|
||||
mavlink_command_long_t cmd_mavlink;
|
||||
mavlink_msg_command_long_decode(msg, &cmd_mavlink);
|
||||
|
||||
if (_debug) { PX4_INFO("Value of command_long.command: %d", cmd_mavlink.command); }
|
||||
if (debug) {
|
||||
PX4_INFO("Value of command_long.command: %d", cmd_mavlink.command);
|
||||
}
|
||||
|
||||
mavlink_command_ack_t ack = {};
|
||||
ack.result = MAV_RESULT_UNSUPPORTED;
|
||||
@ -524,140 +470,46 @@ handle_message_command_long_dsp(mavlink_message_t *msg)
|
||||
uint16_t acknewBufLen = 0;
|
||||
acknewBufLen = mavlink_msg_to_send_buffer(acknewBuf, &ack_message);
|
||||
int writeRetval = writeResponse(&acknewBuf, acknewBufLen);
|
||||
|
||||
if (_debug) { PX4_INFO("Succesful write of ACK back over UART: %d at %llu", writeRetval, hrt_absolute_time()); }
|
||||
PX4_INFO("Succesful write of ACK back over UART: %d at %llu", writeRetval, hrt_absolute_time());
|
||||
}
|
||||
|
||||
int flow_debug_counter = 0;
|
||||
|
||||
void
|
||||
handle_message_hil_optical_flow(mavlink_message_t *msg)
|
||||
handle_message_vision_position_estimate_dsp(mavlink_message_t *msg)
|
||||
{
|
||||
mavlink_hil_optical_flow_t flow;
|
||||
mavlink_msg_hil_optical_flow_decode(msg, &flow);
|
||||
mavlink_vision_position_estimate_t vpe;
|
||||
mavlink_msg_vision_position_estimate_decode(msg, &vpe);
|
||||
|
||||
if ((_debug) && (!(flow_debug_counter % 10))) {
|
||||
PX4_INFO("optflow: time: %llu, quality %d", flow.time_usec, (int) flow.quality);
|
||||
PX4_INFO("optflow: x: %.2f y: %.2f", (double) flow.integrated_x, (double) flow.integrated_y);
|
||||
}
|
||||
// fill vehicle_odometry from Mavlink VISION_POSITION_ESTIMATE
|
||||
vehicle_odometry_s odom{};
|
||||
uint64_t timestamp = hrt_absolute_time();
|
||||
odom.timestamp_sample = timestamp;
|
||||
|
||||
flow_debug_counter++;
|
||||
odom.pose_frame = vehicle_odometry_s::POSE_FRAME_NED;
|
||||
odom.position[0] = vpe.x;
|
||||
odom.position[1] = vpe.y;
|
||||
odom.position[2] = vpe.z;
|
||||
|
||||
device::Device::DeviceId device_id;
|
||||
device_id.devid_s.bus_type = device::Device::DeviceBusType::DeviceBusType_MAVLINK;
|
||||
device_id.devid_s.bus = 1;
|
||||
device_id.devid_s.address = msg->sysid;
|
||||
device_id.devid_s.devtype = DRV_FLOW_DEVTYPE_SIM;
|
||||
const matrix::Quatf q(matrix::Eulerf(vpe.roll, vpe.pitch, vpe.yaw));
|
||||
q.copyTo(odom.q);
|
||||
|
||||
sensor_optical_flow_s sensor_optical_flow{};
|
||||
// VISION_POSITION_ESTIMATE covariance
|
||||
// Row-major representation of pose 6x6 cross-covariance matrix upper right triangle
|
||||
// (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.).
|
||||
// If unknown, assign NaN value to first element in the array.
|
||||
odom.position_variance[0] = vpe.covariance[0]; // X row 0, col 0
|
||||
odom.position_variance[1] = vpe.covariance[6]; // Y row 1, col 1
|
||||
odom.position_variance[2] = vpe.covariance[11]; // Z row 2, col 2
|
||||
|
||||
sensor_optical_flow.timestamp_sample = hrt_absolute_time();
|
||||
sensor_optical_flow.device_id = device_id.devid;
|
||||
odom.orientation_variance[0] = vpe.covariance[15]; // R row 3, col 3
|
||||
odom.orientation_variance[1] = vpe.covariance[18]; // P row 4, col 4
|
||||
odom.orientation_variance[2] = vpe.covariance[20]; // Y row 5, col 5
|
||||
|
||||
sensor_optical_flow.pixel_flow[0] = flow.integrated_x;
|
||||
sensor_optical_flow.pixel_flow[1] = flow.integrated_y;
|
||||
odom.reset_counter = vpe.reset_counter;
|
||||
|
||||
sensor_optical_flow.integration_timespan_us = flow.integration_time_us;
|
||||
sensor_optical_flow.quality = flow.quality;
|
||||
odom.timestamp = hrt_absolute_time();
|
||||
|
||||
int index = (int) position_source::FLOW;
|
||||
|
||||
if (position_source_data[index].fail) {
|
||||
uint32_t duration = position_source_data[index].failure_duration;
|
||||
hrt_abstime start = position_source_data[index].failure_duration_start;
|
||||
|
||||
if (duration) {
|
||||
if (hrt_elapsed_time(&start) > (duration * 1000000)) {
|
||||
PX4_INFO("Optical flow failure ending");
|
||||
position_source_data[index].fail = false;
|
||||
position_source_data[index].failure_duration = 0;
|
||||
position_source_data[index].failure_duration_start = 0;
|
||||
|
||||
} else {
|
||||
sensor_optical_flow.quality = 0;
|
||||
}
|
||||
|
||||
} else {
|
||||
sensor_optical_flow.quality = 0;
|
||||
}
|
||||
}
|
||||
|
||||
const matrix::Vector3f integrated_gyro(flow.integrated_xgyro, flow.integrated_ygyro, flow.integrated_zgyro);
|
||||
|
||||
if (integrated_gyro.isAllFinite()) {
|
||||
integrated_gyro.copyTo(sensor_optical_flow.delta_angle);
|
||||
sensor_optical_flow.delta_angle_available = true;
|
||||
}
|
||||
|
||||
sensor_optical_flow.max_flow_rate = NAN;
|
||||
sensor_optical_flow.min_ground_distance = NAN;
|
||||
sensor_optical_flow.max_ground_distance = NAN;
|
||||
|
||||
// Use distance value for distance sensor topic
|
||||
// if (PX4_ISFINITE(flow.distance) && (flow.distance >= 0.f)) {
|
||||
// // Positive value (including zero): distance known. Negative value: Unknown distance.
|
||||
// sensor_optical_flow.distance_m = flow.distance;
|
||||
// sensor_optical_flow.distance_available = true;
|
||||
// }
|
||||
|
||||
// Emulate voxl-flow-server where distance comes in a separate
|
||||
// distance sensor topic message
|
||||
sensor_optical_flow.distance_m = 0.0f;
|
||||
sensor_optical_flow.distance_available = false;
|
||||
|
||||
sensor_optical_flow.timestamp = hrt_absolute_time();
|
||||
|
||||
_sensor_optical_flow_pub.publish(sensor_optical_flow);
|
||||
|
||||
flow_sent_counter++;
|
||||
}
|
||||
|
||||
int distance_debug_counter = 0;
|
||||
|
||||
void handle_message_distance_sensor(mavlink_message_t *msg)
|
||||
{
|
||||
mavlink_distance_sensor_t dist_sensor;
|
||||
mavlink_msg_distance_sensor_decode(msg, &dist_sensor);
|
||||
|
||||
if ((_debug) && (!(distance_debug_counter % 10))) {
|
||||
PX4_INFO("distance: time: %u, quality: %u, height: %u",
|
||||
dist_sensor.time_boot_ms, dist_sensor.signal_quality,
|
||||
dist_sensor.current_distance);
|
||||
}
|
||||
|
||||
distance_debug_counter++;
|
||||
|
||||
distance_sensor_s ds{};
|
||||
|
||||
device::Device::DeviceId device_id;
|
||||
device_id.devid_s.bus_type = device::Device::DeviceBusType::DeviceBusType_MAVLINK;
|
||||
device_id.devid_s.bus = 1;
|
||||
device_id.devid_s.address = msg->sysid;
|
||||
device_id.devid_s.devtype = DRV_DIST_DEVTYPE_MAVLINK;
|
||||
|
||||
ds.timestamp = hrt_absolute_time(); /* Use system time for now, don't trust sender to attach correct timestamp */
|
||||
ds.min_distance = static_cast<float>(dist_sensor.min_distance) * 1e-2f; /* cm to m */
|
||||
ds.max_distance = static_cast<float>(dist_sensor.max_distance) * 1e-2f; /* cm to m */
|
||||
ds.current_distance = static_cast<float>(dist_sensor.current_distance) * 1e-2f; /* cm to m */
|
||||
ds.variance = dist_sensor.covariance * 1e-4f; /* cm^2 to m^2 */
|
||||
ds.h_fov = dist_sensor.horizontal_fov;
|
||||
ds.v_fov = dist_sensor.vertical_fov;
|
||||
ds.q[0] = dist_sensor.quaternion[0];
|
||||
ds.q[1] = dist_sensor.quaternion[1];
|
||||
ds.q[2] = dist_sensor.quaternion[2];
|
||||
ds.q[3] = dist_sensor.quaternion[3];
|
||||
ds.type = dist_sensor.type;
|
||||
ds.device_id = device_id.devid;
|
||||
ds.orientation = dist_sensor.orientation;
|
||||
|
||||
// MAVLink DISTANCE_SENSOR signal_quality value of 0 means unset/unknown
|
||||
// quality value. Also it comes normalised between 1 and 100 while the uORB
|
||||
// signal quality is normalised between 0 and 100.
|
||||
ds.signal_quality = dist_sensor.signal_quality == 0 ? -1 : 100 * (dist_sensor.signal_quality - 1) / 99;
|
||||
|
||||
_distance_sensor_pub.publish(ds);
|
||||
|
||||
distance_sent_counter++;
|
||||
_visual_odometry_pub.publish(odom);
|
||||
vision_msg_counter++;
|
||||
}
|
||||
|
||||
void
|
||||
@ -666,8 +518,6 @@ handle_message_odometry_dsp(mavlink_message_t *msg)
|
||||
mavlink_odometry_t odom_in;
|
||||
mavlink_msg_odometry_decode(msg, &odom_in);
|
||||
|
||||
odometry_sent_counter++;
|
||||
|
||||
// fill vehicle_odometry from Mavlink ODOMETRY
|
||||
vehicle_odometry_s odom{};
|
||||
uint64_t timestamp = hrt_absolute_time();
|
||||
@ -849,28 +699,6 @@ handle_message_odometry_dsp(mavlink_message_t *msg)
|
||||
odom.reset_counter = odom_in.reset_counter;
|
||||
odom.quality = odom_in.quality;
|
||||
|
||||
int index = (int) position_source::VIO;
|
||||
|
||||
if (position_source_data[index].fail) {
|
||||
uint32_t duration = position_source_data[index].failure_duration;
|
||||
hrt_abstime start = position_source_data[index].failure_duration_start;
|
||||
|
||||
if (duration) {
|
||||
if (hrt_elapsed_time(&start) > (duration * 1000000)) {
|
||||
PX4_INFO("VIO failure ending");
|
||||
position_source_data[index].fail = false;
|
||||
position_source_data[index].failure_duration = 0;
|
||||
position_source_data[index].failure_duration_start = 0;
|
||||
|
||||
} else {
|
||||
odom.quality = 0;
|
||||
}
|
||||
|
||||
} else {
|
||||
odom.quality = 0;
|
||||
}
|
||||
}
|
||||
|
||||
switch (odom_in.estimator_type) {
|
||||
case MAV_ESTIMATOR_TYPE_UNKNOWN: // accept MAV_ESTIMATOR_TYPE_UNKNOWN for legacy support
|
||||
case MAV_ESTIMATOR_TYPE_NAIVE:
|
||||
@ -917,6 +745,10 @@ void actuator_controls_from_outputs_dsp(mavlink_hil_actuator_controls_t *msg)
|
||||
msg->mode = mode_flag_custom;
|
||||
msg->mode |= (armed) ? mode_flag_armed : 0;
|
||||
msg->flags = 0;
|
||||
|
||||
#if defined(ENABLE_LOCKSTEP_SCHEDULER)
|
||||
msg->flags |= 1;
|
||||
#endif
|
||||
}
|
||||
|
||||
int openPort(const char *dev, speed_t speed)
|
||||
@ -927,8 +759,7 @@ int openPort(const char *dev, speed_t speed)
|
||||
}
|
||||
|
||||
_uart_fd = qurt_uart_open(dev, speed);
|
||||
|
||||
if (_debug) { PX4_INFO("qurt_uart_opened"); }
|
||||
PX4_DEBUG("qurt_uart_opened");
|
||||
|
||||
if (_uart_fd < 0) {
|
||||
PX4_ERR("Error opening port: %s (%i)", dev, errno);
|
||||
@ -1009,50 +840,25 @@ int stop()
|
||||
|
||||
void usage()
|
||||
{
|
||||
PX4_INFO("Usage: dsp_hitl {start|status|clear|failure|stop}");
|
||||
PX4_INFO(" failure <source> <duration>");
|
||||
PX4_INFO(" source: gps, vio, flow");
|
||||
PX4_INFO(" duration: 0 (toggle state), else seconds");
|
||||
PX4_INFO("Usage: dsp_hitl {start|info|status|stop}");
|
||||
}
|
||||
|
||||
void print_status()
|
||||
int get_status()
|
||||
{
|
||||
PX4_INFO("Running: %s", _is_running ? "yes" : "no");
|
||||
PX4_INFO("HIL Sensor received: %i", hil_sensor_counter);
|
||||
PX4_INFO("IMU updates: %i", imu_counter);
|
||||
PX4_INFO("\tCurrent accel x, y, z: %f, %f, %f", double(x_accel), double(y_accel), double(z_accel));
|
||||
PX4_INFO("\tCurrent gyro x, y, z: %f, %f, %f", double(x_gyro), double(y_gyro), double(z_gyro));
|
||||
PX4_INFO("Magnetometer sent: %i", mag_counter);
|
||||
PX4_INFO("Barometer sent: %i", baro_counter);
|
||||
PX4_INFO("Heartbeat received: %i, sent: %i", heartbeat_received_counter, heartbeat_sent_counter);
|
||||
PX4_INFO("Odometry received: %i, sent: %i", odometry_received_counter, odometry_sent_counter);
|
||||
PX4_INFO("GPS received: %i, sent: %i", gps_received_counter, gps_sent_counter);
|
||||
PX4_INFO("Distance sensor received: %i, sent: %i", distance_received_counter, distance_sent_counter);
|
||||
PX4_INFO("Optical flow received: %i, sent: %i", flow_received_counter, flow_sent_counter);
|
||||
PX4_INFO("Actuator updates sent: %i", actuator_sent_counter);
|
||||
PX4_INFO("Unknown messages received: %i", unknown_msg_received_counter);
|
||||
PX4_INFO("Status of IMU_Data counter: %i", imu_counter);
|
||||
PX4_INFO("Value of current accel x, y, z data: %f, %f, %f", double(x_accel), double(y_accel), double(z_accel));
|
||||
PX4_INFO("Value of current gyro x, y, z data: %f, %f, %f", double(x_gyro), double(y_gyro), double(z_gyro));
|
||||
PX4_INFO("Value of HIL_Sensor counter: %i", hil_sensor_counter);
|
||||
PX4_INFO("Value of Heartbeat counter: %i", heartbeat_counter);
|
||||
PX4_INFO("Value of Vision data counter: %i", vision_msg_counter);
|
||||
PX4_INFO("Value of GPS Data counter: %i", gps_counter);
|
||||
return 0;
|
||||
}
|
||||
|
||||
void
|
||||
clear_status_counters()
|
||||
{
|
||||
heartbeat_received_counter = 0;
|
||||
heartbeat_sent_counter = 0;
|
||||
imu_counter = 0;
|
||||
hil_sensor_counter = 0;
|
||||
mag_counter = 0;
|
||||
baro_counter = 0;
|
||||
actuator_sent_counter = 0;
|
||||
odometry_received_counter = 0;
|
||||
odometry_sent_counter = 0;
|
||||
gps_received_counter = 0;
|
||||
gps_sent_counter = 0;
|
||||
distance_received_counter = 0;
|
||||
distance_sent_counter = 0;
|
||||
flow_received_counter = 0;
|
||||
flow_sent_counter = 0;
|
||||
unknown_msg_received_counter = 0;
|
||||
}
|
||||
uint64_t first_sensor_msg_timestamp = 0;
|
||||
uint64_t first_sensor_report_timestamp = 0;
|
||||
uint64_t last_sensor_report_timestamp = 0;
|
||||
|
||||
void
|
||||
handle_message_hil_sensor_dsp(mavlink_message_t *msg)
|
||||
@ -1122,8 +928,6 @@ handle_message_hil_sensor_dsp(mavlink_message_t *msg)
|
||||
}
|
||||
|
||||
_px4_mag->update(gyro_accel_time, hil_sensor.xmag, hil_sensor.ymag, hil_sensor.zmag);
|
||||
|
||||
mag_counter++;
|
||||
}
|
||||
}
|
||||
|
||||
@ -1138,8 +942,17 @@ handle_message_hil_sensor_dsp(mavlink_message_t *msg)
|
||||
sensor_baro.error_count = 0;
|
||||
sensor_baro.timestamp = hrt_absolute_time();
|
||||
_sensor_baro_pub.publish(sensor_baro);
|
||||
}
|
||||
|
||||
baro_counter++;
|
||||
// differential pressure
|
||||
if ((hil_sensor.fields_updated & SensorSource::DIFF_PRESS) == SensorSource::DIFF_PRESS) {
|
||||
differential_pressure_s report{};
|
||||
report.timestamp_sample = gyro_accel_time;
|
||||
report.device_id = 1377548; // 1377548: DRV_DIFF_PRESS_DEVTYPE_SIM, BUS: 1, ADDR: 5, TYPE: SIMULATION
|
||||
report.temperature = hil_sensor.temperature;
|
||||
report.differential_pressure_pa = hil_sensor.diff_pressure * 100.0f; // hPa to Pa
|
||||
report.timestamp = hrt_absolute_time();
|
||||
_differential_pressure_pub.publish(report);
|
||||
}
|
||||
|
||||
// battery status
|
||||
@ -1157,6 +970,7 @@ handle_message_hil_sensor_dsp(mavlink_message_t *msg)
|
||||
|
||||
_battery_pub.publish(hil_battery_status);
|
||||
}
|
||||
hil_sensor_counter++;
|
||||
}
|
||||
|
||||
void
|
||||
@ -1175,41 +989,15 @@ handle_message_hil_gps_dsp(mavlink_message_t *msg)
|
||||
|
||||
gps.device_id = device_id.devid;
|
||||
|
||||
gps.latitude_deg = hil_gps.lat * 1e-7;
|
||||
gps.longitude_deg = hil_gps.lon * 1e-7;
|
||||
gps.altitude_msl_m = hil_gps.alt * 1e-3;
|
||||
gps.altitude_ellipsoid_m = hil_gps.alt * 1e-3;
|
||||
gps.latitude_deg = hil_gps.lat;
|
||||
gps.longitude_deg = hil_gps.lon;
|
||||
gps.altitude_msl_m = hil_gps.alt;
|
||||
gps.altitude_ellipsoid_m = hil_gps.alt;
|
||||
|
||||
gps.s_variance_m_s = 0.25f;
|
||||
gps.c_variance_rad = 0.5f;
|
||||
|
||||
gps.satellites_used = hil_gps.satellites_visible;
|
||||
gps.fix_type = hil_gps.fix_type;
|
||||
|
||||
int index = (int) position_source::GPS;
|
||||
|
||||
if (position_source_data[index].fail) {
|
||||
uint32_t duration = position_source_data[index].failure_duration;
|
||||
hrt_abstime start = position_source_data[index].failure_duration_start;
|
||||
|
||||
if (duration) {
|
||||
if (hrt_elapsed_time(&start) > (duration * 1000000)) {
|
||||
PX4_INFO("GPS failure ending");
|
||||
position_source_data[index].fail = false;
|
||||
position_source_data[index].failure_duration = 0;
|
||||
position_source_data[index].failure_duration_start = 0;
|
||||
|
||||
} else {
|
||||
gps.satellites_used = 1;
|
||||
gps.fix_type = 0;
|
||||
}
|
||||
|
||||
} else {
|
||||
gps.satellites_used = 1;
|
||||
gps.fix_type = 0;
|
||||
}
|
||||
}
|
||||
|
||||
gps.eph = (float)hil_gps.eph * 1e-2f; // cm -> m
|
||||
gps.epv = (float)hil_gps.epv * 1e-2f; // cm -> m
|
||||
|
||||
@ -1233,6 +1021,7 @@ handle_message_hil_gps_dsp(mavlink_message_t *msg)
|
||||
gps.timestamp_time_relative = 0;
|
||||
gps.time_utc_usec = hil_gps.time_usec;
|
||||
|
||||
gps.satellites_used = hil_gps.satellites_visible;
|
||||
|
||||
gps.heading = NAN;
|
||||
gps.heading_offset = NAN;
|
||||
@ -1240,51 +1029,10 @@ handle_message_hil_gps_dsp(mavlink_message_t *msg)
|
||||
gps.timestamp = hrt_absolute_time();
|
||||
|
||||
_sensor_gps_pub.publish(gps);
|
||||
|
||||
gps_sent_counter++;
|
||||
gps_counter++;
|
||||
}
|
||||
|
||||
int
|
||||
process_failure(dsp_hitl::position_source src, int duration)
|
||||
{
|
||||
if (src >= position_source::NUM_POSITION_SOURCES) {
|
||||
return 1;
|
||||
}
|
||||
|
||||
int index = (int) src;
|
||||
|
||||
if (position_source_data[index].send) {
|
||||
if (duration <= 0) {
|
||||
// Toggle state
|
||||
if (position_source_data[index].fail) {
|
||||
PX4_INFO("Ending indefinite %s failure", position_source_data[index].label);
|
||||
position_source_data[index].fail = false;
|
||||
|
||||
} else {
|
||||
PX4_INFO("Starting indefinite %s failure", position_source_data[index].label);
|
||||
position_source_data[index].fail = true;
|
||||
}
|
||||
|
||||
position_source_data[index].failure_duration = 0;
|
||||
position_source_data[index].failure_duration_start = 0;
|
||||
|
||||
} else {
|
||||
PX4_INFO("%s failure for %d seconds", position_source_data[index].label, duration);
|
||||
position_source_data[index].fail = true;
|
||||
position_source_data[index].failure_duration = duration;
|
||||
position_source_data[index].failure_duration_start = hrt_absolute_time();
|
||||
}
|
||||
|
||||
} else {
|
||||
PX4_ERR("%s not active, cannot create failure", position_source_data[index].label);
|
||||
return 1;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
} // End dsp_hitl namespace
|
||||
|
||||
int dsp_hitl_main(int argc, char *argv[])
|
||||
{
|
||||
int myoptind = 1;
|
||||
@ -1296,47 +1044,20 @@ int dsp_hitl_main(int argc, char *argv[])
|
||||
|
||||
const char *verb = argv[myoptind];
|
||||
|
||||
|
||||
if (!strcmp(verb, "start")) {
|
||||
return dsp_hitl::start(argc - 1, argv + 1);
|
||||
}
|
||||
|
||||
} else if (!strcmp(verb, "stop")) {
|
||||
else if (!strcmp(verb, "stop")) {
|
||||
return dsp_hitl::stop();
|
||||
}
|
||||
|
||||
} else if (!strcmp(verb, "status")) {
|
||||
dsp_hitl::print_status();
|
||||
return 0;
|
||||
else if (!strcmp(verb, "status")) {
|
||||
return dsp_hitl::get_status();
|
||||
}
|
||||
|
||||
} else if (!strcmp(verb, "clear")) {
|
||||
dsp_hitl::clear_status_counters();
|
||||
return 0;
|
||||
|
||||
} else if (!strcmp(verb, "failure")) {
|
||||
if (argc != 4) {
|
||||
dsp_hitl::usage();
|
||||
return 1;
|
||||
}
|
||||
|
||||
const char *source = argv[myoptind + 1];
|
||||
int duration = atoi(argv[myoptind + 2]);
|
||||
|
||||
if (!strcmp(source, "gps")) {
|
||||
return dsp_hitl::process_failure(dsp_hitl::position_source::GPS, duration);
|
||||
|
||||
} else if (!strcmp(source, "vio")) {
|
||||
return dsp_hitl::process_failure(dsp_hitl::position_source::VIO, duration);
|
||||
|
||||
} else if (!strcmp(source, "flow")) {
|
||||
return dsp_hitl::process_failure(dsp_hitl::position_source::FLOW, duration);
|
||||
|
||||
} else {
|
||||
PX4_ERR("Unknown failure source %s, duration %d", source, duration);
|
||||
dsp_hitl::usage();
|
||||
return 1;
|
||||
}
|
||||
|
||||
return 0;
|
||||
|
||||
} else {
|
||||
else {
|
||||
dsp_hitl::usage();
|
||||
return 1;
|
||||
}
|
||||
|
||||
@ -11,6 +11,7 @@ CONFIG_DRIVERS_VOXL2_IO=y
|
||||
CONFIG_MODULES_COMMANDER=y
|
||||
CONFIG_MODULES_CONTROL_ALLOCATOR=y
|
||||
CONFIG_MODULES_DATAMAN=y
|
||||
CONFIG_MODULES_LOAD_MON=y
|
||||
CONFIG_MODULES_LOGGER=y
|
||||
CONFIG_MODULES_MAVLINK=y
|
||||
CONFIG_MODULES_MUORB_APPS=y
|
||||
@ -25,4 +26,3 @@ CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y
|
||||
CONFIG_SYSTEMCMDS_UORB=y
|
||||
CONFIG_SYSTEMCMDS_VER=y
|
||||
CONFIG_ORB_COMMUNICATOR=y
|
||||
CONFIG_PARAM_PRIMARY=y
|
||||
|
||||
@ -76,13 +76,12 @@ qshell flight_mode_manager start
|
||||
# Start all of the processing modules on the applications processor
|
||||
dataman start
|
||||
navigator start
|
||||
load_mon start
|
||||
|
||||
# Start microdds_client for ros2 offboard messages from agent over localhost
|
||||
microdds_client start -t udp -h 127.0.0.1 -p 8888
|
||||
|
||||
qshell pwm_out_sim start -m hil
|
||||
# g = gps, m = mag, o = odometry (vio), h = distance sensor, f = optic flow
|
||||
# qshell dsp_hitl start -g -m -o -h -f
|
||||
qshell dsp_hitl start -g -m
|
||||
|
||||
# start the onboard fast link to connect to voxl-mavlink-server
|
||||
|
||||
@ -207,6 +207,7 @@ qshell flight_mode_manager start
|
||||
# Start all of the processing modules on the applications processor
|
||||
dataman start
|
||||
navigator start
|
||||
load_mon start
|
||||
|
||||
# This bridge allows raw data packets to be sent over UART to the ESC
|
||||
voxl2_io_bridge start
|
||||
|
||||
@ -1,11 +1,9 @@
|
||||
CONFIG_BOARD_TOOLCHAIN="arm-none-eabi"
|
||||
CONFIG_BOARD_ARCHITECTURE="cortex-m7"
|
||||
CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS3"
|
||||
CONFIG_BOARD_SERIAL_GPS2="/dev/ttyS4"
|
||||
CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS1"
|
||||
CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS2"
|
||||
CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS5"
|
||||
CONFIG_BOARD_SERIAL_TEL4="/dev/ttyS0"
|
||||
CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS2"
|
||||
CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS0"
|
||||
CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS1"
|
||||
CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS4"
|
||||
CONFIG_DRIVERS_ADC_ADS1115=y
|
||||
CONFIG_DRIVERS_ADC_BOARD_ADC=y
|
||||
CONFIG_DRIVERS_BAROMETER_DPS310=y
|
||||
@ -27,7 +25,6 @@ CONFIG_DRIVERS_PCA9685_PWM_OUT=y
|
||||
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
|
||||
CONFIG_DRIVERS_PWM_OUT=y
|
||||
CONFIG_DRIVERS_RC_INPUT=y
|
||||
CONFIG_DRIVERS_SAFETY_BUTTON=y
|
||||
CONFIG_DRIVERS_SMART_BATTERY_BATMON=y
|
||||
CONFIG_COMMON_TELEMETRY=y
|
||||
CONFIG_DRIVERS_TONE_ALARM=y
|
||||
@ -49,6 +46,7 @@ CONFIG_MODULES_FW_POS_CONTROL=y
|
||||
CONFIG_MODULES_FW_RATE_CONTROL=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_GYRO_CALIBRATION=y
|
||||
CONFIG_MODULES_GYRO_FFT=y
|
||||
CONFIG_MODULES_LAND_DETECTOR=y
|
||||
CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y
|
||||
CONFIG_MODULES_LOAD_MON=y
|
||||
@ -98,3 +96,4 @@ CONFIG_SYSTEMCMDS_UORB=y
|
||||
CONFIG_SYSTEMCMDS_USB_CONNECTED=y
|
||||
CONFIG_SYSTEMCMDS_VER=y
|
||||
CONFIG_SYSTEMCMDS_WORK_QUEUE=y
|
||||
CONFIG_EXAMPLES_FAKE_GPS=y
|
||||
|
||||
@ -6,4 +6,4 @@
|
||||
param set-default BAT1_V_DIV 10.1
|
||||
param set-default BAT1_A_PER_V 17
|
||||
|
||||
param set-default TEL_FRSKY_CONFIG 103
|
||||
safety_button start
|
||||
|
||||
@ -16,5 +16,3 @@ icm20948 -s -b 1 -R 8 -M start
|
||||
|
||||
# Interal DPS310 (barometer)
|
||||
dps310 -s -b 2 start
|
||||
|
||||
safety_button start
|
||||
|
||||
@ -15,7 +15,7 @@ CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/mro/ctrl-zero-classic/nuttx-con
|
||||
CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y
|
||||
CONFIG_ARCH_BOARD_CUSTOM_NAME="px4"
|
||||
CONFIG_ARCH_CHIP="stm32h7"
|
||||
CONFIG_ARCH_CHIP_STM32H743ZI=y
|
||||
CONFIG_ARCH_CHIP_STM32H743II=y
|
||||
CONFIG_ARCH_CHIP_STM32H7=y
|
||||
CONFIG_ARCH_INTERRUPTSTACK=768
|
||||
CONFIG_ARMV7M_BASEPRI_WAR=y
|
||||
|
||||
@ -222,9 +222,6 @@
|
||||
|
||||
|
||||
/* UART/USART */
|
||||
#define GPIO_USART1_TX GPIO_USART1_TX_3 /* PB6 */
|
||||
#define GPIO_USART1_RX GPIO_USART1_RX_3 /* PB7 */
|
||||
|
||||
#define GPIO_USART2_TX GPIO_USART2_TX_2 /* PD5 */
|
||||
#define GPIO_USART2_RX GPIO_USART2_RX_2 /* PD6 */
|
||||
#define GPIO_USART2_CTS GPIO_USART2_CTS_NSS_2 /* PD3 */
|
||||
@ -238,6 +235,9 @@
|
||||
#define GPIO_UART4_TX GPIO_UART4_TX_2 /* PA0 */
|
||||
#define GPIO_UART4_RX GPIO_UART4_RX_2 /* PA1 */
|
||||
|
||||
#define GPIO_USART6_TX 0 /* USART6 is RX-only */
|
||||
#define GPIO_USART6_RX GPIO_USART6_RX_1 /* PC7 */
|
||||
|
||||
#define GPIO_UART7_TX GPIO_UART7_TX_3 /* PE8 */
|
||||
#define GPIO_UART7_RX GPIO_UART7_RX_3 /* PE7 */
|
||||
|
||||
@ -268,14 +268,13 @@
|
||||
#define GPIO_SPI5_MISO GPIO_SPI5_MISO_1 /* PF8 */
|
||||
#define GPIO_SPI5_MOSI GPIO_SPI5_MOSI_2 /* PF9 */
|
||||
|
||||
#define GPIO_SPI6_SCK ADJ_SLEW_RATE(GPIO_SPI6_SCK_1) /* PG13 */
|
||||
#define GPIO_SPI6_MISO GPIO_SPI6_MISO_1 /* PG12 */
|
||||
#define GPIO_SPI6_MOSI GPIO_SPI6_MOSI_1 /* PG14 */
|
||||
|
||||
|
||||
/* I2C */
|
||||
#define GPIO_I2C1_SCL GPIO_I2C1_SCL_2 /* PB8 */
|
||||
#define GPIO_I2C1_SDA GPIO_I2C1_SDA_2 /* PB9 */
|
||||
|
||||
#define GPIO_I2C4_SCL GPIO_I2C4_SCL_2 /* PF14 */
|
||||
#define GPIO_I2C4_SDA GPIO_I2C4_SDA_2 /* PF15 */
|
||||
#define GPIO_I2C3_SCL GPIO_I2C3_SCL_2 /* PH7 */
|
||||
#define GPIO_I2C3_SDA GPIO_I2C3_SDA_2 /* PH8 */
|
||||
|
||||
#define GPIO_I2C4_SCL GPIO_I2C4_SCL_4 /* PB6 */
|
||||
#define GPIO_I2C4_SDA GPIO_I2C4_SDA_4 /* PB7 */
|
||||
|
||||
@ -56,7 +56,7 @@ CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/mro/ctrl-zero-classic/nuttx-con
|
||||
CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y
|
||||
CONFIG_ARCH_BOARD_CUSTOM_NAME="px4"
|
||||
CONFIG_ARCH_CHIP="stm32h7"
|
||||
CONFIG_ARCH_CHIP_STM32H743ZI=y
|
||||
CONFIG_ARCH_CHIP_STM32H743II=y
|
||||
CONFIG_ARCH_CHIP_STM32H7=y
|
||||
CONFIG_ARCH_INTERRUPTSTACK=768
|
||||
CONFIG_ARCH_STACKDUMP=y
|
||||
@ -192,6 +192,7 @@ CONFIG_STM32H7_DMA2=y
|
||||
CONFIG_STM32H7_DMACAPABLE=y
|
||||
CONFIG_STM32H7_FLOWCONTROL_BROKEN=y
|
||||
CONFIG_STM32H7_I2C1=y
|
||||
CONFIG_STM32H7_I2C3=y
|
||||
CONFIG_STM32H7_I2C4=y
|
||||
CONFIG_STM32H7_I2C_DYNTIMEO=y
|
||||
CONFIG_STM32H7_I2C_DYNTIMEO_STARTSTOP=10
|
||||
@ -211,20 +212,17 @@ CONFIG_STM32H7_SPI2=y
|
||||
CONFIG_STM32H7_SPI5=y
|
||||
CONFIG_STM32H7_SPI5_DMA=y
|
||||
CONFIG_STM32H7_SPI5_DMA_BUFFER=1024
|
||||
CONFIG_STM32H7_SPI6=y
|
||||
CONFIG_STM32H7_TIM15=y
|
||||
CONFIG_STM32H7_TIM16=y
|
||||
CONFIG_STM32H7_TIM1=y
|
||||
CONFIG_STM32H7_TIM2=y
|
||||
CONFIG_STM32H7_TIM3=y
|
||||
CONFIG_STM32H7_TIM4=y
|
||||
CONFIG_STM32H7_TIM8=y
|
||||
CONFIG_STM32H7_USART1=y
|
||||
CONFIG_STM32H7_USART2=y
|
||||
CONFIG_STM32H7_USART3=y
|
||||
CONFIG_STM32H7_UART4=y
|
||||
CONFIG_STM32H7_UART7=y
|
||||
CONFIG_STM32H7_UART8=y
|
||||
CONFIG_STM32H7_USART2=y
|
||||
CONFIG_STM32H7_USART3=y
|
||||
CONFIG_STM32H7_USART6=y
|
||||
CONFIG_STM32H7_USART_BREAKS=y
|
||||
CONFIG_STM32H7_USART_INVERT=y
|
||||
CONFIG_STM32H7_USART_SINGLEWIRE=y
|
||||
@ -254,6 +252,9 @@ CONFIG_USART3_IFLOWCONTROL=y
|
||||
CONFIG_USART3_OFLOWCONTROL=y
|
||||
CONFIG_USART3_RXBUFSIZE=600
|
||||
CONFIG_USART3_TXBUFSIZE=3000
|
||||
CONFIG_USART6_BAUD=57600
|
||||
CONFIG_USART6_RXBUFSIZE=600
|
||||
CONFIG_USART6_TXBUFSIZE=1500
|
||||
CONFIG_USBDEV=y
|
||||
CONFIG_USBDEV_BUSPOWERED=y
|
||||
CONFIG_USBDEV_MAXPOWER=500
|
||||
|
||||
@ -45,111 +45,95 @@
|
||||
#include <stm32_gpio.h>
|
||||
|
||||
/* LEDs are driven with push open drain to support Anode to 5V or 3.3V */
|
||||
#define GPIO_nLED_RED /* PB4 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN4)
|
||||
#define GPIO_nLED_GREEN /* PB5 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN5)
|
||||
#define GPIO_nLED_RED /* PB11 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN11)
|
||||
#define GPIO_nLED_GREEN /* PB1 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN1)
|
||||
#define GPIO_nLED_BLUE /* PB3 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN3)
|
||||
|
||||
#define GPIO_LED_SAFETY /* PE6 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN6)
|
||||
|
||||
#define BOARD_HAS_CONTROL_STATUS_LEDS 1
|
||||
#define BOARD_OVERLOAD_LED LED_RED
|
||||
#define BOARD_ARMED_STATE_LED LED_BLUE
|
||||
|
||||
/* ADC channels */
|
||||
#define PX4_ADC_GPIO \
|
||||
/* PC4 */ GPIO_ADC12_INP4, \
|
||||
/* PA2 */ GPIO_ADC12_INP14, \
|
||||
/* PA3 */ GPIO_ADC12_INP15, \
|
||||
/* PA4 */ GPIO_ADC12_INP18, \
|
||||
/* PC0 */ GPIO_ADC123_INP10, \
|
||||
/* PC5 */ GPIO_ADC12_INP8, \
|
||||
/* PB0 */ GPIO_ADC12_INP9, \
|
||||
/* PB1 */ GPIO_ADC12_INP5
|
||||
/* PC1 */ GPIO_ADC123_INP11
|
||||
|
||||
/* Define Channel numbers must match above GPIO pins */
|
||||
#define ADC_BATTERY_VOLTAGE_CHANNEL 4 /* PC4 BATT_VOLT_SENS */
|
||||
#define ADC_BATTERY_VOLTAGE_CHANNEL 14 /* PA2 BATT_VOLT_SENS */
|
||||
#define ADC_BATTERY_CURRENT_CHANNEL 15 /* PA3 BATT_CURRENT_SENS */
|
||||
#define ADC_SCALED_V5_CHANNEL 18 /* PA4 VDD_5V_SENS */
|
||||
#define ADC_RC_RSSI_CHANNEL 10 /* PC0 */
|
||||
#define ADC_AIRSPEED_VOLTAGE_CHANNEL 8 /* PC5 */
|
||||
#define ADC_AUX1_VOLTAGE_CHANNEL 9 /* PB0 */
|
||||
#define ADC_AUX2_VOLTAGE_CHANNEL 5 /* PB1 */
|
||||
#define ADC_RC_RSSI_CHANNEL 11 /* PC1 */
|
||||
|
||||
#define ADC_CHANNELS \
|
||||
((1 << ADC_BATTERY_VOLTAGE_CHANNEL) | \
|
||||
(1 << ADC_BATTERY_CURRENT_CHANNEL) | \
|
||||
(1 << ADC_SCALED_V5_CHANNEL) | \
|
||||
(1 << ADC_RC_RSSI_CHANNEL) | \
|
||||
(1 << ADC_AIRSPEED_VOLTAGE_CHANNEL) | \
|
||||
(1 << ADC_AUX1_VOLTAGE_CHANNEL) | \
|
||||
(1 << ADC_AUX2_VOLTAGE_CHANNEL))
|
||||
(1 << ADC_RC_RSSI_CHANNEL))
|
||||
|
||||
/* HW has to large of R termination on ADC todo:change when HW value is chosen */
|
||||
#define BOARD_ADC_OPEN_CIRCUIT_V (5.6f)
|
||||
|
||||
/* CAN Silence: Silent mode control */
|
||||
#define GPIO_CAN1_SILENT_S0 /* PF11 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTF|GPIO_PIN11)
|
||||
#define GPIO_CAN2_SILENT_S0 /* PF12 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTF|GPIO_PIN12)
|
||||
#define GPIO_CAN1_SILENT_S0 /* PF5 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTF|GPIO_PIN5)
|
||||
#define GPIO_CAN2_SILENT_S0 /* PF5 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTF|GPIO_PIN5)
|
||||
|
||||
/* PWM */
|
||||
#define DIRECT_PWM_OUTPUT_CHANNELS 12
|
||||
|
||||
/* Power supply control and monitoring GPIOs */
|
||||
#define GPIO_nPOWER_IN_A /* PC1 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN1)
|
||||
#define GPIO_nPOWER_IN_A /* PB5 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN5)
|
||||
|
||||
#define GPIO_VDD_BRICK1_VALID GPIO_nPOWER_IN_A /* Brick 1 Is Chosen */
|
||||
#define BOARD_NUMBER_BRICKS 1
|
||||
|
||||
#define GPIO_VDD_3V3_SPEKTRUM_POWER_EN /* PE4 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN4)
|
||||
|
||||
#define GPIO_LEVEL_SHIFTER_OE /* PC13 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN13)
|
||||
|
||||
/* Define True logic Power Control in arch agnostic form */
|
||||
#define VDD_3V3_SPEKTRUM_POWER_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_3V3_SPEKTRUM_POWER_EN, (!on_true))
|
||||
#define READ_VDD_3V3_SPEKTRUM_POWER_EN() (px4_arch_gpioread(GPIO_VDD_3V3_SPEKTRUM_POWER_EN) == 0)
|
||||
|
||||
/* Tone alarm output */
|
||||
#define TONE_ALARM_TIMER 16 /* timer 16 */
|
||||
#define TONE_ALARM_CHANNEL 1 /* PF6 TIM16_CH1 */
|
||||
#define TONE_ALARM_TIMER 2 /* timer 2 */
|
||||
#define TONE_ALARM_CHANNEL 1 /* PA15 TIM2_CH1 */
|
||||
|
||||
#define GPIO_BUZZER_1 /* PF6 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTF|GPIO_PIN6)
|
||||
#define GPIO_BUZZER_1 /* PA15 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN15)
|
||||
|
||||
#define GPIO_TONE_ALARM_IDLE GPIO_BUZZER_1
|
||||
#define GPIO_TONE_ALARM GPIO_TIM16_CH1OUT_2
|
||||
#define GPIO_TONE_ALARM GPIO_TIM2_CH1OUT_2
|
||||
|
||||
/* USB OTG FS */
|
||||
#define GPIO_OTGFS_VBUS /* PA9 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_100MHz|GPIO_PORTA|GPIO_PIN9)
|
||||
|
||||
/* High-resolution timer */
|
||||
#define HRT_TIMER 3 /* use timer3 for the HRT */
|
||||
#define HRT_TIMER_CHANNEL 2 /* use capture/compare channel 1 */
|
||||
#define HRT_TIMER_CHANNEL 1 /* use capture/compare channel 1 */
|
||||
|
||||
#define HRT_PPM_CHANNEL /* T3C2 */ 2 /* use capture/compare channel 2 */
|
||||
#define GPIO_PPM_IN /* PC7 T3C2 */ GPIO_TIM3_CH2IN_3
|
||||
#define HRT_PPM_CHANNEL /* T3C3 */ 3 /* use capture/compare channel 3 */
|
||||
#define GPIO_PPM_IN /* PB0 T3C3 */ GPIO_TIM3_CH3IN_1
|
||||
|
||||
/* RC Serial port */
|
||||
#define RC_SERIAL_PORT "/dev/ttyS5"
|
||||
#define RC_SERIAL_PORT "/dev/ttyS3"
|
||||
|
||||
#define GPIO_RSSI_IN /* PC0 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN0)
|
||||
#define GPIO_RSSI_IN /* PC1 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN1)
|
||||
|
||||
/* Safety Switch: Enable the FMU to control it if there is no px4io fixme:This should be BOARD_SAFETY_LED(__ontrue) */
|
||||
#define GPIO_SAFETY_SWITCH_IN /* PA10 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTA|GPIO_PIN10)
|
||||
/* Enable the FMU to use the switch it if there is no px4io fixme:This should be BOARD_SAFETY_BUTTON() */
|
||||
#define GPIO_SAFETY_SWITCH_IN /* PC4 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN4)
|
||||
/* Enable the FMU to use the switch it if there is no px4io fixme:This should be BOARD_SAFTY_BUTTON() */
|
||||
#define GPIO_BTN_SAFETY GPIO_SAFETY_SWITCH_IN /* Enable the FMU to control it if there is no px4io */
|
||||
|
||||
/* No PX4IO processor present */
|
||||
#define PX4_MFT_HW_SUPPORTED_PX4_MFT_PX4IO 0
|
||||
|
||||
/* Power switch controls ******************************************************/
|
||||
#define SPEKTRUM_POWER(_on_true) VDD_3V3_SPEKTRUM_POWER_EN(_on_true)
|
||||
|
||||
/*
|
||||
* Board has a separate RC_IN
|
||||
*
|
||||
* GPIO PPM_IN on PC7 T3CH2
|
||||
* GPIO PPM_IN on PB0 T3CH3
|
||||
* SPEKTRUM_RX (it's TX or RX in Bind) on UART6 PC7
|
||||
* Inversion is possible in the UART and can drive GPIO_PPM_IN as an output
|
||||
*/
|
||||
#define GPIO_PPM_IN_AS_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN7)
|
||||
#define GPIO_PPM_IN_AS_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN0)
|
||||
#define SPEKTRUM_RX_AS_GPIO_OUTPUT() px4_arch_configgpio(GPIO_PPM_IN_AS_OUT)
|
||||
#define SPEKTRUM_RX_AS_UART() /* Can be left as uart */
|
||||
#define SPEKTRUM_OUT(_one_true) px4_arch_gpiowrite(GPIO_PPM_IN_AS_OUT, (_one_true))
|
||||
@ -172,7 +156,7 @@
|
||||
#define BOARD_HAS_STATIC_MANIFEST 1
|
||||
|
||||
|
||||
#define BOARD_NUM_IO_TIMERS 6
|
||||
#define BOARD_NUM_IO_TIMERS 5
|
||||
|
||||
|
||||
#define BOARD_ENABLE_CONSOLE_BUFFER
|
||||
@ -187,12 +171,9 @@
|
||||
GPIO_CAN2_SILENT_S0, \
|
||||
GPIO_nPOWER_IN_A, \
|
||||
GPIO_VDD_3V3_SPEKTRUM_POWER_EN, \
|
||||
GPIO_LEVEL_SHIFTER_OE, \
|
||||
GPIO_TONE_ALARM_IDLE, \
|
||||
GPIO_SAFETY_SWITCH_IN, \
|
||||
GPIO_OTGFS_VBUS, \
|
||||
GPIO_BTN_SAFETY, \
|
||||
GPIO_LED_SAFETY, \
|
||||
}
|
||||
|
||||
__BEGIN_DECLS
|
||||
|
||||
@ -35,5 +35,6 @@
|
||||
|
||||
constexpr px4_i2c_bus_t px4_i2c_buses[I2C_BUS_MAX_BUS_ITEMS] = {
|
||||
initI2CBusExternal(1),
|
||||
initI2CBusExternal(3),
|
||||
initI2CBusExternal(4),
|
||||
};
|
||||
|
||||
@ -37,7 +37,7 @@
|
||||
|
||||
constexpr px4_spi_bus_t px4_spi_buses[SPI_BUS_MAX_BUS_ITEMS] = {
|
||||
initSPIBus(SPI::Bus::SPI1, {
|
||||
initSPIDevice(DRV_IMU_DEVTYPE_ICM20602, SPI::CS{GPIO::PortG, GPIO::Pin3}, SPI::DRDY{GPIO::PortG, GPIO::Pin2}),
|
||||
initSPIDevice(DRV_IMU_DEVTYPE_ICM20602, SPI::CS{GPIO::PortC, GPIO::Pin2}, SPI::DRDY{GPIO::PortD, GPIO::Pin15}),
|
||||
initSPIDevice(DRV_IMU_DEVTYPE_ICM20948, SPI::CS{GPIO::PortE, GPIO::Pin15}, SPI::DRDY{GPIO::PortE, GPIO::Pin12}),
|
||||
}, {GPIO::PortE, GPIO::Pin3}),
|
||||
initSPIBus(SPI::Bus::SPI2, {
|
||||
@ -46,10 +46,7 @@ constexpr px4_spi_bus_t px4_spi_buses[SPI_BUS_MAX_BUS_ITEMS] = {
|
||||
}),
|
||||
initSPIBus(SPI::Bus::SPI5, {
|
||||
initSPIDevice(DRV_GYR_DEVTYPE_BMI088, SPI::CS{GPIO::PortF, GPIO::Pin10}, SPI::DRDY{GPIO::PortF, GPIO::Pin3}),
|
||||
initSPIDevice(DRV_ACC_DEVTYPE_BMI088, SPI::CS{GPIO::PortF, GPIO::Pin0}, SPI::DRDY{GPIO::PortF, GPIO::Pin1}),
|
||||
}),
|
||||
initSPIBusExternal(SPI::Bus::SPI6, {
|
||||
initSPIConfigExternal(SPI::CS{GPIO::PortG, GPIO::Pin9}),
|
||||
initSPIDevice(DRV_ACC_DEVTYPE_BMI088, SPI::CS{GPIO::PortF, GPIO::Pin6}, SPI::DRDY{GPIO::PortF, GPIO::Pin1}),
|
||||
}),
|
||||
};
|
||||
|
||||
|
||||
@ -33,28 +33,6 @@
|
||||
|
||||
#include <px4_arch/io_timer_hw_description.h>
|
||||
|
||||
/* Timer allocation
|
||||
*
|
||||
* TIM1_CH4 T FMU_CH1
|
||||
* TIM1_CH3 T FMU_CH2
|
||||
* TIM1_CH2 T FMU_CH3
|
||||
* TIM1_CH1 T FMU_CH4
|
||||
*
|
||||
* TIM4_CH2 T FMU_CH5
|
||||
* TIM4_CH3 T FMU_CH6
|
||||
* TIM2_CH3 T FMU_CH7
|
||||
* TIM2_CH1 T FMU_CH8
|
||||
*
|
||||
* TIM2_CH4 T FMU_CH9
|
||||
* TIM15_CH1 T FMU_CH10
|
||||
*
|
||||
* TIM8_CH1 T FMU_CH11
|
||||
*
|
||||
* TIM4_CH4 T FMU_CH12
|
||||
*
|
||||
* TIM16_CH1 T BUZZER - Driven by other driver
|
||||
*/
|
||||
|
||||
constexpr io_timers_t io_timers[MAX_IO_TIMERS] = {
|
||||
initIOTimer(Timer::Timer1, DMA{DMA::Index1}),
|
||||
initIOTimer(Timer::Timer4, DMA{DMA::Index1}),
|
||||
|
||||
@ -104,6 +104,7 @@ CONFIG_SYSTEMCMDS_PERF=y
|
||||
CONFIG_SYSTEMCMDS_REBOOT=y
|
||||
CONFIG_SYSTEMCMDS_REFLECT=y
|
||||
CONFIG_SYSTEMCMDS_SD_BENCH=y
|
||||
CONFIG_SYSTEMCMDS_SD_STRESS=y
|
||||
CONFIG_SYSTEMCMDS_SYSTEM_TIME=y
|
||||
CONFIG_SYSTEMCMDS_TOP=y
|
||||
CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y
|
||||
|
||||
@ -58,7 +58,6 @@ set(msg_files
|
||||
CameraCapture.msg
|
||||
CameraStatus.msg
|
||||
CameraTrigger.msg
|
||||
CanInterfaceStatus.msg
|
||||
CellularStatus.msg
|
||||
CollisionConstraints.msg
|
||||
CollisionReport.msg
|
||||
@ -74,6 +73,7 @@ set(msg_files
|
||||
DifferentialDriveSetpoint.msg
|
||||
DifferentialPressure.msg
|
||||
DistanceSensor.msg
|
||||
Ekf2Timestamps.msg
|
||||
EscReport.msg
|
||||
EscStatus.msg
|
||||
EstimatorAidSource1d.msg
|
||||
@ -99,7 +99,6 @@ set(msg_files
|
||||
FollowTargetStatus.msg
|
||||
GeneratorStatus.msg
|
||||
GeofenceResult.msg
|
||||
GeofenceStatus.msg
|
||||
GimbalControls.msg
|
||||
GimbalDeviceAttitudeStatus.msg
|
||||
GimbalDeviceInformation.msg
|
||||
@ -154,10 +153,6 @@ set(msg_files
|
||||
OrbTest.msg
|
||||
OrbTestLarge.msg
|
||||
OrbTestMedium.msg
|
||||
ParameterResetRequest.msg
|
||||
ParameterSetUsedRequest.msg
|
||||
ParameterSetValueRequest.msg
|
||||
ParameterSetValueResponse.msg
|
||||
ParameterUpdate.msg
|
||||
Ping.msg
|
||||
PositionControllerLandingStatus.msg
|
||||
@ -289,9 +284,6 @@ foreach(msg_file ${msg_files})
|
||||
list(APPEND uorb_json_files ${msg_source_out_path}/${msg}.json)
|
||||
endforeach()
|
||||
|
||||
# set parent scope msg_files for ROS
|
||||
set(msg_files ${msg_files} PARENT_SCOPE)
|
||||
|
||||
# Generate uORB headers
|
||||
add_custom_command(
|
||||
OUTPUT
|
||||
|
||||
@ -1,6 +0,0 @@
|
||||
uint64 timestamp # time since system start (microseconds)
|
||||
uint8 interface
|
||||
|
||||
uint64 io_errors
|
||||
uint64 frames_tx
|
||||
uint64 frames_rx
|
||||
23
msg/Ekf2Timestamps.msg
Normal file
23
msg/Ekf2Timestamps.msg
Normal file
@ -0,0 +1,23 @@
|
||||
# this message contains the (relative) timestamps of the sensor inputs used by EKF2.
|
||||
# It can be used for reproducible replay.
|
||||
|
||||
# the timestamp field is the ekf2 reference time and matches the timestamp of
|
||||
# the sensor_combined topic.
|
||||
|
||||
uint64 timestamp # time since system start (microseconds)
|
||||
|
||||
int16 RELATIVE_TIMESTAMP_INVALID = 32767 # (0x7fff) If one of the relative timestamps
|
||||
# is set to this value, it means the associated sensor values did not update
|
||||
|
||||
# timestamps are relative to the main timestamp and are in 0.1 ms (timestamp +
|
||||
# *_timestamp_rel = absolute timestamp). For int16, this allows a maximum
|
||||
# difference of +-3.2s to the sensor_combined topic.
|
||||
|
||||
int16 airspeed_timestamp_rel
|
||||
int16 distance_sensor_timestamp_rel
|
||||
int16 optical_flow_timestamp_rel
|
||||
int16 vehicle_air_data_timestamp_rel
|
||||
int16 vehicle_magnetometer_timestamp_rel
|
||||
int16 visual_odometry_timestamp_rel
|
||||
|
||||
# Note: this is a high-rate logged topic, so it needs to be as small as possible
|
||||
@ -1,7 +0,0 @@
|
||||
uint64 timestamp # time since system start (microseconds)
|
||||
|
||||
uint32 geofence_id # loaded geofence id
|
||||
uint8 status # Current geofence status
|
||||
|
||||
uint8 GF_STATUS_LOADING = 0
|
||||
uint8 GF_STATUS_READY = 1
|
||||
@ -1,8 +1,8 @@
|
||||
uint64 timestamp # time since system start (microseconds)
|
||||
|
||||
uint32 mission_id # Id for the mission for which the result was generated
|
||||
uint32 geofence_id # Id for the corresponding geofence for which the result was generated (used for mission feasibility)
|
||||
uint32 home_position_counter # Counter of the home position for which the result was generated (used for mission feasibility)
|
||||
uint16 mission_id # Id for the mission for which the result was generated
|
||||
uint16 geofence_id # Id for the corresponding geofence for which the result was generated (used for mission feasibility)
|
||||
uint64 home_position_counter # Counter of the home position for which the result was generated (used for mission feasibility)
|
||||
|
||||
int32 seq_reached # Sequence of the mission item which has been reached, default -1
|
||||
uint16 seq_current # Sequence of the current mission item
|
||||
|
||||
@ -1,8 +0,0 @@
|
||||
# ParameterResetRequest : Used by the primary to reset one or all parameter value(s) on the remote
|
||||
|
||||
uint64 timestamp
|
||||
uint16 parameter_index
|
||||
|
||||
bool reset_all # If this is true then ignore parameter_index
|
||||
|
||||
uint8 ORB_QUEUE_LENGTH = 4
|
||||
@ -1,6 +0,0 @@
|
||||
# ParameterSetUsedRequest : Used by a remote to update the used flag for a parameter on the primary
|
||||
|
||||
uint64 timestamp
|
||||
uint16 parameter_index
|
||||
|
||||
uint8 ORB_QUEUE_LENGTH = 64
|
||||
@ -1,11 +0,0 @@
|
||||
# ParameterSetValueRequest : Used by a remote or primary to update the value for a parameter at the other end
|
||||
|
||||
uint64 timestamp
|
||||
uint16 parameter_index
|
||||
|
||||
int32 int_value # Optional value for an integer parameter
|
||||
float32 float_value # Optional value for a float parameter
|
||||
|
||||
uint8 ORB_QUEUE_LENGTH = 32
|
||||
|
||||
# TOPICS parameter_set_value_request parameter_remote_set_value_request parameter_primary_set_value_request
|
||||
@ -1,9 +0,0 @@
|
||||
# ParameterSetValueResponse : Response to a set value request by either primary or secondary
|
||||
|
||||
uint64 timestamp
|
||||
uint64 request_timestamp
|
||||
uint16 parameter_index
|
||||
|
||||
uint8 ORB_QUEUE_LENGTH = 4
|
||||
|
||||
# TOPICS parameter_set_value_response parameter_remote_set_value_response parameter_primary_set_value_response
|
||||
@ -47,4 +47,4 @@ uint16 ADSB_EMITTER_TYPE_SERVICE_SURFACE=18
|
||||
uint16 ADSB_EMITTER_TYPE_POINT_OBSTACLE=19
|
||||
uint16 ADSB_EMITTER_TYPE_ENUM_END=20
|
||||
|
||||
uint8 ORB_QUEUE_LENGTH = 16
|
||||
uint8 ORB_QUEUE_LENGTH = 8
|
||||
|
||||
@ -216,7 +216,7 @@ const char *orb_get_c_type(unsigned char short_type)
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
uint8_t orb_get_queue_size(const struct orb_metadata *meta)
|
||||
uint8_t orb_get_queue_depth(const struct orb_metadata *meta)
|
||||
{
|
||||
if (meta) {
|
||||
return meta->o_queue;
|
||||
|
||||
@ -234,10 +234,10 @@ extern int orb_get_interval(int handle, unsigned *interval) __EXPORT;
|
||||
const char *orb_get_c_type(unsigned char short_type);
|
||||
|
||||
/**
|
||||
* Returns the queue size of a topic
|
||||
* Returns the queue depth of a topic
|
||||
* @param meta orb topic metadata
|
||||
*/
|
||||
extern uint8_t orb_get_queue_size(const struct orb_metadata *meta);
|
||||
extern uint8_t orb_get_queue_depth(const struct orb_metadata *meta);
|
||||
|
||||
/**
|
||||
* Print a topic to console. Do not call this directly, use print_message() instead.
|
||||
|
||||
@ -48,6 +48,31 @@
|
||||
|
||||
static uORB::SubscriptionInterval *filp_to_subscription(cdev::file_t *filp) { return static_cast<uORB::SubscriptionInterval *>(filp->f_priv); }
|
||||
|
||||
// round up to nearest power of two
|
||||
// Such as 0 => 1, 1 => 1, 2 => 2 ,3 => 4, 10 => 16, 60 => 64, 65...255 => 128
|
||||
// Note: When the input value > 128, the output is always 128
|
||||
static inline uint8_t round_pow_of_two_8(uint8_t n)
|
||||
{
|
||||
if (n == 0) {
|
||||
return 1;
|
||||
}
|
||||
|
||||
// Avoid is already a power of 2
|
||||
uint8_t value = n - 1;
|
||||
|
||||
// Fill 1
|
||||
value |= value >> 1U;
|
||||
value |= value >> 2U;
|
||||
value |= value >> 4U;
|
||||
|
||||
// Unable to round-up, take the value of round-down
|
||||
if (value == UINT8_MAX) {
|
||||
value >>= 1U;
|
||||
}
|
||||
|
||||
return value + 1;
|
||||
}
|
||||
|
||||
uORB::DeviceNode::DeviceNode(const struct orb_metadata *meta, const uint8_t instance, const char *path) :
|
||||
CDev(strdup(path)), // success is checked in CDev::init
|
||||
_meta(meta),
|
||||
|
||||
@ -77,6 +77,24 @@ bool uORB::Manager::terminate()
|
||||
return false;
|
||||
}
|
||||
|
||||
uORB::Manager::Manager()
|
||||
{
|
||||
#ifdef ORB_USE_PUBLISHER_RULES
|
||||
const char *file_name = PX4_STORAGEDIR"/orb_publisher.rules";
|
||||
int ret = readPublisherRulesFromFile(file_name, _publisher_rule);
|
||||
|
||||
if (ret == PX4_OK) {
|
||||
_has_publisher_rules = true;
|
||||
PX4_INFO("Using orb rules from %s", file_name);
|
||||
|
||||
} else {
|
||||
PX4_ERR("Failed to read publisher rules file %s (%s)", file_name, strerror(-ret));
|
||||
}
|
||||
|
||||
#endif /* ORB_USE_PUBLISHER_RULES */
|
||||
|
||||
}
|
||||
|
||||
uORB::Manager::~Manager()
|
||||
{
|
||||
delete _device_master;
|
||||
@ -249,6 +267,30 @@ int uORB::Manager::orb_exists(const struct orb_metadata *meta, int instance)
|
||||
|
||||
orb_advert_t uORB::Manager::orb_advertise_multi(const struct orb_metadata *meta, const void *data, int *instance)
|
||||
{
|
||||
#ifdef ORB_USE_PUBLISHER_RULES
|
||||
|
||||
// check publisher rule
|
||||
if (_has_publisher_rules) {
|
||||
const char *prog_name = px4_get_taskname();
|
||||
|
||||
if (strcmp(_publisher_rule.module_name, prog_name) == 0) {
|
||||
if (_publisher_rule.ignore_other_topics) {
|
||||
if (!findTopic(_publisher_rule, meta->o_name)) {
|
||||
PX4_DEBUG("not allowing %s to publish topic %s", prog_name, meta->o_name);
|
||||
return (orb_advert_t)_Instance;
|
||||
}
|
||||
}
|
||||
|
||||
} else {
|
||||
if (findTopic(_publisher_rule, meta->o_name)) {
|
||||
PX4_DEBUG("not allowing %s to publish topic %s", prog_name, meta->o_name);
|
||||
return (orb_advert_t)_Instance;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
#endif /* ORB_USE_PUBLISHER_RULES */
|
||||
|
||||
/* open the node as an advertiser */
|
||||
int fd = node_open(meta, true, instance);
|
||||
|
||||
@ -293,6 +335,14 @@ orb_advert_t uORB::Manager::orb_advertise_multi(const struct orb_metadata *meta,
|
||||
|
||||
int uORB::Manager::orb_unadvertise(orb_advert_t handle)
|
||||
{
|
||||
#ifdef ORB_USE_PUBLISHER_RULES
|
||||
|
||||
if (handle == _Instance) {
|
||||
return PX4_OK; //pretend success
|
||||
}
|
||||
|
||||
#endif /* ORB_USE_PUBLISHER_RULES */
|
||||
|
||||
return uORB::DeviceNode::unadvertise(handle);
|
||||
}
|
||||
|
||||
@ -314,6 +364,14 @@ int uORB::Manager::orb_unsubscribe(int fd)
|
||||
|
||||
int uORB::Manager::orb_publish(const struct orb_metadata *meta, orb_advert_t handle, const void *data)
|
||||
{
|
||||
#ifdef ORB_USE_PUBLISHER_RULES
|
||||
|
||||
if (handle == _Instance) {
|
||||
return PX4_OK; //pretend success
|
||||
}
|
||||
|
||||
#endif /* ORB_USE_PUBLISHER_RULES */
|
||||
|
||||
return uORB::DeviceNode::publish(meta, handle, data);
|
||||
}
|
||||
|
||||
@ -572,7 +630,7 @@ int16_t uORB::Manager::process_remote_topic(const char *topic_name)
|
||||
// We didn't find a node so we need to create it via an advertisement
|
||||
PX4_DEBUG("Advertising remote topic %s", topic_name);
|
||||
_remote_topics.insert(topic_name);
|
||||
orb_advertise(topic_ptr, nullptr);
|
||||
orb_advertise(topic_ptr, nullptr, topic_ptr->o_queue);
|
||||
|
||||
return 0;
|
||||
}
|
||||
@ -657,3 +715,142 @@ int16_t uORB::Manager::process_received_message(const char *messageName, int32_t
|
||||
}
|
||||
|
||||
#endif /* CONFIG_ORB_COMMUNICATOR */
|
||||
|
||||
#ifdef ORB_USE_PUBLISHER_RULES
|
||||
|
||||
bool uORB::Manager::startsWith(const char *pre, const char *str)
|
||||
{
|
||||
size_t lenpre = strlen(pre),
|
||||
lenstr = strlen(str);
|
||||
return lenstr < lenpre ? false : strncmp(pre, str, lenpre) == 0;
|
||||
}
|
||||
|
||||
bool uORB::Manager::findTopic(const PublisherRule &rule, const char *topic_name)
|
||||
{
|
||||
const char **topics_ptr = rule.topics;
|
||||
|
||||
while (*topics_ptr) {
|
||||
if (strcmp(*topics_ptr, topic_name) == 0) {
|
||||
return true;
|
||||
}
|
||||
|
||||
++topics_ptr;
|
||||
}
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
void uORB::Manager::strTrim(const char **str)
|
||||
{
|
||||
while (**str == ' ' || **str == '\t') { ++(*str); }
|
||||
}
|
||||
|
||||
int uORB::Manager::readPublisherRulesFromFile(const char *file_name, PublisherRule &rule)
|
||||
{
|
||||
FILE *fp;
|
||||
static const int line_len = 1024;
|
||||
int ret = PX4_OK;
|
||||
char *line = new char[line_len];
|
||||
|
||||
if (!line) {
|
||||
return -ENOMEM;
|
||||
}
|
||||
|
||||
fp = fopen(file_name, "r");
|
||||
|
||||
if (fp == NULL) {
|
||||
delete[](line);
|
||||
return -errno;
|
||||
}
|
||||
|
||||
const char *restrict_topics_str = "restrict_topics:";
|
||||
const char *module_str = "module:";
|
||||
const char *ignore_others = "ignore_others:";
|
||||
|
||||
rule.ignore_other_topics = false;
|
||||
rule.module_name = nullptr;
|
||||
rule.topics = nullptr;
|
||||
|
||||
while (fgets(line, line_len, fp) && ret == PX4_OK) {
|
||||
|
||||
if (strlen(line) < 2 || line[0] == '#') {
|
||||
continue;
|
||||
}
|
||||
|
||||
if (startsWith(restrict_topics_str, line)) {
|
||||
//read topics list
|
||||
char *start = line + strlen(restrict_topics_str);
|
||||
strTrim((const char **)&start);
|
||||
char *topics = strdup(start);
|
||||
int topic_len = 0, num_topics = 0;
|
||||
|
||||
for (int i = 0; topics[i]; ++i) {
|
||||
if (topics[i] == ',' || topics[i] == '\n') {
|
||||
if (topic_len > 0) {
|
||||
topics[i] = 0;
|
||||
++num_topics;
|
||||
}
|
||||
|
||||
topic_len = 0;
|
||||
|
||||
} else {
|
||||
++topic_len;
|
||||
}
|
||||
}
|
||||
|
||||
if (num_topics > 0) {
|
||||
rule.topics = new const char *[num_topics + 1];
|
||||
int topic = 0;
|
||||
strTrim((const char **)&topics);
|
||||
rule.topics[topic++] = topics;
|
||||
|
||||
while (topic < num_topics) {
|
||||
if (*topics == 0) {
|
||||
++topics;
|
||||
strTrim((const char **)&topics);
|
||||
rule.topics[topic++] = topics;
|
||||
|
||||
} else {
|
||||
++topics;
|
||||
}
|
||||
}
|
||||
|
||||
rule.topics[num_topics] = nullptr;
|
||||
}
|
||||
|
||||
} else if (startsWith(module_str, line)) {
|
||||
//read module name
|
||||
char *start = line + strlen(module_str);
|
||||
strTrim((const char **)&start);
|
||||
int len = strlen(start);
|
||||
|
||||
if (len > 0 && start[len - 1] == '\n') {
|
||||
start[len - 1] = 0;
|
||||
}
|
||||
|
||||
rule.module_name = strdup(start);
|
||||
|
||||
} else if (startsWith(ignore_others, line)) {
|
||||
const char *start = line + strlen(ignore_others);
|
||||
strTrim(&start);
|
||||
|
||||
if (startsWith("true", start)) {
|
||||
rule.ignore_other_topics = true;
|
||||
}
|
||||
|
||||
} else {
|
||||
PX4_ERR("orb rules file: wrong format: %s", line);
|
||||
ret = -EINVAL;
|
||||
}
|
||||
}
|
||||
|
||||
if (ret == PX4_OK && (!rule.module_name || !rule.topics)) {
|
||||
PX4_ERR("Wrong format in orb publisher rules file");
|
||||
ret = -EINVAL;
|
||||
}
|
||||
|
||||
delete[](line);
|
||||
fclose(fp);
|
||||
return ret;
|
||||
}
|
||||
#endif /* ORB_USE_PUBLISHER_RULES */
|
||||
|
||||
@ -503,7 +503,7 @@ private: // data members
|
||||
DeviceMaster *_device_master{nullptr};
|
||||
|
||||
private: //class methods
|
||||
Manager() = default;
|
||||
Manager();
|
||||
virtual ~Manager();
|
||||
|
||||
#ifdef CONFIG_ORB_COMMUNICATOR
|
||||
@ -559,6 +559,46 @@ private: //class methods
|
||||
*/
|
||||
virtual int16_t process_received_message(const char *messageName, int32_t length, uint8_t *data);
|
||||
#endif /* CONFIG_ORB_COMMUNICATOR */
|
||||
|
||||
#ifdef ORB_USE_PUBLISHER_RULES
|
||||
|
||||
struct PublisherRule {
|
||||
const char **topics; //null-terminated list of topic names
|
||||
const char *module_name; //only this module is allowed to publish one of the topics
|
||||
bool ignore_other_topics;
|
||||
};
|
||||
|
||||
/**
|
||||
* test if str starts with pre
|
||||
*/
|
||||
bool startsWith(const char *pre, const char *str);
|
||||
|
||||
/**
|
||||
* find a topic in a rule
|
||||
*/
|
||||
bool findTopic(const PublisherRule &rule, const char *topic_name);
|
||||
|
||||
/**
|
||||
* trim whitespace from the beginning of a string
|
||||
*/
|
||||
void strTrim(const char **str);
|
||||
|
||||
/**
|
||||
* Read publisher rules from a file. It has the format:
|
||||
*
|
||||
* restrict_topics: <topic1>, <topic2>, <topic3>
|
||||
* module: <module_name>
|
||||
* [ignore_others:true]
|
||||
*
|
||||
* @return 0 on success, <0 otherwise
|
||||
*/
|
||||
int readPublisherRulesFromFile(const char *file_name, PublisherRule &rule);
|
||||
|
||||
PublisherRule _publisher_rule;
|
||||
bool _has_publisher_rules = false;
|
||||
|
||||
#endif /* ORB_USE_PUBLISHER_RULES */
|
||||
|
||||
};
|
||||
|
||||
#endif /* _uORBManager_hpp_ */
|
||||
|
||||
@ -181,7 +181,7 @@ MessageFormatReader::State MessageFormatReader::readMore()
|
||||
}
|
||||
|
||||
// Not expected to get here
|
||||
PX4_ERR("logic error (not expected to get here)");
|
||||
PX4_ERR("logic error");
|
||||
_state = State::Failure;
|
||||
return _state;
|
||||
}
|
||||
@ -237,7 +237,7 @@ int MessageFormatReader::expandMessageFormat(char *format, unsigned len, unsigne
|
||||
}
|
||||
|
||||
if (format_idx + 1 != (int)len) {
|
||||
PX4_ERR("logic error (format_idx %d, len %d)", format_idx, len);
|
||||
PX4_ERR("logic error");
|
||||
return -1;
|
||||
}
|
||||
|
||||
|
||||
@ -574,7 +574,7 @@ int uORBTest::UnitTest::test_wrap_around()
|
||||
bool updated{false};
|
||||
|
||||
// Advertise but not publish topics, only generate device_node, which is convenient for modifying DeviceNode::_generation
|
||||
const int queue_size = orb_get_queue_size(ORB_ID(orb_test_medium_wrap_around));
|
||||
const int queue_size = orb_test_medium_s::ORB_QUEUE_LENGTH;
|
||||
ptopic = orb_advertise(ORB_ID(orb_test_medium_wrap_around), nullptr);
|
||||
|
||||
if (ptopic == nullptr) {
|
||||
@ -828,7 +828,7 @@ int uORBTest::UnitTest::test_queue()
|
||||
return test_fail("subscribe failed: %d", errno);
|
||||
}
|
||||
|
||||
const int queue_size = orb_get_queue_size(ORB_ID(orb_test_medium_queue));
|
||||
const int queue_size = orb_test_medium_s::ORB_QUEUE_LENGTH;
|
||||
orb_test_medium_s t{};
|
||||
ptopic = orb_advertise(ORB_ID(orb_test_medium_queue), &t);
|
||||
|
||||
@ -935,7 +935,7 @@ int uORBTest::UnitTest::pub_test_queue_main()
|
||||
{
|
||||
orb_test_medium_s t{};
|
||||
orb_advert_t ptopic{nullptr};
|
||||
const int queue_size = orb_get_queue_size(ORB_ID(orb_test_medium_queue_poll));
|
||||
const int queue_size = orb_test_medium_s::ORB_QUEUE_LENGTH;
|
||||
|
||||
if ((ptopic = orb_advertise(ORB_ID(orb_test_medium_queue_poll), &t)) == nullptr) {
|
||||
_thread_should_exit = true;
|
||||
|
||||
@ -13,4 +13,4 @@ param set-default -s MC_AT_EN 1
|
||||
|
||||
param set-default -s UAVCAN_ENABLE 2
|
||||
|
||||
set LOGGER_BUF 256
|
||||
set LOGGER_BUF 64
|
||||
|
||||
@ -160,11 +160,6 @@ status_t Argus_InitMode(argus_hnd_t *hnd, s2pi_slave_t spi_slave, argus_mode_t m
|
||||
* Also refer to #Argus_ReinitMode, which uses a specified measurement
|
||||
* mode instead of the currently active measurement mode.
|
||||
*
|
||||
* @note If a full re-initialization is not desired, refer to the
|
||||
* #Argus_RestoreDeviceState function that will only re-write the
|
||||
* register map to the device to restore its state after an power
|
||||
* cycle.
|
||||
*
|
||||
* @param hnd The API handle; contains all internal states and data.
|
||||
*
|
||||
* @return Returns the \link #status_t status\endlink (#STATUS_OK on success).
|
||||
@ -187,11 +182,6 @@ status_t Argus_Reinit(argus_hnd_t *hnd);
|
||||
* Also refer to #Argus_Reinit, which re-uses the currently active
|
||||
* measurement mode instead of an user specified measurement mode.
|
||||
*
|
||||
* @note If a full re-initialization is not desired, refer to the
|
||||
* #Argus_RestoreDeviceState function that will only re-write the
|
||||
* register map to the device to restore its state after an power
|
||||
* cycle.
|
||||
*
|
||||
* @param hnd The API handle; contains all internal states and data.
|
||||
*
|
||||
* @param mode The specified measurement mode to be initialized.
|
||||
@ -284,69 +274,6 @@ argus_hnd_t *Argus_CreateHandle(void);
|
||||
*****************************************************************************/
|
||||
status_t Argus_DestroyHandle(argus_hnd_t *hnd);
|
||||
|
||||
/*!***************************************************************************
|
||||
* @brief Restores the device state with a re-write of all register values.
|
||||
*
|
||||
* @details The function invalidates and restores the device state by executing
|
||||
* a re-write of the full register map.
|
||||
*
|
||||
* The purpose of this function is to recover from known external
|
||||
* events like power cycles, for example due to sleep / wake-up
|
||||
* functionality. This can be implemented by cutting off the external
|
||||
* power supply of the device (e.g. via a MOSFET switch controlled by
|
||||
* a GPIB pin). By calling this function, the expected state of the
|
||||
* API is written to the device without the need to fully re-initialize
|
||||
* the device. Thus, the API can resume where it has stopped as if
|
||||
* there has never been a power cycle.
|
||||
*
|
||||
* The internal state machines like the dynamic configuration adaption
|
||||
* (DCA) algorithm will not be reseted. The API/sensor will immediately
|
||||
* resume at the last state that was optimized for the given
|
||||
* environmental conditions.
|
||||
*
|
||||
* The use case of sleep / wake-up can be implemented as follows:
|
||||
*
|
||||
* 1. In case of ongoing measurements, stop the measurements via
|
||||
* the #Argus_StopMeasurementTimer function (if started by the
|
||||
* #Argus_StartMeasurementTimer function).
|
||||
*
|
||||
* 2. Shut down the device by removing the 5V power supply, e.g.
|
||||
* via a GPIO pin that switches a MOSFET circuit.
|
||||
*
|
||||
* 3. After the desired sleep period, power the device by switching
|
||||
* the 5V power supply on again. Wait until the power-on-reset
|
||||
* (POR) is finished (approx. 1 ms) or just repeat step 4 until
|
||||
* it succeeds.
|
||||
*
|
||||
* 4. Call the #Argus_RestoreDeviceState function to trigger the
|
||||
* restoration of the device state in the API. Note that the
|
||||
* function will return an error code if it fails. One can repeat
|
||||
* the execution of that function a few times until it succeeds.
|
||||
*
|
||||
* 6. Continue with measurements via #Argus_StartMeasurementTimer
|
||||
* of #Argus_TriggerMeasurement functions as desired.
|
||||
*
|
||||
* @note If a complete re-initialization (= soft-reset) is desired, see
|
||||
* the #Argus_Reinit functionality.
|
||||
*
|
||||
* @note Changing a configuration or calibration parameter will always
|
||||
* invalidate the device state as well as the state machine of the
|
||||
* dynamic configuration adaption (DCA) algorithm. In that case, the
|
||||
* device/API needs a few measurements to adopt to the present
|
||||
* environmental conditions before the first valid measurement result
|
||||
* can be obtained. This is almost similar to re-initializing the
|
||||
* device (see #Argus_Reinit) which would also re-read the EEPROM.
|
||||
* On the other hand, the #Argus_RestoreDeviceState does not reset
|
||||
* or re-initialize anything. It just makes sure that the device
|
||||
* register map (which has changed to its reset values after the
|
||||
* power cycle) is what the API expects upon the next measurement.
|
||||
*
|
||||
* @param hnd The device handle object to be invalidated.
|
||||
*
|
||||
* @return Returns the \link #status_t status\endlink (#STATUS_OK on success).
|
||||
*****************************************************************************/
|
||||
status_t Argus_RestoreDeviceState(argus_hnd_t *hnd);
|
||||
|
||||
/*!**************************************************************************
|
||||
* Generic API
|
||||
****************************************************************************/
|
||||
@ -799,7 +726,7 @@ status_t Argus_ExecuteXtalkCalibrationSequence(argus_hnd_t *hnd);
|
||||
* After calibration has finished successfully, the obtained data is
|
||||
* applied immediately and can be read from the API using the
|
||||
* #Argus_GetCalibrationPixelRangeOffsets or
|
||||
* #Argus_GetCalibrationGlobalRangeOffsets function.
|
||||
* #Argus_GetCalibrationGlobalRangeOffset function.
|
||||
*
|
||||
* @param hnd The API handle; contains all internal states and data.
|
||||
* @return Returns the \link #status_t status\endlink (#STATUS_OK on success).
|
||||
@ -848,7 +775,7 @@ status_t Argus_ExecuteRelativeRangeOffsetCalibrationSequence(argus_hnd_t *hnd);
|
||||
* After calibration has finished successfully, the obtained data is
|
||||
* applied immediately and can be read from the API using the
|
||||
* #Argus_GetCalibrationPixelRangeOffsets or
|
||||
* #Argus_GetCalibrationGlobalRangeOffsets function.
|
||||
* #Argus_GetCalibrationGlobalRangeOffset function.
|
||||
*
|
||||
* @param hnd The API handle; contains all internal states and data.
|
||||
* @param targetRange The absolute range between the reference plane and the
|
||||
@ -1116,40 +1043,28 @@ status_t Argus_GetConfigurationUnambiguousRange(argus_hnd_t *hnd,
|
||||
****************************************************************************/
|
||||
|
||||
/*!***************************************************************************
|
||||
* @brief Sets the global range offset values to a specified device.
|
||||
* @brief Sets the global range offset value to a specified device.
|
||||
*
|
||||
* @details The global range offsets are subtracted from the raw range values.
|
||||
* There are two distinct values that are applied in low or high
|
||||
* power stage setting respectively.
|
||||
* @details The global range offset is subtracted from the raw range values.
|
||||
*
|
||||
* @param hnd The API handle; contains all internal states and data.
|
||||
* @param offset_low The new global range offset for the low power stage in
|
||||
* meter and Q0.15 format.
|
||||
* @param offset_high The new global range offset for the high power stage in
|
||||
* meter and Q0.15 format.
|
||||
* @param value The new global range offset in meter and Q0.15 format.
|
||||
* @return Returns the \link #status_t status\endlink (#STATUS_OK on success).
|
||||
*****************************************************************************/
|
||||
status_t Argus_SetCalibrationGlobalRangeOffsets(argus_hnd_t *hnd,
|
||||
q0_15_t offset_low,
|
||||
q0_15_t offset_high);
|
||||
status_t Argus_SetCalibrationGlobalRangeOffset(argus_hnd_t *hnd,
|
||||
q0_15_t value);
|
||||
|
||||
/*!***************************************************************************
|
||||
* @brief Gets the global range offset values from a specified device.
|
||||
* @brief Gets the global range offset value from a specified device.
|
||||
*
|
||||
* @details The global range offsets are subtracted from the raw range values.
|
||||
* There are two distinct values that are applied in low or high
|
||||
* power stage setting respectively.
|
||||
* @details The global range offset is subtracted from the raw range values.
|
||||
*
|
||||
* @param hnd The API handle; contains all internal states and data.
|
||||
* @param offset_low The current range offset for the low power stage in
|
||||
* meter and Q0.15 format.
|
||||
* @param offset_high The current global range offset for the high power stage
|
||||
* in meter and Q0.15 format.
|
||||
* @param value The current global range offset in meter and Q0.15 format.
|
||||
* @return Returns the \link #status_t status\endlink (#STATUS_OK on success).
|
||||
*****************************************************************************/
|
||||
status_t Argus_GetCalibrationGlobalRangeOffsets(argus_hnd_t *hnd,
|
||||
q0_15_t *offset_low,
|
||||
q0_15_t *offset_high);
|
||||
status_t Argus_GetCalibrationGlobalRangeOffset(argus_hnd_t *hnd,
|
||||
q0_15_t *value);
|
||||
|
||||
/*!***************************************************************************
|
||||
* @brief Sets the relative pixel offset table to a specified device.
|
||||
|
||||
@ -210,13 +210,9 @@ typedef enum argus_dca_gain_t {
|
||||
* - [9]: #ARGUS_STATE_LASER_ERROR
|
||||
* - [10]: #ARGUS_STATE_HAS_DATA
|
||||
* - [11]: #ARGUS_STATE_HAS_AUX_DATA
|
||||
* - [12]: #ARGUS_STATE_SATURATED_PIXELS
|
||||
* - [12]: #ARGUS_STATE_DCA_MAX
|
||||
* - [13]: DCA Power Stage
|
||||
* - [14-15]: DCA Gain Stages
|
||||
* - [16]: #ARGUS_STATE_DCA_MIN
|
||||
* - [17]: #ARGUS_STATE_DCA_MAX
|
||||
* - [18]: #ARGUS_STATE_DCA_RESET
|
||||
* - [18-31]: not used
|
||||
* .
|
||||
*****************************************************************************/
|
||||
typedef enum argus_state_t {
|
||||
@ -233,35 +229,36 @@ typedef enum argus_state_t {
|
||||
* - 1: Enabled: measurement with detuned frequency. */
|
||||
ARGUS_STATE_DUAL_FREQ_MODE = 1U << 1U,
|
||||
|
||||
/*! 0x0004: Measurement Frequency for Dual Frequency Mode \n
|
||||
/*! 0x0004: Measurement Frequency for Dual Frequency Mode
|
||||
* (only if #ARGUS_STATE_DUAL_FREQ_MODE flag is set).
|
||||
* - 0: A-Frame w/ detuned frequency,
|
||||
* - 1: B-Frame w/ detuned frequency */
|
||||
ARGUS_STATE_MEASUREMENT_FREQ = 1U << 2U,
|
||||
|
||||
/*! 0x0008: Debug Mode. \n
|
||||
* If set, the range value of erroneous pixels
|
||||
/*! 0x0008: Debug Mode. If set, the range value of erroneous pixels
|
||||
* are not cleared or reset.
|
||||
* - 0: Disabled (default).
|
||||
* - 1: Enabled. */
|
||||
ARGUS_STATE_DEBUG_MODE = 1U << 3U,
|
||||
|
||||
/*! 0x0010: Weak Signal Flag. \n
|
||||
/*! 0x0010: Weak Signal Flag.
|
||||
* Set whenever the Pixel Binning Algorithm is detecting a
|
||||
* weak signal, i.e. if the amplitude dies not reach its
|
||||
* (absolute) threshold.
|
||||
* (absolute) threshold. If the Golden Pixel is enabled,
|
||||
* this also indicates that the Pixel Binning Algorithm
|
||||
* falls back to the Golden Pixel.
|
||||
* - 0: Normal Signal.
|
||||
* - 1: Weak Signal. */
|
||||
* - 1: Weak Signal or Golden Pixel Mode. */
|
||||
ARGUS_STATE_WEAK_SIGNAL = 1U << 4U,
|
||||
|
||||
/*! 0x0020: Background Light Warning Flag. \n
|
||||
/*! 0x0020: Background Light Warning Flag.
|
||||
* Set whenever the background light is very high and the
|
||||
* measurement data might be unreliable.
|
||||
* - 0: No Warning: Background Light is within valid range.
|
||||
* - 1: Warning: Background Light is very high. */
|
||||
ARGUS_STATE_BGL_WARNING = 1U << 5U,
|
||||
|
||||
/*! 0x0040: Background Light Error Flag. \n
|
||||
/*! 0x0040: Background Light Error Flag.
|
||||
* Set whenever the background light is too high and the
|
||||
* measurement data is unreliable or invalid.
|
||||
* - 0: No Error: Background Light is within valid range.
|
||||
@ -273,7 +270,7 @@ typedef enum argus_state_t {
|
||||
* - 1: PLL locked at start of integration. */
|
||||
ARGUS_STATE_PLL_LOCKED = 1U << 7U,
|
||||
|
||||
/*! 0x0100: Laser Failure Warning Flag. \n
|
||||
/*! 0x0100: Laser Failure Warning Flag.
|
||||
* Set whenever the an invalid system condition is detected.
|
||||
* (i.e. DCA at max state but no amplitude on any (incl. reference)
|
||||
* pixel, not amplitude but any saturated pixel).
|
||||
@ -282,7 +279,7 @@ typedef enum argus_state_t {
|
||||
* condition stays, a laser malfunction error is raised. */
|
||||
ARGUS_STATE_LASER_WARNING = 1U << 8U,
|
||||
|
||||
/*! 0x0200: Laser Failure Error Flag. \n
|
||||
/*! 0x0200: Laser Failure Error Flag.
|
||||
* Set whenever a laser malfunction error is raised and the
|
||||
* system is put into a safe state.
|
||||
* - 0: No Error: Laser is operating properly.
|
||||
@ -300,12 +297,13 @@ typedef enum argus_state_t {
|
||||
* - 1: Auxiliary data is available and correctly evaluated. */
|
||||
ARGUS_STATE_HAS_AUX_DATA = 1U << 11U,
|
||||
|
||||
/*! 0x0100: Pixel Saturation Flag. \n
|
||||
* Set whenever any pixel is saturated, i.e. its pixel state is
|
||||
* #PIXEL_SAT
|
||||
* - 0: No saturated pixels.
|
||||
* - 1: Any saturated pixels. */
|
||||
ARGUS_STATE_SATURATED_PIXELS = 1U << 12U,
|
||||
/*! 0x1000: DCA Maximum State Flag.
|
||||
* Set whenever the DCA has extended all its parameters to their
|
||||
* maximum values and can not increase the integration energy any
|
||||
* further.
|
||||
* - 0: DCA has not yet reached its maximum state.
|
||||
* - 1: DCA has reached its maximum state and can not increase any further. */
|
||||
ARGUS_STATE_DCA_MAX = 1U << 12U,
|
||||
|
||||
/*! 0x2000: DCA is in high Optical Output Power stage. */
|
||||
ARGUS_STATE_DCA_POWER_HIGH = DCA_POWER_HIGH << ARGUS_STATE_DCA_POWER_SHIFT,
|
||||
@ -322,31 +320,6 @@ typedef enum argus_state_t {
|
||||
/*! 0xC000: DCA is in high Pixel Input Gain stage. */
|
||||
ARGUS_STATE_DCA_GAIN_HIGH = DCA_GAIN_HIGH << ARGUS_STATE_DCA_GAIN_SHIFT,
|
||||
|
||||
/*! 0x10000: DCA Minimum State Flag. \n
|
||||
* Set whenever the DCA has reduced all its parameters to their
|
||||
* minimum values and it can not decrease the integration energy
|
||||
* any further.
|
||||
* - 0: DCA has not yet reached its minimum state.
|
||||
* - 1: DCA has reached its minimum state and can not decrease
|
||||
* its parameters any further. */
|
||||
ARGUS_STATE_DCA_MIN = 1U << 16U,
|
||||
|
||||
/*! 0x20000: DCA Maximum State Flag. \n
|
||||
* Set whenever the DCA has extended all its parameters to their
|
||||
* maximum values and it can not increase the integration energy
|
||||
* any further.
|
||||
* - 0: DCA has not yet reached its maximum state.
|
||||
* - 1: DCA has reached its maximum state and can not increase
|
||||
* its parameters any further. */
|
||||
ARGUS_STATE_DCA_MAX = 1U << 17U,
|
||||
|
||||
/*! 0x20000: DCA Reset State Flag. \n
|
||||
* Set whenever the DCA is resetting all its parameters to their
|
||||
* minimum values because it has detected too many saturated pixels.
|
||||
* - 0: DCA is operating in normal mode.
|
||||
* - 1: DCA is performing a reset. */
|
||||
ARGUS_STATE_DCA_RESET = 1U << 18U,
|
||||
|
||||
} argus_state_t;
|
||||
|
||||
/*!***************************************************************************
|
||||
|
||||
@ -58,7 +58,6 @@ extern "C" {
|
||||
*****************************************************************************/
|
||||
|
||||
#include "utility/int_math.h"
|
||||
#include <stdbool.h>
|
||||
#include <assert.h>
|
||||
|
||||
|
||||
@ -139,13 +138,6 @@ extern "C" {
|
||||
#define PIXEL_CH2N(c) (((((c) << 1U) ^ 0x1CU) & 0x1CU) | (((c) >> 3U) & 0x02U) | ((c) & 0x01U))
|
||||
|
||||
|
||||
/*!*****************************************************************************
|
||||
* @brief Macro to create a pixel mask given by the pixels n-index.
|
||||
* @param n n-index of the pixel.
|
||||
* @return The pixel mask with only n-index pixel set.
|
||||
******************************************************************************/
|
||||
#define PIXELN_MASK(n) (0x01U << (n))
|
||||
|
||||
/*!*****************************************************************************
|
||||
* @brief Macro to determine if a pixel given by the n-index is enabled in a pixel mask.
|
||||
* @param msk 32-bit pixel mask
|
||||
@ -159,23 +151,16 @@ extern "C" {
|
||||
* @param msk 32-bit pixel mask
|
||||
* @param n n-index of the pixel to enable.
|
||||
******************************************************************************/
|
||||
#define PIXELN_ENABLE(msk, n) ((msk) |= (PIXELN_MASK(n)))
|
||||
#define PIXELN_ENABLE(msk, n) ((msk) |= (0x01U << (n)))
|
||||
|
||||
/*!*****************************************************************************
|
||||
* @brief Macro disable a pixel given by the n-index in a pixel mask.
|
||||
* @param msk 32-bit pixel mask
|
||||
* @param n n-index of the pixel to disable.
|
||||
******************************************************************************/
|
||||
#define PIXELN_DISABLE(msk, n) ((msk) &= (~PIXELN_MASK(n)))
|
||||
#define PIXELN_DISABLE(msk, n) ((msk) &= (~(0x01U << (n))))
|
||||
|
||||
|
||||
/*!*****************************************************************************
|
||||
* @brief Macro to create a pixel mask given by the pixels ADC channel number.
|
||||
* @param c The ADC channel number of the pixel.
|
||||
* @return The 32-bit pixel mask with only pixel ADC channel set.
|
||||
******************************************************************************/
|
||||
#define PIXELCH_MASK(c) (0x01U << (PIXEL_CH2N(c)))
|
||||
|
||||
/*!*****************************************************************************
|
||||
* @brief Macro to determine if an ADC pixel channel is enabled from a pixel mask.
|
||||
* @param msk The 32-bit pixel mask
|
||||
@ -199,14 +184,6 @@ extern "C" {
|
||||
#define PIXELCH_DISABLE(msk, c) (PIXELN_DISABLE(msk, PIXEL_CH2N(c)))
|
||||
|
||||
|
||||
/*!*****************************************************************************
|
||||
* @brief Macro to create a pixel mask given by the pixel x-y-indices.
|
||||
* @param x x-index of the pixel.
|
||||
* @param y y-index of the pixel.
|
||||
* @return The 32-bit pixel mask with only pixel ADC channel set.
|
||||
******************************************************************************/
|
||||
#define PIXELXY_MASK(x, y) (0x01U << (PIXEL_XY2N(x, y)))
|
||||
|
||||
/*!*****************************************************************************
|
||||
* @brief Macro to determine if a pixel given by the x-y-indices is enabled in a pixel mask.
|
||||
* @param msk 32-bit pixel mask
|
||||
@ -360,10 +337,10 @@ static inline uint32_t ShiftSelectedPixels(const uint32_t pixel_mask,
|
||||
|
||||
uint32_t shifted_mask = 0;
|
||||
|
||||
for (int8_t x = 0; x < ARGUS_PIXELS_X; ++x) {
|
||||
for (int8_t y = 0; y < ARGUS_PIXELS_Y; ++y) {
|
||||
int8_t x_src = (int8_t)(x - dx);
|
||||
int8_t y_src = (int8_t)(y - dy);
|
||||
for (uint8_t x = 0; x < ARGUS_PIXELS_X; ++x) {
|
||||
for (uint8_t y = 0; y < ARGUS_PIXELS_Y; ++y) {
|
||||
int8_t x_src = x - dx;
|
||||
int8_t y_src = y - dy;
|
||||
|
||||
if (dy & 0x1) {
|
||||
/* Compensate for hexagonal pixel shape. */
|
||||
@ -432,8 +409,8 @@ static inline uint32_t FillPixelMask(uint32_t pixel_mask,
|
||||
int8_t min_y = -1;
|
||||
|
||||
/* Find nearest not selected pixel. */
|
||||
for (int8_t x = 0; x < ARGUS_PIXELS_X; ++x) {
|
||||
for (int8_t y = 0; y < ARGUS_PIXELS_Y; ++y) {
|
||||
for (uint8_t x = 0; x < ARGUS_PIXELS_X; ++x) {
|
||||
for (uint8_t y = 0; y < ARGUS_PIXELS_Y; ++y) {
|
||||
if (!PIXELXY_ISENABLED(pixel_mask, x, y)) {
|
||||
int32_t distx = (x - center_x) << 1;
|
||||
|
||||
@ -446,8 +423,8 @@ static inline uint32_t FillPixelMask(uint32_t pixel_mask,
|
||||
|
||||
if (dist < min_dist) {
|
||||
min_dist = dist;
|
||||
min_x = (int8_t)x;
|
||||
min_y = (int8_t)y;
|
||||
min_x = x;
|
||||
min_y = y;
|
||||
}
|
||||
}
|
||||
}
|
||||
@ -461,64 +438,6 @@ static inline uint32_t FillPixelMask(uint32_t pixel_mask,
|
||||
|
||||
return pixel_mask;
|
||||
}
|
||||
|
||||
/*!*****************************************************************************
|
||||
* @brief Fills a pixel mask with the direct neighboring pixels around a pixel.
|
||||
*
|
||||
* @details The pixel mask is iteratively filled with the direct neighbors of the
|
||||
* specified center pixel.
|
||||
*
|
||||
* Note that the function is able to handle corner and edge pixels and
|
||||
* also to handle odd/even lines (which have different layouts)
|
||||
*
|
||||
* @param x The selected pixel x-index.
|
||||
* @param y The selected pixel y-index.
|
||||
* @return The filled pixel mask with all direct neighbors of the selected pixel.
|
||||
******************************************************************************/
|
||||
static inline uint32_t GetAdjacentPixelsMask(const uint_fast8_t x,
|
||||
const uint_fast8_t y)
|
||||
{
|
||||
assert(x < ARGUS_PIXELS_X);
|
||||
assert(y < ARGUS_PIXELS_Y);
|
||||
|
||||
uint32_t mask = 0u;
|
||||
|
||||
bool isXEdgeLow = (x == 0);
|
||||
bool isXEdgeHigh = (x == (ARGUS_PIXELS_X - 1));
|
||||
bool isYEdgeLow = (y == 0);
|
||||
bool isYEdgeHigh = (y == (ARGUS_PIXELS_Y - 1));
|
||||
|
||||
if (y % 2 == 0) {
|
||||
if (!isYEdgeLow) { PIXELXY_ENABLE(mask, x, y - 1); }
|
||||
|
||||
if ((!isXEdgeHigh) && (!isYEdgeLow)) { PIXELXY_ENABLE(mask, x + 1, y - 1); }
|
||||
|
||||
if (!isXEdgeHigh) { PIXELXY_ENABLE(mask, x + 1, y); }
|
||||
|
||||
if ((!isXEdgeHigh) && (!isYEdgeHigh)) { PIXELXY_ENABLE(mask, x + 1, y + 1); }
|
||||
|
||||
if (!isYEdgeHigh) { PIXELXY_ENABLE(mask, x, y + 1); }
|
||||
|
||||
if (!isXEdgeLow) { PIXELXY_ENABLE(mask, x - 1, y); }
|
||||
|
||||
} else {
|
||||
if ((!isXEdgeLow) && (!isYEdgeLow)) { PIXELXY_ENABLE(mask, x - 1, y - 1); }
|
||||
|
||||
if (!isYEdgeLow) { PIXELXY_ENABLE(mask, x, y - 1); }
|
||||
|
||||
if (!isXEdgeHigh) { PIXELXY_ENABLE(mask, x + 1, y); }
|
||||
|
||||
if (!isYEdgeHigh) { PIXELXY_ENABLE(mask, x, y + 1); }
|
||||
|
||||
if ((!isXEdgeLow) && (!isYEdgeHigh)) { PIXELXY_ENABLE(mask, x - 1, y + 1); }
|
||||
|
||||
if (!isXEdgeLow) { PIXELXY_ENABLE(mask, x - 1, y); }
|
||||
}
|
||||
|
||||
return mask;
|
||||
}
|
||||
|
||||
|
||||
/*! @} */
|
||||
#ifdef __cplusplus
|
||||
} // extern "C"
|
||||
|
||||
170
src/drivers/distance_sensor/broadcom/afbrs50/Inc/api/argus_msk.h
Normal file
170
src/drivers/distance_sensor/broadcom/afbrs50/Inc/api/argus_msk.h
Normal file
@ -0,0 +1,170 @@
|
||||
/*************************************************************************//**
|
||||
* @file
|
||||
* @brief This file is part of the AFBR-S50 API.
|
||||
* @details Defines macros to work with pixel and ADC channel masks.
|
||||
*
|
||||
* @copyright
|
||||
*
|
||||
* Copyright (c) 2021, Broadcom Inc
|
||||
* 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 of the copyright holder 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 HOLDER 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.
|
||||
*****************************************************************************/
|
||||
|
||||
#ifndef ARGUS_MSK_H
|
||||
#define ARGUS_MSK_H
|
||||
|
||||
/*!***************************************************************************
|
||||
* @defgroup argusmap ADC Channel Mapping
|
||||
* @ingroup argusres
|
||||
*
|
||||
* @brief Pixel ADC Channel (n) to x-y-Index Mapping
|
||||
*
|
||||
* @details The ADC Channels of each pixel or auxiliary channel on the device
|
||||
* is numbered in a way that is convenient on the chip. The macros
|
||||
* in this module are defined in order to obtain the x-y-indices of
|
||||
* each channel and vice versa.
|
||||
*
|
||||
* @addtogroup argusmap
|
||||
* @{
|
||||
*****************************************************************************/
|
||||
|
||||
#include "api/argus_def.h"
|
||||
#include "utility/int_math.h"
|
||||
|
||||
/*!*****************************************************************************
|
||||
* @brief Macro to determine the channel number of an specified Pixel.
|
||||
* @param x The x index of the pixel.
|
||||
* @param y The y index of the pixel.
|
||||
* @return The channel number n of the pixel.
|
||||
******************************************************************************/
|
||||
#define PIXEL_XY2N(x, y) ((((x) ^ 7) << 1) | ((y) & 2) << 3 | ((y) & 1))
|
||||
|
||||
/*!*****************************************************************************
|
||||
* @brief Macro to determine the x index of an specified Pixel channel.
|
||||
* @param n The channel number of the pixel.
|
||||
* @return The x index number of the pixel.
|
||||
******************************************************************************/
|
||||
#define PIXEL_N2X(n) ((((n) >> 1U) & 7) ^ 7)
|
||||
|
||||
/*!*****************************************************************************
|
||||
* @brief Macro to determine the y index of an specified Pixel channel.
|
||||
* @param n The channel number of the pixel.
|
||||
* @return The y index number of the pixel.
|
||||
******************************************************************************/
|
||||
#define PIXEL_N2Y(n) (((n) & 1U) | (((n) >> 3) & 2U))
|
||||
|
||||
/*!*****************************************************************************
|
||||
* @brief Macro to determine if a ADC Pixel channel was enabled from a pixel mask.
|
||||
* @param msk The 32-bit pixel mask
|
||||
* @param ch The channel number of the pixel.
|
||||
* @return True if the pixel channel n was enabled, false elsewise.
|
||||
******************************************************************************/
|
||||
#define PIXELN_ISENABLED(msk, ch) (((msk) >> (ch)) & 0x01U)
|
||||
|
||||
/*!*****************************************************************************
|
||||
* @brief Macro enables an ADC Pixel channel in a pixel mask.
|
||||
* @param msk The 32-bit pixel mask
|
||||
* @param ch The channel number of the pixel.
|
||||
******************************************************************************/
|
||||
#define PIXELN_ENABLE(msk, ch) ((msk) |= (0x01U << (ch)))
|
||||
|
||||
/*!*****************************************************************************
|
||||
* @brief Macro disables an ADC Pixel channel in a pixel mask.
|
||||
* @param msk The 32-bit pixel mask
|
||||
* @param ch The channel number of the pixel.
|
||||
******************************************************************************/
|
||||
#define PIXELN_DISABLE(msk, ch) ((msk) &= (~(0x01U << (ch))))
|
||||
|
||||
/*!*****************************************************************************
|
||||
* @brief Macro to determine if an ADC Pixel channel was enabled from a pixel mask.
|
||||
* @param msk 32-bit pixel mask
|
||||
* @param x x index of the pixel.
|
||||
* @param y y index of the pixel.
|
||||
* @return True if the pixel (x,y) was enabled, false elsewise.
|
||||
******************************************************************************/
|
||||
#define PIXELXY_ISENABLED(msk, x, y) (PIXELN_ISENABLED(msk, PIXEL_XY2N(x, y)))
|
||||
|
||||
/*!*****************************************************************************
|
||||
* @brief Macro enables an ADC Pixel channel in a pixel mask.
|
||||
* @param msk 32-bit pixel mask
|
||||
* @param x x index of the pixel.
|
||||
* @param y y index of the pixel.
|
||||
******************************************************************************/
|
||||
#define PIXELXY_ENABLE(msk, x, y) (PIXELN_ENABLE(msk, PIXEL_XY2N(x, y)))
|
||||
|
||||
/*!*****************************************************************************
|
||||
* @brief Macro disables an ADC Pixel channel in a pixel mask.
|
||||
* @param msk 32-bit pixel mask
|
||||
* @param x x index of the pixel.
|
||||
* @param y y index of the pixel.
|
||||
******************************************************************************/
|
||||
#define PIXELXY_DISABLE(msk, x, y) (PIXELN_DISABLE(msk, PIXEL_XY2N(x, y)))
|
||||
|
||||
/*!*****************************************************************************
|
||||
* @brief Macro to determine if a ADC channel was enabled from a channel mask.
|
||||
* @param msk 32-bit channel mask
|
||||
* @param ch channel number of the ADC channel.
|
||||
* @return True if the ADC channel n was enabled, false elsewise.
|
||||
******************************************************************************/
|
||||
#define CHANNELN_ISENABLED(msk, ch) (((msk) >> ((ch) - 32U)) & 0x01U)
|
||||
|
||||
/*!*****************************************************************************
|
||||
* @brief Macro to determine if a ADC channel was enabled from a channel mask.
|
||||
* @param msk 32-bit channel mask
|
||||
* @param ch channel number of the ADC channel.
|
||||
* @return True if the ADC channel n was enabled, false elsewise.
|
||||
******************************************************************************/
|
||||
#define CHANNELN_ENABLE(msk, ch) ((msk) |= (0x01U << ((ch) - 32U)))
|
||||
|
||||
/*!*****************************************************************************
|
||||
* @brief Macro to determine if a ADC channel was enabled from a channel mask.
|
||||
* @param msk 32-bit channel mask
|
||||
* @param ch channel number of the ADC channel.
|
||||
* @return True if the ADC channel n was enabled, false elsewise.
|
||||
******************************************************************************/
|
||||
#define CHANNELN_DISABLE(msk, ch) ((msk) &= (~(0x01U << ((ch) - 32U))))
|
||||
|
||||
|
||||
/*!*****************************************************************************
|
||||
* @brief Macro to determine the number of enabled pixel channels via a popcount
|
||||
* algorithm.
|
||||
* @param pxmsk 32-bit pixel mask
|
||||
* @return The count of enabled pixel channels.
|
||||
******************************************************************************/
|
||||
#define PIXEL_COUNT(pxmsk) popcount(pxmsk)
|
||||
|
||||
/*!*****************************************************************************
|
||||
* @brief Macro to determine the number of enabled channels via a popcount
|
||||
* algorithm.
|
||||
* @param pxmsk 32-bit pixel mask
|
||||
* @param chmsk 32-bit channel mask
|
||||
* @return The count of enabled ADC channels.
|
||||
******************************************************************************/
|
||||
#define CHANNEL_COUNT(pxmsk, chmsk) (popcount(pxmsk) + popcount(chmsk))
|
||||
|
||||
/*! @} */
|
||||
#endif /* ARGUS_MSK_H */
|
||||
@ -36,9 +36,6 @@
|
||||
|
||||
#ifndef ARGUS_OFFSET_H
|
||||
#define ARGUS_OFFSET_H
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
/*!***************************************************************************
|
||||
* @addtogroup argus_cal
|
||||
@ -51,26 +48,12 @@ extern "C" {
|
||||
* @brief Pixel Range Offset Table.
|
||||
* @details Contains pixel range offset values for all 32 active pixels.
|
||||
*****************************************************************************/
|
||||
typedef union argus_cal_offset_table_t {
|
||||
struct {
|
||||
/*! The offset values table for Low Power Stage of all 32 pixels.
|
||||
* Unit: meter; Format: Q0.15 */
|
||||
q0_15_t LowPower[ARGUS_PIXELS_X][ARGUS_PIXELS_Y];
|
||||
|
||||
/*! The offset values table for High Power Stage of all 32 pixels.
|
||||
* Unit: meter; Format: Q0.15 */
|
||||
q0_15_t HighPower[ARGUS_PIXELS_X][ARGUS_PIXELS_Y];
|
||||
};
|
||||
|
||||
/*! The offset values table for Low/High Power Stages of all 32 pixels.
|
||||
* Unit: meter; Format: Q0.15 */
|
||||
q0_15_t Table[ARGUS_DCA_POWER_STAGE_COUNT][ARGUS_PIXELS_X][ARGUS_PIXELS_Y];
|
||||
typedef struct argus_cal_offset_table_t {
|
||||
/*! The offset values per pixel in meter and Q0.15 format. */
|
||||
q0_15_t Table[ARGUS_PIXELS_X][ARGUS_PIXELS_Y];
|
||||
|
||||
} argus_cal_offset_table_t;
|
||||
|
||||
|
||||
/*! @} */
|
||||
#ifdef __cplusplus
|
||||
} // extern "C"
|
||||
#endif
|
||||
#endif /* ARGUS_OFFSET_T */
|
||||
|
||||
@ -55,11 +55,11 @@ extern "C" {
|
||||
* information from the filtered pixels by averaging them in a
|
||||
* specified way.
|
||||
*
|
||||
* Basically, the Pixel Binning Algorithm is a multi-stage filter:
|
||||
* The Pixel Binning Algorithm is a three-stage filter with a
|
||||
* fallback value:
|
||||
*
|
||||
* -# A fixed pre-filter mask is applied to statically disable
|
||||
* specified pixels.
|
||||
*
|
||||
* -# A relative and absolute amplitude filter is applied in the
|
||||
* second stage. The relative filter is determined by a ratio
|
||||
* of the maximum amplitude off all available (i.e. not filtered
|
||||
@ -75,28 +75,12 @@ extern "C" {
|
||||
* selected and considered for the final 1D distance. The
|
||||
* absolute threshold is used to dismiss pixels that are below
|
||||
* the noise level. The latter would be considered for the 1D
|
||||
* result if the maximum amplitude is already very low.\n
|
||||
* Those threshold are implemented using a hysteresis behavior.
|
||||
* For its configuration, see the following parameters:
|
||||
* - #argus_cfg_pba_t::RelativeAmplitudeInclusion
|
||||
* - #argus_cfg_pba_t::RelativeAmplitudeExclusion
|
||||
* - #argus_cfg_pba_t::AbsoluteAmplitudeInclusion
|
||||
* - #argus_cfg_pba_t::AbsoluteAmplitudeExclusion
|
||||
* .
|
||||
*
|
||||
* result if the maximum amplitude is already very low.
|
||||
* -# An absolute minimum distance filter is applied in addition
|
||||
* to the amplitude filter. This removes all pixel that have
|
||||
* a lower distance than the specified threshold. This is used
|
||||
* to remove invalid pixels that can be detected by a physically
|
||||
* not correct negative distance.\n
|
||||
* For its configuration, see the following parameters:
|
||||
* - #PBA_ENABLE_MIN_DIST_SCOPE
|
||||
* - #argus_cfg_pba_t::AbsoluteDistanceScopeInclusion
|
||||
* - #argus_cfg_pba_t::AbsoluteDistanceScopeExclusion
|
||||
* - #argus_cfg_pba_t::RelativeDistanceScopeInclusion
|
||||
* - #argus_cfg_pba_t::RelativeDistanceScopeExclusion
|
||||
* .
|
||||
*
|
||||
* not correct negative distance.
|
||||
* -# A distance filter is used to distinguish pixels that target
|
||||
* the actual object from pixels that see the brighter background,
|
||||
* e.g. white walls. Thus, the pixel with the minimum distance
|
||||
@ -106,31 +90,11 @@ extern "C" {
|
||||
* determined by an relative (to the current minimum distance)
|
||||
* and an absolute value. The larger scope value is the
|
||||
* relevant one, i.e. the relative distance scope can be used
|
||||
* to heed the increasing noise at larger distances.\n
|
||||
* For its configuration, see the following parameters:
|
||||
* - #argus_cfg_pba_t::AbsoluteMinimumDistanceThreshold
|
||||
* .
|
||||
*
|
||||
* to heed the increasing noise at larger distances.
|
||||
* -# If all of the above filters fail to determine a single valid
|
||||
* pixel, the Golden Pixel is used as a fallback value. The
|
||||
* Golden Pixel is the pixel that sits right at the focus point
|
||||
* of the optics at large distances. Thus, it is expected to
|
||||
* have the best signal at large distances.\n
|
||||
* For its configuration, see the following parameters:
|
||||
* - #PBA_ENABLE_GOLDPX_FALLBACK_MODE
|
||||
* .
|
||||
*
|
||||
* -# In order to avoid unwanted effects from "out-of-focus" pixels
|
||||
* in application that require a smaller focus, the Golden Pixel
|
||||
* Priority Mode prioritizes a valid signal on the central
|
||||
* Golden Pixel over other pixels. That is, while the Golden
|
||||
* Pixel has a reasonable signal strength, it is the only pixel
|
||||
* considered for the 1D result.\n
|
||||
* For its configuration, see the following parameters:
|
||||
* - #PBA_ENABLE_GOLDPX_FALLBACK_MODE
|
||||
* - #argus_cfg_pba_t::GoldenPixelPriorityAmplitudeInclusion
|
||||
* - #argus_cfg_pba_t::GoldenPixelPriorityAmplitudeExclusion
|
||||
* .
|
||||
* of the optics at large distances.
|
||||
* .
|
||||
*
|
||||
* After filtering is done, there may be more than a single pixel
|
||||
@ -149,17 +113,14 @@ extern "C" {
|
||||
* @brief Enable flags for the pixel binning algorithm.
|
||||
*
|
||||
* @details Determines the pixel binning algorithm feature enable status.
|
||||
*
|
||||
* - [0]: #PBA_ENABLE: Enables the pixel binning feature.
|
||||
* - [1]: reserved
|
||||
* - [2]: reserved
|
||||
* - [3]: reserved
|
||||
* - [4]: #PBA_ENABLE_GOLDPX_PRIORITY_MODE: Enables the Golden Pixel
|
||||
* priority mode feature.
|
||||
* - [5]: #PBA_ENABLE_GOLDPX_FALLBACK_MODE: Enables the Golden Pixel
|
||||
* fallback mode feature.
|
||||
* - [6]: #PBA_ENABLE_MIN_DIST_SCOPE: Enables the minimum distance
|
||||
* scope feature.
|
||||
* - [4]: reserved
|
||||
* - [5]: #PBA_ENABLE_GOLDPX: Enables the Golden Pixel feature.
|
||||
* - [6]: #PBA_ENABLE_MIN_DIST_SCOPE: Enables the minimum distance scope
|
||||
* feature.
|
||||
* - [7]: reserved
|
||||
* .
|
||||
*****************************************************************************/
|
||||
@ -167,17 +128,8 @@ typedef enum argus_pba_flags_t {
|
||||
/*! Enables the pixel binning feature. */
|
||||
PBA_ENABLE = 1U << 0U,
|
||||
|
||||
/*! Enables the Golden Pixel Priority Mode.
|
||||
* If enabled, the Golden Pixel is prioritized over other Pixels as long
|
||||
* as it has a good signal (determined by # */
|
||||
PBA_ENABLE_GOLDPX_PRIORITY_MODE = 1U << 4U,
|
||||
|
||||
/*! Enables the Golden Pixel Fallback Mode.
|
||||
* If enabled, the Golden Pixel is used as a last fallback pixel to obtain
|
||||
* a valid signal from. This is recommended for all non-multi pixel
|
||||
* devices whose TX field-of-view is aligned to target the Golden Pixel in
|
||||
* factory calibration. */
|
||||
PBA_ENABLE_GOLDPX_FALLBACK_MODE = 1U << 5U,
|
||||
/*! Enables the Golden Pixel. */
|
||||
PBA_ENABLE_GOLDPX = 1U << 5U,
|
||||
|
||||
/*! Enables the minimum distance scope filter. */
|
||||
PBA_ENABLE_MIN_DIST_SCOPE = 1U << 6U,
|
||||
@ -216,297 +168,65 @@ typedef struct {
|
||||
* about the individual evaluation modes. */
|
||||
argus_pba_averaging_mode_t AveragingMode;
|
||||
|
||||
/*! The relative amplitude inclusion threshold (in %) of the max. amplitude.
|
||||
/*! The Relative amplitude threshold value (in %) of the max. amplitude.
|
||||
*
|
||||
* Pixels, whose amplitudes raise above this inclusion threshold, are
|
||||
* added to the pixel binning. The amplitude must fall below the
|
||||
* exclusion (#RelativeAmplitudeExclusion) threshold to be removed from
|
||||
* the pixel binning again.
|
||||
* Pixels with amplitude below this threshold value are dismissed.
|
||||
*
|
||||
* All available values from the 8-bit representation are valid.
|
||||
* The actual percentage value is determined by 100%/256*x.
|
||||
*
|
||||
* Note: in addition to the relative criteria, there is also the absolute
|
||||
* criteria (#AbsoluteAmplitudeInclusion, #AbsoluteAmplitudeExclusion).
|
||||
* The pixels are added to the pixel binning if their respective amplitude
|
||||
* is larger than the absolute AND relative inclusion values. On the other
|
||||
* hand, they are removed if their amplitude falls below the absolute OR
|
||||
* relative exclusion threshold.
|
||||
*
|
||||
* Must be greater than or equal to the #RelativeAmplitudeExclusion.
|
||||
*
|
||||
* Use #RelativeAmplitudeExclusion == #RelativeAmplitudeInclusion to
|
||||
* disable the hysteresis behavior and use it as a threshold only.
|
||||
*
|
||||
* Use 0 (for both, #RelativeAmplitudeExclusion and
|
||||
* #RelativeAmplitudeInclusion) to disable the relative amplitude
|
||||
* hysteresis. */
|
||||
uq0_8_t RelativeAmplitudeInclusion;
|
||||
* Use 0 to disable the relative amplitude threshold. */
|
||||
uq0_8_t RelAmplThreshold;
|
||||
|
||||
/*! The relative amplitude exclusion threshold (in %) of the max. amplitude.
|
||||
/*! The relative minimum distance scope value in %.
|
||||
*
|
||||
* Pixels, whose amplitudes fall below this exclusion threshold, are
|
||||
* removed from the pixel binning. The amplitude must raise above the
|
||||
* inclusion (#RelativeAmplitudeInclusion) threshold to be added back
|
||||
* to be pixel binning again.
|
||||
* Pixels that have a range value within [x0, x0 + dx] are considered
|
||||
* for the pixel binning, where x0 is the minimum distance of all
|
||||
* amplitude picked pixels and dx is the minimum distance scope value.
|
||||
* The minimum distance scope value will be the maximum of relative
|
||||
* and absolute value.
|
||||
*
|
||||
* All available values from the 8-bit representation are valid.
|
||||
* The actual percentage value is determined by 100%/256*x.
|
||||
*
|
||||
* Note: in addition to the relative criteria, there is also the absolute
|
||||
* criteria (#AbsoluteAmplitudeInclusion, #AbsoluteAmplitudeExclusion).
|
||||
* The pixels are added to the pixel binning if their respective amplitude
|
||||
* is larger than the absolute AND relative inclusion values. On the other
|
||||
* hand, they are removed if their amplitude falls below the absolute OR
|
||||
* relative exclusion threshold.
|
||||
*
|
||||
* Must be less than or equal to #RelativeAmplitudeInclusion.
|
||||
*
|
||||
* Use #RelativeAmplitudeExclusion == #RelativeAmplitudeInclusion to
|
||||
* disable the hysteresis behavior and use it as a threshold only.
|
||||
*
|
||||
* Use 0 (for both, #RelativeAmplitudeExclusion and
|
||||
* #RelativeAmplitudeInclusion) to disable the relative amplitude
|
||||
* hysteresis. */
|
||||
uq0_8_t RelativeAmplitudeExclusion;
|
||||
* Special values:
|
||||
* - 0: Use 0 for absolute value only or to choose the pixel with the
|
||||
* minimum distance only (of also the absolute value is 0)! */
|
||||
uq0_8_t RelMinDistanceScope;
|
||||
|
||||
/*! The absolute amplitude inclusion threshold in LSB.
|
||||
/*! The absolute amplitude threshold value in LSB.
|
||||
*
|
||||
* Pixels, whose amplitudes raise above this inclusion threshold, are
|
||||
* added to the pixel binning. The amplitude must fall below the
|
||||
* exclusion (#RelativeAmplitudeExclusion) threshold to be removed from
|
||||
* the pixel binning again.
|
||||
* Pixels with amplitude below this threshold value are dismissed.
|
||||
*
|
||||
* The absolute amplitude hysteresis is only valid if the Golden Pixel
|
||||
* mode is enabled. Otherwise, the thresholds are set to 0 LSB internally
|
||||
* which disables the absolute criteria.
|
||||
* The absolute amplitude threshold is only valid if the Golden Pixel
|
||||
* mode is enabled. Otherwise, the threshold is set to 0 LSB internally.
|
||||
*
|
||||
* All available values from the 16-bit representation are valid.
|
||||
* The actual LSB value is determined by x/16.
|
||||
*
|
||||
* Note: in addition to the absolute criteria, there is also the relative
|
||||
* criteria (#RelativeAmplitudeInclusion, #RelativeAmplitudeExclusion).
|
||||
* The pixels are added to the pixel binning if their respective amplitude
|
||||
* is larger than the absolute AND relative inclusion values. On the other
|
||||
* hand, they are removed if their amplitude falls below the absolute OR
|
||||
* relative exclusion threshold.
|
||||
*
|
||||
* Must be greater than or equal to #AbsoluteAmplitudeExclusion.
|
||||
*
|
||||
* Use #AbsoluteAmplitudeExclusion == #AbsoluteAmplitudeInclusion to
|
||||
* disable the hysteresis behavior and use it as a threshold only.
|
||||
*
|
||||
* Use 0 (for both, #AbsoluteAmplitudeExclusion and
|
||||
* #AbsoluteAmplitudeInclusion) to disable the absolute amplitude
|
||||
* hysteresis. */
|
||||
uq12_4_t AbsoluteAmplitudeInclusion;
|
||||
* Use 0 to disable the absolute amplitude threshold. */
|
||||
uq12_4_t AbsAmplThreshold;
|
||||
|
||||
/*! The absolute amplitude exclusion threshold in LSB.
|
||||
/*! The absolute minimum distance scope value in m.
|
||||
*
|
||||
* Pixels, whose amplitudes fall below this exclusion threshold, are
|
||||
* removed from the pixel binning. The amplitude must raise above the
|
||||
* inclusion (#RelativeAmplitudeInclusion) threshold to be added back
|
||||
* to be pixel binning again.
|
||||
*
|
||||
* The absolute amplitude hysteresis is only valid if the Golden Pixel
|
||||
* mode is enabled. Otherwise, the thresholds are set to 0 LSB internally
|
||||
* which disables the absolute criteria.
|
||||
*
|
||||
* All available values from the 16-bit representation are valid.
|
||||
* The actual LSB value is determined by x/16.
|
||||
*
|
||||
* Note: in addition to the absolute criteria, there is also the relative
|
||||
* criteria (#RelativeAmplitudeInclusion, #RelativeAmplitudeExclusion).
|
||||
* The pixels are added to the pixel binning if their respective amplitude
|
||||
* is larger than the absolute AND relative inclusion values. On the other
|
||||
* hand, they are removed if their amplitude falls below the absolute OR
|
||||
* relative exclusion threshold.
|
||||
*
|
||||
* Must be less than or equal to #AbsoluteAmplitudeInclusion.
|
||||
*
|
||||
* Use #AbsoluteAmplitudeExclusion == #AbsoluteAmplitudeInclusion to
|
||||
* disable the hysteresis behavior and use it as a threshold only.
|
||||
*
|
||||
* Use 0 (for both, #AbsoluteAmplitudeExclusion and
|
||||
* #AbsoluteAmplitudeInclusion) to disable the absolute amplitude
|
||||
* hysteresis. */
|
||||
uq12_4_t AbsoluteAmplitudeExclusion;
|
||||
|
||||
/*! The Golden Pixel Priority Mode inclusion threshold in LSB.
|
||||
*
|
||||
* The Golden Pixel Priority Mode prioritizes a valid signal on the
|
||||
* Golden Pixel over other pixel to avoid unwanted effects from
|
||||
* "out-of-focus" pixels in application that require a smaller focus.
|
||||
*
|
||||
* If the Golden Pixel priority mode is enabled (see
|
||||
* #PBA_ENABLE_GOLDPX_PRIORITY_MODE) and the Golden Pixel has a valid signal
|
||||
* with amplitude higher than this inclusion threshold, its priority state
|
||||
* is enabled and the binning exits early by dismissing all other pixels
|
||||
* regardless of their respective amplitude or state. The Golden Pixel
|
||||
* priority state is disabled if the Golden Pixel amplitude falls below
|
||||
* the exclusion threshold (#GoldenPixelPriorityAmplitudeExclusion) or its
|
||||
* state becomes invalid (e.g. #PIXEL_SAT).
|
||||
*
|
||||
* All available values from the 16-bit representation are valid.
|
||||
* The actual LSB value is determined by x/16.
|
||||
*
|
||||
* Use 0 to disable the Golden Pixel priority mode hysteresis. */
|
||||
uq12_4_t GoldenPixelPriorityAmplitudeInclusion;
|
||||
|
||||
/*! The Golden Pixel Priority Mode exclusion threshold in LSB.
|
||||
*
|
||||
* The Golden Pixel Priority Mode prioritizes a valid signal on the
|
||||
* Golden Pixel over other pixel to avoid unwanted effects from
|
||||
* "out-of-focus" pixels in application that require a smaller focus.
|
||||
*
|
||||
* If the Golden Pixel priority mode is enabled (see
|
||||
* #PBA_ENABLE_GOLDPX_PRIORITY_MODE) and the Golden Pixel has a valid
|
||||
* signal with amplitude higher than the exclusion threshold
|
||||
* (#GoldenPixelPriorityAmplitudeInclusion), its priority state is enabled
|
||||
* and the binning exits early by dismissing all other pixels regardless
|
||||
* of their respective amplitude or state. The Golden Pixel priority state
|
||||
* is disabled if the Golden Pixel amplitude falls below this exclusion
|
||||
* threshold or its state becomes invalid (e.g. #PIXEL_SAT).
|
||||
*
|
||||
* All available values from the 16-bit representation are valid.
|
||||
* The actual LSB value is determined by x/16.
|
||||
*
|
||||
* Use 0 to disable the Golden Pixel priority mode hysteresis. */
|
||||
uq12_4_t GoldenPixelPriorityAmplitudeExclusion;
|
||||
|
||||
/*! The relative minimum distance scope inclusion threshold (in %).
|
||||
*
|
||||
* Pixels, whose range is smaller than the minimum distance inclusion
|
||||
* threshold (x_min + dx_incl) are added to the pixel binning. The
|
||||
* range must raise above the exclusion
|
||||
* (#RelativeDistanceScopeExclusion) threshold to be removed
|
||||
* from the pixel binning again. The relative value is determined
|
||||
* by multiplying the percentage with the minimum distance.
|
||||
*
|
||||
* The distance scope determines an interval within that pixels
|
||||
* are considered valid, originating at the minimum distance (x_min).
|
||||
* The width of the interval is specified by the relative and absolute
|
||||
* minimum distance scope thresholds. The actual values it the
|
||||
* maximum of both, the relative and absolute inclusion values
|
||||
* (#AbsoluteDistanceScopeInclusion).
|
||||
*
|
||||
* All available values from the 8-bit representation are valid.
|
||||
* The actual percentage value is determined by 100%/256*x.
|
||||
*
|
||||
* Must be smaller than or equal to the #RelativeDistanceScopeExclusion.
|
||||
*
|
||||
* Use #RelativeDistanceScopeExclusion == #RelativeDistanceScopeInclusion to
|
||||
* disable the hysteresis behavior and use it as a threshold only. */
|
||||
uq0_8_t RelativeDistanceScopeInclusion;
|
||||
|
||||
/*! The relative distance scope exclusion threshold (in %).
|
||||
*
|
||||
* Pixels, whose range is larger than the minimum distance exclusion
|
||||
* threshold (x_min + dx_excl) are removed from the pixel binning. The
|
||||
* range must fall below the inclusion
|
||||
* (#RelativeDistanceScopeInclusion) threshold to be added
|
||||
* to the pixel binning again. The relative value is determined
|
||||
* by multiplying the percentage with the minimum distance.
|
||||
*
|
||||
* The distance scope determines an interval within that pixels
|
||||
* are considered valid, originating at the minimum distance (x_min).
|
||||
* The width of the interval is specified by the relative and absolute
|
||||
* minimum distance scope thresholds. The actual values it the
|
||||
* maximum of both, the relative and absolute exclusion values
|
||||
* (#AbsoluteDistanceScopeExclusion).
|
||||
*
|
||||
* All available values from the 8-bit representation are valid.
|
||||
* The actual percentage value is determined by 100%/256*x.
|
||||
*
|
||||
* Must be larger than or equal to the #RelativeDistanceScopeInclusion.
|
||||
*
|
||||
* Use #RelativeDistanceScopeExclusion == #RelativeDistanceScopeInclusion to
|
||||
* disable the hysteresis behavior and use it as a threshold only. */
|
||||
uq0_8_t RelativeDistanceScopeExclusion;
|
||||
|
||||
/*! The absolute minimum distance scope inclusion threshold (in m).
|
||||
*
|
||||
* Pixels, whose range is smaller than the minimum distance inclusion
|
||||
* threshold (x_min + dx_incl) are added to the pixel binning. The
|
||||
* range must raise above the exclusion
|
||||
* (#AbsoluteDistanceScopeExclusion) threshold to be added
|
||||
* to the pixel binning again.
|
||||
*
|
||||
* The distance scope determines an interval within that pixels
|
||||
* are considered valid, originating at the minimum distance (x_min).
|
||||
* The width of the interval is specified by the relative and absolute
|
||||
* minimum distance scope thresholds. The actual values it the
|
||||
* maximum of both, the relative and absolute exclusion values
|
||||
* (#RelativeDistanceScopeInclusion).
|
||||
* Pixels that have a range value within [x0, x0 + dx] are considered
|
||||
* for the pixel binning, where x0 is the minimum distance of all
|
||||
* amplitude picked pixels and dx is the minimum distance scope value.
|
||||
* The minimum distance scope value will be the maximum of relative
|
||||
* and absolute value.
|
||||
*
|
||||
* All available values from the 16-bit representation are valid.
|
||||
* The actual LSB value is determined by x/2^15.
|
||||
*
|
||||
* Must be smaller than or equal to the #AbsoluteDistanceScopeExclusion.
|
||||
*
|
||||
* Use #AbsoluteDistanceScopeExclusion == #AbsoluteDistanceScopeInclusion to
|
||||
* disable the hysteresis behavior and use it as a threshold only. */
|
||||
uq1_15_t AbsoluteDistanceScopeInclusion;
|
||||
|
||||
/*! The absolute minimum distance scope exclusion threshold (in m).
|
||||
*
|
||||
* Pixels, whose range is larger than the minimum distance exclusion
|
||||
* threshold (x_min + dx_excl) are removed from the pixel binning. The
|
||||
* range must fall below the inclusion
|
||||
* (#AbsoluteDistanceScopeInclusion) threshold to be added
|
||||
* to the pixel binning again.
|
||||
*
|
||||
* The distance scope determines an interval within that pixels
|
||||
* are considered valid, originating at the minimum distance (x_min).
|
||||
* The width of the interval is specified by the relative and absolute
|
||||
* minimum distance scope thresholds. The actual values it the
|
||||
* maximum of both, the relative and absolute exclusion values
|
||||
* (#RelativeDistanceScopeExclusion).
|
||||
*
|
||||
* All available values from the 16-bit representation are valid.
|
||||
* The actual LSB value is determined by x/2^15.
|
||||
*
|
||||
* Must be larger than or equal to the #AbsoluteDistanceScopeInclusion.
|
||||
*
|
||||
* Use #AbsoluteDistanceScopeExclusion == #AbsoluteDistanceScopeInclusion to
|
||||
* disable the hysteresis behavior and use it as a threshold only. */
|
||||
uq1_15_t AbsoluteDistanceScopeExclusion;
|
||||
|
||||
/*! The Golden Pixel Saturation Filter Pixel Threshold.
|
||||
*
|
||||
* The Golden Pixel Saturation Filter will evaluate the status of the
|
||||
* Golden Pixel to #PIXEL_INVALID if a certain number of active pixels,
|
||||
* i.e. pixels that are not removed by the static pre-filter mask
|
||||
* (#PrefilterMask), are saturated (#PIXEL_SAT).
|
||||
*
|
||||
* The purpose of this filter is to avoid erroneous situations with highly
|
||||
* reflective targets (e.g. retro-reflectors) that can invalidate the
|
||||
* Golden Pixel such that it would not show the correct saturation state.
|
||||
* In order to avoid using the Golden Pixel in that scenario, this filter
|
||||
* mechanism can be used to remove the Golden Pixel if a specified number
|
||||
* of other pixels show saturation state.
|
||||
*
|
||||
* Use 0 to disable the Golden Pixel Saturation Filter. */
|
||||
uint8_t GoldenPixelSaturationFilterPixelThreshold;
|
||||
|
||||
/*! The Golden Pixel out-of-sync age limit for the GPPM.
|
||||
*
|
||||
* The Golden Pixel out-of-sync age is the number of consecutive frames
|
||||
* where the Golden Pixel is out-of-sync. This parameters is the threshold
|
||||
* to distinguish between temporary and permanent out-of-sync states.
|
||||
*
|
||||
* Temporary out-of-sync states happen when the target rapidly changes. In
|
||||
* this case, the Golden Pixel Priority Mode (GPPM) is not exited. Only if
|
||||
* the out-of-sync age exceeds the specified threshold, the Golden Pixel is
|
||||
* considered erroneous and the GPPM is exited.
|
||||
*
|
||||
* Use 0 to disable the Golden Pixel out-of-sync aging (= infinity). */
|
||||
uint8_t GoldenPixelOutOfSyncAgeThreshold;
|
||||
* Special values:
|
||||
* - 0: Use 0 for relative value only or to choose the pixel with the
|
||||
* minimum distance only (of also the relative value is 0)! */
|
||||
uq1_15_t AbsMinDistanceScope;
|
||||
|
||||
/*! The absolute minimum distance threshold value in m.
|
||||
*
|
||||
* Pixels with distance below this threshold value are dismissed. */
|
||||
q9_22_t AbsoluteMinimumDistanceThreshold;
|
||||
q9_22_t AbsMinDistanceThreshold;
|
||||
|
||||
/*! The pre-filter pixel mask determines the pixel channels that are
|
||||
* statically excluded from the pixel binning (i.e. 1D distance) result.
|
||||
|
||||
@ -55,9 +55,6 @@ extern "C" {
|
||||
* Also used as a special value to determine no object detected or infinity range. */
|
||||
#define ARGUS_RANGE_MAX (Q9_22_MAX)
|
||||
|
||||
/*! Minimum range value in Q9.22 format. */
|
||||
#define ARGUS_RANGE_MIN (Q9_22_MIN)
|
||||
|
||||
/*!***************************************************************************
|
||||
* @brief Status flags for the evaluated pixel structure.
|
||||
*
|
||||
|
||||
@ -227,19 +227,12 @@ enum Status {
|
||||
|
||||
/*! -114: AFBR-S50 Error: Register data integrity is lost (e.g. due to unexpected
|
||||
* power-on-reset cycle or invalid write cycle of SPI. System tries to
|
||||
* reset the values.
|
||||
*
|
||||
* @note If this error occurs after intentionally cycling the power supply
|
||||
* of the device, use the #Argus_RestoreDeviceState API function to properly
|
||||
* recover the current API state into the device to avoid that issue. */
|
||||
* reset the values. */
|
||||
ERROR_ARGUS_DATA_INTEGRITY_LOST = -114,
|
||||
|
||||
/*! -115: AFBR-S50 Error: The range offsets calibration failed! */
|
||||
ERROR_ARGUS_RANGE_OFFSET_CALIBRATION_FAILED = -115,
|
||||
|
||||
/*! -116: AFBR-S50 Error: The VSUB calibration failed! */
|
||||
ERROR_ARGUS_VSUB_CALIBRATION_FAILED = -116,
|
||||
|
||||
/*! -191: AFBR-S50 Error: The device is currently busy and cannot execute the
|
||||
* requested command. */
|
||||
ERROR_ARGUS_BUSY = -191,
|
||||
|
||||
@ -56,13 +56,13 @@ extern "C" {
|
||||
#define ARGUS_API_VERSION_MAJOR 1
|
||||
|
||||
/*! Minor version number of the AFBR-S50 API. */
|
||||
#define ARGUS_API_VERSION_MINOR 5
|
||||
#define ARGUS_API_VERSION_MINOR 4
|
||||
|
||||
/*! Bugfix version number of the AFBR-S50 API. */
|
||||
#define ARGUS_API_VERSION_BUGFIX 6
|
||||
#define ARGUS_API_VERSION_BUGFIX 4
|
||||
|
||||
/*! Build version number of the AFBR-S50 API. */
|
||||
#define ARGUS_API_VERSION_BUILD "20240208081753"
|
||||
#define ARGUS_API_VERSION_BUILD "20230327150535"
|
||||
|
||||
/*****************************************************************************/
|
||||
|
||||
|
||||
@ -72,28 +72,30 @@ typedef struct xtalk_t {
|
||||
* @details Contains crosstalk vector values for all 32 active pixels,
|
||||
* separated for A/B-Frames.
|
||||
*****************************************************************************/
|
||||
typedef union argus_cal_xtalk_table_t {
|
||||
struct {
|
||||
/*! The crosstalk vector table for A-Frames. */
|
||||
xtalk_t FrameA[ARGUS_PIXELS_X][ARGUS_PIXELS_Y];
|
||||
typedef struct argus_cal_xtalk_table_t {
|
||||
union {
|
||||
struct {
|
||||
/*! The crosstalk vector table for A-Frames. */
|
||||
xtalk_t FrameA[ARGUS_PIXELS_X][ARGUS_PIXELS_Y];
|
||||
|
||||
/*! The crosstalk vector table for B-Frames. */
|
||||
xtalk_t FrameB[ARGUS_PIXELS_X][ARGUS_PIXELS_Y];
|
||||
/*! The crosstalk vector table for B-Frames. */
|
||||
xtalk_t FrameB[ARGUS_PIXELS_X][ARGUS_PIXELS_Y];
|
||||
};
|
||||
|
||||
/*! The crosstalk vector table for A/B-Frames of all 32 pixels.*/
|
||||
xtalk_t Table[ARGUS_DFM_FRAME_COUNT][ARGUS_PIXELS_X][ARGUS_PIXELS_Y];
|
||||
};
|
||||
|
||||
/*! The crosstalk vector table for A/B-Frames of all 32 pixels.*/
|
||||
xtalk_t Table[ARGUS_DFM_FRAME_COUNT][ARGUS_PIXELS_X][ARGUS_PIXELS_Y];
|
||||
|
||||
} argus_cal_xtalk_table_t;
|
||||
|
||||
|
||||
/*!***************************************************************************
|
||||
* @brief Electrical Pixel-To-Pixel Crosstalk Compensation Parameters.
|
||||
* @details Contains calibration data that belongs to the electrical
|
||||
* pixel-to-pixel crosstalk compensation feature.
|
||||
* @brief Pixel-To-Pixel Crosstalk Compensation Parameters.
|
||||
* @details Contains calibration data that belongs to the pixel-to-pixel
|
||||
* crosstalk compensation feature.
|
||||
*****************************************************************************/
|
||||
typedef struct argus_cal_electrical_p2pxtalk_t {
|
||||
/*! Electrical Pixel-To-Pixel Compensation on/off. */
|
||||
typedef struct argus_cal_p2pxtalk_t {
|
||||
/*! Pixel-To-Pixel Compensation on/off. */
|
||||
bool Enabled;
|
||||
|
||||
/*! The relative threshold determines when the compensation is active for
|
||||
@ -132,40 +134,9 @@ typedef struct argus_cal_electrical_p2pxtalk_t {
|
||||
* Higher values determine more influence on the reference pixel signal. */
|
||||
q3_12_t KcFactorCRefPx;
|
||||
|
||||
} argus_cal_electrical_p2pxtalk_t;
|
||||
|
||||
/*!***************************************************************************
|
||||
* @brief Optical Pixel-To-Pixel Crosstalk Compensation Parameters.
|
||||
* @details Contains calibration data that belongs to the optical
|
||||
* pixel-to-pixel crosstalk compensation feature.
|
||||
*****************************************************************************/
|
||||
typedef struct argus_cal_optical_p2pxtalk_t {
|
||||
/*! Optical Pixel-To-Pixel Compensation on/off. */
|
||||
bool Enabled;
|
||||
|
||||
/*! The sine component of the coupling coefficient that determines the amount
|
||||
* of a neighbour pixel signal that influences the raw signal of certain pixel.
|
||||
* Higher values determine more influence on the individual pixel signal. */
|
||||
q3_12_t CouplingCoeffS;
|
||||
|
||||
/*! The cosine component of the coupling coefficient that determines the amount
|
||||
* of a neighbour pixel signal that influences the raw signal of a certain pixel.
|
||||
* Higher values determine more influence on the individual pixel signal. */
|
||||
q3_12_t CouplingCoeffC;
|
||||
|
||||
} argus_cal_optical_p2pxtalk_t;
|
||||
|
||||
/*!***************************************************************************
|
||||
* @brief Pixel-To-Pixel Crosstalk Compensation Parameters.
|
||||
* @details Contains combined calibration data for electrical and
|
||||
* optical pixel-to-pixel crosstalk compensation feature.
|
||||
*****************************************************************************/
|
||||
typedef struct argus_cal_p2pxtalk_t {
|
||||
argus_cal_electrical_p2pxtalk_t Electrical;
|
||||
|
||||
argus_cal_optical_p2pxtalk_t Optical;
|
||||
} argus_cal_p2pxtalk_t;
|
||||
|
||||
|
||||
/*! @} */
|
||||
#ifdef __cplusplus
|
||||
} // extern "C"
|
||||
|
||||
@ -61,7 +61,7 @@ extern "C" {
|
||||
* @details Algorithm to evaluate a/b, where b is in Q15.16 format, on a 32-bit
|
||||
* architecture with maximum precision.
|
||||
* The result is correctly rounded and given as the input format.
|
||||
* Division by 0 yields max. values determined by signs of numerator.
|
||||
* Division by 0 yields max. values determined by signa of numerator.
|
||||
* Too high/low results are truncated to max/min values.
|
||||
*
|
||||
* Depending on the architecture, the division is implemented with a 64-bit
|
||||
@ -89,14 +89,14 @@ inline int32_t fp_div16(int32_t a, q15_16_t b)
|
||||
|
||||
if (c > 0x80000000U) { return INT32_MIN; }
|
||||
|
||||
return (int32_t) - c;
|
||||
return -c;
|
||||
|
||||
} else {
|
||||
c = ((c / b) + (1 << 13U)) >> 14U;
|
||||
|
||||
if (c > (int64_t)INT32_MAX) { return INT32_MAX; }
|
||||
|
||||
return (int32_t)c;
|
||||
return c;
|
||||
}
|
||||
|
||||
#else
|
||||
@ -159,16 +159,10 @@ inline int32_t fp_div16(int32_t a, q15_16_t b)
|
||||
|
||||
/* Figure out the sign of result */
|
||||
if ((uint32_t)(a ^ b) & 0x80000000U) {
|
||||
return (int32_t) - result;
|
||||
|
||||
} else {
|
||||
// fix 05.10.2023; the corner case, when result == INT32_MAX + 1:
|
||||
// Catch the wraparound (to INT32_MIN) and truncate instead.
|
||||
if (quotient > INT32_MAX) { return INT32_MAX; }
|
||||
|
||||
return (int32_t)result;
|
||||
result = -result;
|
||||
}
|
||||
|
||||
return (int32_t)result;
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
@ -118,7 +118,7 @@ inline uint32_t fp_mulu(uint32_t u, uint32_t v, uint_fast8_t shift)
|
||||
assert(shift <= 32);
|
||||
#if USE_64BIT_MUL
|
||||
const uint64_t w = (uint64_t)u * (uint64_t)v;
|
||||
return (uint32_t)((w >> shift) + ((w >> (shift - 1)) & 1U));
|
||||
return (w >> shift) + ((w >> (shift - 1)) & 1U);
|
||||
#else
|
||||
uint32_t tmp[2] = { 0 };
|
||||
muldwu(tmp, u, v);
|
||||
@ -158,15 +158,15 @@ inline int32_t fp_muls(int32_t u, int32_t v, uint_fast8_t shift)
|
||||
|
||||
uint32_t u2, v2;
|
||||
|
||||
if (u < 0) { u2 = (uint32_t) - u; sign = -sign; } else { u2 = (uint32_t)u; }
|
||||
if (u < 0) { u2 = -u; sign = -sign; } else { u2 = u; }
|
||||
|
||||
if (v < 0) { v2 = (uint32_t) - v; sign = -sign; } else { v2 = (uint32_t)v; }
|
||||
if (v < 0) { v2 = -v; sign = -sign; } else { v2 = v; }
|
||||
|
||||
const uint32_t res = fp_mulu(u2, v2, shift);
|
||||
|
||||
assert(sign > 0 ? res <= 0x7FFFFFFFU : res <= 0x80000000U);
|
||||
|
||||
return sign > 0 ? (int32_t)res : -(int32_t)res;
|
||||
return sign > 0 ? res : -res;
|
||||
}
|
||||
|
||||
|
||||
@ -225,9 +225,7 @@ inline uint32_t fp_mul_u32_u16(uint32_t u, uint16_t v, uint_fast8_t shift)
|
||||
*****************************************************************************/
|
||||
inline int32_t fp_mul_s32_u16(int32_t u, uint16_t v, uint_fast8_t shift)
|
||||
{
|
||||
return u >= 0 ?
|
||||
(int32_t)fp_mul_u32_u16((uint32_t)u, v, shift) :
|
||||
-(int32_t)fp_mul_u32_u16((uint32_t) - u, v, shift);
|
||||
return u >= 0 ? fp_mul_u32_u16(u, v, shift) : - fp_mul_u32_u16(-u, v, shift);
|
||||
}
|
||||
|
||||
/*! @} */
|
||||
|
||||
@ -80,7 +80,7 @@ inline uint32_t fp_rndu(uint32_t Q, uint_fast8_t n)
|
||||
*****************************************************************************/
|
||||
inline int32_t fp_rnds(int32_t Q, uint_fast8_t n)
|
||||
{
|
||||
return (Q < 0) ? -(int32_t)fp_rndu((uint32_t)(-Q), n) : (int32_t)fp_rndu((uint32_t)Q, n);
|
||||
return (Q < 0) ? -fp_rndu(-Q, n) : fp_rndu(Q, n);
|
||||
}
|
||||
|
||||
/*!***************************************************************************
|
||||
@ -108,7 +108,7 @@ inline uint32_t fp_truncu(uint32_t Q, uint_fast8_t n)
|
||||
*****************************************************************************/
|
||||
inline int32_t fp_truncs(int32_t Q, uint_fast8_t n)
|
||||
{
|
||||
return (Q < 0) ? -(int32_t)fp_truncu((uint32_t)(-Q), n) : (int32_t)fp_truncu((uint32_t)Q, n);
|
||||
return (Q < 0) ? -fp_truncu(-Q, n) : fp_truncu(Q, n);
|
||||
}
|
||||
|
||||
/*! @} */
|
||||
|
||||
@ -66,7 +66,7 @@ inline uint32_t log2i(uint32_t x)
|
||||
{
|
||||
assert(x != 0);
|
||||
#if 1
|
||||
return (uint32_t)(31 - __builtin_clz(x));
|
||||
return 31 - __builtin_clz(x);
|
||||
#else
|
||||
#define S(k) if (x >= (1 << k)) { i += k; x >>= k; }
|
||||
int i = 0; S(16); S(8); S(4); S(2); S(1); return i;
|
||||
|
||||
Binary file not shown.
Binary file not shown.
@ -75,7 +75,6 @@ add_definitions(
|
||||
-DUAVCAN_${UAVCAN_DRIVER_UPPER}_${OS_UPPER}=1
|
||||
-DUAVCAN_${UAVCAN_DRIVER_UPPER}_NUM_IFACES=${config_uavcan_num_ifaces}
|
||||
-DUAVCAN_${UAVCAN_DRIVER_UPPER}_TIMER_NUMBER=${UAVCAN_TIMER}
|
||||
-DUAVCAN_NUM_IFACES=${config_uavcan_num_ifaces}
|
||||
-DUAVCAN_CPP_VERSION=UAVCAN_CPP03
|
||||
-DUAVCAN_DRIVER=uavcan_${UAVCAN_DRIVER}
|
||||
-DUAVCAN_IMPLEMENT_PLACEMENT_NEW=1
|
||||
|
||||
@ -744,41 +744,6 @@ UavcanNode::Run()
|
||||
|
||||
_node.spinOnce(); // expected to be non-blocking
|
||||
|
||||
// Publish status
|
||||
constexpr hrt_abstime status_pub_interval = 100_ms;
|
||||
|
||||
if (hrt_absolute_time() - _last_can_status_pub >= status_pub_interval) {
|
||||
_last_can_status_pub = hrt_absolute_time();
|
||||
|
||||
for (int i = 0; i < _node.getDispatcher().getCanIOManager().getCanDriver().getNumIfaces(); i++) {
|
||||
if (i > UAVCAN_NUM_IFACES) {
|
||||
break;
|
||||
}
|
||||
|
||||
auto iface = _node.getDispatcher().getCanIOManager().getCanDriver().getIface(i);
|
||||
|
||||
if (!iface) {
|
||||
continue;
|
||||
}
|
||||
|
||||
auto iface_perf_cnt = _node.getDispatcher().getCanIOManager().getIfacePerfCounters(i);
|
||||
can_interface_status_s status{
|
||||
.timestamp = hrt_absolute_time(),
|
||||
.io_errors = iface_perf_cnt.errors,
|
||||
.frames_tx = iface_perf_cnt.frames_tx,
|
||||
.frames_rx = iface_perf_cnt.frames_rx,
|
||||
.interface = static_cast<uint8_t>(i),
|
||||
};
|
||||
|
||||
if (_can_status_pub_handles[i] == nullptr) {
|
||||
int instance{0};
|
||||
_can_status_pub_handles[i] = orb_advertise_multi(ORB_ID(can_interface_status), nullptr, &instance);
|
||||
}
|
||||
|
||||
(void)orb_publish(ORB_ID(can_interface_status), _can_status_pub_handles[i], &status);
|
||||
}
|
||||
}
|
||||
|
||||
// check for parameter updates
|
||||
if (_parameter_update_sub.updated()) {
|
||||
// clear update
|
||||
|
||||
@ -96,7 +96,6 @@
|
||||
#include <uORB/Publication.hpp>
|
||||
#include <uORB/Subscription.hpp>
|
||||
#include <uORB/SubscriptionInterval.hpp>
|
||||
#include <uORB/topics/can_interface_status.h>
|
||||
#include <uORB/topics/parameter_update.h>
|
||||
#include <uORB/topics/uavcan_parameter_request.h>
|
||||
#include <uORB/topics/uavcan_parameter_value.h>
|
||||
@ -310,10 +309,6 @@ private:
|
||||
|
||||
uORB::Publication<uavcan_parameter_value_s> _param_response_pub{ORB_ID(uavcan_parameter_value)};
|
||||
uORB::Publication<vehicle_command_ack_s> _command_ack_pub{ORB_ID(vehicle_command_ack)};
|
||||
uORB::PublicationMulti<can_interface_status_s> _can_status_pub{ORB_ID(can_interface_status)};
|
||||
|
||||
hrt_abstime _last_can_status_pub{0};
|
||||
orb_advert_t _can_status_pub_handles[UAVCAN_NUM_IFACES] = {nullptr};
|
||||
|
||||
/*
|
||||
* The MAVLink parameter bridge needs to know the maximum parameter index
|
||||
|
||||
@ -67,7 +67,6 @@ add_subdirectory(pid_design EXCLUDE_FROM_ALL)
|
||||
add_subdirectory(rate_control EXCLUDE_FROM_ALL)
|
||||
add_subdirectory(rc EXCLUDE_FROM_ALL)
|
||||
add_subdirectory(ringbuffer EXCLUDE_FROM_ALL)
|
||||
add_subdirectory(rtl EXCLUDE_FROM_ALL)
|
||||
add_subdirectory(sensor_calibration EXCLUDE_FROM_ALL)
|
||||
add_subdirectory(slew_rate EXCLUDE_FROM_ALL)
|
||||
add_subdirectory(systemlib EXCLUDE_FROM_ALL)
|
||||
|
||||
@ -1 +0,0 @@
|
||||
rsource "*/Kconfig"
|
||||
@ -39,8 +39,6 @@
|
||||
|
||||
DatamanClient::DatamanClient()
|
||||
{
|
||||
_sync_perf = perf_alloc(PC_ELAPSED, "DatamanClient: sync");
|
||||
|
||||
_dataman_request_pub.advertise();
|
||||
_dataman_response_sub = orb_subscribe(ORB_ID(dataman_response));
|
||||
|
||||
@ -76,8 +74,6 @@ DatamanClient::DatamanClient()
|
||||
|
||||
DatamanClient::~DatamanClient()
|
||||
{
|
||||
perf_free(_sync_perf);
|
||||
|
||||
if (_dataman_response_sub >= 0) {
|
||||
orb_unsubscribe(_dataman_response_sub);
|
||||
}
|
||||
@ -89,7 +85,6 @@ bool DatamanClient::syncHandler(const dataman_request_s &request, dataman_respon
|
||||
bool response_received = false;
|
||||
int32_t ret = 0;
|
||||
hrt_abstime time_elapsed = hrt_elapsed_time(&start_time);
|
||||
perf_begin(_sync_perf);
|
||||
_dataman_request_pub.publish(request);
|
||||
|
||||
while (!response_received && (time_elapsed < timeout)) {
|
||||
@ -137,8 +132,6 @@ bool DatamanClient::syncHandler(const dataman_request_s &request, dataman_respon
|
||||
time_elapsed = hrt_elapsed_time(&start_time);
|
||||
}
|
||||
|
||||
perf_end(_sync_perf);
|
||||
|
||||
if (!response_received && ret >= 0) {
|
||||
PX4_ERR("timeout after %" PRIu32 " ms!", static_cast<uint32_t>(timeout / 1000));
|
||||
}
|
||||
|
||||
@ -62,7 +62,7 @@ public:
|
||||
*
|
||||
* @return true if data was read successfully within the timeout, false otherwise.
|
||||
*/
|
||||
bool readSync(dm_item_t item, uint32_t index, uint8_t *buffer, uint32_t length, hrt_abstime timeout = 5000_ms);
|
||||
bool readSync(dm_item_t item, uint32_t index, uint8_t *buffer, uint32_t length, hrt_abstime timeout = 1000_ms);
|
||||
|
||||
/**
|
||||
* @brief Write data to the dataman synchronously.
|
||||
@ -75,7 +75,7 @@ public:
|
||||
*
|
||||
* @return True if the write operation succeeded, false otherwise.
|
||||
*/
|
||||
bool writeSync(dm_item_t item, uint32_t index, uint8_t *buffer, uint32_t length, hrt_abstime timeout = 5000_ms);
|
||||
bool writeSync(dm_item_t item, uint32_t index, uint8_t *buffer, uint32_t length, hrt_abstime timeout = 1000_ms);
|
||||
|
||||
/**
|
||||
* @brief Clears the data in the specified dataman item.
|
||||
@ -85,7 +85,7 @@ public:
|
||||
*
|
||||
* @return True if the operation was successful, false otherwise.
|
||||
*/
|
||||
bool clearSync(dm_item_t item, hrt_abstime timeout = 5000_ms);
|
||||
bool clearSync(dm_item_t item, hrt_abstime timeout = 1000_ms);
|
||||
|
||||
/**
|
||||
* @brief Initiates an asynchronous request to read the data from dataman for a specific item and index.
|
||||
@ -185,8 +185,6 @@ private:
|
||||
|
||||
uint8_t _client_id{0};
|
||||
|
||||
perf_counter_t _sync_perf{nullptr};
|
||||
|
||||
static constexpr uint8_t CLIENT_ID_NOT_SET{0};
|
||||
};
|
||||
|
||||
@ -248,7 +246,7 @@ public:
|
||||
*
|
||||
* @return True if the write operation succeeded, false otherwise.
|
||||
*/
|
||||
bool writeWait(dm_item_t item, uint32_t index, uint8_t *buffer, uint32_t length, hrt_abstime timeout = 5000_ms);
|
||||
bool writeWait(dm_item_t item, uint32_t index, uint8_t *buffer, uint32_t length, hrt_abstime timeout = 1000_ms);
|
||||
|
||||
/**
|
||||
* @brief Updates the dataman cache by checking for responses from the DatamanClient and processing them.
|
||||
|
||||
@ -364,7 +364,7 @@
|
||||
},
|
||||
"1": {
|
||||
"name": "manual_control_loss",
|
||||
"description": "Manual control loss"
|
||||
"description": "manual control loss"
|
||||
},
|
||||
"2": {
|
||||
"name": "gcs_connection_loss",
|
||||
@ -372,19 +372,15 @@
|
||||
},
|
||||
"3": {
|
||||
"name": "low_battery_level",
|
||||
"description": "Low battery level"
|
||||
"description": "low battery level"
|
||||
},
|
||||
"4": {
|
||||
"name": "critical_battery_level",
|
||||
"description": "Critical battery level"
|
||||
"description": "critical battery level"
|
||||
},
|
||||
"5": {
|
||||
"name": "emergency_battery_level",
|
||||
"description": "Emergency battery level"
|
||||
},
|
||||
"6": {
|
||||
"name": "low_remaining_flight_time",
|
||||
"description": "Remaining flight time low"
|
||||
"description": "emergency battery level"
|
||||
}
|
||||
}
|
||||
},
|
||||
@ -402,19 +398,19 @@
|
||||
},
|
||||
"2": {
|
||||
"name": "fallback_posctrl",
|
||||
"description": "Position mode"
|
||||
"description": "fallback to position control"
|
||||
},
|
||||
"3": {
|
||||
"name": "fallback_altctrl",
|
||||
"description": "Altitude mode"
|
||||
"description": "fallback to altitude control"
|
||||
},
|
||||
"4": {
|
||||
"name": "fallback_stabilized",
|
||||
"description": "Stabilized mode"
|
||||
"description": "fallback to stabilized"
|
||||
},
|
||||
"5": {
|
||||
"name": "hold",
|
||||
"description": "Hold"
|
||||
"description": "hold"
|
||||
},
|
||||
"6": {
|
||||
"name": "rtl",
|
||||
@ -422,11 +418,11 @@
|
||||
},
|
||||
"7": {
|
||||
"name": "land",
|
||||
"description": "Land"
|
||||
"description": "land"
|
||||
},
|
||||
"8": {
|
||||
"name": "descend",
|
||||
"description": "Descend"
|
||||
"description": "descend"
|
||||
},
|
||||
"9": {
|
||||
"name": "disarm",
|
||||
|
||||
@ -1,6 +1,6 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2020-2024 PX4 Development Team. All rights reserved.
|
||||
* Copyright (c) 2020-2022 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
|
||||
@ -51,18 +51,17 @@ static constexpr float sq(float var) { return var * var; }
|
||||
// rot312(1) - Second rotation is a RH rotation about the X axis (rad)
|
||||
// rot312(2) - Third rotation is a RH rotation about the Y axis (rad)
|
||||
// See http://www.atacolorado.com/eulersequences.doc
|
||||
template<typename T = float>
|
||||
inline matrix::Dcm<T> taitBryan312ToRotMat(const matrix::Vector3<T> &rot312)
|
||||
inline matrix::Dcmf taitBryan312ToRotMat(const matrix::Vector3f &rot312)
|
||||
{
|
||||
// Calculate the frame2 to frame 1 rotation matrix from a 312 Tait-Bryan rotation sequence
|
||||
const T c2 = cosf(rot312(2)); // third rotation is pitch
|
||||
const T s2 = sinf(rot312(2));
|
||||
const T s1 = sinf(rot312(1)); // second rotation is roll
|
||||
const T c1 = cosf(rot312(1));
|
||||
const T s0 = sinf(rot312(0)); // first rotation is yaw
|
||||
const T c0 = cosf(rot312(0));
|
||||
const float c2 = cosf(rot312(2)); // third rotation is pitch
|
||||
const float s2 = sinf(rot312(2));
|
||||
const float s1 = sinf(rot312(1)); // second rotation is roll
|
||||
const float c1 = cosf(rot312(1));
|
||||
const float s0 = sinf(rot312(0)); // first rotation is yaw
|
||||
const float c0 = cosf(rot312(0));
|
||||
|
||||
matrix::Dcm<T> R;
|
||||
matrix::Dcmf R;
|
||||
R(0, 0) = c0 * c2 - s0 * s1 * s2;
|
||||
R(1, 1) = c0 * c1;
|
||||
R(2, 2) = c2 * c1;
|
||||
@ -76,21 +75,20 @@ inline matrix::Dcm<T> taitBryan312ToRotMat(const matrix::Vector3<T> &rot312)
|
||||
return R;
|
||||
}
|
||||
|
||||
template<typename T = float>
|
||||
inline matrix::Dcm<T> quatToInverseRotMat(const matrix::Quaternion<T> &quat)
|
||||
inline matrix::Dcmf quatToInverseRotMat(const matrix::Quatf &quat)
|
||||
{
|
||||
const T q00 = quat(0) * quat(0);
|
||||
const T q11 = quat(1) * quat(1);
|
||||
const T q22 = quat(2) * quat(2);
|
||||
const T q33 = quat(3) * quat(3);
|
||||
const T q01 = quat(0) * quat(1);
|
||||
const T q02 = quat(0) * quat(2);
|
||||
const T q03 = quat(0) * quat(3);
|
||||
const T q12 = quat(1) * quat(2);
|
||||
const T q13 = quat(1) * quat(3);
|
||||
const T q23 = quat(2) * quat(3);
|
||||
const float q00 = quat(0) * quat(0);
|
||||
const float q11 = quat(1) * quat(1);
|
||||
const float q22 = quat(2) * quat(2);
|
||||
const float q33 = quat(3) * quat(3);
|
||||
const float q01 = quat(0) * quat(1);
|
||||
const float q02 = quat(0) * quat(2);
|
||||
const float q03 = quat(0) * quat(3);
|
||||
const float q12 = quat(1) * quat(2);
|
||||
const float q13 = quat(1) * quat(3);
|
||||
const float q23 = quat(2) * quat(3);
|
||||
|
||||
matrix::Dcm<T> dcm;
|
||||
matrix::Dcmf dcm;
|
||||
dcm(0, 0) = q00 + q11 - q22 - q33;
|
||||
dcm(1, 1) = q00 - q11 + q22 - q33;
|
||||
dcm(2, 2) = q00 - q11 - q22 + q33;
|
||||
@ -107,46 +105,40 @@ inline matrix::Dcm<T> quatToInverseRotMat(const matrix::Quaternion<T> &quat)
|
||||
// We should use a 3-2-1 Tait-Bryan (yaw-pitch-roll) rotation sequence
|
||||
// when there is more roll than pitch tilt and a 3-1-2 rotation sequence
|
||||
// when there is more pitch than roll tilt to avoid gimbal lock.
|
||||
template<typename T = float>
|
||||
inline bool shouldUse321RotationSequence(const matrix::Dcm<T> &R)
|
||||
inline bool shouldUse321RotationSequence(const matrix::Dcmf &R)
|
||||
{
|
||||
return fabsf(R(2, 0)) < fabsf(R(2, 1));
|
||||
}
|
||||
|
||||
template<typename T = float>
|
||||
inline float getEuler321Yaw(const matrix::Dcm<T> &R)
|
||||
inline float getEuler321Yaw(const matrix::Dcmf &R)
|
||||
{
|
||||
return atan2f(R(1, 0), R(0, 0));
|
||||
}
|
||||
|
||||
template<typename T = float>
|
||||
inline float getEuler312Yaw(const matrix::Dcm<T> &R)
|
||||
inline float getEuler312Yaw(const matrix::Dcmf &R)
|
||||
{
|
||||
return atan2f(-R(0, 1), R(1, 1));
|
||||
}
|
||||
|
||||
template<typename T = float>
|
||||
inline T getEuler321Yaw(const matrix::Quaternion<T> &q)
|
||||
inline float getEuler321Yaw(const matrix::Quatf &q)
|
||||
{
|
||||
// Values from yaw_input_321.c file produced by
|
||||
// https://github.com/PX4/ecl/blob/master/matlab/scripts/Inertial%20Nav%20EKF/quat2yaw321.m
|
||||
const T a = static_cast<T>(2.) * (q(0) * q(3) + q(1) * q(2));
|
||||
const T b = sq(q(0)) + sq(q(1)) - sq(q(2)) - sq(q(3));
|
||||
const float a = 2.f * (q(0) * q(3) + q(1) * q(2));
|
||||
const float b = sq(q(0)) + sq(q(1)) - sq(q(2)) - sq(q(3));
|
||||
return atan2f(a, b);
|
||||
}
|
||||
|
||||
template<typename T = float>
|
||||
inline T getEuler312Yaw(const matrix::Quaternion<T> &q)
|
||||
inline float getEuler312Yaw(const matrix::Quatf &q)
|
||||
{
|
||||
// Values from yaw_input_312.c file produced by
|
||||
// https://github.com/PX4/ecl/blob/master/matlab/scripts/Inertial%20Nav%20EKF/quat2yaw312.m
|
||||
const T a = static_cast<T>(2.) * (q(0) * q(3) - q(1) * q(2));
|
||||
const T b = sq(q(0)) - sq(q(1)) + sq(q(2)) - sq(q(3));
|
||||
const float a = 2.f * (q(0) * q(3) - q(1) * q(2));
|
||||
const float b = sq(q(0)) - sq(q(1)) + sq(q(2)) - sq(q(3));
|
||||
return atan2f(a, b);
|
||||
}
|
||||
|
||||
template<typename T = float>
|
||||
inline T getEulerYaw(const matrix::Dcm<T> &R)
|
||||
inline float getEulerYaw(const matrix::Dcmf &R)
|
||||
{
|
||||
if (shouldUse321RotationSequence(R)) {
|
||||
return getEuler321Yaw(R);
|
||||
@ -156,32 +148,23 @@ inline T getEulerYaw(const matrix::Dcm<T> &R)
|
||||
}
|
||||
}
|
||||
|
||||
template<typename T = float>
|
||||
inline T getEulerYaw(const matrix::Quaternion<T> &q)
|
||||
inline matrix::Dcmf updateEuler321YawInRotMat(float yaw, const matrix::Dcmf &rot_in)
|
||||
{
|
||||
return getEulerYaw(matrix::Dcm<T>(q));
|
||||
}
|
||||
|
||||
template<typename T = float>
|
||||
inline matrix::Dcm<T> updateEuler321YawInRotMat(T yaw, const matrix::Dcm<T> &rot_in)
|
||||
{
|
||||
matrix::Euler<T> euler321(rot_in);
|
||||
matrix::Eulerf euler321(rot_in);
|
||||
euler321(2) = yaw;
|
||||
return matrix::Dcm<T>(euler321);
|
||||
return matrix::Dcmf(euler321);
|
||||
}
|
||||
|
||||
template<typename T = float>
|
||||
inline matrix::Dcm<T> updateEuler312YawInRotMat(T yaw, const matrix::Dcm<T> &rot_in)
|
||||
inline matrix::Dcmf updateEuler312YawInRotMat(float yaw, const matrix::Dcmf &rot_in)
|
||||
{
|
||||
const matrix::Vector3<T> rotVec312(yaw, // yaw
|
||||
asinf(rot_in(2, 1)), // roll
|
||||
atan2f(-rot_in(2, 0), rot_in(2, 2))); // pitch
|
||||
const matrix::Vector3f rotVec312(yaw, // yaw
|
||||
asinf(rot_in(2, 1)), // roll
|
||||
atan2f(-rot_in(2, 0), rot_in(2, 2))); // pitch
|
||||
return taitBryan312ToRotMat(rotVec312);
|
||||
}
|
||||
|
||||
// Checks which euler rotation sequence to use and update yaw in rotation matrix
|
||||
template<typename T = float>
|
||||
inline matrix::Dcm<T> updateYawInRotMat(T yaw, const matrix::Dcm<T> &rot_in)
|
||||
inline matrix::Dcmf updateYawInRotMat(float yaw, const matrix::Dcmf &rot_in)
|
||||
{
|
||||
if (shouldUse321RotationSequence(rot_in)) {
|
||||
return updateEuler321YawInRotMat(yaw, rot_in);
|
||||
|
||||
@ -156,23 +156,7 @@ add_custom_target(parameters_header DEPENDS px4_parameters.hpp)
|
||||
|
||||
set(SRCS)
|
||||
|
||||
list(APPEND SRCS
|
||||
parameters.cpp
|
||||
atomic_transaction.cpp
|
||||
autosave.cpp
|
||||
)
|
||||
|
||||
if(CONFIG_PARAM_PRIMARY)
|
||||
list(APPEND SRCS
|
||||
parameters_primary.cpp
|
||||
)
|
||||
endif()
|
||||
|
||||
if(CONFIG_PARAM_REMOTE)
|
||||
list(APPEND SRCS
|
||||
parameters_remote.cpp
|
||||
)
|
||||
endif()
|
||||
list(APPEND SRCS parameters.cpp atomic_transaction.cpp autosave.cpp)
|
||||
|
||||
if(BUILD_TESTING)
|
||||
list(APPEND SRCS param_translation_unit_tests.cpp)
|
||||
|
||||
@ -1,11 +0,0 @@
|
||||
menuconfig PARAM_PRIMARY
|
||||
bool "parameter primary"
|
||||
default n
|
||||
---help---
|
||||
Enable support for the parameter primary in distributed board architectures
|
||||
|
||||
menuconfig PARAM_REMOTE
|
||||
bool "parameter remote"
|
||||
default n
|
||||
---help---
|
||||
Enable support for the parameter remote in distributed board architectures
|
||||
@ -267,18 +267,6 @@ __EXPORT void param_set_used(param_t param);
|
||||
*/
|
||||
__EXPORT int param_set_no_notification(param_t param, const void *val);
|
||||
|
||||
/**
|
||||
* Set the value of a parameter, but do not update the remote system. This avoids
|
||||
* a set loop between primary and remote.
|
||||
*
|
||||
* @param param A handle returned by param_find or passed by param_foreach.
|
||||
* @param val The value to set; assumed to point to a variable of the parameter type.
|
||||
* For structures, the pointer is assumed to point to a structure to be copied.
|
||||
* @param notify Set this to true for the primary (to send out a param update) and false on client
|
||||
* @return Zero if the parameter's value could be set from a scalar, nonzero otherwise.
|
||||
*/
|
||||
__EXPORT int param_set_no_remote_update(param_t param, const void *val, bool notify);
|
||||
|
||||
/**
|
||||
* Notify the system about parameter changes. Can be used for example after several calls to
|
||||
* param_set_no_notification() to avoid unnecessary system notifications.
|
||||
|
||||
@ -105,10 +105,8 @@ static DynamicSparseLayer runtime_defaults{&firmware_defaults};
|
||||
DynamicSparseLayer user_config{&runtime_defaults};
|
||||
|
||||
/** parameter update topic handle */
|
||||
#if not defined(CONFIG_PARAM_REMOTE)
|
||||
static orb_advert_t param_topic = nullptr;
|
||||
static unsigned int param_instance = 0;
|
||||
#endif
|
||||
|
||||
static perf_counter_t param_export_perf;
|
||||
static perf_counter_t param_find_perf;
|
||||
@ -118,14 +116,6 @@ static perf_counter_t param_set_perf;
|
||||
static pthread_mutex_t file_mutex =
|
||||
PTHREAD_MUTEX_INITIALIZER; ///< this protects against concurrent param saves (file or flash access).
|
||||
|
||||
// Support for remote parameter node
|
||||
#if defined(CONFIG_PARAM_PRIMARY)
|
||||
# include "parameters_primary.h"
|
||||
#endif // CONFIG_PARAM_PRIMARY
|
||||
#if defined(CONFIG_PARAM_REMOTE)
|
||||
# include "parameters_remote.h"
|
||||
#endif // CONFIG_PARAM_REMOTE
|
||||
|
||||
void
|
||||
param_init()
|
||||
{
|
||||
@ -138,27 +128,14 @@ param_init()
|
||||
px4_register_boardct_ioctl(_PARAMIOCBASE, param_ioctl);
|
||||
#endif
|
||||
|
||||
#if defined(CONFIG_PARAM_PRIMARY)
|
||||
param_primary_init();
|
||||
#endif // CONFIG_PARAM_PRIMARY
|
||||
|
||||
#if defined(CONFIG_PARAM_REMOTE)
|
||||
param_remote_init();
|
||||
#endif // CONFIG_PARAM_REMOTE
|
||||
|
||||
#if not defined(CONFIG_PARAM_REMOTE)
|
||||
autosave_instance = new ParamAutosave();
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
void
|
||||
param_notify_changes()
|
||||
{
|
||||
// Don't send if this is a remote node. Only the primary
|
||||
// sends out update notices
|
||||
#if not defined(CONFIG_PARAM_REMOTE)
|
||||
parameter_update_s pup {};
|
||||
parameter_update_s pup{};
|
||||
pup.instance = param_instance++;
|
||||
pup.get_count = perf_event_count(param_get_perf);
|
||||
pup.set_count = perf_event_count(param_set_perf);
|
||||
@ -175,8 +152,6 @@ param_notify_changes()
|
||||
} else {
|
||||
orb_publish(ORB_ID(parameter_update), param_topic, &pup);
|
||||
}
|
||||
|
||||
#endif
|
||||
}
|
||||
|
||||
static param_t param_find_internal(const char *name, bool notification)
|
||||
@ -397,7 +372,7 @@ param_control_autosave(bool enable)
|
||||
}
|
||||
|
||||
static int
|
||||
param_set_internal(param_t param, const void *val, bool mark_saved, bool notify_changes, bool update_remote = true)
|
||||
param_set_internal(param_t param, const void *val, bool mark_saved, bool notify_changes)
|
||||
{
|
||||
if (!handle_in_range(param)) {
|
||||
PX4_ERR("set invalid param %d", param);
|
||||
@ -446,24 +421,6 @@ param_set_internal(param_t param, const void *val, bool mark_saved, bool notify_
|
||||
param_autosave();
|
||||
}
|
||||
|
||||
// If this is the parameter server, make sure that the remote is updated
|
||||
#if defined(CONFIG_PARAM_PRIMARY)
|
||||
|
||||
if (param_changed && update_remote) {
|
||||
param_primary_set_value(param, val);
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
// If this is the parameter remote, make sure that the primary is updated
|
||||
#if defined(CONFIG_PARAM_REMOTE)
|
||||
|
||||
if (param_changed && update_remote) {
|
||||
param_remote_set_value(param, val);
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
perf_end(param_set_perf);
|
||||
|
||||
/*
|
||||
@ -499,11 +456,6 @@ int param_set_no_notification(param_t param, const void *val)
|
||||
return param_set_internal(param, val, false, false);
|
||||
}
|
||||
|
||||
int param_set_no_remote_update(param_t param, const void *val, bool notify)
|
||||
{
|
||||
return param_set_internal(param, val, false, notify, false);
|
||||
}
|
||||
|
||||
bool param_used(param_t param)
|
||||
{
|
||||
if (handle_in_range(param)) {
|
||||
@ -516,14 +468,6 @@ bool param_used(param_t param)
|
||||
void param_set_used(param_t param)
|
||||
{
|
||||
if (handle_in_range(param)) {
|
||||
#if defined(CONFIG_PARAM_REMOTE)
|
||||
|
||||
if (!param_used(param)) {
|
||||
param_remote_set_used(param);
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
params_active.set(param, true);
|
||||
}
|
||||
}
|
||||
@ -600,11 +544,6 @@ int param_set_default_value(param_t param, const void *val)
|
||||
|
||||
static int param_reset_internal(param_t param, bool notify = true, bool autosave = true)
|
||||
{
|
||||
#if defined(CONFIG_PARAM_REMOTE)
|
||||
// Remote doesn't support reset
|
||||
return false;
|
||||
#endif
|
||||
|
||||
bool param_found = user_config.contains(param);
|
||||
|
||||
if (handle_in_range(param)) {
|
||||
@ -619,10 +558,6 @@ static int param_reset_internal(param_t param, bool notify = true, bool autosave
|
||||
param_notify_changes();
|
||||
}
|
||||
|
||||
#if defined(CONFIG_PARAM_PRIMARY)
|
||||
param_primary_reset(param);
|
||||
#endif
|
||||
|
||||
return param_found;
|
||||
}
|
||||
|
||||
@ -632,11 +567,6 @@ int param_reset_no_notification(param_t param) { return param_reset_internal(par
|
||||
static void
|
||||
param_reset_all_internal(bool auto_save)
|
||||
{
|
||||
#if defined(CONFIG_PARAM_REMOTE)
|
||||
// Remote doesn't support reset
|
||||
return;
|
||||
#endif
|
||||
|
||||
for (param_t param = 0; handle_in_range(param); param++) {
|
||||
param_reset_internal(param, false, false);
|
||||
}
|
||||
@ -645,10 +575,6 @@ param_reset_all_internal(bool auto_save)
|
||||
param_autosave();
|
||||
}
|
||||
|
||||
#if defined(CONFIG_PARAM_PRIMARY)
|
||||
param_primary_reset_all();
|
||||
#endif
|
||||
|
||||
param_notify_changes();
|
||||
}
|
||||
|
||||
@ -1354,27 +1280,4 @@ void param_print_status()
|
||||
perf_print_counter(param_find_perf);
|
||||
perf_print_counter(param_get_perf);
|
||||
perf_print_counter(param_set_perf);
|
||||
|
||||
#if defined(CONFIG_PARAM_PRIMARY)
|
||||
struct param_primary_counters counts;
|
||||
param_primary_get_counters(&counts);
|
||||
PX4_INFO("set value requests received: %" PRIu32 ", set value responses sent: %" PRIu32,
|
||||
counts.set_value_request_received, counts.set_value_response_sent);
|
||||
PX4_INFO("set value requests sent: %" PRIu32 ", set value responses received: %" PRIu32,
|
||||
counts.set_value_request_sent, counts.set_value_response_received);
|
||||
PX4_INFO("resets sent: %" PRIu32 ", set used requests received: %" PRIu32,
|
||||
counts.reset_sent, counts.set_used_received);
|
||||
#endif
|
||||
|
||||
#if defined(CONFIG_PARAM_REMOTE)
|
||||
struct param_remote_counters counts;
|
||||
param_remote_get_counters(&counts);
|
||||
PX4_INFO("set value requests received: %" PRIu32 ", set value responses sent: %" PRIu32,
|
||||
counts.set_value_request_received, counts.set_value_response_sent);
|
||||
PX4_INFO("set value requests sent: %" PRIu32 ", set value responses received: %" PRIu32,
|
||||
counts.set_value_request_sent, counts.set_value_response_received);
|
||||
PX4_INFO("resets received: %" PRIu32 ", set used requests sent: %" PRIu32,
|
||||
counts.reset_received, counts.set_used_sent);
|
||||
#endif
|
||||
|
||||
}
|
||||
|
||||
@ -1,314 +0,0 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2024 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#include "parameters_primary.h"
|
||||
|
||||
#include "uORB/uORBManager.hpp"
|
||||
|
||||
#include <px4_platform_common/log.h>
|
||||
#include <px4_platform_common/tasks.h>
|
||||
|
||||
// uORB topics needed to keep parameter server and client in sync
|
||||
#include <uORB/topics/parameter_reset_request.h>
|
||||
#include <uORB/topics/parameter_set_used_request.h>
|
||||
#include <uORB/topics/parameter_set_value_request.h>
|
||||
#include <uORB/topics/parameter_set_value_response.h>
|
||||
|
||||
// Debug flag
|
||||
static bool debug = false;
|
||||
|
||||
static struct param_primary_counters param_primary_counters;
|
||||
|
||||
#define TIMEOUT_WAIT 1000
|
||||
#define TIMEOUT_COUNT 50
|
||||
|
||||
static px4_task_t sync_thread_tid;
|
||||
static const char *sync_thread_name = "param_primary_sync";
|
||||
|
||||
static orb_advert_t param_set_value_req_h = nullptr;
|
||||
static orb_advert_t param_reset_req_h = nullptr;
|
||||
|
||||
static int param_set_rsp_fd = PX4_ERROR;
|
||||
|
||||
static int primary_sync_thread(int argc, char *argv[])
|
||||
{
|
||||
// Need to wait until the uORB and muORB are ready
|
||||
// Check for uORB initialization with get_instance
|
||||
while (uORB::Manager::get_instance() == nullptr) { px4_usleep(100); }
|
||||
|
||||
// Check for muORB initialization with get_uorb_communicator
|
||||
while (uORB::Manager::get_instance()->get_uorb_communicator() == nullptr) { px4_usleep(100); }
|
||||
|
||||
orb_advert_t _set_value_rsp_h = nullptr;
|
||||
|
||||
int _set_used_req_fd = orb_subscribe(ORB_ID(parameter_set_used_request));
|
||||
int _set_value_req_fd = orb_subscribe(ORB_ID(parameter_primary_set_value_request));
|
||||
|
||||
struct parameter_set_used_request_s _set_used_request;
|
||||
struct parameter_set_value_request_s _set_value_request;
|
||||
struct parameter_set_value_response_s _set_value_response;
|
||||
|
||||
px4_pollfd_struct_t fds[2] = { { .fd = _set_used_req_fd, .events = POLLIN },
|
||||
{ .fd = _set_value_req_fd, .events = POLLIN }
|
||||
};
|
||||
|
||||
PX4_INFO("Starting parameter primary sync thread");
|
||||
|
||||
while (true) {
|
||||
px4_poll(fds, 2, 1000);
|
||||
|
||||
if (fds[0].revents & POLLIN) {
|
||||
bool updated = true;
|
||||
|
||||
while (updated) {
|
||||
orb_copy(ORB_ID(parameter_set_used_request), _set_used_req_fd, &_set_used_request);
|
||||
|
||||
if (debug) {
|
||||
PX4_INFO("Got parameter_set_used_request for %s", param_name(_set_used_request.parameter_index));
|
||||
}
|
||||
|
||||
param_primary_counters.set_used_received++;
|
||||
|
||||
param_find(param_name(_set_used_request.parameter_index));
|
||||
|
||||
(void) orb_check(_set_used_req_fd, &updated);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
if (fds[1].revents & POLLIN) {
|
||||
bool updated = true;
|
||||
|
||||
while (updated) {
|
||||
orb_copy(ORB_ID(parameter_primary_set_value_request), _set_value_req_fd, &_set_value_request);
|
||||
|
||||
if (debug) {
|
||||
PX4_INFO("Got parameter_primary_set_value_request for %s", param_name(_set_value_request.parameter_index));
|
||||
}
|
||||
|
||||
param_primary_counters.set_value_request_received++;
|
||||
|
||||
param_t param = _set_value_request.parameter_index;
|
||||
|
||||
switch (param_type(param)) {
|
||||
case PARAM_TYPE_INT32:
|
||||
param_set_no_remote_update(param, (const void *) &_set_value_request.int_value, true);
|
||||
break;
|
||||
|
||||
case PARAM_TYPE_FLOAT:
|
||||
param_set_no_remote_update(param, (const void *) &_set_value_request.float_value, true);
|
||||
break;
|
||||
|
||||
default:
|
||||
PX4_ERR("Parameter must be either int or float");
|
||||
break;
|
||||
}
|
||||
|
||||
_set_value_response.timestamp = hrt_absolute_time();
|
||||
_set_value_response.request_timestamp = _set_value_request.timestamp;
|
||||
_set_value_response.parameter_index = _set_value_request.parameter_index;
|
||||
|
||||
if (_set_value_rsp_h == nullptr) {
|
||||
_set_value_rsp_h = orb_advertise(ORB_ID(parameter_primary_set_value_response), &_set_value_response);
|
||||
|
||||
} else {
|
||||
orb_publish(ORB_ID(parameter_primary_set_value_response), _set_value_rsp_h, &_set_value_response);
|
||||
}
|
||||
|
||||
param_primary_counters.set_value_response_sent++;
|
||||
|
||||
(void) orb_check(_set_value_req_fd, &updated);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
void param_primary_init()
|
||||
{
|
||||
|
||||
sync_thread_tid = px4_task_spawn_cmd(sync_thread_name,
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_PARAMS,
|
||||
(1024 * 4),
|
||||
primary_sync_thread,
|
||||
NULL);
|
||||
|
||||
}
|
||||
|
||||
// void param_primary_set_value(param_t param, const void *val, bool from_file)
|
||||
void param_primary_set_value(param_t param, const void *val)
|
||||
{
|
||||
bool send_request = true;
|
||||
struct parameter_set_value_request_s req;
|
||||
req.timestamp = hrt_absolute_time();
|
||||
req.parameter_index = param;
|
||||
|
||||
switch (param_type(param)) {
|
||||
case PARAM_TYPE_INT32:
|
||||
req.int_value = *(int32_t *)val;
|
||||
|
||||
if (debug) {
|
||||
PX4_INFO("*** Setting %s to %d ***", param_name(req.parameter_index), req.int_value);
|
||||
}
|
||||
|
||||
break;
|
||||
|
||||
case PARAM_TYPE_FLOAT:
|
||||
req.float_value = *(float *)val;
|
||||
|
||||
if (debug) {
|
||||
PX4_INFO("*** Setting %s to %f ***", param_name(req.parameter_index), (double) req.float_value);
|
||||
}
|
||||
|
||||
break;
|
||||
|
||||
default:
|
||||
PX4_ERR("Parameter must be either int or float");
|
||||
send_request = false;
|
||||
break;
|
||||
}
|
||||
|
||||
if (param_set_rsp_fd == PX4_ERROR) {
|
||||
if (debug) {
|
||||
PX4_INFO("Subscribing to parameter_client_set_value_response");
|
||||
}
|
||||
|
||||
param_set_rsp_fd = orb_subscribe(ORB_ID(parameter_remote_set_value_response));
|
||||
|
||||
if (param_set_rsp_fd == PX4_ERROR) {
|
||||
PX4_ERR("Subscription to parameter_remote_set_value_response failed");
|
||||
|
||||
} else {
|
||||
if (debug) {
|
||||
PX4_INFO("Subscription to parameter_client_set_value_response succeeded");
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
if (send_request) {
|
||||
if (debug) {
|
||||
PX4_INFO("Sending param set request to remote for %s", param_name(req.parameter_index));
|
||||
}
|
||||
|
||||
if (param_set_value_req_h == nullptr) {
|
||||
param_set_value_req_h = orb_advertise(ORB_ID(parameter_remote_set_value_request), nullptr);
|
||||
}
|
||||
|
||||
orb_publish(ORB_ID(parameter_remote_set_value_request), param_set_value_req_h, &req);
|
||||
|
||||
param_primary_counters.set_value_request_sent++;
|
||||
|
||||
// Wait for response
|
||||
bool updated = false;
|
||||
|
||||
if (debug) {
|
||||
PX4_INFO("Waiting for parameter_client_set_value_response for %s", param_name(req.parameter_index));
|
||||
}
|
||||
|
||||
px4_usleep(TIMEOUT_WAIT);
|
||||
int count = TIMEOUT_COUNT;
|
||||
|
||||
while (--count) {
|
||||
(void) orb_check(param_set_rsp_fd, &updated);
|
||||
|
||||
struct parameter_set_value_response_s rsp;
|
||||
|
||||
while (updated) {
|
||||
|
||||
orb_copy(ORB_ID(parameter_remote_set_value_response), param_set_rsp_fd, &rsp);
|
||||
|
||||
if ((rsp.request_timestamp == req.timestamp) && (rsp.parameter_index == req.parameter_index)) {
|
||||
if (debug) {
|
||||
PX4_INFO("Got parameter_remote_set_value_response for %s", param_name(req.parameter_index));
|
||||
}
|
||||
|
||||
param_primary_counters.set_value_response_received++;
|
||||
return;
|
||||
}
|
||||
|
||||
(void) orb_check(param_set_rsp_fd, &updated);
|
||||
}
|
||||
|
||||
px4_usleep(TIMEOUT_WAIT);
|
||||
}
|
||||
|
||||
PX4_ERR("Timeout waiting for parameter_client_set_value_response for %s", param_name(req.parameter_index));
|
||||
}
|
||||
}
|
||||
|
||||
static void param_primary_reset_internal(param_t param, bool reset_all)
|
||||
{
|
||||
if (debug) {
|
||||
PX4_INFO("Param reset at primary");
|
||||
}
|
||||
|
||||
struct parameter_reset_request_s req;
|
||||
|
||||
req.timestamp = hrt_absolute_time();
|
||||
|
||||
req.reset_all = reset_all;
|
||||
|
||||
if (reset_all == false) {
|
||||
req.parameter_index = param;
|
||||
}
|
||||
|
||||
if (debug) {
|
||||
PX4_INFO("Sending param reset request to remote");
|
||||
}
|
||||
|
||||
if (param_reset_req_h == nullptr) {
|
||||
param_reset_req_h = orb_advertise(ORB_ID(parameter_reset_request), &req);
|
||||
|
||||
} else {
|
||||
orb_publish(ORB_ID(parameter_reset_request), param_reset_req_h, &req);
|
||||
}
|
||||
|
||||
param_primary_counters.reset_sent++;
|
||||
}
|
||||
|
||||
void param_primary_reset(param_t param)
|
||||
{
|
||||
param_primary_reset_internal(param, false);
|
||||
}
|
||||
|
||||
void param_primary_reset_all()
|
||||
{
|
||||
param_primary_reset_internal(0, true);
|
||||
}
|
||||
|
||||
void param_primary_get_counters(struct param_primary_counters *cnt)
|
||||
{
|
||||
*cnt = param_primary_counters;
|
||||
}
|
||||
@ -1,52 +0,0 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2024 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "param.h"
|
||||
|
||||
struct param_primary_counters {
|
||||
uint32_t set_value_request_received;
|
||||
uint32_t set_value_response_sent;
|
||||
uint32_t reset_sent;
|
||||
uint32_t set_value_request_sent;
|
||||
uint32_t set_value_response_received;
|
||||
uint32_t set_used_received;
|
||||
};
|
||||
|
||||
void param_primary_init();
|
||||
void param_primary_set_value(param_t param, const void *val);
|
||||
void param_primary_reset(param_t param);
|
||||
void param_primary_reset_all();
|
||||
void param_primary_get_counters(struct param_primary_counters *cnt);
|
||||
|
||||
@ -1,310 +0,0 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2024 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#include "parameters_remote.h"
|
||||
|
||||
#include "uORB/uORBManager.hpp"
|
||||
|
||||
#include <inttypes.h>
|
||||
|
||||
#include <px4_platform_common/log.h>
|
||||
#include <px4_platform_common/tasks.h>
|
||||
|
||||
// uORB topics needed to keep parameter server and client in sync
|
||||
#include <uORB/topics/parameter_reset_request.h>
|
||||
#include <uORB/topics/parameter_set_used_request.h>
|
||||
#include <uORB/topics/parameter_set_value_request.h>
|
||||
#include <uORB/topics/parameter_set_value_response.h>
|
||||
|
||||
// Debug flag
|
||||
static bool debug = false;
|
||||
|
||||
static struct param_remote_counters param_remote_counters;
|
||||
|
||||
#define TIMEOUT_WAIT 1000
|
||||
#define TIMEOUT_COUNT 50
|
||||
|
||||
static orb_advert_t parameter_set_used_h = nullptr;
|
||||
static orb_advert_t param_set_value_req_h = nullptr;
|
||||
|
||||
static int param_set_rsp_fd = PX4_ERROR;
|
||||
|
||||
static px4_task_t sync_thread_tid;
|
||||
static const char *sync_thread_name = "param_remote_sync";
|
||||
|
||||
static int remote_sync_thread(int argc, char *argv[])
|
||||
{
|
||||
// This thread gets started by the remote side during PX4 initialization.
|
||||
// We cannot send out the subscribe request immediately because the other
|
||||
// side will not be ready to receive it on the muorb yet and it will get dropped.
|
||||
// So, sleep a little bit to give other side a chance to finish initialization
|
||||
// of the muorb. But don't wait too long otherwise a set request from the server
|
||||
// side could be missed.
|
||||
usleep(200000);
|
||||
|
||||
orb_advert_t _set_value_rsp_h = nullptr;
|
||||
|
||||
int _reset_req_fd = orb_subscribe(ORB_ID(parameter_reset_request));
|
||||
int _set_value_req_fd = orb_subscribe(ORB_ID(parameter_remote_set_value_request));
|
||||
|
||||
struct parameter_reset_request_s _reset_request;
|
||||
struct parameter_set_value_request_s _set_value_request;
|
||||
struct parameter_set_value_response_s _set_value_response;
|
||||
|
||||
px4_pollfd_struct_t fds[2] = { { .fd = _reset_req_fd, .events = POLLIN },
|
||||
{ .fd = _set_value_req_fd, .events = POLLIN }
|
||||
};
|
||||
|
||||
PX4_INFO("Starting parameter remote sync thread");
|
||||
|
||||
while (true) {
|
||||
px4_poll(fds, 2, 1000);
|
||||
|
||||
if (fds[0].revents & POLLIN) {
|
||||
bool updated = true;
|
||||
|
||||
while (updated) {
|
||||
orb_copy(ORB_ID(parameter_reset_request), _reset_req_fd, &_reset_request);
|
||||
|
||||
if (debug) {
|
||||
PX4_INFO("Got parameter_reset_request for %s", param_name(_reset_request.parameter_index));
|
||||
}
|
||||
|
||||
param_remote_counters.reset_received++;
|
||||
|
||||
if (_reset_request.reset_all) {
|
||||
param_reset_all();
|
||||
|
||||
} else {
|
||||
param_reset_no_notification(_reset_request.parameter_index);
|
||||
|
||||
}
|
||||
|
||||
(void) orb_check(_reset_req_fd, &updated);
|
||||
}
|
||||
}
|
||||
|
||||
if (fds[1].revents & POLLIN) {
|
||||
bool updated = true;
|
||||
|
||||
while (updated) {
|
||||
orb_copy(ORB_ID(parameter_primary_set_value_request), _set_value_req_fd, &_set_value_request);
|
||||
|
||||
if (debug) {
|
||||
PX4_INFO("Got parameter_remote_set_value_request for %s", param_name(_set_value_request.parameter_index));
|
||||
}
|
||||
|
||||
param_remote_counters.set_value_request_received++;
|
||||
|
||||
switch (param_type(_set_value_request.parameter_index)) {
|
||||
case PARAM_TYPE_INT32:
|
||||
param_set_no_remote_update(_set_value_request.parameter_index,
|
||||
(const void *) &_set_value_request.int_value,
|
||||
false);
|
||||
break;
|
||||
|
||||
case PARAM_TYPE_FLOAT:
|
||||
param_set_no_remote_update(_set_value_request.parameter_index,
|
||||
(const void *) &_set_value_request.float_value,
|
||||
false);
|
||||
break;
|
||||
|
||||
default:
|
||||
PX4_ERR("Parameter must be either int or float");
|
||||
break;
|
||||
}
|
||||
|
||||
_set_value_response.timestamp = hrt_absolute_time();
|
||||
_set_value_response.request_timestamp = _set_value_request.timestamp;
|
||||
_set_value_response.parameter_index = _set_value_request.parameter_index;
|
||||
|
||||
if (_set_value_rsp_h == nullptr) {
|
||||
_set_value_rsp_h = orb_advertise(ORB_ID(parameter_remote_set_value_response), &_set_value_response);
|
||||
|
||||
} else {
|
||||
if (debug) {
|
||||
PX4_INFO("Sending set value response for %s", param_name(_set_value_request.parameter_index));
|
||||
}
|
||||
|
||||
orb_publish(ORB_ID(parameter_remote_set_value_response), _set_value_rsp_h, &_set_value_response);
|
||||
}
|
||||
|
||||
param_remote_counters.set_value_response_sent++;
|
||||
|
||||
(void) orb_check(_set_value_req_fd, &updated);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
void param_remote_init()
|
||||
{
|
||||
|
||||
sync_thread_tid = px4_task_spawn_cmd(sync_thread_name,
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_PARAMS,
|
||||
(1024 * 4),
|
||||
remote_sync_thread,
|
||||
NULL);
|
||||
|
||||
}
|
||||
|
||||
void param_remote_set_used(param_t param)
|
||||
{
|
||||
// Notify the parameter server that this parameter has been marked as used
|
||||
if (debug) {
|
||||
PX4_INFO("Requesting server to mark %s as used", param_name(param));
|
||||
}
|
||||
|
||||
struct parameter_set_used_request_s req;
|
||||
|
||||
req.timestamp = hrt_absolute_time();
|
||||
|
||||
req.parameter_index = param;
|
||||
|
||||
if (parameter_set_used_h == nullptr) {
|
||||
parameter_set_used_h = orb_advertise(ORB_ID(parameter_set_used_request), &req);
|
||||
|
||||
} else {
|
||||
orb_publish(ORB_ID(parameter_set_used_request), parameter_set_used_h, &req);
|
||||
}
|
||||
|
||||
param_remote_counters.set_used_sent++;
|
||||
}
|
||||
|
||||
void param_remote_set_value(param_t param, const void *val)
|
||||
{
|
||||
bool send_request = true;
|
||||
struct parameter_set_value_request_s req;
|
||||
req.timestamp = hrt_absolute_time();
|
||||
req.parameter_index = param;
|
||||
|
||||
switch (param_type(param)) {
|
||||
case PARAM_TYPE_INT32:
|
||||
req.int_value = *(int32_t *)val;
|
||||
|
||||
if (debug) {
|
||||
PX4_INFO("*** Setting %s to %" PRIi32 " ***", param_name(req.parameter_index), req.int_value);
|
||||
}
|
||||
|
||||
break;
|
||||
|
||||
case PARAM_TYPE_FLOAT:
|
||||
req.float_value = *(float *)val;
|
||||
|
||||
if (debug) {
|
||||
PX4_INFO("*** Setting %s to %f ***", param_name(req.parameter_index), (double) req.float_value);
|
||||
}
|
||||
|
||||
break;
|
||||
|
||||
default:
|
||||
PX4_ERR("Parameter must be either int or float");
|
||||
send_request = false;
|
||||
break;
|
||||
}
|
||||
|
||||
if (param_set_rsp_fd == PX4_ERROR) {
|
||||
if (debug) {
|
||||
PX4_INFO("Subscribing to parameter_primary_set_value_response");
|
||||
}
|
||||
|
||||
param_set_rsp_fd = orb_subscribe(ORB_ID(parameter_primary_set_value_response));
|
||||
|
||||
if (param_set_rsp_fd == PX4_ERROR) {
|
||||
PX4_ERR("Subscription to parameter_primary_set_value_response failed");
|
||||
|
||||
} else {
|
||||
if (debug) {
|
||||
PX4_INFO("Subscription to parameter_primary_set_value_response succeeded");
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
if (send_request) {
|
||||
if (debug) {
|
||||
PX4_INFO("Sending param set value request to primary for %s", param_name(req.parameter_index));
|
||||
}
|
||||
|
||||
if (param_set_value_req_h == nullptr) {
|
||||
param_set_value_req_h = orb_advertise(ORB_ID(parameter_primary_set_value_request), nullptr);
|
||||
}
|
||||
|
||||
orb_publish(ORB_ID(parameter_primary_set_value_request), param_set_value_req_h, &req);
|
||||
|
||||
param_remote_counters.set_value_request_sent++;
|
||||
|
||||
// Wait for response
|
||||
bool updated = false;
|
||||
|
||||
if (debug) {
|
||||
PX4_INFO("Waiting for parameter_client_set_value_response for %s", param_name(req.parameter_index));
|
||||
}
|
||||
|
||||
px4_usleep(TIMEOUT_WAIT);
|
||||
int count = TIMEOUT_COUNT;
|
||||
|
||||
while (--count) {
|
||||
(void) orb_check(param_set_rsp_fd, &updated);
|
||||
|
||||
struct parameter_set_value_response_s rsp;
|
||||
|
||||
while (updated) {
|
||||
|
||||
orb_copy(ORB_ID(parameter_primary_set_value_response), param_set_rsp_fd, &rsp);
|
||||
|
||||
if ((rsp.request_timestamp == req.timestamp) && (rsp.parameter_index == req.parameter_index)) {
|
||||
if (debug) {
|
||||
PX4_INFO("Got parameter_primary_set_value_response for %s", param_name(req.parameter_index));
|
||||
}
|
||||
|
||||
param_remote_counters.set_value_response_received++;
|
||||
return;
|
||||
}
|
||||
|
||||
(void) orb_check(param_set_rsp_fd, &updated);
|
||||
}
|
||||
|
||||
px4_usleep(TIMEOUT_WAIT);
|
||||
}
|
||||
|
||||
PX4_ERR("Timeout waiting for parameter_primary_set_value_response for %s", param_name(req.parameter_index));
|
||||
}
|
||||
}
|
||||
|
||||
void param_remote_get_counters(struct param_remote_counters *cnt)
|
||||
{
|
||||
*cnt = param_remote_counters;
|
||||
}
|
||||
@ -1,50 +0,0 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2024 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "param.h"
|
||||
|
||||
struct param_remote_counters {
|
||||
uint32_t set_value_request_received;
|
||||
uint32_t set_value_response_sent;
|
||||
uint32_t reset_received;
|
||||
uint32_t set_value_request_sent;
|
||||
uint32_t set_value_response_received;
|
||||
uint32_t set_used_sent;
|
||||
};
|
||||
|
||||
void param_remote_init();
|
||||
void param_remote_set_used(param_t param);
|
||||
void param_remote_set_value(param_t param, const void *val);
|
||||
void param_remote_get_counters(struct param_remote_counters *cnt);
|
||||
@ -1,34 +0,0 @@
|
||||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2024 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.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
px4_add_library(rtl_time_estimator rtl_time_estimator.cpp)
|
||||
@ -1,267 +0,0 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2024 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 rtl_time_estimator.cpp
|
||||
*
|
||||
* Helper class to calculate the remaining time estimate to go to RTL landing point.
|
||||
*
|
||||
*/
|
||||
|
||||
#include "rtl_time_estimator.h"
|
||||
|
||||
#include <float.h>
|
||||
#include <math.h>
|
||||
|
||||
#include <px4_platform_common/defines.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <uORB/topics/vehicle_status.h>
|
||||
|
||||
RtlTimeEstimator::RtlTimeEstimator() : ModuleParams(nullptr)
|
||||
{
|
||||
_param_mpc_z_v_auto_up = param_find("MPC_Z_V_AUTO_UP");
|
||||
_param_mpc_z_v_auto_dn = param_find("MPC_Z_V_AUTO_DN");
|
||||
_param_mpc_land_speed = param_find("MPC_LAND_SPEED");
|
||||
_param_fw_climb_rate = param_find("FW_T_CLMB_R_SP");
|
||||
_param_fw_sink_rate = param_find("FW_T_SINK_R_SP");
|
||||
_param_fw_airspeed_trim = param_find("FW_AIRSPD_TRIM");
|
||||
_param_mpc_xy_cruise = param_find("MPC_XY_CRUISE");
|
||||
_param_rover_cruise_speed = param_find("GND_SPEED_THR_SC");
|
||||
};
|
||||
|
||||
rtl_time_estimate_s RtlTimeEstimator::getEstimate() const
|
||||
{
|
||||
rtl_time_estimate_s time_estimate{};
|
||||
|
||||
if (_is_valid && PX4_ISFINITE(_time_estimate)) {
|
||||
time_estimate.valid = true;
|
||||
time_estimate.time_estimate = _time_estimate;
|
||||
// Use actual time estimate to compute the safer time estimate with additional scale factor and a margin
|
||||
time_estimate.safe_time_estimate = _param_rtl_time_factor.get() * _time_estimate + _param_rtl_time_margin.get();
|
||||
|
||||
} else {
|
||||
time_estimate.valid = false;
|
||||
}
|
||||
|
||||
time_estimate.timestamp = hrt_absolute_time();
|
||||
return time_estimate;
|
||||
}
|
||||
|
||||
void RtlTimeEstimator::update()
|
||||
{
|
||||
_vehicle_status_sub.update();
|
||||
_wind_sub.update();
|
||||
|
||||
if (_parameter_update_sub.updated()) {
|
||||
parameter_update_s param_update;
|
||||
_parameter_update_sub.copy(¶m_update);
|
||||
|
||||
// If any parameter updated, call updateParams() to check if
|
||||
// this class attributes need updating (and do so).
|
||||
updateParams();
|
||||
}
|
||||
}
|
||||
|
||||
void RtlTimeEstimator::addVertDistance(float alt)
|
||||
{
|
||||
if (PX4_ISFINITE(alt)) {
|
||||
_is_valid = true;
|
||||
|
||||
_time_estimate += calcVertTimeEstimate(alt);
|
||||
}
|
||||
}
|
||||
|
||||
void RtlTimeEstimator::addDistance(float hor_dist, const matrix::Vector2f &direction, float vert_dist)
|
||||
{
|
||||
if (PX4_ISFINITE(hor_dist) && PX4_ISFINITE(vert_dist)) {
|
||||
_is_valid = true;
|
||||
|
||||
float hor_time_estimate{0.f};
|
||||
|
||||
if (hor_dist > FLT_EPSILON && PX4_ISFINITE(hor_dist)) {
|
||||
hor_time_estimate = hor_dist / getCruiseGroundSpeed(direction.normalized());
|
||||
}
|
||||
|
||||
float ver_time_estimate{calcVertTimeEstimate(vert_dist)};
|
||||
|
||||
_time_estimate += math::max(hor_time_estimate, ver_time_estimate);
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
void RtlTimeEstimator::addWait(float time_s)
|
||||
{
|
||||
if (PX4_ISFINITE(time_s)) {
|
||||
_is_valid = true;
|
||||
|
||||
if (time_s > FLT_EPSILON) {
|
||||
_time_estimate += time_s;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void RtlTimeEstimator::addDescendMCLand(float alt)
|
||||
{
|
||||
if (PX4_ISFINITE(alt)) {
|
||||
_is_valid = true;
|
||||
|
||||
if (alt < -FLT_EPSILON && PX4_ISFINITE(alt)) {
|
||||
_time_estimate += -alt / getHoverLandSpeed();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
float RtlTimeEstimator::getCruiseGroundSpeed(const matrix::Vector2f &direction_norm)
|
||||
{
|
||||
float cruise_speed = getCruiseSpeed();
|
||||
|
||||
if (_vehicle_status_sub.get().vehicle_type == vehicle_status_s::VEHICLE_TYPE_FIXED_WING) {
|
||||
matrix::Vector2f wind = get_wind();
|
||||
|
||||
const float wind_along_dir = wind.dot(direction_norm);
|
||||
const float wind_across_dir = matrix::Vector2f(wind - direction_norm * wind_along_dir).norm();
|
||||
|
||||
// Note: use fminf so that we don't _rely_ on tailwind towards direction to make RTL more efficient
|
||||
const float ground_speed = sqrtf(cruise_speed * cruise_speed - wind_across_dir * wind_across_dir) + fminf(
|
||||
0.f, wind_along_dir);
|
||||
|
||||
cruise_speed = ground_speed;
|
||||
}
|
||||
|
||||
return cruise_speed;
|
||||
}
|
||||
|
||||
float RtlTimeEstimator::calcVertTimeEstimate(float alt)
|
||||
{
|
||||
float vertical_rate{0.1f};
|
||||
float time_estimate{0.f};
|
||||
|
||||
if (alt > FLT_EPSILON) {
|
||||
vertical_rate = getClimbRate();
|
||||
|
||||
} else {
|
||||
vertical_rate = getDescendRate();
|
||||
}
|
||||
|
||||
float abs_alt = fabsf(alt);
|
||||
|
||||
if (abs_alt > FLT_EPSILON) {
|
||||
time_estimate = abs_alt / vertical_rate;
|
||||
}
|
||||
|
||||
return time_estimate;
|
||||
}
|
||||
|
||||
float RtlTimeEstimator::getCruiseSpeed()
|
||||
{
|
||||
float ret = 1e6f;
|
||||
|
||||
if (_vehicle_status_sub.get().vehicle_type == vehicle_status_s::VEHICLE_TYPE_ROTARY_WING) {
|
||||
if (_param_mpc_xy_cruise == PARAM_INVALID || param_get(_param_mpc_xy_cruise, &ret) != PX4_OK) {
|
||||
ret = 1e6f;
|
||||
}
|
||||
|
||||
} else if (_vehicle_status_sub.get().vehicle_type == vehicle_status_s::VEHICLE_TYPE_FIXED_WING) {
|
||||
if (_param_fw_airspeed_trim == PARAM_INVALID || param_get(_param_fw_airspeed_trim, &ret) != PX4_OK) {
|
||||
ret = 1e6f;
|
||||
}
|
||||
|
||||
} else if (_vehicle_status_sub.get().vehicle_type == vehicle_status_s::VEHICLE_TYPE_ROVER) {
|
||||
if (_param_rover_cruise_speed == PARAM_INVALID || param_get(_param_rover_cruise_speed, &ret) != PX4_OK) {
|
||||
ret = 1e6f;
|
||||
}
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
float RtlTimeEstimator::getHoverLandSpeed()
|
||||
{
|
||||
float ret = 1e6f;
|
||||
|
||||
if (_param_mpc_land_speed == PARAM_INVALID || param_get(_param_mpc_land_speed, &ret) != PX4_OK) {
|
||||
ret = 1e6f;
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
matrix::Vector2f RtlTimeEstimator::get_wind()
|
||||
{
|
||||
_wind_sub.update();
|
||||
matrix::Vector2f wind{};
|
||||
|
||||
if (hrt_absolute_time() - _wind_sub.get().timestamp < 1_s) {
|
||||
wind(0) = _wind_sub.get().windspeed_north;
|
||||
wind(1) = _wind_sub.get().windspeed_east;
|
||||
}
|
||||
|
||||
return wind;
|
||||
}
|
||||
|
||||
float RtlTimeEstimator::getClimbRate()
|
||||
{
|
||||
float ret = 1e6f;
|
||||
|
||||
if (_vehicle_status_sub.get().vehicle_type == vehicle_status_s::VEHICLE_TYPE_ROTARY_WING) {
|
||||
if (_param_mpc_z_v_auto_up == PARAM_INVALID || param_get(_param_mpc_z_v_auto_up, &ret) != PX4_OK) {
|
||||
ret = 1e6f;
|
||||
}
|
||||
|
||||
} else if (_vehicle_status_sub.get().vehicle_type == vehicle_status_s::VEHICLE_TYPE_FIXED_WING) {
|
||||
|
||||
if (_param_fw_climb_rate == PARAM_INVALID || param_get(_param_fw_climb_rate, &ret) != PX4_OK) {
|
||||
ret = 1e6f;
|
||||
}
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
float RtlTimeEstimator::getDescendRate()
|
||||
{
|
||||
float ret = 1e6f;
|
||||
|
||||
if (_vehicle_status_sub.get().vehicle_type == vehicle_status_s::VEHICLE_TYPE_ROTARY_WING) {
|
||||
if (_param_mpc_z_v_auto_dn == PARAM_INVALID || param_get(_param_mpc_z_v_auto_dn, &ret) != PX4_OK) {
|
||||
ret = 1e6f;
|
||||
}
|
||||
|
||||
} else if (_vehicle_status_sub.get().vehicle_type == vehicle_status_s::VEHICLE_TYPE_FIXED_WING) {
|
||||
if (_param_fw_sink_rate == PARAM_INVALID || param_get(_param_fw_sink_rate, &ret) != PX4_OK) {
|
||||
ret = 1e6f;
|
||||
}
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
@ -1,146 +0,0 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2024 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 rtl_time_estimator.h
|
||||
*
|
||||
* Helper class to calculate the remaining time estimate to go to RTL landing point.
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef RTL_TIME_ESTIMATOR_H_
|
||||
#define RTL_TIME_ESTIMATOR_H_
|
||||
|
||||
#include <px4_platform_common/module_params.h>
|
||||
|
||||
#include <uORB/Subscription.hpp>
|
||||
#include <uORB/SubscriptionInterval.hpp>
|
||||
#include <uORB/topics/parameter_update.h>
|
||||
#include <uORB/topics/rtl_time_estimate.h>
|
||||
#include <uORB/topics/vehicle_status.h>
|
||||
#include <uORB/topics/wind.h>
|
||||
|
||||
#include <matrix/Vector2.hpp>
|
||||
|
||||
using namespace time_literals;
|
||||
|
||||
class Navigator;
|
||||
|
||||
class RtlTimeEstimator : public ModuleParams
|
||||
{
|
||||
public:
|
||||
RtlTimeEstimator();
|
||||
~RtlTimeEstimator() = default;
|
||||
|
||||
void update();
|
||||
void reset() { _time_estimate = 0.f; _is_valid = false;};
|
||||
rtl_time_estimate_s getEstimate() const;
|
||||
void addDistance(float hor_dist, const matrix::Vector2f &hor_direction, float vert_dist);
|
||||
void addVertDistance(float alt);
|
||||
void addWait(float time_s);
|
||||
void addDescendMCLand(float alt);
|
||||
|
||||
private:
|
||||
/**
|
||||
* @brief Get the Cruise Ground Speed
|
||||
*
|
||||
* @param direction_norm normalized direction in which to fly
|
||||
* @return Ground speed in cruise mode [m/s].
|
||||
*/
|
||||
float getCruiseGroundSpeed(const matrix::Vector2f &direction_norm);
|
||||
|
||||
/**
|
||||
* @brief Get time estimate of vertical distance
|
||||
*
|
||||
*/
|
||||
float calcVertTimeEstimate(float alt);
|
||||
|
||||
/**
|
||||
* @brief Get the climb rate
|
||||
*
|
||||
* @return Climb rate [m/s]
|
||||
*/
|
||||
float getClimbRate();
|
||||
|
||||
/**
|
||||
* @brief Get the descend rate
|
||||
*
|
||||
* @return descend rate [m/s]
|
||||
*/
|
||||
float getDescendRate();
|
||||
|
||||
/**
|
||||
* @brief Get the cruise speed
|
||||
*
|
||||
* @return cruise speed [m/s]
|
||||
*/
|
||||
float getCruiseSpeed();
|
||||
|
||||
/**
|
||||
* @brief Get the Hover Land Speed
|
||||
*
|
||||
* @return Hover land speed [m/s]
|
||||
*/
|
||||
float getHoverLandSpeed();
|
||||
|
||||
/**
|
||||
* @brief Get the horizontal wind velocity
|
||||
*
|
||||
* @return horizontal wind velocity.
|
||||
*/
|
||||
matrix::Vector2f get_wind();
|
||||
|
||||
float _time_estimate; /**< Accumulated time estimate [s] */
|
||||
bool _is_valid{false}; /**< Checks if time estimate is valid */
|
||||
|
||||
DEFINE_PARAMETERS(
|
||||
(ParamFloat<px4::params::RTL_TIME_FACTOR>) _param_rtl_time_factor, /**< Safety factory for safe time estimate */
|
||||
(ParamInt<px4::params::RTL_TIME_MARGIN>) _param_rtl_time_margin /**< Safety margin for safe time estimate */
|
||||
)
|
||||
|
||||
param_t _param_mpc_z_v_auto_up{PARAM_INVALID}; /**< MC climb velocity parameter */
|
||||
param_t _param_mpc_z_v_auto_dn{PARAM_INVALID}; /**< MC descend velocity parameter */
|
||||
param_t _param_mpc_land_speed{PARAM_INVALID}; /**< MC land descend speed parameter */
|
||||
param_t _param_fw_climb_rate{PARAM_INVALID}; /**< FW climb speed parameter */
|
||||
param_t _param_fw_sink_rate{PARAM_INVALID}; /**< FW descend speed parameter */
|
||||
|
||||
param_t _param_fw_airspeed_trim{PARAM_INVALID}; /**< FW cruise airspeed parameter */
|
||||
param_t _param_mpc_xy_cruise{PARAM_INVALID}; /**< MC horizontal cruise speed parameter */
|
||||
param_t _param_rover_cruise_speed{PARAM_INVALID}; /**< Rover cruise speed parameter */
|
||||
|
||||
uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; /**< Parameter update topic */
|
||||
uORB::SubscriptionData<vehicle_status_s> _vehicle_status_sub{ORB_ID(vehicle_status)}; /**< vehicle status subscription */
|
||||
uORB::SubscriptionData<wind_s> _wind_sub{ORB_ID(wind)}; /**< wind topic */
|
||||
};
|
||||
|
||||
#endif /* RTL_TIME_ESTIMATOR_H_ */
|
||||
@ -598,9 +598,6 @@ transition_result_t Commander::arm(arm_disarm_reason_t calling_reason, bool run_
|
||||
|
||||
if (!_health_and_arming_checks.canArm(_vehicle_status.nav_state)) {
|
||||
tune_negative(true);
|
||||
mavlink_log_critical(&_mavlink_log_pub, "Arming denied: Resolve system health failures first\t");
|
||||
events::send(events::ID("commander_arm_denied_resolve_failures"), {events::Log::Critical, events::LogInternal::Info},
|
||||
"Arming denied: Resolve system health failures first");
|
||||
return TRANSITION_DENIED;
|
||||
}
|
||||
}
|
||||
@ -2422,14 +2419,7 @@ void Commander::control_status_leds(bool changed, const uint8_t battery_warning)
|
||||
if (_cpuload_sub.copy(&cpuload)) {
|
||||
const float cpuload_percent = cpuload.load * 100.f;
|
||||
|
||||
bool overload = false;
|
||||
|
||||
// Only check CPU load if it hasn't been disabled
|
||||
if (!(_param_com_cpu_max.get() < FLT_EPSILON)) {
|
||||
overload = (cpuload_percent > _param_com_cpu_max.get());
|
||||
}
|
||||
|
||||
overload = overload || (cpuload.ram_usage > 0.99f);
|
||||
bool overload = (cpuload_percent > _param_com_cpu_max.get()) || (cpuload.ram_usage > 0.99f);
|
||||
|
||||
if (_overload_start == 0 && overload) {
|
||||
_overload_start = time_now_us;
|
||||
|
||||
@ -285,16 +285,12 @@ void BatteryChecks::rtlEstimateCheck(const Context &context, Report &reporter, f
|
||||
rtl_time_estimate_s rtl_time_estimate;
|
||||
|
||||
// Compare estimate of RTL time to estimate of remaining flight time
|
||||
// add hysterisis: if already in the condition, only get out of it if the remaining flight time is significantly higher again
|
||||
const float hysteresis_factor = reporter.failsafeFlags().battery_low_remaining_time ? 1.1f : 1.0f;
|
||||
|
||||
reporter.failsafeFlags().battery_low_remaining_time = _rtl_time_estimate_sub.copy(&rtl_time_estimate)
|
||||
&& (hrt_absolute_time() - rtl_time_estimate.timestamp) < 3_s
|
||||
&& (hrt_absolute_time() - rtl_time_estimate.timestamp) < 2_s
|
||||
&& rtl_time_estimate.valid
|
||||
&& context.isArmed()
|
||||
&& PX4_ISFINITE(worst_battery_time_s)
|
||||
&& rtl_time_estimate.safe_time_estimate * hysteresis_factor >= worst_battery_time_s;
|
||||
|
||||
&& rtl_time_estimate.safe_time_estimate >= worst_battery_time_s;
|
||||
|
||||
if (reporter.failsafeFlags().battery_low_remaining_time) {
|
||||
/* EVENT
|
||||
|
||||
@ -293,9 +293,7 @@ void EstimatorChecks::checkEstimatorStatus(const Context &context, Report &repor
|
||||
mavlink_log_warning(reporter.mavlink_log_pub(), "GNSS data fusion stopped\t");
|
||||
}
|
||||
|
||||
// only report this failure as critical if not already in a local position invalid state
|
||||
events::Log log_level = reporter.failsafeFlags().local_position_invalid ? events::Log::Info : events::Log::Error;
|
||||
events::send(events::ID("check_estimator_gnss_fusion_stopped"), {log_level, events::LogInternal::Info},
|
||||
events::send(events::ID("check_estimator_gnss_fusion_stopped"), {events::Log::Error, events::LogInternal::Info},
|
||||
"GNSS data fusion stopped");
|
||||
|
||||
} else if (!_gps_was_fused && ekf_gps_fusion) {
|
||||
|
||||
@ -1030,17 +1030,3 @@ PARAM_DEFINE_INT32(COM_THROW_EN, 0);
|
||||
* @unit m/s
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(COM_THROW_SPEED, 5);
|
||||
|
||||
/**
|
||||
* Remaining flight time low failsafe
|
||||
*
|
||||
* Action the system takes when the remaining flight time is below
|
||||
* the estimated time it takes to reach the RTL destination.
|
||||
*
|
||||
* @group Commander
|
||||
* @value 0 None
|
||||
* @value 1 Warning
|
||||
* @value 3 Return
|
||||
* @increment 1
|
||||
*/
|
||||
PARAM_DEFINE_INT32(COM_FLTT_LOW_ACT, 3);
|
||||
|
||||
@ -365,36 +365,6 @@ FailsafeBase::ActionOptions Failsafe::fromHighWindLimitActParam(int param_value)
|
||||
return options;
|
||||
}
|
||||
|
||||
FailsafeBase::ActionOptions Failsafe::fromRemainingFlightTimeLowActParam(int param_value)
|
||||
{
|
||||
ActionOptions options{};
|
||||
|
||||
options.allow_user_takeover = UserTakeoverAllowed::Auto;
|
||||
options.cause = Cause::RemainingFlightTimeLow;
|
||||
|
||||
switch (command_after_remaining_flight_time_low(param_value)) {
|
||||
case command_after_remaining_flight_time_low::None:
|
||||
options.action = Action::None;
|
||||
break;
|
||||
|
||||
case command_after_remaining_flight_time_low::Warning:
|
||||
options.action = Action::Warn;
|
||||
break;
|
||||
|
||||
case command_after_remaining_flight_time_low::Return_mode:
|
||||
options.action = Action::RTL;
|
||||
options.clear_condition = ClearCondition::OnModeChangeOrDisarm;
|
||||
break;
|
||||
|
||||
default:
|
||||
options.action = Action::None;
|
||||
break;
|
||||
|
||||
}
|
||||
|
||||
return options;
|
||||
}
|
||||
|
||||
void Failsafe::checkStateAndMode(const hrt_abstime &time_us, const State &state,
|
||||
const failsafe_flags_s &status_flags)
|
||||
{
|
||||
@ -474,10 +444,9 @@ void Failsafe::checkStateAndMode(const hrt_abstime &time_us, const State &state,
|
||||
|
||||
CHECK_FAILSAFE(status_flags, geofence_breached, fromGfActParam(_param_gf_action.get()).cannotBeDeferred());
|
||||
|
||||
// Battery flight time remaining failsafe
|
||||
|
||||
// Battery
|
||||
CHECK_FAILSAFE(status_flags, battery_low_remaining_time,
|
||||
ActionOptions(fromRemainingFlightTimeLowActParam(_param_com_fltt_low_act.get())));
|
||||
ActionOptions(Action::RTL).causedBy(Cause::BatteryLow).clearOn(ClearCondition::OnModeChangeOrDisarm));
|
||||
|
||||
if ((_armed_time != 0)
|
||||
&& (time_us < _armed_time + static_cast<hrt_abstime>(_param_com_spoolup_time.get() * 1_s))
|
||||
@ -488,7 +457,6 @@ void Failsafe::checkStateAndMode(const hrt_abstime &time_us, const State &state,
|
||||
CHECK_FAILSAFE(status_flags, battery_unhealthy, Action::Warn);
|
||||
}
|
||||
|
||||
// Battery low failsafe
|
||||
switch (status_flags.battery_warning) {
|
||||
case battery_status_s::BATTERY_WARNING_LOW:
|
||||
_last_state_battery_warning_low = checkFailsafe(_caller_id_battery_warning_low, _last_state_battery_warning_low,
|
||||
|
||||
@ -141,12 +141,6 @@ private:
|
||||
Land_mode = 5
|
||||
};
|
||||
|
||||
enum class command_after_remaining_flight_time_low : int32_t {
|
||||
None = 0,
|
||||
Warning = 1,
|
||||
Return_mode = 3
|
||||
};
|
||||
|
||||
static ActionOptions fromNavDllOrRclActParam(int param_value);
|
||||
|
||||
static ActionOptions fromGfActParam(int param_value);
|
||||
@ -156,7 +150,6 @@ private:
|
||||
static ActionOptions fromQuadchuteActParam(int param_value);
|
||||
static Action fromOffboardLossActParam(int param_value, uint8_t &user_intended_mode);
|
||||
static ActionOptions fromHighWindLimitActParam(int param_value);
|
||||
static ActionOptions fromRemainingFlightTimeLowActParam(int param_value);
|
||||
|
||||
const int _caller_id_mode_fallback{genCallerId()};
|
||||
bool _last_state_mode_fallback{false};
|
||||
@ -189,8 +182,7 @@ private:
|
||||
(ParamInt<px4::params::COM_LOW_BAT_ACT>) _param_com_low_bat_act,
|
||||
(ParamInt<px4::params::COM_OBL_RC_ACT>) _param_com_obl_rc_act,
|
||||
(ParamInt<px4::params::COM_QC_ACT>) _param_com_qc_act,
|
||||
(ParamInt<px4::params::COM_WIND_MAX_ACT>) _param_com_wind_max_act,
|
||||
(ParamInt<px4::params::COM_FLTT_LOW_ACT>) _param_com_fltt_low_act
|
||||
(ParamInt<px4::params::COM_WIND_MAX_ACT>) _param_com_wind_max_act
|
||||
);
|
||||
|
||||
};
|
||||
|
||||
@ -195,7 +195,7 @@ void FailsafeBase::notifyUser(uint8_t user_intended_mode, Action action, Action
|
||||
events::send<uint32_t, events::px4::enums::failsafe_action_t, uint16_t>(
|
||||
events::ID("commander_failsafe_enter_generic_hold"),
|
||||
{events::Log::Critical, events::LogInternal::Warning},
|
||||
"Failsafe, triggering {2} in {3} seconds", mavlink_mode, failsafe_action,
|
||||
"Failsafe activated, triggering {2} in {3} seconds", mavlink_mode, failsafe_action,
|
||||
(uint16_t) delay_s);
|
||||
|
||||
} else {
|
||||
@ -204,7 +204,7 @@ void FailsafeBase::notifyUser(uint8_t user_intended_mode, Action action, Action
|
||||
events::send<uint32_t, events::px4::enums::failsafe_action_t, uint16_t, events::px4::enums::failsafe_cause_t>(
|
||||
events::ID("commander_failsafe_enter_hold"),
|
||||
{events::Log::Critical, events::LogInternal::Warning},
|
||||
"{4}, triggering {2} in {3} seconds", mavlink_mode, failsafe_action,
|
||||
"Failsafe activated due to {4}, triggering {2} in {3} seconds", mavlink_mode, failsafe_action,
|
||||
(uint16_t) delay_s, failsafe_cause);
|
||||
}
|
||||
|
||||
@ -231,7 +231,7 @@ void FailsafeBase::notifyUser(uint8_t user_intended_mode, Action action, Action
|
||||
events::send<uint32_t, events::px4::enums::failsafe_action_t>(
|
||||
events::ID("commander_failsafe_enter_generic"),
|
||||
{events::Log::Critical, events::LogInternal::Warning},
|
||||
"Failsafe, triggering {2}", mavlink_mode, failsafe_action);
|
||||
"Failsafe activated, triggering {2}", mavlink_mode, failsafe_action);
|
||||
}
|
||||
|
||||
} else {
|
||||
@ -250,11 +250,6 @@ void FailsafeBase::notifyUser(uint8_t user_intended_mode, Action action, Action
|
||||
events::send(events::ID("commander_failsafe_enter_crit_low_bat_warn"), {events::Log::Emergency, events::LogInternal::Info},
|
||||
"Emergency battery level, land immediately");
|
||||
|
||||
} else if (cause == Cause::RemainingFlightTimeLow) {
|
||||
events::send(events::ID("commander_failsafe_enter_low_flight_time_warn"),
|
||||
{events::Log::Warning, events::LogInternal::Info},
|
||||
"Low remaining flight time, return advised");
|
||||
|
||||
} else {
|
||||
/* EVENT
|
||||
* @description No action is triggered.
|
||||
@ -272,7 +267,7 @@ void FailsafeBase::notifyUser(uint8_t user_intended_mode, Action action, Action
|
||||
events::send<uint32_t, events::px4::enums::failsafe_action_t, events::px4::enums::failsafe_cause_t>(
|
||||
events::ID("commander_failsafe_enter"),
|
||||
{events::Log::Critical, events::LogInternal::Warning},
|
||||
"{3}, triggering {2}", mavlink_mode, failsafe_action, failsafe_cause);
|
||||
"Failsafe activated due to {3}, triggering {2}", mavlink_mode, failsafe_action, failsafe_cause);
|
||||
}
|
||||
}
|
||||
|
||||
@ -517,8 +512,6 @@ void FailsafeBase::getSelectedAction(const State &state, const failsafe_flags_s
|
||||
break;
|
||||
}
|
||||
|
||||
returned_state.cause = Cause::Generic;
|
||||
|
||||
// fallthrough
|
||||
case Action::FallbackAltCtrl:
|
||||
if (modeCanRun(status_flags, vehicle_status_s::NAVIGATION_STATE_ALTCTL)) {
|
||||
@ -526,8 +519,6 @@ void FailsafeBase::getSelectedAction(const State &state, const failsafe_flags_s
|
||||
break;
|
||||
}
|
||||
|
||||
returned_state.cause = Cause::Generic;
|
||||
|
||||
// fallthrough
|
||||
case Action::FallbackStab:
|
||||
if (modeCanRun(status_flags, vehicle_status_s::NAVIGATION_STATE_STAB)) {
|
||||
@ -535,8 +526,6 @@ void FailsafeBase::getSelectedAction(const State &state, const failsafe_flags_s
|
||||
break;
|
||||
} // else: fall through here as well. If stabilized isn't available, we most certainly end up in Terminate
|
||||
|
||||
returned_state.cause = Cause::Generic;
|
||||
|
||||
// fallthrough
|
||||
case Action::Hold:
|
||||
if (modeCanRun(status_flags, vehicle_status_s::NAVIGATION_STATE_AUTO_LOITER)) {
|
||||
@ -544,8 +533,6 @@ void FailsafeBase::getSelectedAction(const State &state, const failsafe_flags_s
|
||||
break;
|
||||
}
|
||||
|
||||
returned_state.cause = Cause::Generic;
|
||||
|
||||
// fallthrough
|
||||
case Action::RTL:
|
||||
if (modeCanRun(status_flags, vehicle_status_s::NAVIGATION_STATE_AUTO_RTL)) {
|
||||
@ -553,8 +540,6 @@ void FailsafeBase::getSelectedAction(const State &state, const failsafe_flags_s
|
||||
break;
|
||||
}
|
||||
|
||||
returned_state.cause = Cause::Generic;
|
||||
|
||||
// fallthrough
|
||||
case Action::Land:
|
||||
if (modeCanRun(status_flags, vehicle_status_s::NAVIGATION_STATE_AUTO_LAND)) {
|
||||
@ -562,8 +547,6 @@ void FailsafeBase::getSelectedAction(const State &state, const failsafe_flags_s
|
||||
break;
|
||||
}
|
||||
|
||||
returned_state.cause = Cause::Generic;
|
||||
|
||||
// fallthrough
|
||||
case Action::Descend:
|
||||
if (modeCanRun(status_flags, vehicle_status_s::NAVIGATION_STATE_DESCEND)) {
|
||||
@ -571,8 +554,6 @@ void FailsafeBase::getSelectedAction(const State &state, const failsafe_flags_s
|
||||
break;
|
||||
}
|
||||
|
||||
returned_state.cause = Cause::Generic;
|
||||
|
||||
// fallthrough
|
||||
case Action::Terminate:
|
||||
selected_action = Action::Terminate;
|
||||
|
||||
@ -83,7 +83,6 @@ public:
|
||||
BatteryLow,
|
||||
BatteryCritical,
|
||||
BatteryEmergency,
|
||||
RemainingFlightTimeLow,
|
||||
|
||||
Count
|
||||
};
|
||||
@ -147,7 +146,7 @@ public:
|
||||
bool rc_sticks_takeover_request,
|
||||
const failsafe_flags_s &status_flags);
|
||||
|
||||
bool inFailsafe() const { return (_selected_action != Action::None && _selected_action != Action::Warn); }
|
||||
bool inFailsafe() const { return _selected_action != Action::None; }
|
||||
|
||||
Action selectedAction() const { return _selected_action; }
|
||||
|
||||
|
||||
@ -334,9 +334,6 @@ struct parameters {
|
||||
float req_hdrift{0.3f}; ///< maximum acceptable horizontal drift speed (m/s)
|
||||
float req_vdrift{0.5f}; ///< maximum acceptable vertical drift speed (m/s)
|
||||
|
||||
float gps_kill_t{0};
|
||||
|
||||
|
||||
# if defined(CONFIG_EKF2_GNSS_YAW)
|
||||
// GNSS heading fusion
|
||||
float gps_heading_noise{0.1f}; ///< measurement noise standard deviation used for GNSS heading fusion (rad)
|
||||
|
||||
@ -84,9 +84,6 @@ void Ekf::reset()
|
||||
_control_status.flags.in_air = true;
|
||||
_control_status_prev.flags.in_air = true;
|
||||
|
||||
_time_last_on_ground_us = _time_delayed_us;
|
||||
_time_last_in_air = _time_delayed_us;
|
||||
|
||||
_ang_rate_delayed_raw.zero();
|
||||
|
||||
_fault_status.value = 0;
|
||||
|
||||
@ -485,14 +485,9 @@ public:
|
||||
#else
|
||||
// Efficient implementation of the Joseph stabilized covariance update
|
||||
// Based on "G. J. Bierman. Factorization Methods for Discrete Sequential Estimation. Academic Press, Dover Publications, New York, 1977, 2006"
|
||||
// P = (I - K * H) * P * (I - K * H).T + K * R * K.T
|
||||
// = P_temp * (I - H.T * K.T) + K * R * K.T
|
||||
// = P_temp - P_temp * H.T * K.T + K * R * K.T
|
||||
|
||||
// Step 1: conventional update
|
||||
// Compute P_temp and store it in P to avoid allocating more memory
|
||||
// P is symmetric, so PH == H.T * P.T == H.T * P. Taking the row is faster as matrices are row-major
|
||||
VectorState PH = P * H; // H is stored as a column vector. H is in fact H.T
|
||||
VectorState PH = P * H;
|
||||
|
||||
for (unsigned i = 0; i < State::size; i++) {
|
||||
for (unsigned j = 0; j < State::size; j++) {
|
||||
@ -501,7 +496,7 @@ public:
|
||||
}
|
||||
|
||||
// Step 2: stabilized update
|
||||
PH = P * H; // H is stored as a column vector. H is in fact H.T
|
||||
PH = P * H;
|
||||
|
||||
for (unsigned i = 0; i < State::size; i++) {
|
||||
for (unsigned j = 0; j <= i; j++) {
|
||||
|
||||
@ -865,24 +865,18 @@ bool Ekf::fuseDirectStateMeasurement(const float innov, const float innov_var, c
|
||||
#else
|
||||
// Efficient implementation of the Joseph stabilized covariance update
|
||||
// Based on "G. J. Bierman. Factorization Methods for Discrete Sequential Estimation. Academic Press, Dover Publications, New York, 1977, 2006"
|
||||
// P = (I - K * H) * P * (I - K * H).T + K * R * K.T
|
||||
// = P_temp * (I - H.T * K.T) + K * R * K.T
|
||||
// = P_temp - P_temp * H.T * K.T + K * R * K.T
|
||||
|
||||
// Step 1: conventional update
|
||||
// Compute P_temp and store it in P to avoid allocating more memory
|
||||
// P is symmetric, so PH == H.T * P.T == H.T * P. Taking the row is faster as matrices are row-major
|
||||
VectorState PH = P.row(state_index);
|
||||
|
||||
for (unsigned i = 0; i < State::size; i++) {
|
||||
for (unsigned j = 0; j < State::size; j++) {
|
||||
P(i, j) -= K(i) * PH(j); // P is now not symmetric if K is not optimal (e.g.: some gains have been zeroed)
|
||||
P(i, j) -= K(i) * PH(j); // P is now not symmetrical if K is not optimal (e.g.: some gains have been zeroed)
|
||||
}
|
||||
}
|
||||
|
||||
// Step 2: stabilized update
|
||||
// P (or "P_temp") is not symmetric so we must take the column
|
||||
PH = P.col(state_index);
|
||||
PH = P.row(state_index);
|
||||
|
||||
for (unsigned i = 0; i < State::size; i++) {
|
||||
for (unsigned j = 0; j <= i; j++) {
|
||||
|
||||
@ -85,7 +85,6 @@ void Ekf::controlGpsFusion(const imuSample &imu_delayed)
|
||||
}
|
||||
|
||||
updateGnssVel(gnss_sample, _aid_src_gnss_vel);
|
||||
controlGnssYawEstimator(_aid_src_gnss_vel);
|
||||
|
||||
} else if (_control_status.flags.gps) {
|
||||
if (!isNewestSampleRecent(_time_last_gps_buffer_push, _params.reset_timeout_max)) {
|
||||
@ -95,33 +94,14 @@ void Ekf::controlGpsFusion(const imuSample &imu_delayed)
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
#if 1
|
||||
// GPS HACK
|
||||
if (_control_status.flags.in_air
|
||||
&& _params.gps_kill_t > 0.f
|
||||
&& _time_last_on_ground_us > 0
|
||||
&& _time_delayed_us > _time_last_on_ground_us + (1'000'000 * _params.gps_kill_t)
|
||||
//&& false
|
||||
) {
|
||||
_gps_data_ready = false;
|
||||
// _control_status.flags.wind_dead_reckoning
|
||||
_control_status.flags.gps = false;
|
||||
return;
|
||||
} else {
|
||||
if (_time_last_on_ground_us > 0) {
|
||||
//ECL_INFO("time: %llu, in_air:%d, gnd: %llu, ?:%d", _time_delayed_us, _control_status.flags.in_air, _time_last_on_ground_us, _time_delayed_us > _time_last_on_ground_us + (1'000'000 * 100));
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
if (_gps_data_ready) {
|
||||
#if defined(CONFIG_EKF2_GNSS_YAW)
|
||||
const gnssSample &gnss_sample = _gps_sample_delayed;
|
||||
controlGpsYawFusion(gnss_sample);
|
||||
#endif // CONFIG_EKF2_GNSS_YAW
|
||||
|
||||
controlGnssYawEstimator(_aid_src_gnss_vel);
|
||||
|
||||
const bool gnss_vel_enabled = (_params.gnss_ctrl & static_cast<int32_t>(GnssCtrl::VEL));
|
||||
const bool gnss_pos_enabled = (_params.gnss_ctrl & static_cast<int32_t>(GnssCtrl::HPOS));
|
||||
|
||||
@ -266,7 +246,7 @@ bool Ekf::tryYawEmergencyReset()
|
||||
bool success = false;
|
||||
|
||||
/* A rapid reset to the yaw emergency estimate is performed if horizontal velocity innovation checks continuously
|
||||
* fails while the difference between the yaw emergency estimator and the yaw estimate is large.
|
||||
* fails while the difference between the yaw emergency estimator and the yas estimate is large.
|
||||
* This enables recovery from a bad yaw estimate. A reset is not performed if the fault condition was
|
||||
* present before flight to prevent triggering due to GPS glitches or other sensor errors.
|
||||
*/
|
||||
|
||||
Some files were not shown because too many files have changed in this diff Show More
Loading…
x
Reference in New Issue
Block a user