Compare commits

..

31 Commits

Author SHA1 Message Date
Niklas Hauser c7aae96cd2 [WIP] Run the ROMFS through a CPP with the boardconfig 2026-01-22 15:38:49 +01:00
Silvan 52308735a7 px4/v6x: remove AUAV differential pressure to save flash
Signed-off-by: Silvan <silvan@auterion.com>
2026-01-22 15:14:54 +01:00
alexcekay b1c2820d69 gps: update drivers submodule 2026-01-22 15:02:30 +01:00
alexcekay 1df5e62cc3 gps: fix rate reading on UART 2026-01-22 15:02:30 +01:00
bresch 2ad25570ee do not check pointer validity before deleting
Deleting a nullptr has no effect
(this addresses a clang-tidy error)
2026-01-22 10:03:24 +01:00
tompsontan b8577c753f board:changed ap-h743r1 dma allocation and internal mag to qmc5883p. (#26112)
*Mag Sensor changed in the docs and the board
*DMA Allocation changed for the board
2026-01-22 01:06:51 -05:00
Baardrw c9e3118fea Driver: fix mb12xx driver set address feature (#26282)
* fixed set_address function
2026-01-22 00:45:45 -05:00
William Reynaldi Solichin 55e0810d8d Expose u-blox min elevation, min SNR and DGNSS timeout parameters RTK Fix Improvements (#25720)
* Exposing u-Blox min CNO, min elevation, and DGNSS timeout for RTK Fix Improvement

* update gps submodule

---------

Co-authored-by: Julian Oes <julian@oes.ch>
Co-authored-by: Jacob Dahl <37091262+dakejahl@users.noreply.github.com>
Co-authored-by: Jacob Dahl <dahl.jakejacob@gmail.com>
2026-01-21 14:50:36 -09:00
Alexander Lerach 4ac7853479 auterion autostarter: Added autostart for PWM_EXPANDER, generalized c… (#25925)
* auterion autostarter: Added autostart for PWM_EXPANDER, generalized code, renamed module

* auterion autostarter: Enable on v6s, robustify error handling

* review comments
2026-01-21 19:05:09 +01:00
Jacob Dahl 06db25c078 boards: remove CONFIG_COMMON_OPTICAL_FLOW from all non-CANnode hardware (#26315) 2026-01-21 10:51:09 -05:00
Eurus 5635d639fe rtl_mission_fast: supplement to #24115 (#26199)
Co-authored-by: EurusAkai <1826983968@qq.com>
2026-01-21 09:49:31 +01:00
Jacob Dahl bbce142129 boards: ark_pi6x: add rover target (#26296) 2026-01-20 13:35:42 -09:00
Julian Oes 475715818b Tools: fix make format (#26298)
These two submodules were touched when they shouldn't be.
2026-01-19 17:23:06 -09:00
Julian Oes 02103b9100 mavlink: fix deadlock on USB disconnect/reconnect (#26297)
Commit 5fe82aa added mutex protection in ~Mavlink() to fix a race
condition when start_helper() deleted an instance without holding the
mutex. However, this caused a deadlock because stop_command() and
destroy_all_instances() already hold mavlink_module_mutex when calling
delete, and the mutex is non-recursive.

Fix by moving instance cleanup to the callers:
- All callers now hold the mutex and remove the instance from
  mavlink_module_instances BEFORE calling delete
- The destructor no longer touches mavlink_module_instances
- Event handoff remains in destructor (works because `this` is already
  removed from the list when destructor runs)

This hopefully fixes the original race condition while avoiding the
deadlock that caused USB mavlink to hang on reconnect.
2026-01-19 12:25:50 -09:00
mahima-yoga 25de111a4a FWModeManager: improve fixed-wing landing flare stability
- Ramp pitch_min and pitch_max from current pitch to flare minimum
- Ramp throttle from current setpoint to idle
2026-01-19 17:58:20 +01:00
mahima-yoga 9169f9cd44 Revert "FWModeManger: remove throttle spike during flaring by waiting with height rate change"
This reverts commit 259e7d1d53.
2026-01-19 17:58:20 +01:00
Alexander Lerach 273766a4ea drivers: auav, read sensor eeprom to get cal range (#26294)
* drivers: auav, read sensor eeprom to get cal range

* added review feedback
2026-01-19 15:21:18 +01:00
Ryan Johnston f98fdbc452 FW Takeoff: fix loiter altitude not set in some cases
* Fix Takeoff mode to respect MIS_TAKEOFF_ALT

Takeoff mode never transitions to hold after takeoff alt.

* style: run make format
2026-01-16 17:32:15 +01:00
jonas edc2536bdd move EKF2 ring buffer to the lib folder 2026-01-16 11:51:37 +01:00
Silvan e90f8b500f v5: remove UUV to save flash
Signed-off-by: Silvan <silvan@auterion.com>
2026-01-16 11:33:45 +01:00
Pernilla fbdc31b60c gimbal: add filter 2026-01-16 11:33:45 +01:00
Pernilla 392002f671 gimbal-bug-fix: store angle setpoints for next iteration 2026-01-16 11:33:45 +01:00
Pernilla c0c7f6ec40 gimbal: report relative and absolute angles 2026-01-16 11:33:45 +01:00
Pernilla 8c5c4a0504 gimbal: update gz gimbal 2026-01-16 11:33:45 +01:00
Pernilla 0da6efa52d gimbal: remove offset as it should be accounted for in PWM driver 2026-01-16 11:33:45 +01:00
Pernilla 9de10d672c gimbal: mavlink streamed angular ranges should be radians 2026-01-16 11:33:45 +01:00
Pernilla 0fa5a83409 gimbal: account for non zero symmetrical angular ranges 2026-01-16 11:33:45 +01:00
Pernilla aed175451a gimbal: add pitch stabilization 2026-01-16 11:33:45 +01:00
Kimminkyu df42ef84f1 Update NuttX fmu-v6x config use with Zenoh (#26213) 2026-01-15 11:40:09 -09:00
Baardrw fe30ef7f16 GZ: Update GZMixingInterfaceESC to support more than 8 ESCs (#25081)
* Changed GZMixingInterfaceESC to GZMixingInterfaceMotor
- GZMixingInterfaceMotor checks if there are more than 8 motors configured if its less than 8 it behaves exactly the same as GZMixingInterfaceESC, else it behaves as a PWM motor interface
- This change allows drones with more than 8 motors to be simulated by Gazebo

Fixes #25080

* code quality fix

* Changed GZMixingInterfacMotor back to GZMixingInterfaceESC and changed variable names to match ESC terminology

* formatting issue resolved

* updated interface to support 16 ESCs, allowing the first 8 to report telemetry

* rebased
2026-01-15 10:37:35 -09:00
Beniamino Pozzan 0b834dd0e7 docs(uxrce_dds): add docs for UXRCE_DDS_FLCTRL (#26242)
Signed-off-by: Beniamino Pozzan <beniamino.pozzan@gmail.com>
2026-01-15 00:51:35 -09:00
138 changed files with 1265 additions and 484 deletions
+9 -2
View File
@@ -146,6 +146,11 @@ add_custom_command(
${romfs_copy_stamp}
COMMAND ${CMAKE_COMMAND} -E remove_directory ${romfs_gen_root_dir}/*
COMMAND ${CMAKE_COMMAND} -E tar xf ${romfs_tar_file}
# Preprocess ROMFS files with KConfig definitions
COMMAND ${PYTHON_EXECUTABLE} ${PX4_SOURCE_DIR}/Tools/px_romfs_preprocess.py
--romfs-dir ${romfs_gen_root_dir}
--kconfig-header ${PX4_BINARY_DIR}/px4_boardconfig.h
--cpp ${CMAKE_C_COMPILER}
COMMAND ${PYTHON_EXECUTABLE} ${PX4_SOURCE_DIR}/Tools/px_process_airframes.py
--airframes-path ${romfs_gen_root_dir}/init.d
--start-script ${romfs_gen_root_dir}/init.d/rc.autostart
@@ -159,8 +164,10 @@ add_custom_command(
--params-file ${CONFIG_BOARD_PARAM_FILE}
COMMAND ${CMAKE_COMMAND} -E touch ${romfs_copy_stamp}
WORKING_DIRECTORY ${romfs_gen_root_dir}
DEPENDS ${romfs_tar_file}
COMMENT "ROMFS: copying, generating airframes"
DEPENDS
${romfs_tar_file}
${PX4_BINARY_DIR}/px4_boardconfig.h
COMMENT "ROMFS: copying, preprocessing, generating airframes"
)
# copy extras into ROMFS
@@ -1,35 +0,0 @@
#!/bin/sh
#
# @name Boat
#
. ${R}etc/init.d/rc.uuv_defaults
PX4_SIMULATOR=${PX4_SIMULATOR:=gz}
PX4_GZ_WORLD=${PX4_GZ_WORLD:=ocean}
PX4_SIM_MODEL=${PX4_SIM_MODEL:=boat}
param set-default SIM_GZ_EN 1
param set-default CA_AIRFRAME 9
param set-default CA_ROTOR_COUNT 2
param set-default CA_ROTOR0_AX 1
param set-default CA_ROTOR0_AZ 0
param set-default CA_ROTOR0_KM 0
param set-default CA_ROTOR0_PX -2
param set-default CA_ROTOR0_PY -1
param set-default CA_ROTOR1_AX 1
param set-default CA_ROTOR1_AZ 0
param set-default CA_ROTOR1_KM 0
param set-default CA_ROTOR1_PX -2
param set-default CA_ROTOR1_PY 1
param set-default CA_R_REV 3
param set-default CA_SV_CS_COUNT 1
param set-default CA_SV_CS0_TYPE 4
param set-default CA_SV_CS0_TRQ_Y 1
param set-default SIM_GZ_EC_FUNC1 101
param set-default SIM_GZ_EC_FUNC2 102
param set-default SIM_GZ_SV_FUNC1 201
@@ -19,5 +19,6 @@ param set-default MNT_MAN_PITCH 2
param set-default MNT_MAN_YAW 3
param set-default MNT_RANGE_ROLL 180
param set-default MNT_RANGE_PITCH 180
param set-default MNT_MAX_PITCH 45
param set-default MNT_MIN_PITCH -135
param set-default MNT_RANGE_YAW 720
@@ -111,8 +111,6 @@ px4_add_romfs_files(
17001_flightgear_tf-g1
17002_flightgear_tf-g2
40000_gz_boat
50000_gz_rover_differential
51000_gz_rover_ackermann
52000_gz_rover_mecanum
+100 -1
View File
@@ -8,17 +8,24 @@
# Begin Optional drivers #
###############################################################################
%ifdef CONFIG_DRIVERS_BATT_SMBUS
if param compare -s SENS_EN_BATT 1
then
batt_smbus start -X
fi
%endif
%ifdef CONFIG_DRIVERS_SMART_BATTERY_BATMON
# Start batmon driver if enabled using BATMON_DRIVER_EN
if param compare -s BATMON_DRIVER_EN 1
then
batmon start -X #start on external bus
fi
%endif
%ifdef CONFIG_DRIVERS_PWM_INPUT
%ifdef CONFIG_DRIVERS_DISTANCE_SENSOR_LL40LS
# Sensors on the PWM interface bank
if param compare -s SENS_EN_LL40LS 1
then
@@ -27,92 +34,121 @@ then
ll40ls_pwm start
fi
fi
%endif
# External automatic trigger system
if param compare FD_EXT_ATS_EN 1
then
pwm_input start
fi
%endif
%ifdef CONFIG_DRIVERS_DISTANCE_SENSOR_LL40LS
# Lidar-Lite on I2C
if param compare -s SENS_EN_LL40LS 2
then
ll40ls start -X
fi
%endif
%ifdef CONFIG_DRIVERS_DISTANCE_SENSOR_MAPPYDOT
# mappydot lidar sensor
if param compare -s SENS_EN_MPDT 1
then
mappydot start -X
fi
%endif
%ifdef CONFIG_DRIVERS_DISTANCE_SENSOR_MB12XX
# mb12xx sonar sensor
if param greater -s SENS_EN_MB12XX 0
then
mb12xx start -X
fi
%endif
%ifdef CONFIG_DRIVERS_DISTANCE_SENSOR_PGA460
# pga460 sonar sensor
if param greater -s SENS_EN_PGA460 0
then
pga460 start
fi
%endif
%ifdef CONFIG_DRIVERS_DISTANCE_SENSOR_LIGHTWARE_LASER_I2C
# Lightware i2c lidar sensor
if param greater -s SENS_EN_SF1XX 0
then
lightware_laser_i2c start -X
fi
%endif
%ifdef CONFIG_DRIVERS_DISTANCE_SENSOR_SRF05
# Sensor HY-SRF05 or HC-SR05 ultrasonic sensor
if param compare -s SENS_EN_SR05 1
then
srf05 start
fi
%endif
%ifdef CONFIG_DRIVERS_DISTANCE_SENSOR_TERARANGER
# Teraranger one tof sensor
if param greater -s SENS_EN_TRANGER 0
then
teraranger start -X
fi
%endif
%ifdef CONFIG_DRIVERS_OPTICAL_FLOW_PAA3905
# paa3905 optical flow sensor (external SPI)
if param greater -s SENS_EN_PAA3905 0
then
paa3905 -S start
fi
%endif
%ifdef CONFIG_DRIVERS_OPTICAL_FLOW_PAW3902
# paw3902 optical flow sensor (external SPI)
if param greater -s SENS_EN_PAW3902 0
then
paw3902 -S start
fi
%endif
%ifdef CONFIG_DRIVERS_OPTICAL_FLOW_PMW3901
# pmw3901 optical flow sensor (external SPI)
if param greater -s SENS_EN_PMW3901 0
then
pmw3901 -S start
fi
%endif
%ifdef CONFIG_DRIVERS_DISTANCE_SENSOR_VL53L0X
# vl53l0x i2c distance sensor
if param compare -s SENS_EN_VL53L0X 1
then
vl53l0x start -X
fi
%endif
%ifdef CONFIG_DRIVERS_DISTANCE_SENSOR_VL53L1X
# vl53l1x i2c distance sensor
if param compare -s SENS_EN_VL53L1X 1
then
vl53l1x start -X
fi
%endif
%ifdef CONFIG_DRIVERS_DISTANCE_SENSOR_TF02PRO
# tf02 pro i2c distance sensor
if param compare -s SENS_EN_TF02PRO 1
then
tf02pro start -X
fi
%endif
%ifdef CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16448
# ADIS16448 spi external IMU
if param compare -s SENS_EN_ADIS164X 1
then
@@ -125,25 +161,33 @@ then
adis16448 -S start -R 4
fi
fi
%endif
%ifdef CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16507
# ADIS16507 spi external IMU
if param greater -s SENS_EN_ADIS165X 0
then
adis16507 -S start
fi
%endif
%ifdef CONFIG_DRIVERS_IMU_MURATA_SCH16T
# SCH16T spi external IMU
if param compare -s SENS_EN_SCH16T 1
then
sch16t -S start
fi
%endif
%ifdef CONFIG_DRIVERS_DIFFERENTIAL_PRESSURE_ETS
# Eagle Tree airspeed sensor external I2C
if param compare -s SENS_EN_ETSASPD 1
then
ets_airspeed start -X
fi
%endif
%ifdef CONFIG_DRIVERS_DIFFERENTIAL_PRESSURE_SDP3X
# Sensirion SDP3X differential pressure sensor external I2C
if param compare -s SENS_EN_SDP3X 1
then
@@ -153,116 +197,171 @@ then
sdp3x start -X -a 0x22
fi
fi
%endif
%ifdef CONFIG_DRIVERS_TEMPERATURE_SENSOR_MCP9808
# Microchip MCP9808 temperature sensor external I2C
if param compare -s SENS_EN_MCP9808 1
then
mcp9808 start -X
fi
%endif
%ifdef CONFIG_DRIVERS_DIFFERENTIAL_PRESSURE_MS4515
# TE MS4515 differential pressure sensor external I2C
if param compare -s SENS_EN_MS4515 1
then
ms4515 start -X
fi
%endif
%ifdef CONFIG_DRIVERS_DIFFERENTIAL_PRESSURE_MS4525DO
# TE MS4525DO differential pressure sensor external I2C
if param compare -s SENS_EN_MS4525DO 1
then
ms4525do start -X
fi
%endif
%ifdef CONFIG_DRIVERS_DIFFERENTIAL_PRESSURE_MS5525DSO
# TE MS5525DSO differential pressure sensor external I2C
if param compare -s SENS_EN_MS5525DS 1
then
ms5525dso start -X
fi
%endif
%ifdef CONFIG_DRIVERS_DIFFERENTIAL_PRESSURE_ASP5033
# TE ASP5033 differential pressure sensor external I2C
if param compare -s SENS_EN_ASP5033 1
then
asp5033 start -X
fi
%endif
%ifdef CONFIG_DRIVERS_DIFFERENTIAL_PRESSURE_AUAV
# AUAV absolute/differential pressure sensor external I2C
if param greater -s SENS_EN_AUAVX 0
then
auav start -D -X
auav start -A -X
fi
%endif
%ifdef CONFIG_DRIVERS_HYGROMETER_SHT3X
# SHT3x temperature and hygrometer sensor, external I2C
if param compare -s SENS_EN_SHT3X 1
then
sht3x start -X
sht3x start -X -a 0x45
fi
%endif
%ifdef CONFIG_DRIVERS_IRLOCK
# IR-LOCK sensor external I2C
if param compare -s SENS_EN_IRLOCK 1
then
irlock start -X
fi
%endif
%ifdef CONFIG_DRIVERS_BAROMETER_GOERTEK_SPL06
# SPL06 sensor external I2C
if param compare -s SENS_EN_SPL06 1
then
spl06 -X start
spl06 -X -a 0x77 start
fi
%endif
%ifdef CONFIG_DRIVERS_BAROMETER_GOERTEK_SPA06
# SPA06 sensor external I2C
if param compare -s SENS_EN_SPA06 1
then
spa06 -X start
spa06 -X -a 0x77 start
fi
%endif
%ifdef CONFIG_DRIVERS_RPM_PCF8583
# PCF8583 counter (RPM sensor)
if param compare -s SENS_EN_PCF8583 1
then
pcf8583 start -X
pcf8583 start -X -a 0x51
fi
%endif
%ifdef CONFIG_DRIVERS_ADC_ADS7953
# ADC sensor ADS7953 external SPI
if param compare -s ADC_ADS7953_EN 1
then
ads7953 start -S
fi
%endif
%ifdef CONFIG_DRIVERS_ADC_TLA2528
# ADC sensor tla2528 external I2C
if param compare -s ADC_TLA2528_EN 1
then
tla2528 start -X
fi
%endif
%ifdef CONFIG_DRIVERS_TEMPERATURE_SENSOR_TMP102
# Start TMP102 temperature sensor
if param compare SENS_EN_TMP102 1
if param compare -s SENS_EN_TMP102 1
then
tmp102 start -X
fi
%endif
%ifdef COMMON_MAGNETOMETER
# probe for optional external I2C devices
if param compare SENS_EXT_I2C_PRB 1
then
%ifdef CONFIG_DRIVERS_IMU_INVENSENSE_ICM20948
icm20948_i2c_passthrough -X -q start
%endif
# compasses
%ifdef CONFIG_DRIVERS_MAGNETOMETER_HMC5883
hmc5883 -T -X -q start
%endif
%ifdef CONFIG_DRIVERS_MAGNETOMETER_ST_IIS2MDC
iis2mdc -X -q start
%endif
%ifdef CONFIG_DRIVERS_MAGNETOMETER_ISENTEK_IST8308
ist8308 -X -q start
%endif
%ifdef CONFIG_DRIVERS_MAGNETOMETER_ISENTEK_IST8310
ist8310 -X -q start
%endif
%ifdef CONFIG_DRIVERS_MAGNETOMETER_LIS3MDL
if ! lis3mdl -X -q start
then
lis3mdl -X -q -a 0x1c start
fi
%endif
%ifdef CONFIG_DRIVERS_MAGNETOMETER_QMC5883L
qmc5883l -X -q start
%endif
%ifdef CONFIG_DRIVERS_MAGNETOMETER_QMC5883P
qmc5883p -X -q start
%endif
%ifdef CONFIG_DRIVERS_MAGNETOMETER_RM3100
rm3100 -X -q start
%endif
%ifdef CONFIG_DRIVERS_MAGNETOMETER_BOSCH_BMM350
bmm350 -X -q start
%endif
%ifdef CONFIG_DRIVERS_MAGNETOMETER_ST_IIS2MDC
iis2mdc -X -q start
%endif
# start last (wait for possible icm20948 passthrough mode)
%ifdef CONFIG_DRIVERS_MAGNETOMETER_AKM_AK09916
ak09916 -X -q start
%endif
fi
%endif
+104 -13
View File
@@ -265,12 +265,15 @@ else
# Start the tone_alarm driver.
# Needs to be started after the parameters are loaded (for CBRK_BUZZER).
#
%ifdef CONFIG_DRIVERS_TONE_ALARM
tone_alarm start
%endif
#
# Waypoint storage.
# REBOOTWORK this needs to start in parallel.
#
%ifdef CONFIG_MODULES_DATAMAN
if param compare -s SYS_DM_BACKEND 1
then
dataman start -r
@@ -281,11 +284,14 @@ else
dataman start
fi
fi
%endif
#
# Start the socket communication send_event handler.
#
%ifdef CONFIG_MODULES_SEND_EVENT
send_event start
%endif
#
# Start the hardfault streamer.
@@ -298,15 +304,25 @@ else
#
# Start the resource load monitor.
#
%ifdef CONFIG_MODULES_LOAD_MON
load_mon start
%endif
#
# Start system state indicator.
#
%ifdef CONFIG_DRIVERS_LIGHTS_RGBLED
rgbled start -X -q
%endif
%ifdef CONFIG_DRIVERS_LIGHTS_RGBLED_NCP5623C
rgbled_ncp5623c start -X -q
%endif
%ifdef CONFIG_DRIVERS_LIGHTS_RGBLED_LP5562
rgbled_lp5562 start -X -q
%endif
%ifdef CONFIG_DRIVERS_LIGHTS_RGBLED_IS31FL3195
rgbled_is31fl3195 start -X -q
%endif
#
# Override parameters from user configuration file.
@@ -331,11 +347,21 @@ else
# start the simulator in hardware if needed
if param compare SYS_HITL 2
then
%ifdef CONFIG_MODULES_SIMULATION_SIMULATOR_SIH
simulator_sih start
%endif
%ifdef CONFIG_MODULES_SIMULATION_SENSOR_BARO_SIM
sensor_baro_sim start
%endif
%ifdef CONFIG_MODULES_SIMULATION_SENSOR_MAG_SIM
sensor_mag_sim start
%endif
%ifdef CONFIG_MODULES_SIMULATION_SENSOR_GPS_SIM
sensor_gps_sim start
%endif
%ifdef CONFIG_MODULES_SIMULATION_SENSOR_AGP_SIM
sensor_agp_sim start
%endif
fi
else
@@ -352,43 +378,58 @@ else
. ${R}etc/init.d/rc.sensors
%ifdef CONFIG_MODULES_SENSORS
%ifdef CONFIG_MODULES_ESC_BATTERY
if param compare -s BAT1_SOURCE 2
then
esc_battery start
fi
%endif
%ifdef CONFIG_MODULES_BATTERY_STATUS
if ! param compare BAT1_SOURCE 1
then
battery_status start
fi
%endif
%endif
%ifdef CONFIG_MODULES_SENSORS
sensors start
%endif
fi
#
# state estimator selection
#
%ifdef CONFIG_MODULES_EKF2
if param compare -s EKF2_EN 1
then
ekf2 start &
fi
%endif
%ifdef CONFIG_MODULES_LOCAL_POSITION_ESTIMATOR
if param compare -s LPE_EN 1
then
local_position_estimator start
fi
%endif
%ifdef CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q
if param compare -s ATT_EN 1
then
attitude_estimator_q start
fi
%endif
%ifdef CONFIG_DRIVERS_PX4IO
#
# px4io
#
if px4io supported
then
# Check if PX4IO present and update firmware if needed.
# Check if PX4IO present and update firmware if needed.
if [ -f $IOFW ]
then
if ! px4io checkcrc ${IOFW}
@@ -418,40 +459,56 @@ else
fi
fi
fi
%endif
# Heater driver for temperature regulated IMUs.
# The heater needs to start after px4io.
%ifdef CONFIG_DRIVERS_HEATER
if param compare -s SENS_EN_THERMAL 1
then
heater start
fi
%endif
#
# RC update (map raw RC input to calibrate manual control)
# start before commander
#
%ifdef CONFIG_MODULES_RC_UPDATE
rc_update start
%endif
%ifdef CONFIG_MODULES_MANUAL_CONTROL
manual_control start
%endif
# Start camera trigger, capture and PPS before pwm_out as they might access
# pwm pins
%ifdef CONFIG_DRIVERS_CAMERA_TRIGGER
if param greater -s TRIG_MODE 0
then
camera_trigger start
%ifdef CONFIG_MODULES_CAMERA_FEEDBACK
camera_feedback start
%endif
fi
%endif
# PPS capture driver
%ifdef CONFIG_DRIVERS_PPS_CAPTURE
if param greater -s PPS_CAP_ENABLE 0
then
pps_capture start
fi
%endif
# RPM capture driver
%ifdef CONFIG_DRIVERS_RPM_CAPTURE
if param greater -s RPM_CAP_ENABLE 0
then
rpm_capture start
fi
%endif
# Camera capture driver
%ifdef CONFIG_DRIVERS_CAMERA_CAPTURE
if param greater -s CAM_CAP_FBACK 0
then
if camera_capture start
@@ -459,25 +516,34 @@ else
camera_capture on
fi
fi
%endif
#
# Commander
#
%ifdef CONFIG_MODULES_COMMANDER
if param greater SYS_HITL 0
then
commander start -h
%ifdef CONFIG_MODULES_SIMULATION_PWM_OUT_SIM
if ! pwm_out_sim start -m hil
then
tune_control play error
fi
%endif
else
commander start
%ifdef CONFIG_DRIVERS_DSHOT
dshot start
%endif
%ifdef CONFIG_DRIVERS_PWM_OUT
pwm_out start
%endif
fi
%endif
#
# Configure vehicle type specific parameters.
@@ -485,10 +551,12 @@ else
. ${R}etc/init.d/rc.vehicle_setup
# Pre-takeoff continuous magnetometer calibration
%ifdef CONFIG_MODULES_MAG_BIAS_ESTIMATOR
if param compare -s MBE_ENABLE 1
then
mag_bias_estimator start
fi
%endif
#
# Optional board mavlink streams: rc.board_mavlink
@@ -533,54 +601,67 @@ else
#
# Start the navigator.
#
%ifdef CONFIG_MODULES_NAVIGATOR
navigator start
%endif
%ifdef CONFIG_MODULES_TEMPERATURE_COMPENSATION
#
# Start a thermal calibration if required.
#
set RC_THERMAL_CAL ${R}etc/init.d/rc.thermal_cal
if [ -f ${RC_THERMAL_CAL} ]
then
. ${RC_THERMAL_CAL}
fi
unset RC_THERMAL_CAL
. ${R}etc/init.d/rc.thermal_cal
%endif
#
# Start gimbal to control mounts such as gimbals, disabled by default.
#
%ifdef CONFIG_MODULES_GIMBAL
if param greater -s MNT_MODE_IN -1
then
gimbal start
fi
%endif
# Blacksheep telemetry
%ifdef CONFIG_DRIVERS_TELEMETRY_BST
if param compare -s TEL_BST_EN 1
then
bst start -X
fi
%endif
%ifdef CONFIG_MODULES_GYRO_FFT
if param compare -s IMU_GYRO_FFT_EN 1
then
gyro_fft start
fi
%endif
%ifdef CONFIG_MODULES_GYRO_CALIBRATION
if param compare -s IMU_GYRO_CAL_EN 1
then
gyro_calibration start
fi
%endif
# Check for px4flow sensor
%ifdef CONFIG_DRIVERS_OPTICAL_FLOW_PX4FLOW
if param compare -s SENS_EN_PX4FLOW 1
then
px4flow start -X &
fi
%endif
%ifdef CONFIG_MODULES_PAYLOAD_DELIVERER
payload_deliverer start
%endif
%ifdef CONFIG_MODULES_INTERNAL_COMBUSTION_ENGINE_CONTROL
if param compare -s ICE_EN 1
then
internal_combustion_engine_control start
fi
%endif
#
# Optional board supplied extras: rc.board_extras
@@ -602,15 +683,12 @@ else
. $FEXTRAS
fi
%ifdef CONFIG_MODULES_LOGGER
#
# Start the logger.
#
set RC_LOGGING ${R}etc/init.d/rc.logging
if [ -f ${RC_LOGGING} ]
then
. ${RC_LOGGING}
fi
unset RC_LOGGING
. ${R}etc/init.d/rc.logging
%endif
#
# Set additional parameters and env variables for selected AUTOSTART.
@@ -631,6 +709,7 @@ else
#
# Check if UAVCAN is enabled, default to it for ESCs.
#
%ifdef CONFIG_DRIVERS_UAVCAN
if param greater -s UAVCAN_ENABLE 0
then
# Start core UAVCAN module.
@@ -639,15 +718,27 @@ else
tune_control play error
fi
else
%ifdef CONFIG_DRIVERS_CYPHAL
if param greater -s CYPHAL_ENABLE 0
then
cyphal start
fi
%endif
fi
%else
%ifdef CONFIG_DRIVERS_CYPHAL
if param greater -s CYPHAL_ENABLE 0
then
cyphal start
fi
%endif
%endif
%ifdef CONFIG_MODULES_ZENOH
if param greater -s ZENOH_ENABLE 0
then
zenoh start
fi
%endif
#
# End of autostart.
@@ -21,11 +21,13 @@ exec find boards msg src platforms test \
-path src/lib/crypto/monocypher -prune -o \
-path src/lib/events/libevents -prune -o \
-path src/lib/parameters/uthash -prune -o \
-path src/lib/rl_tools/rl_tools -prune -o \
-path src/lib/wind_estimator/python/generated -prune -o \
-path src/modules/ekf2/EKF/python/ekf_derivation/generated -prune -o \
-path src/modules/ekf2/EKF/yaw_estimator/derivation/generated -prune -o \
-path src/modules/gyro_fft/CMSIS_5 -prune -o \
-path src/modules/mavlink/mavlink -prune -o \
-path src/modules/mc_raptor/blob -prune -o \
-path test/fuzztest -prune -o \
-path test/mavsdk_tests/catch2 -prune -o \
-path src/lib/crypto/monocypher -prune -o \
+188
View File
@@ -0,0 +1,188 @@
#!/usr/bin/env python3
"""
Preprocesses ROMFS files with C preprocessor to enable KConfig support.
This script processes all rc* files in the ROMFS directory through the C preprocessor,
allowing use of #ifdef, #ifndef, #if, #else, #endif directives with KConfig definitions.
"""
import argparse
import os
import subprocess
import sys
import tempfile
from pathlib import Path
def preprocess_file(file_path, kconfig_header, cpp_command):
"""
Preprocess a single file through the C preprocessor.
Uses % as the preprocessor directive symbol (instead of #) to avoid conflicts
with shell comments. Converts %ifdef, %ifndef, %if, %else, %endif to
#ifdef, #ifndef, #if, #else, #endif before preprocessing.
Args:
file_path: Path to the file to preprocess
kconfig_header: Path to the px4_boardconfig.h header
cpp_command: C preprocessor command (usually the C compiler)
"""
# Read original file
with open(file_path, 'r') as f:
original_content = f.read()
# Process the file line by line:
# 1. Remove shell comment lines (to avoid conflicts with CPP)
# 2. Convert % preprocessor directives to # directives
lines = original_content.split('\n')
converted_lines = []
for line in lines:
stripped = line.lstrip()
# Check if line starts with % followed by a preprocessor keyword
if stripped.startswith('%ifdef ') or stripped.startswith('%ifdef\t'):
# Preserve leading whitespace, convert %ifdef to #ifdef
converted_lines.append(line.replace('%ifdef', '#ifdef', 1))
elif stripped.startswith('%ifndef ') or stripped.startswith('%ifndef\t'):
converted_lines.append(line.replace('%ifndef', '#ifndef', 1))
elif stripped.startswith('%if '):
converted_lines.append(line.replace('%if', '#if', 1))
elif stripped.startswith('%elif '):
converted_lines.append(line.replace('%elif', '#elif', 1))
elif stripped.startswith('%else'):
converted_lines.append(line.replace('%else', '#else', 1))
elif stripped.startswith('%endif'):
converted_lines.append(line.replace('%endif', '#endif', 1))
elif stripped.startswith('#') and not stripped.startswith('#!'):
# Remove shell comment lines (but keep shebang)
# This prevents "# if ..." comments from being interpreted as "#if" by CPP
continue
else:
converted_lines.append(line)
converted_content = '\n'.join(converted_lines)
# Create temporary file with include directive and converted content
with tempfile.NamedTemporaryFile(mode='w', suffix='.in', delete=False) as tmp:
tmp.write(f'#include "{kconfig_header}"\n')
tmp.write(converted_content)
tmp_path = tmp.name
try:
# Run C preprocessor
# -P: don't generate #line directives
# -E: preprocess only
# -undef: don't predefine any non-standard macros
# -nostdinc: don't search standard include directories
# -x assembler-with-cpp: treat input as assembly (allows # comments to pass through)
result = subprocess.run(
[cpp_command, '-P', '-E', '-undef', '-nostdinc', '-x', 'assembler-with-cpp', tmp_path],
capture_output=True,
text=True,
check=True
)
preprocessed = result.stdout
# Clean up the output:
# 1. Remove empty lines at the beginning
# 2. Remove lines that are just whitespace
lines = preprocessed.split('\n')
cleaned_lines = []
started = False
for line in lines:
# Skip empty lines at the beginning
if not started and not line.strip():
continue
started = True
cleaned_lines.append(line)
# Remove trailing empty lines
while cleaned_lines and not cleaned_lines[-1].strip():
cleaned_lines.pop()
# Write preprocessed content back
with open(file_path, 'w') as f:
f.write('\n'.join(cleaned_lines))
if cleaned_lines: # Add final newline if file is not empty
f.write('\n')
return True
except subprocess.CalledProcessError as e:
print(f"Error preprocessing {file_path}: {e}")
print(f"stderr: {e.stderr}")
return False
finally:
# Clean up temporary file
try:
os.unlink(tmp_path)
except:
pass
def main():
parser = argparse.ArgumentParser(description='Preprocess ROMFS files with KConfig definitions')
parser.add_argument('--romfs-dir', required=True, help='ROMFS root directory')
parser.add_argument('--kconfig-header', required=True, help='Path to px4_boardconfig.h')
parser.add_argument('--cpp', required=True, help='C preprocessor command')
parser.add_argument('--pattern', default='rc*', help='File pattern to preprocess (default: rc*)')
args = parser.parse_args()
# Verify inputs
romfs_dir = Path(args.romfs_dir)
kconfig_header = Path(args.kconfig_header)
if not romfs_dir.exists():
print(f"Error: ROMFS directory not found: {romfs_dir}")
return 1
if not kconfig_header.exists():
print(f"Error: KConfig header not found: {kconfig_header}")
return 1
# Find all files to preprocess in init.d directory
init_d_dir = romfs_dir / 'init.d'
if not init_d_dir.exists():
print(f"Warning: init.d directory not found in {romfs_dir}")
return 0
# Find all rc* files (shell scripts)
files_to_process = []
for pattern in ['rc*', 'rcS']:
files_to_process.extend(init_d_dir.glob(pattern))
# Also check subdirectories like airframes
for subdir in init_d_dir.iterdir():
if subdir.is_dir():
for pattern in ['rc*']:
files_to_process.extend(subdir.glob(pattern))
# Remove duplicates and filter only files
files_to_process = list(set([f for f in files_to_process if f.is_file()]))
if not files_to_process:
print(f"Warning: No files matching pattern '{args.pattern}' found in {init_d_dir}")
return 0
print(f"Preprocessing {len(files_to_process)} ROMFS files with KConfig definitions...")
# Process each file
success_count = 0
for file_path in sorted(files_to_process):
rel_path = file_path.relative_to(romfs_dir)
print(f" Processing: {rel_path}")
if preprocess_file(file_path, kconfig_header.absolute(), args.cpp):
success_count += 1
else:
print(f" Warning: Failed to preprocess {rel_path}")
print(f"Successfully preprocessed {success_count}/{len(files_to_process)} files")
return 0 if success_count == len(files_to_process) else 1
if __name__ == '__main__':
sys.exit(main())
@@ -21,7 +21,6 @@ CONFIG_DRIVERS_IMU_INVENSENSE_ICM20948=y
CONFIG_DRIVERS_IRLOCK=y
CONFIG_COMMON_LIGHT=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_DRIVERS_PCA9685_PWM_OUT=y
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
CONFIG_DRIVERS_PWM_OUT=y
@@ -34,7 +34,6 @@ CONFIG_DRIVERS_OSD_MSP_OSD=y
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
CONFIG_DRIVERS_POWER_MONITOR_INA228=y
CONFIG_DRIVERS_POWER_MONITOR_INA238=y
CONFIG_DRIVERS_POWER_MONITOR_PM_SELECTOR_AUTERION=y
CONFIG_DRIVERS_PWM_OUT=y
CONFIG_DRIVERS_PX4IO=y
CONFIG_DRIVERS_RC_INPUT=y
@@ -22,7 +22,6 @@ CONFIG_DRIVERS_IMU_ST_LSM303D=y
CONFIG_DRIVERS_IRLOCK=y
CONFIG_COMMON_LIGHT=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_DRIVERS_PCA9685_PWM_OUT=y
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
CONFIG_DRIVERS_PWM_INPUT=y
+17
View File
@@ -0,0 +1,17 @@
CONFIG_MODULES_AIRSPEED_SELECTOR=n
CONFIG_MODULES_FLIGHT_MODE_MANAGER=n
CONFIG_MODULES_FW_ATT_CONTROL=n
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=n
CONFIG_MODULES_FW_MODE_MANAGER=n
CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=n
CONFIG_MODULES_FW_RATE_CONTROL=n
CONFIG_MODULES_MC_ATT_CONTROL=n
CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=n
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=n
CONFIG_MODULES_MC_POS_CONTROL=n
CONFIG_MODULES_MC_RATE_CONTROL=n
CONFIG_MODULES_VTOL_ATT_CONTROL=n
CONFIG_DRIVERS_ROBOCLAW=y
CONFIG_MODULES_ROVER_ACKERMANN=y
CONFIG_MODULES_ROVER_DIFFERENTIAL=y
CONFIG_MODULES_ROVER_MECANUM=y
+1
View File
@@ -22,6 +22,7 @@ CONFIG_COMMON_MAGNETOMETER=y
CONFIG_DATAMAN_PERSISTENT_STORAGE=n
CONFIG_DRIVERS_PWM_OUT=y
CONFIG_COMMON_RC=y
CONFIG_DRIVERS_AUTERION_AUTOSTARTER=y
CONFIG_DRIVERS_PCA9685_PWM_OUT=y
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
CONFIG_DRIVERS_POWER_MONITOR_INA228=y
@@ -60,6 +60,9 @@ then
set INA_CONFIGURED yes
fi
# Auterion auto starter
auterion_autostarter start
if param compare BAT1_V_CHANNEL -2
then
if [ "$INA_CONFIGURED" != "yes" ]
+1 -1
View File
@@ -26,10 +26,10 @@ CONFIG_DRIVERS_IMU_INVENSENSE_ICM20602=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y
CONFIG_COMMON_LIGHT=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_DRIVERS_AUTERION_AUTOSTARTER=y
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
CONFIG_DRIVERS_POWER_MONITOR_INA228=y
CONFIG_DRIVERS_POWER_MONITOR_INA238=y
CONFIG_DRIVERS_POWER_MONITOR_PM_SELECTOR_AUTERION=y
CONFIG_DRIVERS_PWM_INPUT=y
CONFIG_DRIVERS_PWM_OUT=y
CONFIG_DRIVERS_PX4IO=y
@@ -55,8 +55,8 @@ then
set INA_CONFIGURED yes
fi
#Start Auterion Power Module selector for Skynode boards
pm_selector_auterion start
# Auterion auto starter
auterion_autostarter start
# Auterion's INA238 uses a shunt value of 0.0003 instead of 0.0005.
param set-default INA238_SHUNT 0.0003
-1
View File
@@ -21,7 +21,6 @@ CONFIG_DRIVERS_IMU_INVENSENSE_ICM20948=y
CONFIG_DRIVERS_IRLOCK=y
CONFIG_COMMON_LIGHT=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_DRIVERS_PCA9685_PWM_OUT=y
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
CONFIG_DRIVERS_PWM_OUT=y
-1
View File
@@ -30,7 +30,6 @@ CONFIG_DRIVERS_OSD_MSP_OSD=y
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
CONFIG_DRIVERS_POWER_MONITOR_INA228=y
CONFIG_DRIVERS_POWER_MONITOR_INA238=y
CONFIG_DRIVERS_POWER_MONITOR_PM_SELECTOR_AUTERION=y
CONFIG_DRIVERS_PWM_OUT=y
CONFIG_DRIVERS_PX4IO=y
CONFIG_DRIVERS_RC_INPUT=y
-1
View File
@@ -27,7 +27,6 @@ CONFIG_DRIVERS_IRLOCK=y
CONFIG_COMMON_LIGHT=y
CONFIG_DRIVERS_LIGHTS_RGBLED_PWM=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_DRIVERS_PCA9685_PWM_OUT=y
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
CONFIG_DRIVERS_PWM_OUT=y
-1
View File
@@ -28,7 +28,6 @@ CONFIG_DRIVERS_OSD_MSP_OSD=y
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
CONFIG_DRIVERS_POWER_MONITOR_INA228=y
CONFIG_DRIVERS_POWER_MONITOR_INA238=y
CONFIG_DRIVERS_POWER_MONITOR_PM_SELECTOR_AUTERION=y
CONFIG_DRIVERS_PWM_OUT=y
CONFIG_DRIVERS_RC_INPUT=y
CONFIG_DRIVERS_SAFETY_BUTTON=y
-1
View File
@@ -27,7 +27,6 @@ CONFIG_DRIVERS_IRLOCK=y
CONFIG_COMMON_LIGHT=y
CONFIG_DRIVERS_LIGHTS_RGBLED_PWM=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_DRIVERS_PCA9685_PWM_OUT=y
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
CONFIG_DRIVERS_PWM_OUT=y
@@ -24,7 +24,6 @@ CONFIG_DRIVERS_IMU_INVENSENSE_ICM20948=y
CONFIG_DRIVERS_IRLOCK=y
CONFIG_COMMON_LIGHT=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_DRIVERS_PCA9685_PWM_OUT=y
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
CONFIG_DRIVERS_PWM_INPUT=y
@@ -25,7 +25,6 @@ CONFIG_DRIVERS_IMU_INVENSENSE_ICM45686=y
CONFIG_DRIVERS_IRLOCK=y
CONFIG_COMMON_LIGHT=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_DRIVERS_PCA9685_PWM_OUT=y
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
CONFIG_DRIVERS_PWM_INPUT=y
@@ -24,7 +24,6 @@ CONFIG_DRIVERS_IMU_INVENSENSE_ICM20948=y
CONFIG_DRIVERS_IRLOCK=y
CONFIG_COMMON_LIGHT=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_DRIVERS_PCA9685_PWM_OUT=y
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
CONFIG_DRIVERS_PWM_OUT=y
-1
View File
@@ -22,7 +22,6 @@ CONFIG_DRIVERS_IMU_BOSCH_BMI088=y
CONFIG_DRIVERS_IRLOCK=y
CONFIG_COMMON_LIGHT=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_DRIVERS_PWM_OUT=y
CONFIG_DRIVERS_RC_INPUT=y
CONFIG_COMMON_TELEMETRY=y
-1
View File
@@ -23,7 +23,6 @@ CONFIG_DRIVERS_IMU_INVENSENSE_MPU6500=y
CONFIG_DRIVERS_IRLOCK=y
CONFIG_COMMON_LIGHT=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_DRIVERS_PWM_OUT=y
CONFIG_DRIVERS_RC_INPUT=y
CONFIG_DRIVERS_ROBOCLAW=y
@@ -23,7 +23,6 @@ CONFIG_DRIVERS_IMU_INVENSENSE_ICM20689=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20948=y
CONFIG_COMMON_LIGHT=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_DRIVERS_PCA9685_PWM_OUT=y
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
CONFIG_DRIVERS_PWM_OUT=y
-1
View File
@@ -19,7 +19,6 @@ CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y
CONFIG_DRIVERS_IMU_INVENSENSE_MPU6000=y
CONFIG_COMMON_LIGHT=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
CONFIG_DRIVERS_PWM_OUT=y
CONFIG_DRIVERS_RC_INPUT=y
@@ -22,7 +22,6 @@ CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM45686=y
CONFIG_COMMON_LIGHT=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_DRIVERS_PWM_OUT=y
CONFIG_DRIVERS_RC_INPUT=y
CONFIG_COMMON_TELEMETRY=y
@@ -19,7 +19,6 @@ CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y
CONFIG_DRIVERS_IMU_INVENSENSE_MPU6000=y
CONFIG_COMMON_LIGHT=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
CONFIG_DRIVERS_PWM_OUT=y
CONFIG_DRIVERS_RC_INPUT=y
@@ -19,7 +19,6 @@ CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y
CONFIG_DRIVERS_IMU_INVENSENSE_MPU6000=y
CONFIG_COMMON_LIGHT=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
CONFIG_DRIVERS_PWM_OUT=y
CONFIG_DRIVERS_RC_INPUT=y
-1
View File
@@ -25,7 +25,6 @@ CONFIG_DRIVERS_IRLOCK=y
CONFIG_COMMON_LIGHT=y
CONFIG_DRIVERS_LIGHTS_RGBLED_PWM=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_DRIVERS_PCA9685_PWM_OUT=y
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
CONFIG_DRIVERS_PWM_INPUT=y
-1
View File
@@ -14,7 +14,6 @@ CONFIG_DRIVERS_IMU_INVENSENSE_ICM20602=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM42605=y
CONFIG_DRIVERS_IMU_INVENSENSE_MPU6000=y
CONFIG_DRIVERS_MAGNETOMETER_QMC5883L=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_DRIVERS_PWM_OUT=y
CONFIG_DRIVERS_RC_INPUT=y
CONFIG_COMMON_TELEMETRY=y
-1
View File
@@ -17,7 +17,6 @@ CONFIG_DRIVERS_IMU_INVENSENSE_ICM42605=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y
CONFIG_DRIVERS_IMU_INVENSENSE_MPU6000=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_DRIVERS_PWM_OUT=y
CONFIG_DRIVERS_RC_INPUT=y
CONFIG_COMMON_TELEMETRY=y
-1
View File
@@ -16,7 +16,6 @@ CONFIG_DRIVERS_IMU_INVENSENSE_ICM42605=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y
CONFIG_DRIVERS_IMU_INVENSENSE_MPU6000=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_DRIVERS_PWM_OUT=y
CONFIG_DRIVERS_RC_INPUT=y
CONFIG_COMMON_TELEMETRY=y
-2
View File
@@ -26,13 +26,11 @@ CONFIG_COMMON_HYGROMETERS=y
CONFIG_DRIVERS_IMU_BOSCH_BMI088=y
CONFIG_DRIVERS_IMU_BOSCH_BMI270=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_DRIVERS_OSD_MSP_OSD=y
CONFIG_DRIVERS_POWER_MONITOR_INA220=y
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
CONFIG_DRIVERS_POWER_MONITOR_INA228=y
CONFIG_DRIVERS_POWER_MONITOR_INA238=y
CONFIG_DRIVERS_POWER_MONITOR_PM_SELECTOR_AUTERION=y
CONFIG_DRIVERS_POWER_MONITOR_VOXLPM=y
CONFIG_DRIVERS_PPS_CAPTURE=y
CONFIG_DRIVERS_PWM_OUT=y
@@ -24,12 +24,10 @@ CONFIG_DRIVERS_GNSS_SEPTENTRIO=y
CONFIG_DRIVERS_GPS=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM45686=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_DRIVERS_POWER_MONITOR_INA220=y
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
CONFIG_DRIVERS_POWER_MONITOR_INA228=y
CONFIG_DRIVERS_POWER_MONITOR_INA238=y
CONFIG_DRIVERS_POWER_MONITOR_PM_SELECTOR_AUTERION=y
CONFIG_DRIVERS_POWER_MONITOR_VOXLPM=y
CONFIG_DRIVERS_PPS_CAPTURE=y
CONFIG_DRIVERS_PWM_OUT=y
-2
View File
@@ -25,13 +25,11 @@ CONFIG_DRIVERS_GPS=y
CONFIG_DRIVERS_IMU_BOSCH_BMI088=y
CONFIG_DRIVERS_IMU_BOSCH_BMI270=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_DRIVERS_OSD_MSP_OSD=y
CONFIG_DRIVERS_POWER_MONITOR_INA220=y
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
CONFIG_DRIVERS_POWER_MONITOR_INA228=y
CONFIG_DRIVERS_POWER_MONITOR_INA238=y
CONFIG_DRIVERS_POWER_MONITOR_PM_SELECTOR_AUTERION=y
CONFIG_DRIVERS_POWER_MONITOR_VOXLPM=y
CONFIG_DRIVERS_PPS_CAPTURE=y
CONFIG_DRIVERS_PWM_OUT=y
-2
View File
@@ -27,13 +27,11 @@ CONFIG_COMMON_HYGROMETERS=y
CONFIG_DRIVERS_IMU_BOSCH_BMI088=y
CONFIG_DRIVERS_IMU_BOSCH_BMI270=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_DRIVERS_OSD_MSP_OSD=y
CONFIG_DRIVERS_POWER_MONITOR_INA220=y
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
CONFIG_DRIVERS_POWER_MONITOR_INA228=y
CONFIG_DRIVERS_POWER_MONITOR_INA238=y
CONFIG_DRIVERS_POWER_MONITOR_PM_SELECTOR_AUTERION=y
CONFIG_DRIVERS_POWER_MONITOR_VOXLPM=y
CONFIG_DRIVERS_PPS_CAPTURE=y
CONFIG_DRIVERS_PWM_OUT=y
-1
View File
@@ -24,7 +24,6 @@ CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y
CONFIG_DRIVERS_IRLOCK=y
CONFIG_COMMON_LIGHT=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_COMMON_OSD=y
CONFIG_DRIVERS_PCA9685_PWM_OUT=y
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
-1
View File
@@ -19,7 +19,6 @@ CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y
CONFIG_DRIVERS_IRLOCK=y
CONFIG_COMMON_LIGHT=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_COMMON_OSD=y
CONFIG_DRIVERS_PCA9685_PWM_OUT=y
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
@@ -23,7 +23,6 @@ CONFIG_DRIVERS_IMU_INVENSENSE_ICM20948=y
CONFIG_DRIVERS_IRLOCK=y
CONFIG_COMMON_LIGHT=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_DRIVERS_PCA9685_PWM_OUT=y
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
CONFIG_DRIVERS_PWM_OUT=y
@@ -21,7 +21,6 @@ CONFIG_DRIVERS_IMU_INVENSENSE_ICM20948=y
CONFIG_DRIVERS_IRLOCK=y
CONFIG_COMMON_LIGHT=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_DRIVERS_PCA9685_PWM_OUT=y
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
CONFIG_DRIVERS_PWM_OUT=y
-1
View File
@@ -20,7 +20,6 @@ CONFIG_DRIVERS_IMU_INVENSENSE_ICM20948=y
CONFIG_DRIVERS_IRLOCK=y
CONFIG_COMMON_LIGHT=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_DRIVERS_PCA9685_PWM_OUT=y
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
CONFIG_DRIVERS_PWM_OUT=y
@@ -22,7 +22,6 @@ CONFIG_DRIVERS_IMU_INVENSENSE_ICM20948=y
CONFIG_DRIVERS_IRLOCK=y
CONFIG_COMMON_LIGHT=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_DRIVERS_PCA9685_PWM_OUT=y
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
CONFIG_DRIVERS_PWM_OUT=y
-1
View File
@@ -22,7 +22,6 @@ CONFIG_DRIVERS_IMU_INVENSENSE_ICM20948=y
CONFIG_DRIVERS_IRLOCK=y
CONFIG_COMMON_LIGHT=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_DRIVERS_PCA9685_PWM_OUT=y
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
CONFIG_DRIVERS_PWM_OUT=y
-1
View File
@@ -26,7 +26,6 @@ CONFIG_DRIVERS_IMU_INVENSENSE_ICM20948=y
CONFIG_DRIVERS_IRLOCK=y
CONFIG_COMMON_LIGHT=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_DRIVERS_PCA9685_PWM_OUT=y
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
CONFIG_DRIVERS_PWM_OUT=y
-1
View File
@@ -22,7 +22,6 @@ CONFIG_DRIVERS_IMU_INVENSENSE_ICM20948=y
CONFIG_DRIVERS_IRLOCK=y
CONFIG_COMMON_LIGHT=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_DRIVERS_PCA9685_PWM_OUT=y
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
CONFIG_DRIVERS_PWM_OUT=y
-1
View File
@@ -21,7 +21,6 @@ CONFIG_DRIVERS_IMU_INVENSENSE_MPU9250=y
CONFIG_DRIVERS_IRLOCK=y
CONFIG_COMMON_LIGHT=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_DRIVERS_PCA9685_PWM_OUT=y
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
CONFIG_DRIVERS_PWM_INPUT=y
-1
View File
@@ -22,7 +22,6 @@ CONFIG_DRIVERS_IMU_INVENSENSE_MPU9250=y
CONFIG_DRIVERS_IRLOCK=y
CONFIG_COMMON_LIGHT=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_DRIVERS_PCA9685_PWM_OUT=y
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
CONFIG_DRIVERS_PWM_INPUT=y
-1
View File
@@ -27,7 +27,6 @@ CONFIG_DRIVERS_IRLOCK=y
CONFIG_COMMON_LIGHT=y
CONFIG_DRIVERS_LIGHTS_RGBLED_PWM=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_DRIVERS_PCA9685_PWM_OUT=y
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
CONFIG_DRIVERS_PWM_OUT=y
-1
View File
@@ -23,7 +23,6 @@ CONFIG_DRIVERS_IRLOCK=y
CONFIG_COMMON_LIGHT=y
CONFIG_DRIVERS_LIGHTS_RGBLED_PWM=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_DRIVERS_PCA9685_PWM_OUT=y
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
CONFIG_DRIVERS_PWM_OUT=y
-1
View File
@@ -24,7 +24,6 @@ CONFIG_DRIVERS_LIGHTS_RGBLED=y
CONFIG_DRIVERS_LIGHTS_RGBLED_NCP5623C=y
CONFIG_DRIVERS_LIGHTS_RGBLED_PWM=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_DRIVERS_PCA9685_PWM_OUT=y
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
CONFIG_DRIVERS_PWM_OUT=y
-1
View File
@@ -14,7 +14,6 @@ CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
CONFIG_COMMON_DISTANCE_SENSOR=y
CONFIG_COMMON_LIGHT=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_CYPHAL_BMS_SUBSCRIBER=y
CONFIG_DRIVERS_ADC_BOARD_ADC=y
CONFIG_DRIVERS_CYPHAL=y
-1
View File
@@ -29,7 +29,6 @@ CONFIG_COMMON_LIGHT=y
CONFIG_DRIVERS_LIGHTS_RGBLED_PWM=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_DRIVERS_MAGNETOMETER_BOSCH_BMM350=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_DRIVERS_OSD_MSP_OSD=y
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
CONFIG_DRIVERS_POWER_MONITOR_INA228=y
@@ -26,7 +26,6 @@ CONFIG_COMMON_INS=y
CONFIG_COMMON_LIGHT=y
CONFIG_DRIVERS_LIGHTS_RGBLED_PWM=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_DRIVERS_OSD_MSP_OSD=y
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
CONFIG_DRIVERS_POWER_MONITOR_INA228=y
-1
View File
@@ -28,7 +28,6 @@ CONFIG_DRIVERS_IMU_ST_LSM303D=y
CONFIG_DRIVERS_IRLOCK=y
CONFIG_COMMON_LIGHT=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_DRIVERS_PCA9685_PWM_OUT=y
CONFIG_DRIVERS_PWM_INPUT=y
CONFIG_DRIVERS_PWM_OUT=y
-1
View File
@@ -26,7 +26,6 @@ CONFIG_DRIVERS_IMU_INVENSENSE_MPU9250=y
CONFIG_DRIVERS_IRLOCK=y
CONFIG_COMMON_LIGHT=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_DRIVERS_PCA9685_PWM_OUT=y
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
CONFIG_DRIVERS_PWM_INPUT=y
-1
View File
@@ -25,7 +25,6 @@ CONFIG_DRIVERS_IMU_INVENSENSE_MPU9250=y
CONFIG_DRIVERS_IRLOCK=y
CONFIG_COMMON_LIGHT=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_DRIVERS_PCA9685_PWM_OUT=y
CONFIG_DRIVERS_PWM_INPUT=y
CONFIG_DRIVERS_PWM_OUT=y
-3
View File
@@ -27,7 +27,6 @@ CONFIG_DRIVERS_IRLOCK=y
CONFIG_COMMON_LIGHT=y
CONFIG_DRIVERS_LIGHTS_RGBLED_PWM=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_COMMON_OSD=y
CONFIG_DRIVERS_PCA9685_PWM_OUT=y
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
@@ -77,8 +76,6 @@ CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_SENSORS=y
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_UXRCE_DDS_CLIENT=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
+1 -2
View File
@@ -34,12 +34,11 @@ CONFIG_DRIVERS_IMU_INVENSENSE_IIM42652=y
CONFIG_DRIVERS_IRLOCK=y
CONFIG_COMMON_LIGHT=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_DRIVERS_AUTERION_AUTOSTARTER=y
CONFIG_DRIVERS_OSD_MSP_OSD=y
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
CONFIG_DRIVERS_POWER_MONITOR_INA228=y
CONFIG_DRIVERS_POWER_MONITOR_INA238=y
CONFIG_DRIVERS_POWER_MONITOR_PM_SELECTOR_AUTERION=y
CONFIG_DRIVERS_PWM_INPUT=y
CONFIG_DRIVERS_PWM_OUT=y
CONFIG_DRIVERS_PX4IO=y
+2 -2
View File
@@ -72,8 +72,8 @@ then
# Internal magnetometer on I2c
bmm150 -I -R 6 start
# Auto start power monitors
pm_selector_auterion start
# Auterion auto starter
auterion_autostarter start
# Auterion's INA238 uses a shunt value of 0.0003 instead of 0.0005.
param set-default INA238_SHUNT 0.0003
-1
View File
@@ -24,7 +24,6 @@ CONFIG_DRIVERS_IMU_BOSCH_BMI088=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y
CONFIG_COMMON_LIGHT=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
CONFIG_DRIVERS_POWER_MONITOR_INA228=y
CONFIG_DRIVERS_POWER_MONITOR_INA238=y
-1
View File
@@ -22,7 +22,6 @@ CONFIG_DRIVERS_IMU_BOSCH_BMI088=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y
CONFIG_COMMON_LIGHT=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
CONFIG_DRIVERS_POWER_MONITOR_INA228=y
CONFIG_DRIVERS_POWER_MONITOR_INA238=y
-1
View File
@@ -10,7 +10,6 @@ CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
CONFIG_COMMON_DISTANCE_SENSOR=y
CONFIG_COMMON_LIGHT=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_COMMON_TELEMETRY=y
CONFIG_DRIVERS_ACTUATORS_VERTIQ_IO=y
CONFIG_DRIVERS_ADC_BOARD_ADC=y
-1
View File
@@ -24,7 +24,6 @@ CONFIG_DRIVERS_IMU_INVENSENSE_ICM42605=y
CONFIG_DRIVERS_IRLOCK=y
CONFIG_COMMON_LIGHT=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_DRIVERS_PCA9685_PWM_OUT=y
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
CONFIG_DRIVERS_PWM_OUT=y
-1
View File
@@ -16,7 +16,6 @@ CONFIG_DRIVERS_CAMERA_CAPTURE=y
CONFIG_DRIVERS_CAMERA_TRIGGER=y
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
CONFIG_DRIVERS_DIFFERENTIAL_PRESSURE_AUAV=y
CONFIG_COMMON_DISTANCE_SENSOR=y
CONFIG_DRIVERS_DSHOT=y
CONFIG_DRIVERS_GNSS_SEPTENTRIO=y
@@ -189,6 +189,7 @@ CONFIG_PIPES=y
CONFIG_PREALLOC_TIMERS=50
CONFIG_PRIORITY_INHERITANCE=y
CONFIG_PTHREAD_MUTEX_ROBUST=y
CONFIG_PTHREAD_MUTEX_TYPES=y
CONFIG_PTHREAD_STACK_MIN=512
CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5
CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5
-1
View File
@@ -24,7 +24,6 @@ CONFIG_DRIVERS_IMU_INVENSENSE_MPU9250=y
CONFIG_DRIVERS_IRLOCK=y
CONFIG_COMMON_LIGHT=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_COMMON_OSD=y
CONFIG_DRIVERS_OSD_MSP_OSD=y
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
-1
View File
@@ -18,7 +18,6 @@ CONFIG_DRIVERS_IMU_BOSCH_BMI088=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20689=y
CONFIG_COMMON_LIGHT=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
CONFIG_DRIVERS_PWM_OUT=y
CONFIG_DRIVERS_PX4IO=y
@@ -23,7 +23,6 @@ CONFIG_DRIVERS_IMU_INVENSENSE_MPU9250=y
CONFIG_DRIVERS_IRLOCK=y
CONFIG_COMMON_LIGHT=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_DRIVERS_PCA9685_PWM_OUT=y
CONFIG_DRIVERS_PWM_INPUT=y
CONFIG_DRIVERS_PWM_OUT=y
@@ -13,7 +13,6 @@ CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y
CONFIG_DRIVERS_IMU_INVENSENSE_MPU6000=y
CONFIG_COMMON_LIGHT=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_DRIVERS_PWM_OUT=y
CONFIG_DRIVERS_RC_INPUT=y
CONFIG_COMMON_TELEMETRY=y
-1
View File
@@ -31,7 +31,6 @@ CONFIG_DRIVERS_OSD_MSP_OSD=y
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
CONFIG_DRIVERS_POWER_MONITOR_INA228=y
CONFIG_DRIVERS_POWER_MONITOR_INA238=y
CONFIG_DRIVERS_POWER_MONITOR_PM_SELECTOR_AUTERION=y
CONFIG_DRIVERS_PWM_OUT=y
CONFIG_DRIVERS_PX4IO=y
CONFIG_COMMON_RC=y
-1
View File
@@ -21,7 +21,6 @@ CONFIG_DRIVERS_IMU_INVENSENSE_MPU9250=y
CONFIG_DRIVERS_IRLOCK=y
CONFIG_COMMON_LIGHT=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_DRIVERS_PCA9685_PWM_OUT=y
CONFIG_DRIVERS_PWM_INPUT=y
CONFIG_DRIVERS_PWM_OUT=y
-1
View File
@@ -21,7 +21,6 @@ CONFIG_DRIVERS_IMU_INVENSENSE_MPU9250=y
CONFIG_DRIVERS_IRLOCK=y
CONFIG_COMMON_LIGHT=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_DRIVERS_PCA9685_PWM_OUT=y
CONFIG_DRIVERS_PWM_INPUT=y
CONFIG_DRIVERS_PWM_OUT=y
-1
View File
@@ -22,7 +22,6 @@ CONFIG_DRIVERS_LIGHTS_RGBLED_NCP5623C=y
CONFIG_DRIVERS_MAGNETOMETER_BOSCH_BMM150=y
CONFIG_DRIVERS_MAGNETOMETER_ISENTEK_IST8310=y
CONFIG_DRIVERS_MAGNETOMETER_LIS3MDL=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_DRIVERS_PWM_INPUT=y
CONFIG_DRIVERS_PWM_OUT=y
CONFIG_DRIVERS_RC_INPUT=y
+1 -1
View File
@@ -21,7 +21,7 @@ CONFIG_DRIVERS_IMU_BOSCH_BMI270=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y
CONFIG_DRIVERS_MAGNETOMETER_ISENTEK_IST8310=y
CONFIG_DRIVERS_MAGNETOMETER_QMC5883L=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_DRIVERS_MAGNETOMETER_QMC5883P=y
CONFIG_COMMON_OSD=y
CONFIG_DRIVERS_PWM_OUT=y
CONFIG_DRIVERS_PX4IO=y
+1 -1
View File
@@ -23,4 +23,4 @@ then
fi
# internal mag
ist8310 -I -R 6 start
qmc5883p -I -R 2 start
@@ -42,20 +42,20 @@
#define DMAMAP_SPI2_RX DMAMAP_DMA12_SPI2RX_0 /* DMA1:39 */
#define DMAMAP_SPI2_TX DMAMAP_DMA12_SPI2TX_0 /* DMA1:40 */
#define DMAMAP_SPI4_RX DMAMAP_DMA12_SPI4RX_0 /* 3 DMA1:83 IMU */
#define DMAMAP_SPI4_TX DMAMAP_DMA12_SPI4TX_0 /* 4 DMA1:84 IMU */
#define DMAMAP_SPI4_RX DMAMAP_DMA12_SPI4RX_1 /* 3 DMA2:83 IMU */
#define DMAMAP_SPI4_TX DMAMAP_DMA12_SPI4TX_1 /* 4 DMA2:84 IMU */
#define DMAMAP_USART1_RX DMAMAP_DMA12_USART1RX_0 /* DMA1:41 GPS1 */
#define DMAMAP_USART1_TX DMAMAP_DMA12_USART1TX_0 /* DMA1:42 GPS1 */
// #define DMAMAP_USART1_RX DMAMAP_DMA12_USART1RX_0 /* DMA1:41 GPS1 */
// #define DMAMAP_USART1_TX DMAMAP_DMA12_USART1TX_0 /* DMA1:42 GPS1 */
#define DMAMAP_USART2_RX DMAMAP_DMA12_USART2RX_0 /* DMA1:43 GPS2 */
#define DMAMAP_USART2_TX DMAMAP_DMA12_USART2TX_0 /* DMA1:44 GPS2 */
// #define DMAMAP_USART2_RX DMAMAP_DMA12_USART2RX_0 /* DMA1:43 GPS2 */
// #define DMAMAP_USART2_TX DMAMAP_DMA12_USART2TX_0 /* DMA1:44 GPS2 */
#define DMAMAP_USART3_RX DMAMAP_DMA12_USART3RX_0 /* DMA1:45 TELEM1 */
#define DMAMAP_USART3_TX DMAMAP_DMA12_USART3TX_0 /* DMA1:46 TELEM1 */
#define DMAMAP_UART4_RX DMAMAP_DMA12_UART4RX_1 /* DMA1:63 TELEM2 */
#define DMAMAP_UART4_TX DMAMAP_DMA12_UART4TX_1 /* DMA1:64 TELEM2 */
#define DMAMAP_UART4_RX DMAMAP_DMA12_UART4RX_1 /* DMA2:63 TELEM2 */
#define DMAMAP_UART4_TX DMAMAP_DMA12_UART4TX_1 /* DMA2:64 TELEM2 */
#define DMAMAP_USART6_RX DMAMAP_DMA12_USART6RX_0 /* DMA1:71 PX4IO */
#define DMAMAP_USART6_TX DMAMAP_DMA12_USART6TX_0 /* DMA1:72 PX4IO */
@@ -247,14 +247,10 @@ CONFIG_UART8_SERIAL_CONSOLE=y
CONFIG_UART8_TXBUFSIZE=3000
CONFIG_USART1_BAUD=57600
CONFIG_USART1_RXBUFSIZE=600
CONFIG_USART1_RXDMA=y
CONFIG_USART1_TXBUFSIZE=1500
CONFIG_USART1_TXDMA=y
CONFIG_USART2_BAUD=57600
CONFIG_USART2_RXBUFSIZE=600
CONFIG_USART2_RXDMA=y
CONFIG_USART2_TXBUFSIZE=3000
CONFIG_USART2_TXDMA=y
CONFIG_USART3_BAUD=57600
CONFIG_USART3_RXBUFSIZE=180
CONFIG_USART3_RXDMA=y
-1
View File
@@ -21,7 +21,6 @@ CONFIG_DRIVERS_IMU_BOSCH_BMI088=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y
CONFIG_DRIVERS_MAGNETOMETER_ISENTEK_IST8310=y
CONFIG_DRIVERS_MAGNETOMETER_QMC5883L=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_COMMON_OSD=y
CONFIG_DRIVERS_PWM_OUT=y
CONFIG_DRIVERS_RC_INPUT=y
-1
View File
@@ -21,7 +21,6 @@ CONFIG_DRIVERS_IMU_BOSCH_BMI088=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y
CONFIG_DRIVERS_MAGNETOMETER_ISENTEK_IST8310=y
CONFIG_DRIVERS_MAGNETOMETER_QMC5883L=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_DRIVERS_PWM_OUT=y
CONFIG_DRIVERS_RC_INPUT=y
CONFIG_COMMON_TELEMETRY=y
-1
View File
@@ -21,7 +21,6 @@ CONFIG_DRIVERS_IMU_BOSCH_BMI088=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y
CONFIG_DRIVERS_MAGNETOMETER_ISENTEK_IST8310=y
CONFIG_DRIVERS_MAGNETOMETER_QMC5883L=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_DRIVERS_PWM_OUT=y
CONFIG_DRIVERS_RC_INPUT=y
CONFIG_COMMON_TELEMETRY=y
-1
View File
@@ -29,7 +29,6 @@ CONFIG_DRIVERS_OSD_MSP_OSD=y
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
CONFIG_DRIVERS_POWER_MONITOR_INA228=y
CONFIG_DRIVERS_POWER_MONITOR_INA238=y
CONFIG_DRIVERS_POWER_MONITOR_PM_SELECTOR_AUTERION=y
CONFIG_DRIVERS_PWM_OUT=y
CONFIG_DRIVERS_PX4IO=y
CONFIG_DRIVERS_RC_INPUT=y
+1 -1
View File
@@ -25,7 +25,7 @@ These flight controllers are [manufacturer supported](../flight_controller/autop
- 32 Bit Arm® Cortex®-M3, 72MHz, 20KB SRAM
- On-board sensors
- Accel/Gyro: ICM-42688-P\*2(Version1), BMI270\*2(Version2)
- Mag: IST8310
- Mag: QMC5883P
- Barometer: DPS310(Version1),SPL06(Version2)
### Interfaces
+3 -1
View File
@@ -321,9 +321,11 @@ The configuration can be done using the [UXRCE-DDS parameters](../advanced_confi
- [UXRCE_DDS_SYNCT](../advanced_config/parameter_reference.md#UXRCE_DDS_SYNCT): Bridge time synchronization enable.
The uXRCE-DDS client module can synchronize the timestamp of the messages exchanged over the bridge.
This is the default configuration. In certain situations, for example during [simulations](../ros2/user_guide.md#ros-gazebo-and-px4-time-synchronization), this feature may be disabled.
- [UXRCE_DDS_NS_IDX](../advanced_config/parameter_reference.md#UXRCE_DDS_NS_IDX) <Badge type="tip" text="PX4 v1.17" />: Index-based namespace definition
- [UXRCE_DDS_NS_IDX](../advanced_config/parameter_reference.md#UXRCE_DDS_NS_IDX) <Badge type="tip" text="PX4 v1.17" />: Index-based namespace definition.
Setting this parameter to any value other than `-1` creates a namespace with the prefix `uav_` and the specified value, e.g. `uav_0`, `uav_1`, etc.
See [namespace](#customizing-the-namespace) for methods to define richer or arbitrary namespaces.
- [`UXRCE_DDS_FLCTRL`](../advanced_config/parameter_reference.md#UXRCE_DDS_FLCTRL) <Badge type="tip" text="PX4 main" />: Serial port hardware flow control enable.
To use hardware flow control, a custom MicroXRCE Agent needs to be adopted. Please refer to [this PR](https://github.com/eProsima/Micro-XRCE-DDS-Agent/pull/407) for the required changes, cherry-pick them on top of the [agent version](#build-run-within-ros-2-workspace) you need to use and then run the agent with the additional `--flow-control` option.
::: info
Many ports are already have a default configuration.
+1 -1
View File
@@ -25,7 +25,7 @@ It brings you ultimate performance, stability, and reliability in every aspect.
- 32 Bit Arm® Cortex®-M3, 72MHz, 20KB SRAM
- 내장 센서 :
- Accel/Gyro: ICM-42688-P\*2(Version1), BMI270\*2(Version2)
- 자력계: IST8310
- 자력계: QMC5883P
- Barometer: DPS310(Version1),SPL06(Version2)
### 인터페이스
+1 -1
View File
@@ -25,7 +25,7 @@ These flight controllers are [manufacturer supported](../flight_controller/autop
- 32 Bit Arm® Cortex®-M3, 72MHz, 20KB SRAM
- Сенсори на платі
- Accel/Gyro: ICM-42688-P\*2(Version1), BMI270\*2(Version2)
- Mag: IST8310
- Mag: QMC5883P
- Barometer: DPS310(Version1),SPL06(Version2)
### Інтерфейси
+1 -1
View File
@@ -25,7 +25,7 @@ These flight controllers are [manufacturer supported](../flight_controller/autop
- 32 Bit Arm® Cortex®-M3, 72MHz, 20KB SRAM
- On-board sensors
- Accel/Gyro: ICM-42688-P\*2(Version1), BMI270\*2(Version2)
- Mag: IST8310
- Mag: QMC5883P
- Barometer: DPS310(Version1),SPL06(Version2)
### 接口
+1 -1
View File
@@ -4,4 +4,4 @@ uint8 INDEX_PITCH = 1
uint8 INDEX_YAW = 2
uint64 timestamp_sample # the timestamp the data this control response is based on was sampled
float32[3] control
float32[3] control # Normalized output. 1 means maximum positive position. -1 maximum negative position. 0 means no deflection. NaN maps to disarmed.
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2021 PX4 Development Team. All rights reserved.
* Copyright (c) 2026 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
@@ -35,26 +35,26 @@
* Automatic handling power monitors
*/
#include "PowerMonitorSelectorAuterion.h"
#include "../ina226/ina226.h"
#include "AuterionAutostarter.h"
#include "../power_monitor/ina226/ina226.h"
#include <builtin/builtin.h>
#include <sys/wait.h>
PowerMonitorSelectorAuterion::PowerMonitorSelectorAuterion() :
AuterionAutostarter::AuterionAutostarter() :
ScheduledWorkItem(MODULE_NAME, px4::wq_configurations::hp_default)
{
}
PowerMonitorSelectorAuterion::~PowerMonitorSelectorAuterion() = default;
AuterionAutostarter::~AuterionAutostarter() = default;
bool PowerMonitorSelectorAuterion::init()
bool AuterionAutostarter::init()
{
ScheduleNow();
return true;
}
void PowerMonitorSelectorAuterion::Run()
void AuterionAutostarter::Run()
{
if (should_exit()) {
exit_and_cleanup();
@@ -83,33 +83,48 @@ void PowerMonitorSelectorAuterion::Run()
ScheduleDelayed(RUN_INTERVAL);
}
void PowerMonitorSelectorAuterion::try_eeprom_start()
void AuterionAutostarter::try_eeprom_start()
{
static_assert(sizeof(_buses) / sizeof(Buses) == BUSES_NUMBERS, "Unexpected number of buses");
static_assert(sizeof(_eeprom_blocks_pm) / sizeof(EepromBlockPm) == EEPROM_MAX_BLOCKS,
static_assert(sizeof(_eeprom_decoded_blocks) / sizeof(DecodedBlock) == EEPROM_MAX_BLOCKS,
"Unexpected number of EEPROM PM blocks");
for (uint32_t i = 0U; i < BUSES_NUMBERS; i++) {
if (!_buses[i].started) {
if (eeprom_read(i) == PX4_OK) {
for (int ii = 0U; ii < _eeprom_valid_blocks_pm && ii < EEPROM_MAX_BLOCKS; ii++) {
EepromBlockPm eeprom_block_pm = _eeprom_blocks_pm[ii];
int ret_val = PX4_OK;
uint16_t dev_type = eeprom_block_pm.dev_type;
set_max_current(dev_type, eeprom_block_pm.max_current);
set_shunt_value(dev_type, eeprom_block_pm.shunt_value);
int ret_val = start_pm(_buses[i].bus_number, dev_type, eeprom_block_pm.i2c_addr, _buses[i].id);
for (uint32_t ii = 0U; ii < _eeprom_num_decoded_blocks && ii < EEPROM_MAX_BLOCKS; ii++) {
DecodedBlock decoded_block = _eeprom_decoded_blocks[ii];
if (ret_val == PX4_OK) {
_buses[i].started = true;
switch (decoded_block.block_type) {
case TYPE_PM: {
EepromBlockPm block_pm = decoded_block.block_pm;
uint16_t dev_type = block_pm.dev_type;
set_max_current(dev_type, block_pm.max_current);
set_shunt_value(dev_type, block_pm.shunt_value);
ret_val |= start_pm(_buses[i].bus_number, dev_type, block_pm.i2c_addr, _buses[i].id);
break;
}
case TYPE_PWM_EXPANDER: {
EepromBlockPwmExpander block_pwm_expader = decoded_block.block_pwm_expander;
uint16_t dev_type = block_pwm_expader.dev_type;
ret_val |= start_i2c_driver(_buses[i].bus_number, dev_type, block_pwm_expader.i2c_addr);
break;
}
}
}
if (ret_val == PX4_OK) {
_buses[i].started = true;
}
}
}
}
}
void PowerMonitorSelectorAuterion::try_probe_start()
void AuterionAutostarter::try_probe_start()
{
static_assert(sizeof(_sensors) / sizeof(Sensor) == SENSORS_NUMBER, "Unexpected number of sensors");
@@ -133,7 +148,7 @@ void PowerMonitorSelectorAuterion::try_probe_start()
}
}
int PowerMonitorSelectorAuterion::ina226_probe(const uint32_t instance) const
int AuterionAutostarter::ina226_probe(const uint32_t instance) const
{
I2CWrapper i2c{_sensors[instance].bus_number};
int ret = PX4_ERROR;
@@ -177,10 +192,10 @@ int PowerMonitorSelectorAuterion::ina226_probe(const uint32_t instance) const
return ret;
}
int PowerMonitorSelectorAuterion::eeprom_read(const uint32_t instance)
int AuterionAutostarter::eeprom_read(const uint32_t instance)
{
I2CWrapper i2c{_buses[instance].bus_number};
_eeprom_valid_blocks_pm = 0;
_eeprom_num_decoded_blocks = 0;
EepromHeader eeprom_header;
if (i2c.is_valid()) {
@@ -228,7 +243,7 @@ int PowerMonitorSelectorAuterion::eeprom_read(const uint32_t instance)
return PX4_ERROR;
}
_eeprom_valid_blocks_pm = transferred_blocks;
_eeprom_num_decoded_blocks = transferred_blocks;
return PX4_OK;
} else {
@@ -236,7 +251,7 @@ int PowerMonitorSelectorAuterion::eeprom_read(const uint32_t instance)
}
}
bool PowerMonitorSelectorAuterion::is_eeprom_header_valid(EepromHeader *eeprom_header) const
bool AuterionAutostarter::is_eeprom_header_valid(EepromHeader *eeprom_header) const
{
if (eeprom_header->magic != EEPROM_MAGIC
|| eeprom_header->version != EEPROM_VERSION
@@ -247,8 +262,8 @@ bool PowerMonitorSelectorAuterion::is_eeprom_header_valid(EepromHeader *eeprom_h
return true;
}
int PowerMonitorSelectorAuterion::eeprom_read_block(struct i2c_master_s *i2c, const uint32_t instance,
const uint16_t transferred_blocks, uint16_t &crc)
int AuterionAutostarter::eeprom_read_block(struct i2c_master_s *i2c, const uint32_t instance, const uint16_t transferred_blocks,
uint16_t &crc)
{
int ret = PX4_ERROR;
EepromBlockHeader eeprom_block_header;
@@ -263,44 +278,76 @@ int PowerMonitorSelectorAuterion::eeprom_read_block(struct i2c_master_s *i2c, co
ret = I2C_TRANSFER(i2c, &msg, 1);
if (ret == PX4_OK && is_eeprom_block_header_valid(&eeprom_block_header)) {
EepromBlockPm &eeprom_block_pm = _eeprom_blocks_pm[transferred_blocks];
eeprom_block_pm.block_header = eeprom_block_header;
if (ret == PX4_OK) {
DecodedBlock &block = _eeprom_decoded_blocks[transferred_blocks];
/* Already read the header, so just need to read the block itself now */
uint8_t *data_ptr = reinterpret_cast<uint8_t *>(&eeprom_block_pm) + offsetof(EepromBlockPm, dev_type);
size_t data_size = sizeof(EepromBlockPm) - offsetof(EepromBlockPm, dev_type);
switch (eeprom_block_header.block_type) {
case TYPE_PM: {
if (!is_eeprom_block_header_valid<TYPE_PM, EepromBlockPm>(&eeprom_block_header)) { return PX4_ERROR; }
/* Read the actual block data from the EEPROM */
msg.buffer = data_ptr;
msg.length = data_size;
EepromBlockPm *block_pm = &block.block_pm;
block.block_type = TYPE_PM;
block_pm->block_header = eeprom_block_header;
ret |= eeprom_read_block_data<EepromBlockPm>(i2c, instance, crc, block_pm);
break;
}
ret = I2C_TRANSFER(i2c, &msg, 1);
case TYPE_PWM_EXPANDER: {
if (!is_eeprom_block_header_valid<TYPE_PWM_EXPANDER, EepromBlockPwmExpander>(&eeprom_block_header)) { return PX4_ERROR; }
if (ret == PX4_OK) {
crc = crc16_update(crc, reinterpret_cast<uint8_t *>(&eeprom_block_pm), sizeof(EepromBlockPm));
EepromBlockPwmExpander *block_pwm_expander = &block.block_pwm_expander;
block.block_type = TYPE_PWM_EXPANDER;
block_pwm_expander->block_header = eeprom_block_header;
ret |= eeprom_read_block_data<EepromBlockPwmExpander>(i2c, instance, crc, block_pwm_expander);
break;
}
default:
return PX4_ERROR;
}
} else {
ret = PX4_ERROR;
}
return ret;
}
bool PowerMonitorSelectorAuterion::is_eeprom_block_header_valid(EepromBlockHeader *eeprom_block_header) const
template <typename T>
int AuterionAutostarter::eeprom_read_block_data(struct i2c_master_s *i2c, const uint32_t instance, uint16_t &crc, T *block)
{
if (eeprom_block_header->block_type != BlockType::TYPE_PM
/* Already read the header, so just need to read the block itself now */
uint8_t *data_ptr = reinterpret_cast<uint8_t *>(block) + offsetof(T, dev_type);
size_t data_size = sizeof(T) - offsetof(T, dev_type);
/* Read the actual block data from the EEPROM */
struct i2c_msg_s msg;
msg.frequency = I2C_SPEED_STANDARD;
msg.addr = _buses[instance].eeprom_i2c_addr;
msg.flags = I2C_M_READ;
msg.buffer = data_ptr;
msg.length = data_size;
int ret = I2C_TRANSFER(i2c, &msg, 1);
if (ret == PX4_OK) {
crc = crc16_update(crc, reinterpret_cast<uint8_t *>(block), sizeof(T));
}
return ret;
}
template <AuterionAutostarter::BlockType ExpectedBlockType, typename T>
bool AuterionAutostarter::is_eeprom_block_header_valid(EepromBlockHeader *eeprom_block_header) const
{
if (eeprom_block_header->block_type != ExpectedBlockType
|| eeprom_block_header->block_type_version != EEPROM_BLOCK_TYPE_VERSION
|| eeprom_block_header->block_length != sizeof(EepromBlockPm)) {
|| eeprom_block_header->block_length != sizeof(T)) {
return false;
}
return true;
}
int PowerMonitorSelectorAuterion::start_pm(const uint8_t bus_number, const uint16_t dev_type,
const uint16_t i2c_addr, const uint16_t id) const
int AuterionAutostarter::start_pm(const uint8_t bus_number, const uint16_t dev_type,
const uint16_t i2c_addr, const uint16_t id) const
{
char bus_number_str[BUS_MAX_LEN];
snprintf(bus_number_str, sizeof(bus_number_str), "%u", bus_number);
@@ -312,33 +359,51 @@ int PowerMonitorSelectorAuterion::start_pm(const uint8_t bus_number, const uint1
snprintf(id_str, sizeof(id_str), "%u", id);
const char *start_command = get_start_command(dev_type);
if (start_command == nullptr) {
return PX4_ERROR;
}
const char *start_argv[] {
start_command,
"-X", "-b", bus_number_str, "-a", i2c_addr_str,
"-t", id_str, "-q", "start", NULL
};
int status = PX4_ERROR;
int pid = exec_builtin(start_command, (char **)start_argv, NULL, 0);
return start(start_command, start_argv);
}
if (pid != -1) {
waitpid(pid, &status, WUNTRACED);
int AuterionAutostarter::start_i2c_driver(const uint8_t bus_number, const uint16_t dev_type, const uint16_t i2c_addr) const
{
char bus_number_str[BUS_MAX_LEN];
snprintf(bus_number_str, sizeof(bus_number_str), "%u", bus_number);
char i2c_addr_str[I2C_ADDR_MAX_LEN];
snprintf(i2c_addr_str, sizeof(i2c_addr_str), "%u", i2c_addr);
const char *start_command = get_start_command(dev_type);
const char *start_argv[] {
start_command,
"-X", "-b", bus_number_str, "-a", i2c_addr_str,
"-q", "start", NULL
};
return start(start_command, start_argv);
}
int AuterionAutostarter::start(const char *start_command, const char **start_argv) const
{
int status = PX4_ERROR;
if (start_command != nullptr) {
int pid = exec_builtin(start_command, (char **)start_argv, NULL, 0);
if (pid != -1) {
waitpid(pid, &status, WUNTRACED);
}
}
return status;
}
const char *PowerMonitorSelectorAuterion::get_start_command(const uint16_t dev_type) const
const char *AuterionAutostarter::get_start_command(const uint16_t dev_type) const
{
switch (dev_type) {
case DRV_POWER_DEVTYPE_INA220:
return "ina220";
case DRV_POWER_DEVTYPE_INA226:
return "ina226";
@@ -348,12 +413,15 @@ const char *PowerMonitorSelectorAuterion::get_start_command(const uint16_t dev_t
case DRV_POWER_DEVTYPE_INA238:
return "ina238";
case DRV_PWM_DEVTYPE_PCA9685:
return "pca9685_pwm_out";
default:
return nullptr;
}
}
bool PowerMonitorSelectorAuterion::is_user_configured(const uint16_t dev_type) const
bool AuterionAutostarter::is_user_configured(const uint16_t dev_type) const
{
const char *ina_type = get_ina_type(dev_type);
@@ -369,7 +437,7 @@ bool PowerMonitorSelectorAuterion::is_user_configured(const uint16_t dev_type) c
return sens_en != 0;
}
void PowerMonitorSelectorAuterion::set_max_current(const uint16_t dev_type, const float max_current) const
void AuterionAutostarter::set_max_current(const uint16_t dev_type, const float max_current) const
{
const char *ina_type = get_ina_type(dev_type);
@@ -382,7 +450,7 @@ void PowerMonitorSelectorAuterion::set_max_current(const uint16_t dev_type, cons
set_float_param(param_name, max_current);
}
void PowerMonitorSelectorAuterion::set_shunt_value(const uint16_t dev_type, const float shunt_value) const
void AuterionAutostarter::set_shunt_value(const uint16_t dev_type, const float shunt_value) const
{
const char *ina_type = get_ina_type(dev_type);
@@ -395,7 +463,7 @@ void PowerMonitorSelectorAuterion::set_shunt_value(const uint16_t dev_type, cons
set_float_param(param_name, shunt_value);
}
void PowerMonitorSelectorAuterion::set_float_param(const char *param_name, const float param_val) const
void AuterionAutostarter::set_float_param(const char *param_name, const float param_val) const
{
float current_param_value = 0;
param_get(param_find(param_name), &current_param_value);
@@ -405,12 +473,9 @@ void PowerMonitorSelectorAuterion::set_float_param(const char *param_name, const
}
}
const char *PowerMonitorSelectorAuterion::get_ina_type(const uint16_t dev_type) const
const char *AuterionAutostarter::get_ina_type(const uint16_t dev_type) const
{
switch (dev_type) {
case DRV_POWER_DEVTYPE_INA220:
return "220";
case DRV_POWER_DEVTYPE_INA226:
return "226";
@@ -425,7 +490,7 @@ const char *PowerMonitorSelectorAuterion::get_ina_type(const uint16_t dev_type)
}
}
uint16_t PowerMonitorSelectorAuterion::crc16_update(const uint16_t current_crc, const uint8_t *data_p,
uint16_t AuterionAutostarter::crc16_update(const uint16_t current_crc, const uint8_t *data_p,
size_t length) const
{
uint8_t x;
@@ -440,9 +505,9 @@ uint16_t PowerMonitorSelectorAuterion::crc16_update(const uint16_t current_crc,
return crc;
}
int PowerMonitorSelectorAuterion::task_spawn(int argc, char *argv[])
int AuterionAutostarter::task_spawn(int argc, char *argv[])
{
PowerMonitorSelectorAuterion *instance = new PowerMonitorSelectorAuterion();
AuterionAutostarter *instance = new AuterionAutostarter();
if (instance) {
_object.store(instance);
@@ -463,12 +528,12 @@ int PowerMonitorSelectorAuterion::task_spawn(int argc, char *argv[])
return PX4_ERROR;
}
int PowerMonitorSelectorAuterion::custom_command(int argc, char *argv[])
int AuterionAutostarter::custom_command(int argc, char *argv[])
{
return print_usage("unknown command");
}
int PowerMonitorSelectorAuterion::print_usage(const char *reason)
int AuterionAutostarter::print_usage(const char *reason)
{
if (reason) {
PX4_WARN("%s\n", reason);
@@ -481,14 +546,14 @@ Driver for starting and auto-detecting different power monitors.
)DESCR_STR");
PRINT_MODULE_USAGE_NAME("pm_selector_auterion", "driver");
PRINT_MODULE_USAGE_NAME("auterion_autostarter", "driver");
PRINT_MODULE_USAGE_COMMAND("start");
PRINT_MODULE_USAGE_DEFAULT_COMMANDS();
return 0;
}
extern "C" __EXPORT int pm_selector_auterion_main(int argc, char *argv[])
extern "C" __EXPORT int auterion_autostarter_main(int argc, char *argv[])
{
return PowerMonitorSelectorAuterion::main(argc, argv);
return AuterionAutostarter::main(argc, argv);
}
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (C) 2021 PX4 Development Team. All rights reserved.
* Copyright (C) 2026 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
@@ -71,12 +71,12 @@ private:
struct i2c_master_s *_i2c {nullptr};
};
class PowerMonitorSelectorAuterion : public ModuleBase<PowerMonitorSelectorAuterion>, public px4::ScheduledWorkItem
class AuterionAutostarter : public ModuleBase<AuterionAutostarter>, public px4::ScheduledWorkItem
{
public:
PowerMonitorSelectorAuterion();
virtual ~PowerMonitorSelectorAuterion();
AuterionAutostarter();
virtual ~AuterionAutostarter();
/** @see ModuleBase */
static int task_spawn(int argc, char *argv[]);
@@ -89,7 +89,14 @@ public:
private:
enum BlockType : uint8_t {
TYPE_PM = 0
TYPE_PM = 0,
TYPE_PWM_EXPANDER = 1,
};
enum ClockType : uint8_t {
CLOCK_NONE = 0,
CLOCK_INTERNAL = 1,
CLOCK_EXTERNAL_GENERIC = 2,
};
struct Buses {
@@ -117,7 +124,7 @@ private:
uint16_t flags; /**< offset 6 */
uint16_t num_blocks; /**< offset 8 */
uint8_t _reserved1[2]; /**< offset 10 */
};
} __attribute__((aligned(4)));
#pragma pack(pop)
#pragma pack(push, 1)
@@ -125,11 +132,11 @@ private:
uint8_t block_type; /**< offset 0 */
uint8_t block_type_version; /**< offset 1 */
uint16_t block_length; /**< offset 2 */
};
} __attribute__((aligned(4)));
#pragma pack(pop)
#pragma pack(push, 1)
/* Block n starts at 12 + (n * 20) */
/* Block n starts at 12 + (n * 20), each block needs to contain a block_header and dev_type! */
struct EepromBlockPm {
EepromBlockHeader block_header; /**< offset 0 */
uint16_t dev_type; /**< offset 4 */
@@ -138,9 +145,33 @@ private:
uint8_t _padding1[2]; /**< offset 10 */
float max_current; /**< offset 12 */
float shunt_value; /**< offset 16 */
};
} __attribute__((aligned(4)));
#pragma pack(pop)
#pragma pack(push, 1)
/* Block n starts at 12 + (n * 20), each block needs to contain a block_header and dev_type! */
struct EepromBlockPwmExpander {
EepromBlockHeader block_header; /**< offset 0 */
uint16_t dev_type; /**< offset 4 */
uint16_t sensor_type; /**< offset 6 */
uint16_t i2c_addr; /**< offset 8 */
uint16_t num_channels; /**< offset 10 */
uint16_t offset_channels; /**< offset 12 */
ClockType clock_type; /**< offset 14 */
uint8_t _padding1; /**< offset 15 */
float signal_level; /**< offset 16 */
} __attribute__((aligned(4)));
#pragma pack(pop)
struct DecodedBlock {
BlockType block_type;
union {
EepromBlockPm block_pm;
EepromBlockPwmExpander block_pwm_expander;
};
};
void Run() override;
bool init();
@@ -152,12 +183,16 @@ private:
int eeprom_read(const uint32_t instance);
bool is_eeprom_header_valid(EepromHeader *eeprom_header) const;
int eeprom_read_block(struct i2c_master_s *i2c, const uint32_t instance, const uint16_t transferred_blocks,
uint16_t &crc);
int eeprom_read_block(struct i2c_master_s *i2c, const uint32_t instance, const uint16_t transferred_blocks, uint16_t &crc);
template <typename T>
int eeprom_read_block_data(struct i2c_master_s *i2c, const uint32_t instance, uint16_t &crc, T *block);
template <AuterionAutostarter::BlockType ExpectedBlockType, typename T>
bool is_eeprom_block_header_valid(EepromBlockHeader *eeprom_block_header) const;
int start_pm(const uint8_t bus_number, const uint16_t dev_type, const uint16_t i2c_addr, const uint16_t id) const;
int start_i2c_driver(const uint8_t bus_number, const uint16_t dev_type, const uint16_t i2c_addr) const;
const char *get_start_command(const uint16_t dev_type) const;
int start(const char *start_command, const char **start_argv) const;
bool is_user_configured(const uint16_t dev_type) const;
void set_max_current(const uint16_t dev_type, const float max_current) const;
@@ -234,6 +269,6 @@ private:
}
};
EepromBlockPm _eeprom_blocks_pm[EEPROM_MAX_BLOCKS] = { 0 };
uint16_t _eeprom_valid_blocks_pm = 0;
DecodedBlock _eeprom_decoded_blocks[EEPROM_MAX_BLOCKS];
uint16_t _eeprom_num_decoded_blocks = 0;
};
@@ -31,10 +31,10 @@
#
############################################################################
px4_add_module(
MODULE drivers__power_monitor_pm_selector_auterion
MAIN pm_selector_auterion
MODULE drivers__auterion_autostarter
MAIN auterion_autostarter
SRCS
PowerMonitorSelectorAuterion.cpp
AuterionAutostarter.cpp
DEPENDS
px4_work_queue
)
+5
View File
@@ -0,0 +1,5 @@
menuconfig DRIVERS_AUTERION_AUTOSTARTER
bool "auterion_autostarter"
default n
---help---
Enable support for auterion_autostarter
+18 -17
View File
@@ -77,6 +77,10 @@ AUAV::~AUAV()
void AUAV::RunImpl()
{
switch (_state) {
case STATE::READ_FACTORY_DATA:
handle_state_read_factory_data();
break;
case STATE::READ_CALIBDATA:
handle_state_read_calibdata();
break;
@@ -107,23 +111,6 @@ int AUAV::init()
return ret;
}
int32_t hw_model = 0;
param_get(param_find("SENS_EN_AUAVX"), &hw_model);
switch (hw_model) {
case 1: /* AUAV L05D (+- 5 inH20) */
_cal_range = 10.0f;
break;
case 2: /* AUAV L10D (+- 10 inH20) */
_cal_range = 20.0f;
break;
case 3: /* AUAV L30D (+- 30 inH20) */
_cal_range = 60.0f;
break;
}
ScheduleClear();
ScheduleNow();
return PX4_OK;
@@ -148,6 +135,20 @@ int AUAV::probe()
return PX4_ERROR;
}
void AUAV::handle_state_read_factory_data()
{
int status = read_factory_data();
if (status == PX4_OK) {
/* Factory data read or sensor does not have any, move to next state */
_state = STATE::READ_CALIBDATA;
ScheduleNow();
} else {
ScheduleDelayed(100_ms);
}
}
void AUAV::handle_state_read_calibdata()
{
int status = PX4_OK;
@@ -61,6 +61,7 @@ public:
protected:
enum class STATE : uint8_t {
READ_FACTORY_DATA,
READ_CALIBDATA,
REQUEST_MEASUREMENT,
GATHER_MEASUREMENT
@@ -107,7 +108,9 @@ protected:
virtual int64_t get_conversion_interval() const = 0;
virtual calib_eeprom_addr_t get_calib_eeprom_addr() const = 0;
virtual float process_pressure_dig(const float pressure_dig) const = 0;
virtual int read_factory_data() = 0;
void handle_state_read_factory_data();
void handle_state_read_calibdata();
void handle_state_request_measurement();
void handle_state_gather_measurement();
@@ -117,8 +120,7 @@ protected:
float correct_pressure(const uint32_t pressure_raw, const uint32_t temperature_raw) const;
float process_temperature_raw(const float temperature_raw) const;
float _cal_range{10.0f};
STATE _state{STATE::READ_CALIBDATA};
STATE _state{STATE::READ_FACTORY_DATA};
calib_data_t _calib_data {};
perf_counter_t _sample_perf;
@@ -77,3 +77,9 @@ float AUAV_Absolute::process_pressure_dig(const float pressure_dig) const
const float pressure_mbar = 250.f + 1.25f * ((pressure_dig - (0.1f * (1 << 24))) / (1 << 24)) * 1000.f;
return pressure_mbar * MBAR_TO_PA;
}
int AUAV_Absolute::read_factory_data()
{
/* Absolute sensor doesn't need to read factory data */
return PX4_OK;
}
@@ -68,6 +68,7 @@ private:
int64_t get_conversion_interval() const override;
calib_eeprom_addr_t get_calib_eeprom_addr() const override;
float process_pressure_dig(const float pressure_dig) const override;
int read_factory_data() override;
uORB::PublicationMulti<sensor_baro_s> _sensor_baro_pub{ORB_ID(sensor_baro)};
};
@@ -33,10 +33,38 @@
#include "AUAV_Differential.hpp"
#include <parameters/param.h>
#include <cctype>
AUAV_Differential::AUAV_Differential(const I2CSPIDriverConfig &config) :
AUAV(config)
{
/* Initialize cal_range from parameter as fallback value */
int32_t hw_model = 0;
param_get(param_find("SENS_EN_AUAVX"), &hw_model);
switch (hw_model) {
case 1: /* AUAV L05D (+- 5 inH20) */
_cal_range = 10;
break;
case 2: /* AUAV L10D (+- 10 inH20) */
_cal_range = 20;
break;
case 3: /* AUAV L30D (+- 30 inH20) */
_cal_range = 60;
break;
default:
_cal_range = 10; /* Default fallback */
break;
}
}
void AUAV_Differential::print_status()
{
AUAV::print_status();
PX4_INFO("cal range: %" PRId32, _cal_range);
}
void AUAV_Differential::publish_pressure(const float pressure_p, const float temperature_c,
@@ -83,6 +111,52 @@ AUAV::calib_eeprom_addr_t AUAV_Differential::get_calib_eeprom_addr() const
float AUAV_Differential::process_pressure_dig(const float pressure_dig) const
{
const float pressure_in_h = 1.25f * ((pressure_dig - (1 << 23)) / (1 << 24)) * _cal_range;
const float pressure_in_h = 1.25f * ((pressure_dig - (1 << 23)) / (1 << 24)) * static_cast<float>(_cal_range);
return pressure_in_h * INH_TO_PA;
}
int AUAV_Differential::read_factory_data()
{
/* The differential sensor needs the cal_range from the absolute sensor's EEPROM.
* Temporarily switch to the absolute sensor's I2C address to read it, then switch back. */
uint8_t original_address = get_device_address();
set_device_address(I2C_ADDRESS_ABSOLUTE);
/* Read the calibration range from the absolute sensor's EEPROM */
uint16_t factory_data = 0;
int status = read_calibration_eeprom(EEPROM_ABS_CAL_RNG, factory_data);
set_device_address(original_address);
if (status != PX4_OK) {
return status;
}
/* If EEPROM data is 0, stop trying (sensor does not have factory data) */
if (factory_data == 0) {
PX4_INFO("Differential: cal range data is 0, using fallback value");
return PX4_OK;
}
/* Decode the two bytes as ASCII characters */
uint8_t char_high = (factory_data >> 8) & 0xFF;
uint8_t char_low = factory_data & 0xFF;
/* Validate that both characters are ASCII digits (0-9) */
if (!isdigit(char_high) || !isdigit(char_low)) {
return PX4_ERROR;
}
int32_t sensor_type = ((char_high - '0') * 10) + (char_low - '0');
/* Check if the detected sensor type is valid */
if (sensor_type != AUAV_LD_05 && sensor_type != AUAV_LD_10 && sensor_type != AUAV_LD_30) {
return PX4_ERROR;
}
_cal_range = sensor_type * 2;
PX4_INFO("Differential: read cal range %" PRId32 " from absolute sensor EEPROM", _cal_range);
return PX4_OK;
}

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