Compare commits

..

1 Commits

Author SHA1 Message Date
Daniel Agar 9586ad0006 [RFC] broadcast parameter changes and ModuleParams skip full updateParams() when possible 2022-12-19 21:14:04 -05:00
129 changed files with 2774 additions and 3670 deletions
+6 -6
View File
@@ -684,7 +684,7 @@ void checkStatus() {
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "param save"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "param status"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "param show SYS*"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "bsondump /fs/mtd_params"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "param dump"'
// status commands
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "cat /proc/fs/blocks"'
@@ -715,7 +715,7 @@ void checkStatus() {
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "mavlink status" || true'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "mount"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "mtd status"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "bsondump /fs/mtd_params"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "param dump"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "param show" || true'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "param status"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "perf latency"'
@@ -767,13 +767,13 @@ void runTests() {
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "tests file" || true'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "bsondump /fs/mtd_params"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "param dump /fs/mtd_params"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "mtd readtest"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "bsondump /fs/mtd_params"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "param dump /fs/mtd_params"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "mtd rwtest"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "bsondump /fs/mtd_params"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "param dump /fs/mtd_params"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "mtd erase"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "bsondump /fs/mtd_params"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "param dump /fs/mtd_params"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "sd_bench"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "sd_bench -v"'
+3 -3
View File
@@ -74,7 +74,7 @@ if [ -f $PARAM_FILE ]; then
then
echo "ERROR [init] param import failed"
bsondump $PARAM_FILE
param dump $PARAM_FILE
# try to make a backup copy
cp $PARAM_FILE param_import_fail.bson
@@ -85,7 +85,7 @@ if [ -f $PARAM_FILE ]; then
echo "[init] importing from parameter backup"
# dump current backup file contents for comparison
bsondump $PARAM_BACKUP_FILE
param dump $PARAM_BACKUP_FILE
param import $PARAM_BACKUP_FILE
@@ -227,7 +227,7 @@ then
elif [ ! -e "$autostart_file" ] && [ "$SYS_AUTOSTART" -ne "0" ]
then
echo "Error: no autostart file found ($autostart_file)"
#exit 1
exit 1
fi
#user defined params for instances can be in PATH
+2 -2
View File
@@ -130,7 +130,7 @@ else
echo "ERROR [init] param import failed"
set STARTUP_TUNE 2 # tune 2 = ERROR_TUNE
bsondump $PARAM_FILE
param dump $PARAM_FILE
if [ -d "/fs/microsd" ]
then
@@ -143,7 +143,7 @@ else
echo "[init] importing from parameter backup"
# dump current backup file contents for comparison
bsondump $PARAM_BACKUP_FILE
param dump $PARAM_BACKUP_FILE
param import $PARAM_BACKUP_FILE
+3 -3
View File
@@ -43,13 +43,13 @@ do
${DIR}/run_nsh_cmd.py --device ${SERIAL_DEVICE} --cmd 'param reset SYS_HITL'
${DIR}/run_nsh_cmd.py --device ${SERIAL_DEVICE} --cmd 'param status'
${DIR}/run_nsh_cmd.py --device ${SERIAL_DEVICE} --cmd 'param save'
${DIR}/run_nsh_cmd.py --device ${SERIAL_DEVICE} --cmd 'bsondump /fs/mtd_params'
${DIR}/run_nsh_cmd.py --device ${SERIAL_DEVICE} --cmd 'param dump'
${DIR}/reboot.py --device ${SERIAL_DEVICE}
${DIR}/run_nsh_cmd.py --device ${SERIAL_DEVICE} --cmd 'param status'
${DIR}/run_nsh_cmd.py --device ${SERIAL_DEVICE} --cmd 'bsondump /fs/mtd_params' || true
${DIR}/run_nsh_cmd.py --device ${SERIAL_DEVICE} --cmd 'bsondump /fs/microsd/parameters_backup.bson' || true
${DIR}/run_nsh_cmd.py --device ${SERIAL_DEVICE} --cmd 'param dump /fs/mtd_params' || true
${DIR}/run_nsh_cmd.py --device ${SERIAL_DEVICE} --cmd 'param dump /fs/microsd/parameters_backup.bson' || true
${DIR}/run_nsh_cmd.py --device ${SERIAL_DEVICE} --cmd 'ps'
${DIR}/run_nsh_cmd.py --device ${SERIAL_DEVICE} --cmd 'work_queue status'
+1 -2
View File
@@ -79,9 +79,8 @@ CONFIG_MODULES_UUV_ATT_CONTROL=y
CONFIG_MODULES_UUV_POS_CONTROL=y
CONFIG_MODULES_GIMBAL=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_DUMPFILE=y
CONFIG_SYSTEMCMDS_GPIO=y
CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y
-1
View File
@@ -70,7 +70,6 @@ CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y
CONFIG_SYSTEMCMDS_I2CDETECT=y
+1 -2
View File
@@ -76,9 +76,8 @@ CONFIG_MODULES_UUV_ATT_CONTROL=y
CONFIG_MODULES_UUV_POS_CONTROL=y
CONFIG_MODULES_GIMBAL=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_DUMPFILE=y
CONFIG_SYSTEMCMDS_GPIO=y
-1
View File
@@ -63,7 +63,6 @@ CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
CONFIG_MODULES_UUV_ATT_CONTROL=y
CONFIG_MODULES_UUV_POS_CONTROL=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_SYSTEMCMDS_DYN=y
CONFIG_SYSTEMCMDS_LED_CONTROL=y
CONFIG_SYSTEMCMDS_PARAM=y
+1 -2
View File
@@ -81,9 +81,8 @@ CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
CONFIG_MODULES_GIMBAL=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_DUMPFILE=y
CONFIG_SYSTEMCMDS_GPIO=y
+6 -4
View File
@@ -27,12 +27,14 @@ CONFIG_COMMON_LIGHT=y
CONFIG_DRIVERS_LIGHTS_RGBLED_PWM=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_DRIVERS_OSD=y
CONFIG_DRIVERS_PCA9685=y
CONFIG_DRIVERS_PCA9685_PWM_OUT=y
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
CONFIG_DRIVERS_PWM_OUT=y
CONFIG_DRIVERS_RC_INPUT=y
CONFIG_DRIVERS_ROBOCLAW=y
CONFIG_DRIVERS_RPM=y
CONFIG_DRIVERS_SAFETY_BUTTON=y
CONFIG_DRIVERS_SMART_BATTERY_BATMON=y
CONFIG_COMMON_TELEMETRY=y
@@ -44,7 +46,6 @@ CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y
CONFIG_MODULES_BATTERY_STATUS=y
CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_EKF2=y
CONFIG_MODULES_ESC_BATTERY=y
@@ -53,7 +54,6 @@ CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
CONFIG_MODULES_FW_ATT_CONTROL=y
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y
CONFIG_MODULES_FW_POS_CONTROL_L1=y
CONFIG_MODULES_GIMBAL=y
CONFIG_MODULES_GYRO_CALIBRATION=y
CONFIG_MODULES_GYRO_FFT=y
CONFIG_MODULES_LAND_DETECTOR=y
@@ -69,6 +69,7 @@ CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
CONFIG_MODULES_MC_POS_CONTROL=y
CONFIG_MODULES_MC_RATE_CONTROL=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_ROVER_POS_CONTROL=y
@@ -79,10 +80,10 @@ CONFIG_MODULES_SIMULATION_SENSOR_GPS_SIM=y
CONFIG_MODULES_SIMULATION_SENSOR_MAG_SIM=y
CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
CONFIG_MODULES_GIMBAL=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_DUMPFILE=y
CONFIG_SYSTEMCMDS_GPIO=y
@@ -105,3 +106,4 @@ CONFIG_SYSTEMCMDS_USB_CONNECTED=y
CONFIG_SYSTEMCMDS_VER=y
CONFIG_SYSTEMCMDS_WORK_QUEUE=y
CONFIG_EXAMPLES_FAKE_GPS=y
#CONFIG_DRIVERS_TRANSPONDER_SAGETECH_MXS=y
@@ -75,7 +75,6 @@ CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_DUMPFILE=y
CONFIG_SYSTEMCMDS_GPIO=y
@@ -1,8 +1,12 @@
CONFIG_DRIVERS_ADC_ADS1115=n
CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16448=n
CONFIG_DRIVERS_IRLOCK=n
CONFIG_DRIVERS_PCA9685=n
CONFIG_DRIVERS_PCA9685_PWM_OUT=n
CONFIG_DRIVERS_RPM=n
CONFIG_DRIVERS_UAVCAN=n
CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=n
CONFIG_MODULES_LOCAL_POSITION_ESTIMATOR=n
CONFIG_MODULES_ROVER_POS_CONTROL=n
CONFIG_MODULES_TEMPERATURE_COMPENSATION=n
CONFIG_BOARD_TESTING=y
+1 -2
View File
@@ -80,9 +80,8 @@ CONFIG_MODULES_UUV_ATT_CONTROL=y
CONFIG_MODULES_UUV_POS_CONTROL=y
CONFIG_MODULES_GIMBAL=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_DUMPFILE=y
CONFIG_SYSTEMCMDS_GPIO=y
-1
View File
@@ -66,7 +66,6 @@ CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
CONFIG_MODULES_UUV_ATT_CONTROL=y
CONFIG_MODULES_UUV_POS_CONTROL=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_SYSTEMCMDS_DYN=y
CONFIG_SYSTEMCMDS_LED_CONTROL=y
CONFIG_SYSTEMCMDS_PARAM=y
+5 -4
View File
@@ -28,8 +28,10 @@ CONFIG_DRIVERS_PCA9685=y
CONFIG_DRIVERS_PCA9685_PWM_OUT=y
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
CONFIG_DRIVERS_PWM_OUT=y
CONFIG_MODULES_SIMULATION_PWM_OUT_SIM=y
CONFIG_DRIVERS_PX4IO=y
CONFIG_DRIVERS_ROBOCLAW=y
CONFIG_DRIVERS_RPM=y
CONFIG_DRIVERS_SMART_BATTERY_BATMON=y
CONFIG_COMMON_TELEMETRY=y
CONFIG_DRIVERS_TONE_ALARM=y
@@ -38,7 +40,6 @@ CONFIG_MODULES_AIRSPEED_SELECTOR=y
CONFIG_MODULES_BATTERY_STATUS=y
CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_EKF2=y
CONFIG_MODULES_ESC_BATTERY=y
@@ -47,7 +48,6 @@ CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
CONFIG_MODULES_FW_ATT_CONTROL=y
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y
CONFIG_MODULES_FW_POS_CONTROL_L1=y
CONFIG_MODULES_GIMBAL=y
CONFIG_MODULES_GYRO_CALIBRATION=y
CONFIG_MODULES_GYRO_FFT=y
CONFIG_MODULES_LAND_DETECTOR=y
@@ -62,6 +62,7 @@ CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
CONFIG_MODULES_MC_POS_CONTROL=y
CONFIG_MODULES_MC_RATE_CONTROL=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_ROVER_POS_CONTROL=y
@@ -72,10 +73,10 @@ CONFIG_MODULES_SIMULATION_SENSOR_GPS_SIM=y
CONFIG_MODULES_SIMULATION_SENSOR_MAG_SIM=y
CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
CONFIG_MODULES_GIMBAL=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_DUMPFILE=y
CONFIG_SYSTEMCMDS_GPIO=y
-1
View File
@@ -71,7 +71,6 @@ CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_DUMPFILE=y
CONFIG_SYSTEMCMDS_GPIO=y
+1 -2
View File
@@ -85,9 +85,8 @@ CONFIG_MODULES_UUV_ATT_CONTROL=y
CONFIG_MODULES_UUV_POS_CONTROL=y
CONFIG_MODULES_GIMBAL=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_DUMPFILE=y
CONFIG_SYSTEMCMDS_GPIO=y
-1
View File
@@ -82,7 +82,6 @@ CONFIG_MODULES_UUV_POS_CONTROL=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_DUMPFILE=y
CONFIG_SYSTEMCMDS_GPIO=y
-1
View File
@@ -76,7 +76,6 @@ CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_GPIO=y
CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y
-1
View File
@@ -8,4 +8,3 @@ CONFIG_ORB_COMMUNICATOR=y
CONFIG_SYSTEMCMDS_PARAM=y
CONFIG_DRIVERS_QSHELL_POSIX=y
CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
@@ -79,7 +79,6 @@ CONFIG_MODULES_GIMBAL=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_DUMPFILE=y
CONFIG_SYSTEMCMDS_GPIO=y
+1 -2
View File
@@ -77,9 +77,8 @@ CONFIG_MODULES_UUV_ATT_CONTROL=y
CONFIG_MODULES_UUV_POS_CONTROL=y
CONFIG_MODULES_GIMBAL=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_DUMPFILE=y
CONFIG_SYSTEMCMDS_GPIO=y
+1 -2
View File
@@ -77,9 +77,8 @@ CONFIG_MODULES_UUV_ATT_CONTROL=y
CONFIG_MODULES_UUV_POS_CONTROL=y
CONFIG_MODULES_GIMBAL=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_DUMPFILE=y
CONFIG_SYSTEMCMDS_GPIO=y
@@ -78,7 +78,6 @@ CONFIG_MODULES_UUV_POS_CONTROL=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_DUMPFILE=y
CONFIG_SYSTEMCMDS_GPIO=y
+1 -1
View File
@@ -21,6 +21,7 @@ CONFIG_DRIVERS_IRLOCK=y
CONFIG_COMMON_LIGHT=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_DRIVERS_OSD=y
CONFIG_DRIVERS_PCA9685=y
CONFIG_DRIVERS_PCA9685_PWM_OUT=y
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
@@ -78,7 +79,6 @@ CONFIG_MODULES_UUV_POS_CONTROL=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_DUMPFILE=y
CONFIG_SYSTEMCMDS_GPIO=y
-1
View File
@@ -78,7 +78,6 @@ CONFIG_MODULES_UUV_POS_CONTROL=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_DUMPFILE=y
CONFIG_SYSTEMCMDS_GPIO=y
+1 -2
View File
@@ -79,9 +79,8 @@ CONFIG_MODULES_UUV_ATT_CONTROL=y
CONFIG_MODULES_UUV_POS_CONTROL=y
CONFIG_MODULES_GIMBAL=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_DUMPFILE=y
CONFIG_SYSTEMCMDS_GPIO=y
+1 -2
View File
@@ -80,9 +80,8 @@ CONFIG_MODULES_UUV_ATT_CONTROL=y
CONFIG_MODULES_UUV_POS_CONTROL=y
CONFIG_MODULES_GIMBAL=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_DUMPFILE=y
CONFIG_SYSTEMCMDS_GPIO=y
CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y
+2 -1
View File
@@ -23,12 +23,14 @@ CONFIG_COMMON_LIGHT=y
CONFIG_DRIVERS_LIGHTS_RGBLED_PWM=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_DRIVERS_OSD=y
CONFIG_DRIVERS_PCA9685=y
CONFIG_DRIVERS_PCA9685_PWM_OUT=y
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
CONFIG_DRIVERS_PWM_OUT=y
CONFIG_DRIVERS_RC_INPUT=y
CONFIG_DRIVERS_ROBOCLAW=y
CONFIG_DRIVERS_RPM=y
CONFIG_DRIVERS_SAFETY_BUTTON=y
CONFIG_DRIVERS_SMART_BATTERY_BATMON=y
CONFIG_COMMON_TELEMETRY=y
@@ -76,7 +78,6 @@ CONFIG_MODULES_SIMULATION_SENSOR_MAG_SIM=y
CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_SYSTEMCMDS_DUMPFILE=y
CONFIG_SYSTEMCMDS_I2CDETECT=y
CONFIG_SYSTEMCMDS_LED_CONTROL=y
+2 -1
View File
@@ -24,12 +24,14 @@ CONFIG_DRIVERS_LIGHTS_RGBLED_NCP5623C=y
CONFIG_DRIVERS_LIGHTS_RGBLED_PWM=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_DRIVERS_OSD=y
CONFIG_DRIVERS_PCA9685=y
CONFIG_DRIVERS_PCA9685_PWM_OUT=y
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
CONFIG_DRIVERS_PWM_OUT=y
CONFIG_DRIVERS_RC_INPUT=y
CONFIG_DRIVERS_ROBOCLAW=y
CONFIG_DRIVERS_RPM=y
CONFIG_DRIVERS_SAFETY_BUTTON=y
CONFIG_DRIVERS_SMART_BATTERY_BATMON=y
CONFIG_COMMON_TELEMETRY=y
@@ -78,7 +80,6 @@ CONFIG_MODULES_SIMULATION_SENSOR_MAG_SIM=y
CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_SYSTEMCMDS_DUMPFILE=y
CONFIG_SYSTEMCMDS_I2CDETECT=y
CONFIG_SYSTEMCMDS_LED_CONTROL=y
+1 -2
View File
@@ -31,7 +31,6 @@ CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_EKF2=y
CONFIG_MODULES_EVENTS=y
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
CONFIG_MODULES_GIMBAL=y
CONFIG_MODULES_GYRO_CALIBRATION=y
CONFIG_MODULES_GYRO_FFT=y
CONFIG_MODULES_LAND_DETECTOR=y
@@ -50,7 +49,7 @@ CONFIG_MODULES_MICRODDS_CLIENT=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_SENSORS=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_MODULES_GIMBAL=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_DUMPFILE=y
CONFIG_SYSTEMCMDS_I2CDETECT=y
-1
View File
@@ -83,7 +83,6 @@ CONFIG_MODULES_UUV_POS_CONTROL=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_SYSTEMCMDS_DUMPFILE=y
CONFIG_SYSTEMCMDS_GPIO=y
CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y
+1 -1
View File
@@ -25,6 +25,7 @@ CONFIG_DRIVERS_IRLOCK=y
CONFIG_COMMON_LIGHT=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_DRIVERS_OSD=y
CONFIG_DRIVERS_PCA9685=y
CONFIG_DRIVERS_PCA9685_PWM_OUT=y
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
@@ -83,7 +84,6 @@ CONFIG_MODULES_UUV_POS_CONTROL=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_SYSTEMCMDS_DUMPFILE=y
CONFIG_SYSTEMCMDS_GPIO=y
CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y
+6 -4
View File
@@ -25,12 +25,15 @@ CONFIG_DRIVERS_IRLOCK=y
CONFIG_COMMON_LIGHT=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_DRIVERS_OSD=y
CONFIG_DRIVERS_PCA9685=y
CONFIG_DRIVERS_PCA9685_PWM_OUT=y
CONFIG_DRIVERS_PWM_INPUT=y
CONFIG_DRIVERS_PWM_OUT=y
CONFIG_MODULES_SIMULATION_PWM_OUT_SIM=y
CONFIG_DRIVERS_PX4IO=y
CONFIG_DRIVERS_ROBOCLAW=y
CONFIG_DRIVERS_RPM=y
CONFIG_DRIVERS_SMART_BATTERY_BATMON=y
CONFIG_COMMON_TELEMETRY=y
CONFIG_DRIVERS_TONE_ALARM=y
@@ -40,7 +43,6 @@ CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y
CONFIG_MODULES_BATTERY_STATUS=y
CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_EKF2=y
CONFIG_MODULES_ESC_BATTERY=y
@@ -49,7 +51,6 @@ CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
CONFIG_MODULES_FW_ATT_CONTROL=y
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y
CONFIG_MODULES_FW_POS_CONTROL_L1=y
CONFIG_MODULES_GIMBAL=y
CONFIG_MODULES_GYRO_CALIBRATION=y
CONFIG_MODULES_GYRO_FFT=y
CONFIG_MODULES_LAND_DETECTOR=y
@@ -65,6 +66,7 @@ CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
CONFIG_MODULES_MC_POS_CONTROL=y
CONFIG_MODULES_MC_RATE_CONTROL=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_ROVER_POS_CONTROL=y
@@ -77,10 +79,10 @@ CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
CONFIG_MODULES_UUV_ATT_CONTROL=y
CONFIG_MODULES_UUV_POS_CONTROL=y
CONFIG_MODULES_GIMBAL=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_DUMPFILE=y
CONFIG_SYSTEMCMDS_GPIO=y
CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y
+4 -1
View File
@@ -11,25 +11,28 @@ CONFIG_DRIVERS_IMU_BOSCH_BMI055=n
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20602=n
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20948=n
CONFIG_DRIVERS_IRLOCK=n
CONFIG_DRIVERS_OSD=n
CONFIG_DRIVERS_PCA9685=n
CONFIG_DRIVERS_PCA9685_PWM_OUT=n
CONFIG_DRIVERS_POWER_MONITOR_INA226=n
CONFIG_DRIVERS_PWM_INPUT=n
CONFIG_DRIVERS_ROBOCLAW=n
CONFIG_DRIVERS_RPM=n
CONFIG_DRIVERS_SMART_BATTERY_BATMON=n
CONFIG_DRIVERS_UAVCAN=n
CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=n
CONFIG_MODULES_CAMERA_FEEDBACK=n
CONFIG_MODULES_ESC_BATTERY=n
CONFIG_MODULES_GIMBAL=n
CONFIG_MODULES_GYRO_CALIBRATION=n
CONFIG_MODULES_GYRO_FFT=n
CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=n
CONFIG_MODULES_LOCAL_POSITION_ESTIMATOR=n
CONFIG_MODULES_ROVER_POS_CONTROL=n
CONFIG_MODULES_SIH=n
CONFIG_MODULES_TEMPERATURE_COMPENSATION=n
CONFIG_MODULES_UUV_ATT_CONTROL=n
CONFIG_MODULES_UUV_POS_CONTROL=n
CONFIG_MODULES_GIMBAL=n
CONFIG_SYSTEMCMDS_SERIAL_TEST=n
CONFIG_BOARD_CONSTRAINED_FLASH=y
CONFIG_BOARD_TESTING=y
-1
View File
@@ -86,7 +86,6 @@ CONFIG_MODULES_UUV_POS_CONTROL=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_DUMPFILE=y
CONFIG_SYSTEMCMDS_GPIO=y
+1
View File
@@ -3,6 +3,7 @@ CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16448=n
CONFIG_DRIVERS_IRLOCK=n
CONFIG_DRIVERS_PCA9685=n
CONFIG_DRIVERS_PCA9685_PWM_OUT=n
CONFIG_DRIVERS_RPM=n
CONFIG_EXAMPLES_FAKE_GPS=n
CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=n
CONFIG_MODULES_GYRO_FFT=n
-2
View File
@@ -59,7 +59,6 @@ CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y
CONFIG_MODULES_FW_POS_CONTROL_L1=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
@@ -85,7 +84,6 @@ CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_GPIO=y
CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y
-1
View File
@@ -68,7 +68,6 @@ CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y
CONFIG_SYSTEMCMDS_I2CDETECT=y
-1
View File
@@ -78,7 +78,6 @@ CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_DUMPFILE=y
CONFIG_SYSTEMCMDS_GPIO=y
-1
View File
@@ -74,7 +74,6 @@ CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_GPIO=y
CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y
-1
View File
@@ -62,7 +62,6 @@ CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
CONFIG_MODULES_UUV_ATT_CONTROL=y
CONFIG_MODULES_UUV_POS_CONTROL=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_SYSTEMCMDS_DYN=y
CONFIG_SYSTEMCMDS_LED_CONTROL=y
CONFIG_SYSTEMCMDS_PARAM=y
-1
View File
@@ -49,7 +49,6 @@ CONFIG_MODULES_UUV_ATT_CONTROL=y
CONFIG_MODULES_UUV_POS_CONTROL=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_SYSTEMCMDS_DYN=y
CONFIG_SYSTEMCMDS_FAILURE=y
CONFIG_SYSTEMCMDS_LED_CONTROL=y
-1
View File
@@ -59,7 +59,6 @@ CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
CONFIG_MODULES_GIMBAL=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_SYSTEMCMDS_DYN=y
CONFIG_SYSTEMCMDS_LED_CONTROL=y
CONFIG_SYSTEMCMDS_PARAM=y
@@ -83,7 +83,6 @@ CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_DUMPFILE=y
CONFIG_SYSTEMCMDS_GPIO=y
-1
View File
@@ -78,7 +78,6 @@ CONFIG_MODULES_UUV_POS_CONTROL=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_SYSTEMCMDS_DUMPFILE=y
CONFIG_SYSTEMCMDS_GPIO=y
CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y
-1
View File
@@ -78,7 +78,6 @@ CONFIG_MODULES_UUV_POS_CONTROL=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_SYSTEMCMDS_DUMPFILE=y
CONFIG_SYSTEMCMDS_GPIO=y
CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y
+3 -4
View File
@@ -33,12 +33,10 @@ CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y
CONFIG_MODULES_BATTERY_STATUS=y
CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_EKF2=y
CONFIG_MODULES_EVENTS=y
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
CONFIG_MODULES_GIMBAL=y
CONFIG_MODULES_GYRO_CALIBRATION=y
CONFIG_MODULES_GYRO_FFT=y
CONFIG_MODULES_LAND_DETECTOR=y
@@ -54,6 +52,7 @@ CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
CONFIG_MODULES_MC_POS_CONTROL=y
CONFIG_MODULES_MC_RATE_CONTROL=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_SENSORS=y
@@ -63,9 +62,9 @@ CONFIG_MODULES_SIMULATION_SENSOR_GPS_SIM=y
CONFIG_MODULES_SIMULATION_SENSOR_MAG_SIM=y
CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_MODULES_GIMBAL=y
CONFIG_SYSTEMCMDS_BL_UPDATE=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_DUMPFILE=y
CONFIG_SYSTEMCMDS_GPIO=y
+3 -10
View File
@@ -134,6 +134,7 @@ set(msg_files
OrbTest.msg
OrbTestLarge.msg
OrbTestMedium.msg
Parameter.msg
ParameterUpdate.msg
Ping.msg
PositionControllerLandingStatus.msg
@@ -182,8 +183,8 @@ set(msg_files
TrajectoryWaypoint.msg
TransponderReport.msg
TuneControl.msg
ParameterRequest.msg
ParameterValue.msg
UavcanParameterRequest.msg
UavcanParameterValue.msg
UlogStream.msg
UlogStreamAck.msg
UwbDistance.msg
@@ -219,14 +220,6 @@ set(msg_files
WheelEncoders.msg
Wind.msg
YawEstimatorStatus.msg
Parameter.msg
SrvParameterGetRequest.msg
SrvParameterGetResponse.msg
SrvParameterSetRequest.msg
SrvParameterSetResponse.msg
)
list(SORT msg_files)
-27
View File
@@ -1,27 +0,0 @@
# parameter request type
uint64 timestamp # time since system start (microseconds)
uint8 MESSAGE_TYPE_INVALID = 0
uint8 MESSAGE_TYPE_PARAM_REQUEST_READ = 1
uint8 MESSAGE_TYPE_PARAM_REQUEST_LIST = 2
uint8 MESSAGE_TYPE_PARAM_SET = 3
uint8 message_type # message type
uint8 NODE_ID_ALL = 0 # MAV_COMP_ID_ALL
uint8 node_id # node ID
char[17] name # parameter name
int16 param_index # -1 if the param_id field should be used as identifier
uint8 TYPE_INVALID = 0
uint8 TYPE_BOOL = 1
uint8 TYPE_INT32 = 2
uint8 TYPE_FLOAT32 = 3
uint8 type # parameter type
int32 int32_value # current value if param_type is int-like
float32 float32_value # current value if param_type is float-like
uint8 ORB_QUEUE_LENGTH = 8
# TOPICS parameter_request uavcan_parameter_request
+2
View File
@@ -7,3 +7,5 @@ uint32 instance # Instance count - constantly incrementing
uint16 count
Parameter changed_param
uint8 ORB_QUEUE_LENGTH = 8
-22
View File
@@ -1,22 +0,0 @@
# parameter response type
uint64 timestamp # time since system start (microseconds)
uint8 node_id # requester node ID
char[17] param_name # parameter name
int16 param_index # parameter index, if known
uint16 param_count # number of parameters exposed by the node
uint8 type # parameter type
int32 int32_value # current value if param_type is int-like
float32 float32_value # current value if param_type is float-like
uint64 timestamp_requested
uint8 ORB_QUEUE_LENGTH = 8
# TOPICS parameter_value uavcan_parameter_value
-6
View File
@@ -1,6 +0,0 @@
uint64 timestamp # time since system start (microseconds)
char[17] name # parameter name
int16 index # -1 if the param_id field should be used as identifier
uint8 ORB_QUEUE_LENGTH = 16
-11
View File
@@ -1,11 +0,0 @@
uint64 timestamp # time since system start (microseconds)
uint64 timestamp_requested
Parameter parameter
uint8 RESULT_GET_SUCCESS = 0
uint8 RESULT_GET_FAILED = 1
uint8 RESULT_ERROR_INVALID_PARAMETER = 2
uint8 result
uint8 ORB_QUEUE_LENGTH = 16
-5
View File
@@ -1,5 +0,0 @@
uint64 timestamp # time since system start (microseconds)
Parameter parameter
uint8 ORB_QUEUE_LENGTH = 8
-11
View File
@@ -1,11 +0,0 @@
uint64 timestamp # time since system start (microseconds)
uint64 timestamp_requested
Parameter parameter
uint8 RESULT_SET_SUCCESS = 0
uint8 RESULT_SET_FAILED = 1
uint8 RESULT_ERROR_INVALID_PARAMETER = 2
uint8 result
uint8 ORB_QUEUE_LENGTH = 8
+23
View File
@@ -0,0 +1,23 @@
# UAVCAN-MAVLink parameter bridge request type
uint64 timestamp # time since system start (microseconds)
uint8 MESSAGE_TYPE_PARAM_REQUEST_READ = 20 # MAVLINK_MSG_ID_PARAM_REQUEST_READ
uint8 MESSAGE_TYPE_PARAM_REQUEST_LIST = 21 # MAVLINK_MSG_ID_PARAM_REQUEST_LIST
uint8 MESSAGE_TYPE_PARAM_SET = 23 # MAVLINK_MSG_ID_PARAM_SET
uint8 message_type # MAVLink message type: PARAM_REQUEST_READ, PARAM_REQUEST_LIST, PARAM_SET
uint8 NODE_ID_ALL = 0 # MAV_COMP_ID_ALL
uint8 node_id # UAVCAN node ID mapped from MAVLink component ID
char[17] param_id # MAVLink/UAVCAN parameter name
int16 param_index # -1 if the param_id field should be used as identifier
uint8 PARAM_TYPE_UINT8 = 1 # MAV_PARAM_TYPE_UINT8
uint8 PARAM_TYPE_INT64 = 8 # MAV_PARAM_TYPE_INT64
uint8 PARAM_TYPE_REAL32 = 9 # MAV_PARAM_TYPE_REAL32
uint8 param_type # MAVLink parameter type
int64 int_value # current value if param_type is int-like
float32 real_value # current value if param_type is float-like
uint8 ORB_QUEUE_LENGTH = 4
+9
View File
@@ -0,0 +1,9 @@
# UAVCAN-MAVLink parameter bridge response type
uint64 timestamp # time since system start (microseconds)
uint8 node_id # UAVCAN node ID mapped from MAVLink component ID
char[17] param_id # MAVLink/UAVCAN parameter name
int16 param_index # parameter index, if known
uint16 param_count # number of parameters exposed by the node
uint8 param_type # MAVLink parameter type
int64 int_value # current value if param_type is int-like
float32 real_value # current value if param_type is float-like
@@ -42,6 +42,8 @@
#include <containers/List.hpp>
#include "param.h"
#include <uORB/Subscription.hpp>
#include <uORB/topics/parameter_update.h>
class ModuleParams : public ListNode<ModuleParams *>
{
@@ -68,6 +70,8 @@ public:
virtual ~ModuleParams()
{
if (_parent) { _parent->_children.remove(this); }
_parameter_update_sub.unsubscribe();
}
// Disallow copy construction and move assignment.
@@ -83,20 +87,75 @@ protected:
*/
virtual void updateParams()
{
for (const auto &child : _children) {
child->updateParams();
bool update_all = true;
int parameter_updates = 0;
while (_parameter_update_sub.updated() && (parameter_updates < parameter_update_s::ORB_QUEUE_LENGTH)) {
parameter_updates++;
parameter_update_s parameter_update;
if (_parameter_update_sub.copy(&parameter_update)
&& (_parameter_update_instance > 0)
&& (parameter_update.instance == _parameter_update_instance + 1)
&& (parameter_update.changed_param.index >= 0)
&& (static_cast<uint16_t>(parameter_update.changed_param.index) != PARAM_INVALID)
) {
update_all = false;
for (const auto &child : _children) {
child->updateParams(parameter_update);
}
updateParamsImpl(parameter_update);
_parameter_update_instance = parameter_update.instance;
} else {
update_all = true;
break;
}
}
updateParamsImpl();
if (update_all) {
PX4_DEBUG("updateParams: updating all params");
parameter_update_s parameter_update;
if (_parameter_update_sub.copy(&parameter_update)) {
_parameter_update_instance = parameter_update.instance;
}
for (const auto &child : _children) {
child->updateParams();
}
updateParamsImpl();
} else {
PX4_DEBUG("updateParams: updating all params skipped");
}
}
virtual void updateParams(const parameter_update_s &parameter_update)
{
for (const auto &child : _children) {
child->updateParams(parameter_update);
}
updateParamsImpl(parameter_update);
}
/**
* @brief The implementation for this is generated with the macro DEFINE_PARAMETERS()
*/
virtual void updateParamsImpl() {}
virtual void updateParamsImpl(const parameter_update_s &parameter_update) {}
private:
/** @list _children The module parameter list of inheriting classes. */
List<ModuleParams *> _children;
ModuleParams *_parent{nullptr};
uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)};
uint32_t _parameter_update_instance{0};
};
@@ -44,11 +44,13 @@
#include <math.h>
#include <parameters/px4_parameters.hpp>
#include <uORB/topics/parameter.h>
#include <uORB/topics/parameter_update.h>
/**
* get the parameter handle from a parameter enum
*/
inline static param_t param_handle(px4::params p)
inline static constexpr param_t param_handle(px4::params p)
{
return (param_t)p;
}
@@ -62,6 +64,9 @@ inline static param_t param_handle(px4::params p)
#define _CALL_UPDATE(x) \
STRIP(x).update();
#define _SET_PARAMETER_UPDATE(x) \
case STRIP(x).handle(): STRIP(x).setValue(parameter_update.changed_param); return;
// define the parameter update method, which will update all parameters.
// It is marked as 'final', so that wrong usages lead to a compile error (see below)
#define _DEFINE_PARAMETER_UPDATE_METHOD(...) \
@@ -69,6 +74,11 @@ inline static param_t param_handle(px4::params p)
void updateParamsImpl() final { \
APPLY_ALL(_CALL_UPDATE, __VA_ARGS__) \
} \
void updateParamsImpl(const parameter_update_s &parameter_update) { \
switch(parameter_update.changed_param.index) { \
APPLY_ALL(_SET_PARAMETER_UPDATE, __VA_ARGS__) \
} \
} \
private:
// Define a list of parameters. This macro also creates code to update parameters.
@@ -88,6 +98,12 @@ inline static param_t param_handle(px4::params p)
parent_class::updateParamsImpl(); \
APPLY_ALL(_CALL_UPDATE, __VA_ARGS__) \
} \
void updateParamsImpl(const parameter_update_s &parameter_update) { \
parent_class::updateParamsImpl(parameter_update); \
switch(parameter_update.changed_param.index) { \
APPLY_ALL(_SET_PARAMETER_UPDATE, __VA_ARGS__) \
} \
} \
private:
#define DEFINE_PARAMETERS_CUSTOM_PARENT(parent_class, ...) \
@@ -125,29 +141,22 @@ public:
const float &reference() const { return _val; }
/// Store the parameter value to the parameter storage (@see param_set())
bool commit() const { return param_set(handle(), &_val) == 0; }
/// Store the parameter value to the parameter storage, w/o notifying the system (@see param_set_no_notification())
bool commit_no_notification() const { return param_set_no_notification(handle(), &_val) == 0; }
/// Set and commit a new value. Returns true if the value changed.
bool commit_no_notification(float val)
bool set(float val)
{
if (fabsf(val - _val) > FLT_EPSILON) {
set(val);
commit_no_notification();
return true;
_val = val;
return (param_set(handle(), &_val) == 0);
}
return false;
}
void set(float val) { _val = val; }
bool update() { return param_get(handle(), &_val) == 0; }
param_t handle() const { return param_handle(p); }
void setValue(const parameter_s &parameter_update) { _val = parameter_update.float32_value; }
static constexpr param_t handle() { return param_handle(p); }
private:
float _val;
};
@@ -170,29 +179,18 @@ public:
const float &reference() const { return _val; }
/// Store the parameter value to the parameter storage (@see param_set())
bool commit() const { return param_set(handle(), &_val) == 0; }
/// Store the parameter value to the parameter storage, w/o notifying the system (@see param_set_no_notification())
bool commit_no_notification() const { return param_set_no_notification(handle(), &_val) == 0; }
/// Set and commit a new value. Returns true if the value changed.
bool commit_no_notification(float val)
bool set(float val)
{
if (fabsf(val - _val) > FLT_EPSILON) {
set(val);
commit_no_notification();
return true;
}
return false;
_val = val;
return (param_set(handle(), &_val) == 0);
}
void set(float val) { _val = val; }
bool update() { return param_get(handle(), &_val) == 0; }
param_t handle() const { return param_handle(p); }
void setValue(const parameter_s &parameter_update) { _val = parameter_update.float32_value; }
static constexpr param_t handle() { return param_handle(p); }
private:
float &_val;
};
@@ -213,29 +211,18 @@ public:
const int32_t &reference() const { return _val; }
/// Store the parameter value to the parameter storage (@see param_set())
bool commit() const { return param_set(handle(), &_val) == 0; }
/// Store the parameter value to the parameter storage, w/o notifying the system (@see param_set_no_notification())
bool commit_no_notification() const { return param_set_no_notification(handle(), &_val) == 0; }
/// Set and commit a new value. Returns true if the value changed.
bool commit_no_notification(int32_t val)
bool set(int32_t val)
{
if (val != _val) {
set(val);
commit_no_notification();
return true;
}
return false;
_val = val;
return (param_set(handle(), &_val) == 0);
}
void set(int32_t val) { _val = val; }
bool update() { return param_get(handle(), &_val) == 0; }
param_t handle() const { return param_handle(p); }
void setValue(const parameter_s &parameter_update) { _val = parameter_update.int32_value; }
static constexpr param_t handle() { return param_handle(p); }
private:
int32_t _val;
};
@@ -259,28 +246,17 @@ public:
const int32_t &reference() const { return _val; }
/// Store the parameter value to the parameter storage (@see param_set())
bool commit() const { return param_set(handle(), &_val) == 0; }
/// Store the parameter value to the parameter storage, w/o notifying the system (@see param_set_no_notification())
bool commit_no_notification() const { return param_set_no_notification(handle(), &_val) == 0; }
/// Set and commit a new value. Returns true if the value changed.
bool commit_no_notification(int32_t val)
bool set(int32_t val)
{
if (val != _val) {
set(val);
commit_no_notification();
return true;
}
return false;
_val = val;
return (param_set(handle(), &_val) == 0);
}
void set(int32_t val) { _val = val; }
bool update() { return param_get(handle(), &_val) == 0; }
param_t handle() const { return param_handle(p); }
void setValue(const parameter_s &parameter_update) { _val = parameter_update.int32_value; }
static constexpr param_t handle() { return param_handle(p); }
private:
int32_t &_val;
};
@@ -301,34 +277,14 @@ public:
const bool &reference() const { return _val; }
/// Store the parameter value to the parameter storage (@see param_set())
bool commit() const
{
int32_t value_int = (int32_t)_val;
return param_set(handle(), &value_int) == 0;
}
/// Store the parameter value to the parameter storage, w/o notifying the system (@see param_set_no_notification())
bool commit_no_notification() const
{
int32_t value_int = (int32_t)_val;
return param_set_no_notification(handle(), &value_int) == 0;
}
/// Set and commit a new value. Returns true if the value changed.
bool commit_no_notification(bool val)
bool set(bool val)
{
if (val != _val) {
set(val);
commit_no_notification();
return true;
}
return false;
_val = val;
int32_t value_int = (int32_t)_val;
return (param_set(handle(), &value_int) == 0);
}
void set(bool val) { _val = val; }
bool update()
{
int32_t value_int;
@@ -342,7 +298,9 @@ public:
return false;
}
param_t handle() const { return param_handle(p); }
void setValue(const parameter_s &parameter_update) { _val = parameter_update.int32_value; }
static constexpr param_t handle() { return param_handle(p); }
private:
bool _val;
};
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2019-2022 PX4 Development Team. All rights reserved.
* Copyright (c) 2019-2021 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -76,8 +76,6 @@ static constexpr wq_config_t hp_default{"wq:hp_default", 1900, -18};
static constexpr wq_config_t uavcan{"wq:uavcan", 3624, -19};
static constexpr wq_config_t parameter_server{"wq:parameter_server", 4096, -20};
static constexpr wq_config_t ttyS0{"wq:ttyS0", 1632, -21};
static constexpr wq_config_t ttyS1{"wq:ttyS1", 1632, -22};
static constexpr wq_config_t ttyS2{"wq:ttyS2", 1632, -23};
@@ -85,7 +85,6 @@ public:
virtual ~SubscriptionBlocking()
{
unregisterCallback();
pthread_mutex_destroy(&_mutex);
pthread_cond_destroy(&_cv);
}
+2 -2
View File
@@ -385,7 +385,7 @@ uORB::DeviceNode::print_statistics(int max_topic_length)
lock();
const uint8_t instance = get_instance();
const int8_t sub_count = subscriber_count();
const int16_t sub_count = subscriber_count();
const uint8_t queue_size = get_queue_size();
unlock();
@@ -514,7 +514,7 @@ uORB::DeviceNode::register_callback(uORB::SubscriptionCallback *callback_sub)
ATOMIC_ENTER;
// prevent duplicate registrations
for (const auto &existing_callbacks : _callbacks) {
for (auto existing_callbacks : _callbacks) {
if (callback_sub == existing_callbacks) {
ATOMIC_LEAVE;
return true;
+2 -2
View File
@@ -197,7 +197,7 @@ public:
uint8_t get_queue_size() const { return _queue_size; }
int8_t subscriber_count() const { return _subscriber_count; }
int16_t subscriber_count() const { return _subscriber_count; }
/**
* Returns the number of updated data relative to the parameter 'generation'
@@ -296,7 +296,7 @@ private:
const uint8_t _instance; /**< orb multi instance identifier */
bool _advertised{false}; /**< has ever been advertised (not necessarily published data yet) */
uint8_t _queue_size; /**< maximum number of elements in the queue */
int8_t _subscriber_count{0};
int16_t _subscriber_count{0};
// Determine the data range
+2 -2
View File
@@ -127,6 +127,8 @@ int px4_platform_init()
hrt_ioctl_init();
#endif
param_init();
/* configure CPU load estimation */
#ifdef CONFIG_SCHED_INSTRUMENTATION
cpuload_initialize_once();
@@ -183,8 +185,6 @@ int px4_platform_init()
uorb_start();
param_init();
px4_log_initialize();
#if defined(CONFIG_SYSTEM_CDCACM) && defined(CONFIG_BUILD_FLAT)
+2 -2
View File
@@ -44,12 +44,12 @@ int px4_platform_init(void)
{
hrt_init();
param_init();
px4::WorkQueueManagerStart();
uorb_start();
param_init();
px4_log_initialize();
return PX4_OK;
@@ -121,19 +121,12 @@ public:
//return param_set(handle(), &_val) == 0;
}
/// Store the parameter value to the parameter storage, w/o notifying the system (@see param_set_no_notification())
bool commit_no_notification() const
{
return true; // TODO
//return param_set_no_notification(handle(), &_val) == 0;
}
/// Set and commit a new value. Returns true if the value changed.
bool commit_no_notification(float val)
bool commit(float val)
{
if (fabsf(val - _val) > FLT_EPSILON) {
set(val);
commit_no_notification();
commit();
return true;
}
@@ -178,19 +171,12 @@ public:
return true;
}
/// Store the parameter value to the parameter storage, w/o notifying the system (@see param_set_no_notification())
bool commit_no_notification() const
{
return true;
//return param_set_no_notification(handle(), &_val) == 0;
}
/// Set and commit a new value. Returns true if the value changed.
bool commit_no_notification(float val)
bool commit(float val)
{
if (fabsf(val - _val) > FLT_EPSILON) {
set(val);
commit_no_notification();
commit();
return true;
}
@@ -233,19 +219,12 @@ public:
//return param_set(handle(), &_val) == 0;
}
/// Store the parameter value to the parameter storage, w/o notifying the system (@see param_set_no_notification())
bool commit_no_notification() const
{
//return param_set_no_notification(handle(), &_val) == 0;
return true;
}
/// Set and commit a new value. Returns true if the value changed.
bool commit_no_notification(int32_t val)
bool commit(int32_t val)
{
if (val != _val) {
set(val);
commit_no_notification();
commit();
return true;
}
@@ -290,19 +269,12 @@ public:
//return param_set(handle(), &_val) == 0;
}
/// Store the parameter value to the parameter storage, w/o notifying the system (@see param_set_no_notification())
bool commit_no_notification() const
{
return true;
//return param_set_no_notification(handle(), &_val) == 0;
}
/// Set and commit a new value. Returns true if the value changed.
bool commit_no_notification(int32_t val)
bool commit(int32_t val)
{
if (val != _val) {
set(val);
commit_no_notification();
commit();
return true;
}
@@ -346,20 +318,12 @@ public:
return true;
}
/// Store the parameter value to the parameter storage, w/o notifying the system (@see param_set_no_notification())
bool commit_no_notification() const
{
int32_t value_int = (int32_t)_val;
//return param_set_no_notification(handle(), &value_int) == 0;
return true;
}
/// Set and commit a new value. Returns true if the value changed.
bool commit_no_notification(bool val)
bool commit(bool val)
{
if (val != _val) {
set(val);
commit_no_notification();
commit();
return true;
}
@@ -308,7 +308,7 @@ CameraTrigger::CameraTrigger() :
_activation_time = 40.0f;
PX4_WARN("Trigger interval too low for PWM interface, setting to 40 ms");
param_set_no_notification(_p_activation_time, &(_activation_time));
param_set(_p_activation_time, &(_activation_time));
}
// Advertise critical publishers here, because we cannot advertise in interrupt context
@@ -581,7 +581,7 @@ CameraTrigger::Run()
*/
if (cmd.param1 > 0.0f) {
_distance = cmd.param1;
param_set_no_notification(_p_distance, &_distance);
param_set(_p_distance, &_distance);
_trigger_enabled = true;
_trigger_paused = false;
@@ -598,7 +598,7 @@ CameraTrigger::Run()
if (cmd.param2 > 0.0f) {
if (_camera_interface_mode == CAMERA_INTERFACE_MODE_GPIO) {
_activation_time = cmd.param2;
param_set_no_notification(_p_activation_time, &(_activation_time));
param_set(_p_activation_time, &(_activation_time));
}
}
@@ -616,14 +616,14 @@ CameraTrigger::Run()
if (cmd.param1 > 0.0f) {
_interval = cmd.param1;
param_set_no_notification(_p_interval, &(_interval));
param_set(_p_interval, &_interval);
}
// We can only control the shutter integration time of the camera in GPIO mode
if (cmd.param2 > 0.0f) {
if (_camera_interface_mode == CAMERA_INTERFACE_MODE_GPIO) {
_activation_time = cmd.param2;
param_set_no_notification(_p_activation_time, &_activation_time);
param_set(_p_activation_time, &_activation_time);
}
}
@@ -637,7 +637,7 @@ CameraTrigger::Run()
if (cmd.param1 > 0.0f) {
_distance = cmd.param1;
param_set_no_notification(_p_distance, &_distance);
param_set(_p_distance, &_distance);
_trigger_enabled = true;
_trigger_paused = false;
@@ -654,14 +654,14 @@ CameraTrigger::Run()
if (cmd.param2 > 0.0f) {
if (_camera_interface_mode == CAMERA_INTERFACE_MODE_GPIO) {
_activation_time = cmd.param2;
param_set_no_notification(_p_activation_time, &(_activation_time));
param_set(_p_activation_time, &_activation_time);
}
}
// Set Param for minimum camera trigger interval
if (cmd.param3 > 0.0f) {
_min_interval = cmd.param3;
param_set_no_notification(_p_min_interval, &(_min_interval));
param_set(_p_min_interval, &_min_interval);
}
if (cmd.param4 >= 2.0f) {
+1 -1
View File
@@ -135,7 +135,7 @@ void DShot::enable_dshot_outputs(const bool enabled)
if (dshot_frequency_request != 0) {
if (dshot_frequency != 0 && dshot_frequency != dshot_frequency_request) {
PX4_WARN("Only supporting a single frequency, adjusting param %s", param_name);
param_set_no_notification(handle, &dshot_frequency_param);
param_set(handle, &dshot_frequency_param);
} else {
dshot_frequency = dshot_frequency_request;
-1
View File
@@ -773,7 +773,6 @@ void RCInput::Run()
) {
// RC_INPUT_PROTO auto => locked selection
_param_rc_input_proto.set(_rc_scan_state);
_param_rc_input_proto.commit();
}
}
}
@@ -106,8 +106,6 @@ int SagetechMXS::task_spawn(int argc, char *argv[])
return PX4_ERROR;
}
bool SagetechMXS::init()
{
ScheduleOnInterval(UPDATE_INTERVAL_US); // 50Hz
@@ -117,7 +115,6 @@ bool SagetechMXS::init()
if (vehicle_list == nullptr) {
if (_adsb_list_max.get() > MAX_VEHICLES_LIMIT) { // Safety Check
_adsb_list_max.set(MAX_VEHICLES_LIMIT);
_adsb_list_max.commit();
list_size_allocated = MAX_VEHICLES_LIMIT;
}
@@ -158,8 +155,7 @@ int SagetechMXS::custom_command(int argc, char *argv[])
}
if (!strcmp(verb, "ident")) {
get_instance()->_adsb_ident.set(1);
return get_instance()->_adsb_ident.commit();
return get_instance()->_adsb_ident.set(1);
}
if (!strcmp(verb, "opmode")) {
@@ -170,20 +166,16 @@ int SagetechMXS::custom_command(int argc, char *argv[])
return PX4_ERROR;
} else if (!strcmp(opmode, "off") || !strcmp(opmode, "0")) {
get_instance()->_mxs_op_mode.set(0);
return get_instance()->_mxs_op_mode.commit();
return get_instance()->_mxs_op_mode.set(0);
} else if (!strcmp(opmode, "on") || !strcmp(opmode, "1")) {
get_instance()->_mxs_op_mode.set(1);
return get_instance()->_mxs_op_mode.commit();
return get_instance()->_mxs_op_mode.set(1);
} else if (!strcmp(opmode, "stby") || !strcmp(opmode, "2")) {
get_instance()->_mxs_op_mode.set(2);
return get_instance()->_mxs_op_mode.commit();
return get_instance()->_mxs_op_mode.set(2);
} else if (!strcmp(opmode, "alt") || !strcmp(opmode, "3")) {
get_instance()->_mxs_op_mode.set(3);
return get_instance()->_mxs_op_mode.commit();
return get_instance()->_mxs_op_mode.set(3);
} else {
print_usage("Invalid Op Mode");
@@ -207,8 +199,7 @@ int SagetechMXS::custom_command(int argc, char *argv[])
return PX4_ERROR;
} else {
get_instance()->_adsb_squawk.set(sqk);
return get_instance()->_adsb_squawk.commit();
return get_instance()->_adsb_squawk.set(sqk);
}
}
@@ -305,7 +296,6 @@ void SagetechMXS::Run()
auto_config_installation();
auto_config_flightid();
_mxs_op_mode.set(sg_op_mode_t::modeStby);
_mxs_op_mode.commit();
send_targetreq_msg();
mxs_state.initialized = true;
}
@@ -751,7 +741,6 @@ void SagetechMXS::send_operating_msg()
if (mxs_state.op.identOn) {
_adsb_ident.set(0);
_adsb_ident.commit();
}
if (_gps.vel_ned_valid) {
@@ -1248,22 +1237,16 @@ int SagetechMXS::handle_fid(const char *fid)
int SagetechMXS::store_inst_resp()
{
_mxs_op_mode.set(mxs_state.ack.opMode);
_mxs_op_mode.commit();
_adsb_icao.set(mxs_state.inst.icao);
_adsb_icao.commit();
_adsb_len_width.set(mxs_state.inst.size);
_adsb_len_width.commit();
_adsb_emit_type.set(convert_sg_to_emitter_type(mxs_state.inst.emitter));
_adsb_emit_type.commit();
return PX4_OK;
}
void SagetechMXS::auto_config_operating()
{
mxs_state.op.opMode = sg_op_mode_t::modeOff;
_mxs_op_mode.set(sg_op_mode_t::modeOff);
_mxs_op_mode.commit();
if (check_valid_squawk(_adsb_squawk.get())) {
mxs_state.op.squawk = convert_base_to_decimal(BASE_OCTAL, _adsb_squawk.get());
+23 -28
View File
@@ -701,8 +701,7 @@ UavcanNode::Run()
// Check for parameter requests (get/set/list)
if (_param_request_sub.updated() && !_param_list_in_progress && !_param_in_progress && !_count_in_progress) {
parameter_request_s request{};
uavcan_parameter_request_s request{};
_param_request_sub.copy(&request);
if (_param_counts[request.node_id]) {
@@ -710,14 +709,14 @@ UavcanNode::Run()
* We know how many parameters are exposed by this node, so
* process the request.
*/
if (request.message_type == parameter_request_s::MESSAGE_TYPE_PARAM_REQUEST_READ) {
if (request.message_type == uavcan_parameter_request_s::MESSAGE_TYPE_PARAM_REQUEST_READ) {
uavcan::protocol::param::GetSet::Request req;
if (request.param_index >= 0) {
req.index = request.param_index;
} else {
req.name = (char *)request.name;
req.name = (char *)request.param_id;
}
int call_res = _param_getset_client.call(request.node_id, req);
@@ -730,28 +729,24 @@ UavcanNode::Run()
_param_index = request.param_index;
}
} else if (request.message_type == parameter_request_s::MESSAGE_TYPE_PARAM_SET) {
} else if (request.message_type == uavcan_parameter_request_s::MESSAGE_TYPE_PARAM_SET) {
uavcan::protocol::param::GetSet::Request req;
if (request.param_index >= 0) {
req.index = request.param_index;
} else {
req.name = (char *)request.name;
req.name = (char *)request.param_id;
}
switch (request.type) {
case parameter_request_s::TYPE_BOOL:
req.value.to<uavcan::protocol::param::Value::Tag::boolean_value>() = request.int32_value;
break;
if (request.param_type == uavcan_parameter_request_s::PARAM_TYPE_REAL32) {
req.value.to<uavcan::protocol::param::Value::Tag::real_value>() = request.real_value;
case parameter_request_s::TYPE_FLOAT32:
req.value.to<uavcan::protocol::param::Value::Tag::real_value>() = request.float32_value;
break;
} else if (request.param_type == uavcan_parameter_request_s::PARAM_TYPE_UINT8) {
req.value.to<uavcan::protocol::param::Value::Tag::boolean_value>() = request.int_value;
default:
req.value.to<uavcan::protocol::param::Value::Tag::integer_value>() = request.int32_value;
break;
} else {
req.value.to<uavcan::protocol::param::Value::Tag::integer_value>() = request.int_value;
}
// Set the dirty bit for this node
@@ -767,7 +762,7 @@ UavcanNode::Run()
_param_index = request.param_index;
}
} else if (request.message_type == parameter_request_s::MESSAGE_TYPE_PARAM_REQUEST_LIST) {
} else if (request.message_type == uavcan_parameter_request_s::MESSAGE_TYPE_PARAM_REQUEST_LIST) {
// This triggers the _param_list_in_progress case below.
_param_index = 0;
_param_list_in_progress = true;
@@ -777,8 +772,8 @@ UavcanNode::Run()
PX4_DEBUG("starting component-specific param list");
}
} else if (request.node_id == parameter_request_s::NODE_ID_ALL) {
if (request.message_type == parameter_request_s::MESSAGE_TYPE_PARAM_REQUEST_LIST) {
} else if (request.node_id == uavcan_parameter_request_s::NODE_ID_ALL) {
if (request.message_type == uavcan_parameter_request_s::MESSAGE_TYPE_PARAM_REQUEST_LIST) {
/*
* This triggers the _param_list_in_progress case below,
* but additionally iterates over all active nodes.
@@ -1096,24 +1091,24 @@ UavcanNode::cb_getset(const uavcan::ServiceCallResult<uavcan::protocol::param::G
if (result.isSuccessful()) {
uavcan::protocol::param::GetSet::Response param = result.getResponse();
parameter_value_s response{};
uavcan_parameter_value_s response{};
response.node_id = result.getCallID().server_node_id.get();
strncpy(response.param_name, param.name.c_str(), sizeof(response.param_name) - 1);
response.param_name[16] = '\0';
strncpy(response.param_id, param.name.c_str(), sizeof(response.param_id) - 1);
response.param_id[16] = '\0';
response.param_index = _param_index;
response.param_count = _param_counts[response.node_id];
if (param.value.is(uavcan::protocol::param::Value::Tag::integer_value)) {
response.type = parameter_request_s::TYPE_INT32;
response.int32_value = param.value.to<uavcan::protocol::param::Value::Tag::integer_value>();
response.param_type = uavcan_parameter_request_s::PARAM_TYPE_INT64;
response.int_value = param.value.to<uavcan::protocol::param::Value::Tag::integer_value>();
} else if (param.value.is(uavcan::protocol::param::Value::Tag::real_value)) {
response.type = parameter_request_s::TYPE_FLOAT32;
response.float32_value = param.value.to<uavcan::protocol::param::Value::Tag::real_value>();
response.param_type = uavcan_parameter_request_s::PARAM_TYPE_REAL32;
response.real_value = param.value.to<uavcan::protocol::param::Value::Tag::real_value>();
} else if (param.value.is(uavcan::protocol::param::Value::Tag::boolean_value)) {
response.type = parameter_request_s::TYPE_BOOL;
response.int32_value = param.value.to<uavcan::protocol::param::Value::Tag::boolean_value>();
response.param_type = uavcan_parameter_request_s::PARAM_TYPE_UINT8;
response.int_value = param.value.to<uavcan::protocol::param::Value::Tag::boolean_value>();
}
_param_response_pub.publish(response);
+3 -3
View File
@@ -75,8 +75,8 @@
#include <uORB/Subscription.hpp>
#include <uORB/SubscriptionInterval.hpp>
#include <uORB/topics/parameter_update.h>
#include <uORB/topics/parameter_request.h>
#include <uORB/topics/parameter_value.h>
#include <uORB/topics/uavcan_parameter_request.h>
#include <uORB/topics/uavcan_parameter_value.h>
#include <uORB/topics/vehicle_command_ack.h>
using namespace time_literals;
@@ -267,7 +267,7 @@ private:
uORB::Subscription _vcmd_sub{ORB_ID(vehicle_command)};
uORB::Subscription _param_request_sub{ORB_ID(uavcan_parameter_request)};
uORB::Publication<parameter_value_s> _param_response_pub{ORB_ID(uavcan_parameter_value)};
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)};
/*
+1 -1
View File
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2014-2022 PX4 Development Team. All rights reserved.
* Copyright (c) 2014-2021 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
-1
View File
@@ -68,7 +68,6 @@ add_subdirectory(system_identification EXCLUDE_FROM_ALL)
add_subdirectory(tecs EXCLUDE_FROM_ALL)
add_subdirectory(terrain_estimation EXCLUDE_FROM_ALL)
add_subdirectory(timesync EXCLUDE_FROM_ALL)
add_subdirectory(tinybson EXCLUDE_FROM_ALL)
add_subdirectory(tunes EXCLUDE_FROM_ALL)
add_subdirectory(version EXCLUDE_FROM_ALL)
add_subdirectory(weather_vane EXCLUDE_FROM_ALL)
-3
View File
@@ -90,9 +90,6 @@ public:
// Store the parameter value to the parameter storage (@see param_set())
bool commit() { return (param_set(_handle, &_val) == PX4_OK); }
// Store the parameter value to the parameter storage, w/o notifying the system (@see param_set_no_notification())
bool commit_no_notification() { return (param_set_no_notification(_handle, &_val) == PX4_OK); }
void set(T val) { _val = val; }
bool update() override { return (param_get(_handle, &_val) == PX4_OK); }
+17 -13
View File
@@ -1,6 +1,6 @@
############################################################################
#
# Copyright (c) 2017 - 2022 PX4 Development Team. All rights reserved.
# Copyright (c) 2017 - 2020 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
@@ -33,6 +33,8 @@
add_compile_options(${MAX_CUSTOM_OPT_LEVEL})
add_subdirectory(tinybson)
if (NOT PARAM_DEFAULT_OVERRIDES)
set(PARAM_DEFAULT_OVERRIDES "{}")
endif()
@@ -149,12 +151,6 @@ add_custom_target(parameters_header DEPENDS px4_parameters.hpp)
set(SRCS)
set(PX4_PARAM_CLIENT_SRV 1)
if(PX4_PARAM_CLIENT_SRV)
add_compile_definitions(PX4_PARAM_CLIENT_SRV)
list(APPEND SRCS parameters_srv.cpp)
endif()
list(APPEND SRCS parameters.cpp)
if(BUILD_TESTING)
@@ -163,23 +159,31 @@ else()
list(APPEND SRCS param_translation.cpp)
endif()
if(${PX4_PLATFORM} STREQUAL "nuttx")
add_subdirectory(flashparams)
# build user-side interface for protected build
if(NOT CONFIG_BUILD_FLAT)
list(APPEND SRCS parameters_ioctl.cpp)
add_library(usr_parameters usr_parameters_if.cpp px4_parameters.hpp)
add_dependencies(usr_parameters prebuild_targets)
target_compile_definitions(usr_parameters PRIVATE -DMODULE_NAME="usr_parameters")
endif()
endif()
# TODO: find a better way to do this
if(NOT "${PX4_BOARD}" MATCHES "px4_io")
add_library(parameters STATIC EXCLUDE_FROM_ALL
${SRCS}
px4_parameters.hpp
ParameterServer.cpp
ParameterServer.hpp
)
target_link_libraries(parameters PRIVATE perf tinybson px4_platform)
target_compile_definitions(parameters PRIVATE -DMODULE_NAME="parameters")
target_compile_definitions(parameters PRIVATE -DMODULE_NAME="parameters" -D__KERNEL__)
target_compile_options(parameters
PRIVATE
#-DDEBUG_BUILD
#${MAX_CUSTOM_OPT_LEVEL}
-O0
-Wno-cast-align # TODO: fix and enable
-Wno-sign-compare # TODO: fix and enable
)
@@ -189,7 +193,7 @@ endif()
add_dependencies(parameters prebuild_targets)
if(${PX4_PLATFORM} STREQUAL "nuttx")
#target_link_libraries(parameters PRIVATE flashparams)
target_link_libraries(parameters PRIVATE flashparams)
endif()
px4_add_functional_gtest(SRC ParameterTest.cpp LINKLIBS parameters)
File diff suppressed because it is too large Load Diff
-516
View File
@@ -1,516 +0,0 @@
/****************************************************************************
*
* Copyright (c) 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
* 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 <px4_platform_common/px4_config.h>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
#include <px4_platform_common/atomic_bitset.h>
#include <px4_platform_common/defines.h>
#include <px4_platform_common/posix.h>
#include <px4_platform_common/sem.h>
#include <px4_platform_common/shutdown.h>
#include <containers/Bitset.hpp>
#include <drivers/drv_hrt.h>
#include <lib/perf/perf_counter.h>
#include "tinybson/tinybson.h"
#include "uthash/utarray.h"
#include <uORB/Publication.hpp>
#include <uORB/Subscription.hpp>
#include <uORB/SubscriptionCallback.hpp>
#include <uORB/topics/actuator_armed.h>
#include <uORB/topics/parameter_request.h>
#include <uORB/topics/parameter_value.h>
#include <uORB/topics/parameter_update.h>
#include <uORB/topics/srv_parameter_get_request.h>
#include <uORB/topics/srv_parameter_get_response.h>
#include <uORB/topics/srv_parameter_set_request.h>
#include <uORB/topics/srv_parameter_set_response.h>
#include "param.h"
#include <parameters/px4_parameters.hpp>
using namespace time_literals;
class ParameterServer : public px4::ScheduledWorkItem
{
public:
ParameterServer();
~ParameterServer() override;
/**
* Look up a parameter by name.
*
* @param name The canonical name of the parameter being looked up.
* @return A handle to the parameter, or PARAM_INVALID if the parameter does not exist.
*/
param_t findParameter(const char *name, bool notification = true);
/**
* Return the total number of parameters.
*
* @return The number of parameters.
*/
unsigned count() const { return param_info_count; }
/**
* Return the actually used number of parameters.
*
* @return The number of parameters.
*/
unsigned countUsed() const { return _params_active.count(); }
/**
* Wether a parameter is in use in the system.
*
* @return True if it has been written or read
*/
bool isParameterUsed(param_t param) const;
/**
* Look up a parameter by index.
*
* @param index An index from 0 to n, where n is param_count()-1.
* @return A handle to the parameter, or PARAM_INVALID if the index is out of range.
*/
param_t forIndex(unsigned index) const;
/**
* Look up an used parameter by index.
*
* @param index The parameter to obtain the index for.
* @return The index of the parameter in use, or -1 if the parameter does not exist.
*/
param_t forUsedIndex(unsigned index) const;
/**
* Look up the index of a parameter.
*
* @param param The parameter to obtain the index for.
* @return The index, or -1 if the parameter does not exist.
*/
int getParameterIndex(param_t param) const;
/**
* Look up the index of an used parameter.
*
* @param param The parameter to obtain the index for.
* @return The index of the parameter in use, or -1 if the parameter does not exist.
*/
int getParameterUsedIndex(param_t param) const;
/**
* Obtain the name of a parameter.
*
* @param param A handle returned by param_find or passed by param_foreach.
* @return The name assigned to the parameter, or NULL if the handle is invalid.
*/
const char *getParameterName(param_t param) const;
/**
* Obtain the volatile state of a parameter.
*
* @param param A handle returned by param_find or passed by param_foreach.
* @return true if the parameter is volatile
*/
bool isParameterVolatile(param_t param) const;
/**
* Test whether a parameter's value has changed from the default.
*
* @return If true, the parameter's value has not been changed from the default.
*/
bool isParameterValueDefault(param_t param);
/**
* Test whether a parameter's value has been changed but not saved.
*
* @return If true, the parameter's value has not been saved.
*/
bool isParameterValueUnsaved(param_t param);
/**
* Obtain the type of a parameter.
*
* @param param A handle returned by param_find or passed by param_foreach.
* @return The type assigned to the parameter.
*/
param_type_t getParameterType(param_t param) const;
/**
* Determine the size of a parameter.
*
* @param param A handle returned by param_find or passed by param_foreach.
* @return The size of the parameter's value.
*/
size_t getParameterSize(param_t param) const;
/**
* Copy the value of a parameter.
*
* @param param A handle returned by param_find or passed by param_foreach.
* @param val Where to return the value, assumed to point to suitable storage for the parameter type.
* @return Zero if the parameter's value could be returned, nonzero otherwise.
*/
int getParameterValue(param_t param, void *val);
/**
* Copy the (airframe-specific) default value of a parameter.
*
* @param param A handle returned by param_find or passed by param_foreach.
* @param default_val Where to return the value, assumed to point to suitable storage for the parameter type.
* @return Zero if the parameter's deafult value could be returned, nonzero otherwise.
*/
int getParameterDefaultValue(param_t param, void *default_val);
/**
* Copy the system-wide default value of a parameter.
*
* @param param A handle returned by param_find or passed by param_foreach.
* @param default_val Where to return the value, assumed to point to suitable storage for the parameter type.
* @return Zero if the parameter's deafult value could be returned, nonzero otherwise.
*/
int getParameterSystemDefaultValue(param_t param, void *default_val);
/**
* Set the value of a parameter.
*
* @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.
* @return Zero if the parameter's value could be set from a scalar, nonzero otherwise.
*/
int setParameter(param_t param, const void *val, bool mark_saved = true, bool notify_changes = true);
/**
* Set the default value of a parameter.
*
* @param param A handle returned by param_find or passed by param_foreach.
* @param val The default value to set; assumed to point to a variable of the parameter type.
* @return Zero if the parameter's default value could be set from a scalar, nonzero otherwise.
*/
int setParameterDefaultValue(param_t param, const void *val);
/**
* Notify the system about parameter changes. Can be used for example after several calls to
* param_set_no_notification() to avoid unnecessary system notifications.
*/
void notifyChanges();
/**
* Reset all parameters to their default values.
*/
void resetAllParameters(bool auto_save = true);
/**
* Reset all parameters to their default values except for excluded parameters.
*
* @param excludes Array of param names to exclude from resetting. Use a wildcard
* at the end to exclude parameters with a certain prefix.
* @param num_excludes The number of excludes provided.
*/
void resetExcludes(const char *excludes[], int num_excludes);
/**
* Reset only specific parameters to their default values.
*
* @param resets Array of param names to reset. Use a wildcard at the end to reset parameters with a certain prefix.
* @param num_resets The number of passed reset conditions in the resets array.
*/
void resetSpecificParameter(const char *resets[], int num_resets);
/**
* Export changed parameters to a file.
* Note: this method requires a large amount of stack size!
*
* @param filename Path to the default parameter file.
* @param filter Filter parameters to be exported. The method should return true if
* the parameter should be exported. No filtering if nullptr is passed.
* @return Zero on success, nonzero on failure.
*/
typedef bool(*param_filter_func)(param_t handle);
int exportToFile(const char *filename, param_filter_func filter);
/**
* Import parameters from a file, discarding any unrecognized parameters.
*
* This function merges the imported parameters with the current parameter set.
*
* @param fd File descriptor to import from (-1 selects the FLASH storage).
* @return Zero on success, nonzero if an error occurred during import.
* Note that in the failure case, parameters may be inconsistent.
*/
int importFromFileDescriptor(int fd);
/**
* Load parameters from a file.
*
* This function resets all parameters to their default values, then loads new
* values from a file.
*
* @param fd File descriptor to import from (-1 selects the FLASH storage).
* @return Zero on success, nonzero if an error occurred during import.
* Note that in the failure case, parameters may be inconsistent.
*/
int loadFromFileDescriptor(int fd);
/**
* Apply a function to each parameter.
*
* Note that the parameter set is not locked during the traversal. It also does
* not hold an internal state, so the callback function can block or sleep between
* parameter callbacks.
*
* @param func The function to invoke for each parameter.
* @param arg Argument passed to the function.
* @param only_changed If true, the function is only called for parameters whose values have
* been changed from the default.
* @param only_used If true, the function is only called for parameters which have been
* used in one of the running applications.
*/
void forEachParameter(void (*func)(void *arg, param_t param), void *arg, bool only_changed, bool only_used);
/**
* Set the default parameter file name.
* This has no effect if the FLASH-based storage is enabled.
*
* @param filename Path to the default parameter file. The file is not required to
* exist.
* @return Zero on success.
*/
int setDefaultFile(const char *filename);
/**
* Get the default parameter file name.
*
* @return The path to the current default parameter file; either as
* a result of a call to param_set_default_file, or the
* built-in default.
*/
const char *getDefaultFile() const { return _param_default_file; }
/**
* Set the backup parameter file name.
*
* @param filename Path to the backup parameter file. The file is not required to
* exist.
* @return Zero on success.
*/
int setBackupFile(const char *filename);
/**
* Get the backup parameter file name.
*
* @return The path to the backup parameter file
*/
const char *getBackupFile() const { return _param_backup_file; }
/**
* Automatically save the parameters after a timeout and limited rate.
*
* This needs to be called with the writer lock held (it's not necessary that it's the writer lock, but it
* needs to be the same lock as autosave_worker() and param_control_autosave() use).
*/
void autoSave(bool now = false);
/**
* Load parameters from the default parameter file.
*
* @return Zero on success.
*/
int loadDefault();
/**
* Generate the hash of all parameters and their values
*
* @return CRC32 hash of all param_ids and values
*/
uint32_t hashCheck();
/**
* Print the status of the param system
*
*/
void printStatus();
/**
* Enable/disable the param autosaving.
* Re-enabling with changed params will not cause an autosave.
* @param enable true: enable autosaving, false: disable autosaving
*/
void controlAutosave(bool enable);
private:
static constexpr uint16_t param_info_count = sizeof(px4::parameters) / sizeof(param_info_s);
/**
* Test whether a param_t is value.
*
* @param param The parameter handle to test.
* @return True if the handle is valid.
*/
static constexpr bool handle_in_range(param_t param) { return (param < param_info_count); }
void lockReader(); // lock the parameter store for read access
void unlockReader(); // unlock the parameter store
void lockWriter(); // lock the parameter store for write access
void unlockWriter(); // unlock the parameter store
// Storage for modified parameters.
struct param_wbuf_s {
union param_value_u val {};
param_t param{PARAM_INVALID};
};
/**
* Compare two modified parameter structures to determine ordering.
*
* This function is suitable for passing to qsort or bsearch.
*/
static int compareValues(const void *a, const void *b);
/**
* Locate the modified parameter structure for a parameter, if it exists.
*
* @param param The parameter being searched.
* @return The structure holding the modified value, or
* nullptr if the parameter has not been modified.
*/
param_wbuf_s *findChanged(param_t param);
/**
* Reset a parameter to its default value.
*
* @param param A handle returned by param_find or passed by param_foreach.
* @return Zero on success, nonzero on failure
*/
int resetParameter(param_t param);
/**
* Obtain a pointer to the storage allocated for a parameter.
*
* @param param The parameter whose storage is sought.
* @return A pointer to the parameter value, or nullptr
* if the parameter does not exist.
*/
const void *getParameterValuePointer(param_t param);
// get parameter default value, caller is responsible for locking
int getParameterDefaultValueInternal(param_t param, void *default_val);
/**
* Save parameters to the default file.
* Note: this method requires a large amount of stack size!
*
* This function saves all parameters with non-default values.
*
* @return Zero on success.
*/
int saveDefault();
// internal parameter export, caller is responsible for locking
int exportInternal(int fd, param_filter_func filter);
int bsonImportCallback(bson_decoder_t decoder, bson_node_t node);
static int importCallbackTrampoline(bson_decoder_t decoder, void *priv, bson_node_t node);
int importFromFileDescriptorInternal(int fd);
int verifyBsonExportCallback(bson_decoder_t decoder, bson_node_t node);
static int verifyBsonExportTrampoline(bson_decoder_t decoder, void *priv, bson_node_t node);
int verifyBsonExport(int fd);
char *_param_default_file{nullptr};
char *_param_backup_file{nullptr};
px4::AtomicBitset<param_info_count> _params_active; // params found
px4::AtomicBitset<param_info_count> _params_changed; // params non-default
px4::Bitset<param_info_count> _params_custom_default; // params with runtime default value
px4::AtomicBitset<param_info_count> _params_unsaved;
/** flexible array holding modified parameter values */
UT_array *_param_values{nullptr};
UT_array *_param_custom_default_values{nullptr};
const UT_icd param_icd = {sizeof(param_wbuf_s), nullptr, nullptr, nullptr};
unsigned int _param_instance{0};
// the following implements an RW-lock using 2 semaphores (used as mutexes). It gives
// priority to readers, meaning a writer could suffer from starvation, but in our use-case
// we only have short periods of reads and writes are rare.
px4_sem_t _param_sem; ///< this protects against concurrent access to _param_values
int _reader_lock_holders{0};
px4_sem_t _reader_lock_holders_lock; ///< this protects against concurrent access to reader_lock_holders
perf_counter_t _export_perf{perf_alloc(PC_ELAPSED, "param: export")};
perf_counter_t _find_count_perf{perf_alloc(PC_COUNT, "param: find")};
perf_counter_t _get_count_perf{perf_alloc(PC_COUNT, "param: get")};
perf_counter_t _set_perf{perf_alloc(PC_ELAPSED, "param: set")};
px4_sem_t _param_sem_save; ///< this protects against concurrent param saves (file or flash access).
///< we use a separate lock to allow concurrent param reads and saves.
///< a param_set could still be blocked by a param save, because it
///< needs to take the reader lock
void Run() override;
uORB::Publication<parameter_update_s> _parameter_update_pub{ORB_ID(parameter_update)};
// srv: parameter_get
uORB::SubscriptionCallbackWorkItem _srv_parameter_get_request_sub{this, ORB_ID(srv_parameter_get_request)};
uORB::Publication<srv_parameter_get_response_s> _srv_parameter_get_response_pub{ORB_ID(srv_parameter_get_response)};
// srv: parameter_set
uORB::SubscriptionCallbackWorkItem _srv_parameter_set_request_sub{this, ORB_ID(srv_parameter_set_request)};
uORB::Publication<srv_parameter_set_response_s> _srv_parameter_set_response_pub{ORB_ID(srv_parameter_set_response)};
// TODO: replace
uORB::Publication<parameter_value_s> _param_response_pub{ORB_ID(parameter_value)};
uORB::SubscriptionCallbackWorkItem _param_request_sub{this, ORB_ID(parameter_request)};
uORB::SubscriptionData<actuator_armed_s> _armed_sub{ORB_ID(actuator_armed)};
// autosaving variables
hrt_abstime _last_autosave_timestamp{0};
px4::atomic_bool _autosave_scheduled{false};
bool _autosave_disabled{false};
px4::atomic_bool _notify_scheduled{false};
};
+11 -11
View File
@@ -55,7 +55,7 @@
#include <parameters/param.h>
#include "../uthash/utarray.h"
#include <lib/tinybson/tinybson.h>
#include <parameters/tinybson/tinybson.h>
#include "flashparams.h"
#include "flashfs.h"
#include "../param_translation.h"
@@ -87,12 +87,12 @@ param_export_internal(param_filter_func filter)
bson_encoder_init_buf(&encoder, nullptr, 0);
/* no modified parameters -> we are done */
if (_param_values == nullptr) {
if (param_values == nullptr) {
result = 0;
goto out;
}
while ((s = (struct param_wbuf_s *)utarray_next(_param_values, s)) != nullptr) {
while ((s = (struct param_wbuf_s *)utarray_next(param_values, s)) != nullptr) {
int32_t i;
float f;
@@ -103,12 +103,12 @@ param_export_internal(param_filter_func filter)
/* append the appropriate BSON type object */
switch (getParameterType(s->param)) {
switch (param_type(s->param)) {
case PARAM_TYPE_INT32:
i = s->val.i;
if (bson_encoder_append_int32(&encoder, getParameterName(s->param), i)) {
debug("BSON append failed for '%s'", getParameterName(s->param));
if (bson_encoder_append_int32(&encoder, param_name(s->param), i)) {
debug("BSON append failed for '%s'", param_name(s->param));
goto out;
}
@@ -117,8 +117,8 @@ param_export_internal(param_filter_func filter)
case PARAM_TYPE_FLOAT:
f = s->val.f;
if (bson_encoder_append_double(&encoder, getParameterName(s->param), f)) {
debug("BSON append failed for '%s'", getParameterName(s->param));
if (bson_encoder_append_double(&encoder, param_name(s->param), f)) {
debug("BSON append failed for '%s'", param_name(s->param));
goto out;
}
@@ -214,7 +214,7 @@ param_import_callback(bson_decoder_t decoder, bson_node_t node)
switch (node->type) {
case BSON_INT32:
if (getParameterType(param) != PARAM_TYPE_INT32) {
if (param_type(param) != PARAM_TYPE_INT32) {
PX4_WARN("unexpected type for %s", node->name);
result = 1; // just skip this entry
goto out;
@@ -225,7 +225,7 @@ param_import_callback(bson_decoder_t decoder, bson_node_t node)
break;
case BSON_DOUBLE:
if (getParameterType(param) != PARAM_TYPE_FLOAT) {
if (param_type(param) != PARAM_TYPE_FLOAT) {
PX4_WARN("unexpected type for %s", node->name);
result = 1; // just skip this entry
goto out;
@@ -241,7 +241,7 @@ param_import_callback(bson_decoder_t decoder, bson_node_t node)
goto out;
}
if (param_set_external(param, v, true, true)) {
if (param_set_external(param, v, true)) {
debug("error setting value for '%s'", node->name);
goto out;
}
+1 -1
View File
@@ -58,7 +58,7 @@ __BEGIN_DECLS
*/
__EXPORT extern UT_array *param_values;
__EXPORT int param_set_external(param_t param, const void *val, bool mark_saved, bool notify_changes);
__EXPORT int param_set_external(param_t param, const void *val, bool mark_saveds);
__EXPORT const void *param_get_value_ptr_external(param_t param);
/* The interface hooks to the Flash based storage. The caller is responsible for locking */
+13 -16
View File
@@ -242,21 +242,6 @@ __EXPORT int param_set(param_t param, const void *val);
*/
__EXPORT int param_set_default_value(param_t param, const void *val);
/**
* Set the value of a parameter, but do not notify the system about the change.
*
* @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.
* @return Zero if the parameter's value could be set from a scalar, nonzero otherwise.
*/
__EXPORT int param_set_no_notification(param_t param, const void *val);
/**
* Notify the system about parameter changes. Can be used for example after several calls to
* param_set_no_notification() to avoid unnecessary system notifications.
*/
__EXPORT void param_notify_changes(void);
/**
* Reset all parameters to their default values.
*/
@@ -271,6 +256,8 @@ __EXPORT void param_reset_all(void);
*/
__EXPORT void param_reset_excludes(const char *excludes[], int num_excludes);
typedef bool(*param_filter_func)(param_t handle);
/**
* Reset only specific parameters to their default values.
*
@@ -288,7 +275,6 @@ __EXPORT void param_reset_specific(const char *resets[], int num_resets);
* the parameter should be exported. No filtering if nullptr is passed.
* @return Zero on success, nonzero on failure.
*/
typedef bool(*param_filter_func)(param_t handle);
__EXPORT int param_export(const char *filename, param_filter_func filter);
/**
@@ -314,6 +300,17 @@ __EXPORT int param_import(int fd);
*/
__EXPORT int param_load(int fd);
/**
* Read saved parameters from file and dump to console.
*
* This function reads the file and dumps all contents to console
* values from a file.
*
* @param fd File descriptor to read from.
* @return Zero on success, nonzero if an error occurred during import.
*/
__EXPORT int param_dump(int fd);
/**
* Apply a function to each parameter.
*
+1 -1
View File
@@ -156,7 +156,7 @@ bool param_modify_on_import(bson_node_t node)
// If was in range height mode, set range aiding to "always"
if (node->i32 == 2) {
int32_t rng_mode = 2;
param_set_no_notification(param_find("EKF2_RNG_CTRL"), &rng_mode);
param_set(param_find("EKF2_RNG_CTRL"), &rng_mode);
}
PX4_INFO("param migrating EKF2_HGT_MODE (removed) -> EKF2_HGT_REF: value=%" PRId32, node->i32);
File diff suppressed because it is too large Load Diff
+139
View File
@@ -0,0 +1,139 @@
/****************************************************************************
*
* Copyright (c) 2012-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
* 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 <string.h>
/**
* @file parameters_common.cpp
*
* Global parameter store, functions common to kernel and user sides
*
*/
static constexpr uint16_t param_info_count = sizeof(px4::parameters) / sizeof(param_info_s);
/**
* Test whether a param_t is value.
*
* @param param The parameter handle to test.
* @return True if the handle is valid.
*/
static constexpr bool handle_in_range(param_t param) { return (param < param_info_count); }
unsigned param_count()
{
return param_info_count;
}
int param_get_index(param_t param)
{
if (handle_in_range(param)) {
return (unsigned)param;
}
return -1;
}
param_t param_for_index(unsigned index)
{
if (index < param_info_count) {
return (param_t)index;
}
return PARAM_INVALID;
}
const char *param_name(param_t param)
{
return handle_in_range(param) ? px4::parameters[param].name : nullptr;
}
param_type_t param_type(param_t param)
{
return handle_in_range(param) ? px4::parameters_type[param] : PARAM_TYPE_UNKNOWN;
}
bool param_is_volatile(param_t param)
{
if (handle_in_range(param)) {
for (const auto &p : px4::parameters_volatile) {
if (static_cast<px4::params>(param) == p) {
return true;
}
}
}
return false;
}
static size_t param_size(param_t param)
{
if (handle_in_range(param)) {
switch (param_type(param)) {
case PARAM_TYPE_INT32:
case PARAM_TYPE_FLOAT:
return 4;
default:
return 0;
}
}
return 0;
}
int
param_get_system_default_value(param_t param, void *default_val)
{
if (!handle_in_range(param)) {
return PX4_ERROR;
}
int ret = PX4_OK;
switch (param_type(param)) {
case PARAM_TYPE_INT32:
memcpy(default_val, &px4::parameters[param].val.i, param_size(param));
break;
case PARAM_TYPE_FLOAT:
memcpy(default_val, &px4::parameters[param].val.f, param_size(param));
break;
default:
ret = PX4_ERROR;
break;
}
return ret;
}
+170
View File
@@ -0,0 +1,170 @@
/****************************************************************************
*
* Copyright (c) 2021 Technology Innovation Institute. 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 parameters_ioctl.cpp
*
* Protected build kernel space interface to global parameter store.
*/
#define PARAM_IMPLEMENTATION
#include <errno.h>
#include "param.h"
#include "parameters_ioctl.h"
#include <px4_platform_common/defines.h>
int param_ioctl(unsigned int cmd, unsigned long arg)
{
int ret = OK;
switch (cmd) {
case PARAMIOCFIND: {
paramiocfind_t *data = (paramiocfind_t *)arg;
if (data->notification) {
data->ret = param_find(data->name);
} else {
data->ret = param_find_no_notification(data->name);
}
}
break;
case PARAMIOCCOUNTUSED: {
paramioccountused_t *data = (paramioccountused_t *)arg;
data->ret = param_count_used();
}
break;
case PARAMIOCFORUSEDINDEX: {
paramiocforusedindex_t *data = (paramiocforusedindex_t *)arg;
data->ret = param_for_used_index(data->index);
}
break;
case PARAMIOCGETUSEDINDEX: {
paramiocgetusedindex_t *data = (paramiocgetusedindex_t *)arg;
data->ret = param_get_used_index(data->param);
}
break;
case PARAMIOCUNSAVED: {
paramiocunsaved_t *data = (paramiocunsaved_t *)arg;
data->ret = param_value_unsaved(data->param);
}
break;
case PARAMIOCGET: {
paramiocget_t *data = (paramiocget_t *)arg;
if (data->deflt) {
data->ret = param_get_default_value(data->param, data->val);
} else {
data->ret = param_get(data->param, data->val);
}
}
break;
case PARAMIOCAUTOSAVE: {
paramiocautosave_t *data = (paramiocautosave_t *)arg;
param_control_autosave(data->enable);
}
break;
case PARAMIOCSET: {
paramiocset_t *data = (paramiocset_t *)arg;
data->ret = param_set(data->param, data->val);
}
break;
case PARAMIOCUSED: {
paramiocused_t *data = (paramiocused_t *)arg;
data->ret = param_used(data->param);
}
break;
case PARAMIOCSETDEFAULT: {
paramiocsetdefault_t *data = (paramiocsetdefault_t *)arg;
data->ret = param_set_default_value(data->param, data->val);
}
break;
case PARAMIOCRESETGROUP: {
paramiocresetgroup_t *data = (paramiocresetgroup_t *)arg;
if (data->type == PARAM_RESET_EXCLUDES) {
param_reset_excludes(data->group, data->num_in_group);
} else if (data->type == PARAM_RESET_SPECIFIC) {
param_reset_specific(data->group, data->num_in_group);
} else {
param_reset_all();
}
}
break;
case PARAMIOCSAVEDEFAULT: {
paramiocsavedefault_t *data = (paramiocsavedefault_t *)arg;
data->ret = param_save_default();
}
break;
case PARAMIOCLOADDEFAULT: {
paramiocloaddefault_t *data = (paramiocloaddefault_t *)arg;
data->ret = param_load_default();
}
break;
case PARAMIOCEXPORT: {
paramiocexport_t *data = (paramiocexport_t *)arg;
data->ret = param_export(data->filename, nullptr);
}
break;
case PARAMIOCHASH: {
paramiochash_t *data = (paramiochash_t *)arg;
data->ret = param_hash_check();
}
break;
default:
ret = -ENOTTY;
break;
}
return ret;
}
+151
View File
@@ -0,0 +1,151 @@
/****************************************************************************
*
* Copyright (c) 2021 Technology Innovation Institute. 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 parameters_ioctl.h
*
* User space - kernel space interface to global parameter store.
*/
#pragma once
#define PARAM_IMPLEMENTATION
#include "param.h"
#include <px4_platform/board_ctrl.h>
#include <px4_platform_common/defines.h>
#define _PARAMIOC(_n) (_PX4_IOC(_PARAMIOCBASE, _n))
#define PARAMIOCNOTIFY _PARAMIOC(1)
#define PARAMIOCFIND _PARAMIOC(2)
typedef struct paramiocfind {
const char *name;
const bool notification;
param_t ret;
} paramiocfind_t;
#define PARAMIOCCOUNTUSED _PARAMIOC(3)
typedef struct paramioccountused {
unsigned ret;
} paramioccountused_t;
#define PARAMIOCFORUSEDINDEX _PARAMIOC(4)
typedef struct paramiocforusedindex {
const unsigned index;
param_t ret;
} paramiocforusedindex_t;
#define PARAMIOCGETUSEDINDEX _PARAMIOC(5)
typedef struct paramiocgetusedindex {
const param_t param;
unsigned ret;
} paramiocgetusedindex_t;
#define PARAMIOCUNSAVED _PARAMIOC(6)
typedef struct paramiocunsaved {
const param_t param;
bool ret;
} paramiocunsaved_t;
#define PARAMIOCGET _PARAMIOC(7)
typedef struct paramiocget {
const param_t param;
const bool deflt;
void *const val;
int ret;
} paramiocget_t;
#define PARAMIOCAUTOSAVE _PARAMIOC(8)
typedef struct paramiocautosave {
const bool enable;
} paramiocautosave_t;
#define PARAMIOCSET _PARAMIOC(9)
typedef struct paramiocset {
const param_t param;
const bool notification;
const void *val;
int ret;
} paramiocset_t;
#define PARAMIOCUSED _PARAMIOC(10)
typedef struct paramiocused {
const param_t param;
bool ret;
} paramiocused_t;
#define PARAMIOCSETDEFAULT _PARAMIOC(12)
typedef struct paramiocsetdefault {
const param_t param;
const void *val;
int ret;
} paramiocsetdefault_t;
#define PARAMIOCRESETGROUP _PARAMIOC(14)
typedef enum {
PARAM_RESET_ALL,
PARAM_RESET_EXCLUDES,
PARAM_RESET_SPECIFIC
} param_reset_type_t;
typedef struct paramiocresetgroup {
param_reset_type_t type;
const char **group;
const int num_in_group;
} paramiocresetgroup_t;
#define PARAMIOCSAVEDEFAULT _PARAMIOC(15)
typedef struct paramiocsavedefault {
int ret;
} paramiocsavedefault_t;
#define PARAMIOCLOADDEFAULT _PARAMIOC(16)
typedef struct paramiocloaddefault {
int ret;
} paramiocloaddefault_t;
#define PARAMIOCEXPORT _PARAMIOC(17)
typedef struct paramiocexport {
const char *filename;
int ret;
} paramiocexport_t;
#define PARAMIOCHASH _PARAMIOC(18)
typedef struct paramiochash {
uint32_t ret;
} paramiochash_t;
int param_ioctl(unsigned int cmd, unsigned long arg);
-189
View File
@@ -1,189 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2012-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
* 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 parameters.cpp
*
* Global parameter store.
*
* Note that it might make sense to convert this into a driver. That would
* offer some interesting options regarding state for e.g. ORB advertisements
* and background parameter saving.
*/
#define PARAM_IMPLEMENTATION
#include "param.h"
#if defined(PX4_PARAM_CLIENT_SRV)
#include <uORB/SubscriptionBlocking.hpp>
#include <uORB/Publication.hpp>
#include <uORB/topics/srv_parameter_get_request.h>
#include <uORB/topics/srv_parameter_get_response.h>
#include <uORB/topics/srv_parameter_set_request.h>
#include <uORB/topics/srv_parameter_set_response.h>
using namespace time_literals;
param_t param_find(const char *name)
{
// request
uORB::Publication<srv_parameter_get_request_s> request_pub{ORB_ID(srv_parameter_get_request)};
uORB::SubscriptionBlocking<srv_parameter_get_response_s> response_sub{ORB_ID(srv_parameter_get_response)};
srv_parameter_get_request_s request{};
request.index = -1;
memcpy(request.name, name, 16);
request.timestamp = hrt_absolute_time();
request_pub.publish(request);
// response
while ((hrt_elapsed_time(&request.timestamp) < 50_ms) || response_sub.updated()) {
const unsigned last_generation = response_sub.get_last_generation();
srv_parameter_get_response_s response{};
if (response_sub.updateBlocking(response, 1'000)) {
if (response_sub.get_last_generation() != last_generation + 1) {
PX4_ERR("param_find: missed srv_parameter_get_response, generation %d -> %d", last_generation,
response_sub.get_last_generation());
}
if ((request.timestamp == response.timestamp_requested)
&& (strncmp(request.name, response.parameter.name, sizeof(request.name)) == 0)) {
return response.parameter.index;
}
}
}
return PARAM_INVALID;
}
param_t param_find_no_notification(const char *name)
{
return param_find(name);
}
int param_get(param_t param, void *val)
{
// request
uORB::Publication<srv_parameter_get_request_s> request_pub{ORB_ID(srv_parameter_get_request)};
uORB::SubscriptionBlocking<srv_parameter_get_response_s> response_sub{ORB_ID(srv_parameter_get_response)};
srv_parameter_get_request_s request{};
request.index = param;
request.timestamp = hrt_absolute_time();
request_pub.publish(request);
// response
while ((hrt_elapsed_time(&request.timestamp) < 50_ms) || response_sub.updated()) {
const unsigned last_generation = response_sub.get_last_generation();
srv_parameter_get_response_s response{};
if (response_sub.updateBlocking(response, 1'000)) {
if (response_sub.get_last_generation() != last_generation + 1) {
PX4_ERR("param_get: missed srv_parameter_get_response, generation %d -> %d", last_generation,
response_sub.get_last_generation());
}
if ((request.timestamp == response.timestamp_requested) && (request.index == response.parameter.index)) {
switch (response.parameter.type) {
case parameter_s::TYPE_INT32:
memcpy(val, &response.parameter.int32_value, sizeof(int32_t));
break;
case parameter_s::TYPE_FLOAT32:
memcpy(val, &response.parameter.float32_value, sizeof(float));
break;
}
if (response.result == srv_parameter_get_response_s::RESULT_GET_SUCCESS) {
return 0;
}
return -1;
}
}
}
return -1;
}
int param_set(param_t param, const void *val)
{
// request
uORB::Publication<srv_parameter_set_request_s> request_pub{ORB_ID(srv_parameter_set_request)};
uORB::SubscriptionBlocking<srv_parameter_set_response_s> response_sub{ORB_ID(srv_parameter_set_response)};
srv_parameter_set_request_s request{};
request.parameter.index = param;
memcpy(&request.parameter.int32_value, val, sizeof(int32_t));
memcpy(&request.parameter.float32_value, val, sizeof(float));
request.timestamp = hrt_absolute_time();
request_pub.publish(request);
// response
while ((hrt_elapsed_time(&request.timestamp) < 50_ms) || response_sub.updated()) {
const unsigned last_generation = response_sub.get_last_generation();
srv_parameter_set_response_s response{};
if (response_sub.updateBlocking(response, 1'000)) {
if (response_sub.get_last_generation() != last_generation + 1) {
PX4_ERR("param_set: missed srv_parameter_set_response, generation %d -> %d", last_generation,
response_sub.get_last_generation());
}
if ((request.timestamp == response.timestamp_requested) && (request.parameter.index == response.parameter.index)) {
if (response.result == srv_parameter_set_response_s::RESULT_SET_SUCCESS) {
return 0;
}
PX4_ERR("param_set %d failed", param);
return -1;
}
}
}
PX4_ERR("param_set %d failed", param);
return -1;
}
int param_set_no_notification(param_t param, const void *val)
{
return param_set(param, val);
}
#endif // PX4_PARAM_CLIENT_SRV
@@ -1,6 +1,6 @@
############################################################################
#
# Copyright (c) 2018-2022 PX4 Development Team. All rights reserved.
# Copyright (c) 2018 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
@@ -31,15 +31,7 @@
#
############################################################################
add_library(tinybson
tinybson.cpp
tinybson.h
)
add_library(tinybson tinybson.cpp)
target_compile_definitions(tinybson PRIVATE -DMODULE_NAME="tinybson")
target_compile_options(tinybson
PRIVATE
-Wno-sign-compare # TODO: fix this
${MAX_CUSTOM_OPT_LEVEL}
)
target_compile_options(tinybson PRIVATE -Wno-sign-compare) # TODO: fix this
add_dependencies(tinybson prebuild_targets)
@@ -115,11 +115,10 @@ read_double(bson_decoder_t decoder, double *d)
}
int
bson_decoder_init_file(bson_decoder_t decoder, int fd, bson_decoder_callback callback, void *priv)
bson_decoder_init_file(bson_decoder_t decoder, int fd, bson_decoder_callback callback)
{
decoder->fd = fd;
decoder->callback = callback;
decoder->priv = priv;
decoder->nesting = 1;
decoder->node.type = BSON_UNDEFINED;
@@ -135,7 +134,7 @@ bson_decoder_init_file(bson_decoder_t decoder, int fd, bson_decoder_callback cal
}
int
bson_decoder_init_buf(bson_decoder_t decoder, void *buf, unsigned bufsize, bson_decoder_callback callback, void *priv)
bson_decoder_init_buf(bson_decoder_t decoder, void *buf, unsigned bufsize, bson_decoder_callback callback)
{
/* argument sanity */
if ((buf == nullptr) || (callback == nullptr)) {
@@ -156,7 +155,6 @@ bson_decoder_init_buf(bson_decoder_t decoder, void *buf, unsigned bufsize, bson_
decoder->bufpos = 0;
decoder->callback = callback;
decoder->priv = priv;
decoder->nesting = 1;
decoder->pending = 0;
decoder->node.type = BSON_UNDEFINED;
@@ -317,7 +315,7 @@ bson_decoder_next(bson_decoder_t decoder)
}
/* call the callback and pass its results back */
return decoder->callback(decoder, decoder->priv, &decoder->node);
return decoder->callback(decoder, &decoder->node);
}
int
@@ -101,7 +101,7 @@ typedef struct bson_decoder_s *bson_decoder_t;
*
* The node callback function's return value is returned by bson_decoder_next.
*/
typedef int (* bson_decoder_callback)(bson_decoder_t decoder, void *priv, bson_node_t node);
typedef int (* bson_decoder_callback)(bson_decoder_t decoder, bson_node_t node);
struct bson_decoder_s {
/* file reader state */
@@ -114,7 +114,6 @@ struct bson_decoder_s {
bool dead{false};
bson_decoder_callback callback;
void *priv{nullptr};
unsigned nesting{0};
struct bson_node_s node {};
int32_t pending{0};
@@ -136,10 +135,9 @@ struct bson_decoder_s {
* @param decoder Decoder state structure to be initialised.
* @param fd File to read BSON data from.
* @param callback Callback to be invoked by bson_decoder_next
* @param priv Callback private data, stored in node.
* @return Zero on success.
*/
__EXPORT int bson_decoder_init_file(bson_decoder_t decoder, int fd, bson_decoder_callback callback, void *priv);
__EXPORT int bson_decoder_init_file(bson_decoder_t decoder, int fd, bson_decoder_callback callback);
/**
* Initialise the decoder to read from a buffer in memory.
@@ -150,11 +148,9 @@ __EXPORT int bson_decoder_init_file(bson_decoder_t decoder, int fd, bson_decoder
* passed as zero if the buffer size should be extracted from the
* BSON header only.
* @param callback Callback to be invoked by bson_decoder_next
* @param priv Callback private data, stored in node.
* @return Zero on success.
*/
__EXPORT int bson_decoder_init_buf(bson_decoder_t decoder, void *buf, unsigned bufsize, bson_decoder_callback callback,
void *priv);
__EXPORT int bson_decoder_init_buf(bson_decoder_t decoder, void *buf, unsigned bufsize, bson_decoder_callback callback);
/**
* Process the next node from the stream and invoke the callback.
+188
View File
@@ -0,0 +1,188 @@
/****************************************************************************
*
* Copyright (c) 2021 Technology Innovation Institute. 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 usr_parameters_if.cpp
*
* Protected build user space interface to global parameter store.
*/
#define PARAM_IMPLEMENTATION
#include "param.h"
#include "parameters_ioctl.h"
#include <parameters/px4_parameters.hpp>
#include <sys/boardctl.h>
#include <px4_platform_common/defines.h>
#include <px4_platform_common/log.h>
#include "parameters_common.cpp"
param_t param_find(const char *name)
{
paramiocfind_t data = {name, true, PARAM_INVALID};
boardctl(PARAMIOCFIND, reinterpret_cast<unsigned long>(&data));
return data.ret;
}
param_t param_find_no_notification(const char *name)
{
paramiocfind_t data = {name, false, PARAM_INVALID};
boardctl(PARAMIOCFIND, reinterpret_cast<unsigned long>(&data));
return data.ret;
}
unsigned param_count_used()
{
paramioccountused_t data = {0};
boardctl(PARAMIOCCOUNTUSED, reinterpret_cast<unsigned long>(&data));
return data.ret;
}
param_t param_for_used_index(unsigned index)
{
paramiocforusedindex_t data = {index, 0};
boardctl(PARAMIOCFORUSEDINDEX, reinterpret_cast<unsigned long>(&data));
return data.ret;
}
int param_get_used_index(param_t param)
{
paramiocgetusedindex_t data = {param, 0};
boardctl(PARAMIOCGETUSEDINDEX, reinterpret_cast<unsigned long>(&data));
return data.ret;
}
bool
param_value_unsaved(param_t param)
{
paramiocunsaved_t data = {param, false};
boardctl(PARAMIOCUNSAVED, reinterpret_cast<unsigned long>(&data));
return data.ret;
}
int
param_get(param_t param, void *val)
{
paramiocget_t data = {param, false, val, PX4_ERROR};
boardctl(PARAMIOCGET, reinterpret_cast<unsigned long>(&data));
return data.ret;
}
int
param_get_default_value(param_t param, void *default_val)
{
paramiocget_t data = {param, true, default_val, PX4_ERROR};
boardctl(PARAMIOCGET, reinterpret_cast<unsigned long>(&data));
return data.ret;
}
void
param_control_autosave(bool enable)
{
paramiocautosave_t data = {enable};
boardctl(PARAMIOCAUTOSAVE, reinterpret_cast<unsigned long>(&data));
}
int param_set(param_t param, const void *val)
{
paramiocset_t data = {param, true, val, PX4_ERROR};
boardctl(PARAMIOCSET, reinterpret_cast<unsigned long>(&data));
return data.ret;
}
bool param_used(param_t param)
{
paramiocused_t data = {param, false};
boardctl(PARAMIOCUSED, reinterpret_cast<unsigned long>(&data));
return data.ret;
}
int param_set_default_value(param_t param, const void *val)
{
paramiocsetdefault_t data = {param, val, PX4_ERROR};
boardctl(PARAMIOCSETDEFAULT, reinterpret_cast<unsigned long>(&data));
return data.ret;
}
void
param_reset_all()
{
paramiocresetgroup_t data = {PARAM_RESET_ALL, nullptr, 0};
boardctl(PARAMIOCRESETGROUP, reinterpret_cast<unsigned long>(&data));
}
void
param_reset_excludes(const char *excludes[], int num_excludes)
{
paramiocresetgroup_t data = {PARAM_RESET_EXCLUDES, excludes, num_excludes};
boardctl(PARAMIOCRESETGROUP, reinterpret_cast<unsigned long>(&data));
}
void
param_reset_specific(const char *resets[], int num_resets)
{
paramiocresetgroup_t data = {PARAM_RESET_SPECIFIC, resets, num_resets};
boardctl(PARAMIOCRESETGROUP, reinterpret_cast<unsigned long>(&data));
}
int param_save_default()
{
paramiocsavedefault_t data = {PX4_ERROR};
boardctl(PARAMIOCSAVEDEFAULT, reinterpret_cast<unsigned long>(&data));
return data.ret;
}
int
param_load_default()
{
paramiocloaddefault_t data = {PX4_ERROR};
boardctl(PARAMIOCLOADDEFAULT, reinterpret_cast<unsigned long>(&data));
return data.ret;
}
int
param_export(const char *filename, param_filter_func filter)
{
paramiocexport_t data = {filename, PX4_ERROR};
if (filter) { PX4_ERR("ERROR: filter not supported in userside blob"); }
boardctl(PARAMIOCEXPORT, reinterpret_cast<unsigned long>(&data));
return data.ret;
}
uint32_t param_hash_check()
{
paramiochash_t data = {0};
boardctl(PARAMIOCHASH, reinterpret_cast<unsigned long>(&data));
return data.ret;
}
+1 -1
View File
@@ -195,7 +195,7 @@ bool SetCalibrationParamsVector3f(const char *sensor_type, const char *cal_type,
// eg CAL_MAGn_{X,Y,Z}OFF
sprintf(str, "CAL_%s%" PRIu8 "_%c%s", sensor_type, instance, axis_char, cal_type);
if (param_set_no_notification(param_find(str), &values(axis)) != 0) {
if (param_set(param_find(str), &values(axis)) != 0) {
PX4_ERR("failed to set %s = %.4f", str, (double)values(axis));
ret = PX4_ERROR;
}
+1 -1
View File
@@ -90,7 +90,7 @@ bool SetCalibrationParam(const char *sensor_type, const char *cal_type, uint8_t
// eg CAL_MAGn_ID/CAL_MAGn_ROT
sprintf(str, "CAL_%s%u_%s", sensor_type, instance, cal_type);
int ret = param_set_no_notification(param_find(str), &value);
int ret = param_set(param_find(str), &value);
if (ret != PX4_OK) {
PX4_ERR("failed to set %s", str);
@@ -409,17 +409,14 @@ AirspeedModule::Run()
switch (i) {
case 0:
_param_airspeed_scale_1.set(_airspeed_validator[i].get_CAS_scale_validated());
_param_airspeed_scale_1.commit_no_notification();
break;
case 1:
_param_airspeed_scale_2.set(_airspeed_validator[i].get_CAS_scale_validated());
_param_airspeed_scale_2.commit_no_notification();
break;
case 2:
_param_airspeed_scale_3.set(_airspeed_validator[i].get_CAS_scale_validated());
_param_airspeed_scale_3.commit_no_notification();
break;
}
}
-1
View File
@@ -1752,7 +1752,6 @@ void Commander::run()
if (_was_armed && !_arm_state_machine.isArmed()) {
const int32_t flight_uuid = _param_flight_uuid.get() + 1;
_param_flight_uuid.set(flight_uuid);
_param_flight_uuid.commit_no_notification();
_last_disarmed_timestamp = hrt_absolute_time();
@@ -363,7 +363,6 @@ int do_accel_calibration(orb_advert_t *mavlink_log_pub)
const Dcmf board_rotation = calibration::GetBoardRotationMatrix();
const Dcmf board_rotation_t = board_rotation.transpose();
bool param_save = false;
bool failed = true;
for (unsigned i = 0; i < MAX_ACCEL_SENS; i++) {
@@ -419,7 +418,6 @@ int do_accel_calibration(orb_advert_t *mavlink_log_pub)
if (calibrations[i].ParametersSave(i, true)) {
param_save = true;
failed = false;
} else {
@@ -434,10 +432,6 @@ int do_accel_calibration(orb_advert_t *mavlink_log_pub)
failed = true;
}
if (param_save) {
param_notify_changes();
}
if (!failed) {
calibration_log_info(mavlink_log_pub, CAL_QGC_DONE_MSG, sensor_name);
px4_usleep(600000); // give this message enough time to propagate
@@ -455,7 +449,6 @@ int do_accel_calibration_quick(orb_advert_t *mavlink_log_pub)
#if !defined(CONSTRAINED_FLASH)
PX4_INFO("Accelerometer quick calibration");
bool param_save = false;
bool failed = true;
FactoryCalibrationStorage factory_storage;
@@ -566,7 +559,6 @@ int do_accel_calibration_quick(orb_advert_t *mavlink_log_pub)
if (calibration.ParametersSave(accel_index)) {
calibration.PrintStatus();
param_save = true;
failed = false;
} else {
@@ -582,10 +574,6 @@ int do_accel_calibration_quick(orb_advert_t *mavlink_log_pub)
failed = true;
}
if (param_save) {
param_notify_changes();
}
if (!failed) {
return PX4_OK;
}
@@ -164,8 +164,6 @@ int do_baro_calibration(orb_advert_t *mavlink_log_pub)
return PX4_ERROR;
}
bool param_save = false;
for (int instance = 0; instance < MAX_SENSOR_COUNT; instance++) {
if ((calibration[instance].device_id() != 0) && (data_sum_count[instance] > 0)) {
@@ -210,16 +208,11 @@ int do_baro_calibration(orb_advert_t *mavlink_log_pub)
if (calibration[instance].ParametersSave(instance, true)) {
calibration[instance].PrintStatus();
param_save = true;
}
}
}
}
if (param_save) {
param_notify_changes();
}
calibration_log_info(mavlink_log_pub, CAL_QGC_DONE_MSG, sensor_name);
return PX4_OK;
}
@@ -100,6 +100,7 @@ std::vector<std::string> get_used_params()
return ret;
}
param_value_u get_param_value(const std::string &name)
{
std::map<param_t, Param> &used_params = failsafe_instance.params();
@@ -248,7 +248,6 @@ int do_gyro_calibration(orb_advert_t *mavlink_log_pub)
if (res == PX4_OK) {
// set offset parameters to new values
bool param_save = false;
bool failed = true;
for (unsigned uorb_index = 0; uorb_index < MAX_GYROS; uorb_index++) {
@@ -260,7 +259,6 @@ int do_gyro_calibration(orb_advert_t *mavlink_log_pub)
calibration.PrintStatus();
if (calibration.ParametersSave(uorb_index, true)) {
param_save = true;
failed = false;
} else {
@@ -275,10 +273,6 @@ int do_gyro_calibration(orb_advert_t *mavlink_log_pub)
failed = true;
}
if (param_save) {
param_notify_changes();
}
if (!failed) {
calibration_log_info(mavlink_log_pub, CAL_QGC_DONE_MSG, sensor_name);
px4_usleep(600000); // give this message enough time to propagate

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