mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-06-09 21:10:05 +08:00
Compare commits
13 Commits
| Author | SHA1 | Date | |
|---|---|---|---|
| 8575199bc7 | |||
| 8dd14d9aaa | |||
| 1e4d7429e1 | |||
| 2c97a875bf | |||
| 2065f577d6 | |||
| a0560d2d82 | |||
| 3c79f25e10 | |||
| db85e12b9f | |||
| 5125059b8f | |||
| e22329d074 | |||
| 3041960cf1 | |||
| d9039b0cf6 | |||
| b054f99e26 |
@@ -29,7 +29,6 @@ set LOGGER_ARGS ""
|
||||
set LOGGER_BUF 8
|
||||
set PARAM_FILE ""
|
||||
set PARAM_BACKUP_FILE ""
|
||||
set RC_INPUT_ARGS ""
|
||||
set STORAGE_AVAILABLE no
|
||||
set SDCARD_EXT_PATH /fs/microsd/ext_autostart
|
||||
set SDCARD_FORMAT no
|
||||
@@ -500,9 +499,6 @@ else
|
||||
#
|
||||
. ${R}etc/init.d/rc.serial
|
||||
|
||||
# Must be started after the serial config is read
|
||||
rc_input start $RC_INPUT_ARGS
|
||||
|
||||
# Manages USB interface
|
||||
if param greater -s SYS_USB_AUTO -1
|
||||
then
|
||||
@@ -664,7 +660,6 @@ unset LOGGER_BUF
|
||||
unset PARAM_FILE
|
||||
unset PARAM_BACKUP_FILE
|
||||
unset PARAM_DEFAULTS_VER
|
||||
unset RC_INPUT_ARGS
|
||||
unset STORAGE_AVAILABLE
|
||||
unset SDCARD_EXT_PATH
|
||||
unset SDCARD_FORMAT
|
||||
|
||||
@@ -4,6 +4,7 @@ CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS2"
|
||||
CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS0"
|
||||
CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS1"
|
||||
CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS4"
|
||||
CONFIG_BOARD_SERIAL_RC="/dev/ttyS3"
|
||||
CONFIG_DRIVERS_ADC_ADS1115=y
|
||||
CONFIG_DRIVERS_ADC_BOARD_ADC=y
|
||||
CONFIG_DRIVERS_BAROMETER_DPS310=y
|
||||
|
||||
@@ -113,9 +113,6 @@
|
||||
#define HRT_PPM_CHANNEL /* T3C3 */ 3 /* use capture/compare channel 3 */
|
||||
#define GPIO_PPM_IN /* PB0 T3C3 */ GPIO_TIM3_CH3IN_1
|
||||
|
||||
/* RC Serial port */
|
||||
#define RC_SERIAL_PORT "/dev/ttyS3"
|
||||
|
||||
#define GPIO_RSSI_IN /* PC1 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN1)
|
||||
|
||||
/* Safety Switch: Enable the FMU to control it if there is no px4io fixme:This should be BOARD_SAFETY_LED(__ontrue) */
|
||||
|
||||
@@ -4,6 +4,7 @@ CONFIG_BOARD_CONSTRAINED_MEMORY=y
|
||||
CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS3"
|
||||
CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS1"
|
||||
CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS2"
|
||||
CONFIG_BOARD_SERIAL_RC="/dev/ttyS0"
|
||||
CONFIG_DRIVERS_ADC_ADS1115=y
|
||||
CONFIG_DRIVERS_ADC_BOARD_ADC=y
|
||||
CONFIG_COMMON_BAROMETERS=y
|
||||
|
||||
@@ -110,8 +110,6 @@
|
||||
#define PWMIN_TIMER_CHANNEL 1
|
||||
#define GPIO_PWM_IN GPIO_TIM1_CH1IN_2
|
||||
|
||||
#define RC_SERIAL_PORT "/dev/ttyS0"
|
||||
|
||||
// #define GPIO_RSSI_IN (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN1)
|
||||
#define GPIO_SBUS_INV (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN10)
|
||||
#define RC_INVERT_INPUT(_invert_true) px4_arch_gpiowrite(GPIO_SBUS_INV, _invert_true);
|
||||
|
||||
@@ -15,6 +15,7 @@ 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_GPS=y
|
||||
|
||||
@@ -322,10 +322,6 @@
|
||||
#define HRT_PPM_CHANNEL /* T8C1 */ 1 /* use capture/compare channel 1 */
|
||||
#define GPIO_PPM_IN /* PI5 T8C1 */ GPIO_TIM8_CH1IN_2
|
||||
|
||||
/* RC Serial port */
|
||||
|
||||
#define RC_SERIAL_PORT "/dev/ttyS5"
|
||||
|
||||
/* Input Capture Channels. */
|
||||
#define INPUT_CAP1_TIMER 1
|
||||
#define INPUT_CAP1_CHANNEL /* T1C2 */ 2
|
||||
|
||||
@@ -270,10 +270,6 @@
|
||||
#define HRT_TIMER 8 /* use timer8 for the HRT */
|
||||
#define HRT_TIMER_CHANNEL 3 /* use capture/compare channel 3 */
|
||||
|
||||
/* RC Serial port */
|
||||
|
||||
#define RC_SERIAL_PORT "/dev/ttyS4"
|
||||
|
||||
/* PWM input driver. Use FMU AUX5 pins attached to timer4 channel 2 */
|
||||
#define PWMIN_TIMER 4
|
||||
#define PWMIN_TIMER_CHANNEL /* T4C2 */ 2
|
||||
|
||||
@@ -1,5 +1,6 @@
|
||||
CONFIG_BOARD_TOOLCHAIN="arm-none-eabi"
|
||||
CONFIG_BOARD_ARCHITECTURE="cortex-m7"
|
||||
CONFIG_BOARD_SERIAL_RC="/dev/ttyS5"
|
||||
CONFIG_DRIVERS_ADC_BOARD_ADC=y
|
||||
CONFIG_DRIVERS_BAROMETER_MAIERTEK_MPC2520=y
|
||||
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
|
||||
|
||||
@@ -142,7 +142,6 @@
|
||||
#define HRT_TIMER_CHANNEL 3 /* use capture/compare channel 3 */
|
||||
|
||||
/* RC Serial port */
|
||||
#define RC_SERIAL_PORT "/dev/ttyS5"
|
||||
#define RC_SERIAL_SINGLEWIRE
|
||||
|
||||
/* power on/off */
|
||||
|
||||
@@ -8,6 +8,7 @@ CONFIG_BOARD_PARAM_FILE="/fs/microsd/params"
|
||||
CONFIG_DRIVERS_ADC_BOARD_ADC=y
|
||||
CONFIG_DRIVERS_BAROMETER_BMP388=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
|
||||
@@ -19,6 +20,9 @@ CONFIG_COMMON_LIGHT=y
|
||||
CONFIG_COMMON_MAGNETOMETER=y
|
||||
CONFIG_DATAMAN_PERSISTENT_STORAGE=n
|
||||
CONFIG_DRIVERS_PWM_OUT=y
|
||||
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
|
||||
CONFIG_DRIVERS_POWER_MONITOR_INA228=y
|
||||
CONFIG_DRIVERS_POWER_MONITOR_INA238=y
|
||||
CONFIG_DRIVERS_RC_INPUT=y
|
||||
CONFIG_DRIVERS_ROBOCLAW=y
|
||||
CONFIG_DRIVERS_UAVCAN=y
|
||||
@@ -42,6 +46,7 @@ CONFIG_FIGURE_OF_EIGHT=y
|
||||
CONFIG_MODULES_FW_RATE_CONTROL=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_GYRO_CALIBRATION=y
|
||||
CONFIG_MODULES_GYRO_FFT=y
|
||||
CONFIG_MODULES_HARDFAULT_STREAM=y
|
||||
CONFIG_MODULES_LAND_DETECTOR=y
|
||||
CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y
|
||||
|
||||
@@ -3,6 +3,12 @@
|
||||
# board specific defaults
|
||||
#------------------------------------------------------------------------------
|
||||
|
||||
# By disabling INA modules, we use the
|
||||
# i2c_launcher instead.
|
||||
param set-default SENS_EN_INA226 0
|
||||
param set-default SENS_EN_INA228 0
|
||||
param set-default SENS_EN_INA238 0
|
||||
|
||||
# Set the backend of the dataman to SRAM
|
||||
param set-default SYS_DM_BACKEND 1
|
||||
# Set TELEM1 as default mavlink connection
|
||||
|
||||
@@ -23,6 +23,48 @@ else
|
||||
bmm350 -I -R 8 start
|
||||
fi
|
||||
|
||||
if param compare SENS_EN_INA226 1
|
||||
then
|
||||
# Start Digital power monitors
|
||||
ina226 -X -b 1 -t 1 -k start
|
||||
|
||||
# Disable analog monitoring
|
||||
param set BAT1_V_CHANNEL -2
|
||||
|
||||
set INA_CONFIGURED yes
|
||||
fi
|
||||
|
||||
|
||||
if param compare SENS_EN_INA228 1
|
||||
then
|
||||
# Start Digital power monitors
|
||||
ina228 -X -b 1 -t 1 -k start
|
||||
|
||||
# Disable analog monitoring
|
||||
param set BAT1_V_CHANNEL -2
|
||||
|
||||
set INA_CONFIGURED yes
|
||||
fi
|
||||
|
||||
if param compare SENS_EN_INA238 1
|
||||
then
|
||||
# Start Digital power monitors
|
||||
ina238 -X -b 1 -t 1 -k start
|
||||
|
||||
# Disable analog monitoring
|
||||
param set BAT1_V_CHANNEL -2
|
||||
|
||||
set INA_CONFIGURED yes
|
||||
fi
|
||||
|
||||
if param compare BAT1_V_CHANNEL -2
|
||||
then
|
||||
if [ "$INA_CONFIGURED" != "yes" ]
|
||||
then
|
||||
param set BAT1_V_CHANNEL -1
|
||||
fi
|
||||
fi
|
||||
|
||||
# External compass on GPS1/I2C1 (the 3rd external bus): standard Holybro Pixhawk 4 or CUAV V5 GPS/compass puck (with lights, safety button, and buzzer)
|
||||
ist8310 -X -b 1 -R 10 start
|
||||
|
||||
|
||||
@@ -6,6 +6,7 @@ CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS0"
|
||||
CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS1"
|
||||
CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS2"
|
||||
CONFIG_BOARD_SERIAL_TEL4="/dev/ttyS3"
|
||||
CONFIG_BOARD_SERIAL_RC="/dev/ttyS4"
|
||||
CONFIG_DRIVERS_ADC_ADS1115=y
|
||||
CONFIG_DRIVERS_ADC_BOARD_ADC=y
|
||||
CONFIG_COMMON_BAROMETERS=y
|
||||
|
||||
@@ -102,9 +102,6 @@
|
||||
#define HRT_TIMER 5 /* use timer5 for the HRT */
|
||||
#define HRT_TIMER_CHANNEL 1 /* use capture/compare channel 3 */
|
||||
|
||||
/* RC Serial port */
|
||||
|
||||
#define RC_SERIAL_PORT "/dev/ttyS4"
|
||||
|
||||
/* Power switch controls ******************************************************/
|
||||
|
||||
|
||||
@@ -6,6 +6,7 @@ CONFIG_BOARD_SERIAL_GPS2="/dev/ttyS6"
|
||||
CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS5"
|
||||
CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS3"
|
||||
CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS1"
|
||||
CONFIG_BOARD_SERIAL_RC="/dev/ttyS4"
|
||||
CONFIG_DRIVERS_ADC_ADS1115=y
|
||||
CONFIG_DRIVERS_ADC_BOARD_ADC=y
|
||||
CONFIG_DRIVERS_BAROMETER_BMP581=y
|
||||
|
||||
@@ -227,8 +227,6 @@
|
||||
#define GPIO_PPM_IN /* PC6 T8C1 */ GPIO_TIM3_CH1IN_3
|
||||
|
||||
/* RC Serial port */
|
||||
|
||||
#define RC_SERIAL_PORT "/dev/ttyS4"
|
||||
#define RC_SERIAL_SINGLEWIRE
|
||||
|
||||
/* Input Capture Channels. */
|
||||
|
||||
@@ -4,6 +4,7 @@ CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS0"
|
||||
CONFIG_BOARD_SERIAL_GPS2="/dev/ttyS2"
|
||||
CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS1"
|
||||
CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS3"
|
||||
CONFIG_BOARD_SERIAL_RC="/dev/ttyS5"
|
||||
CONFIG_DRIVERS_ADC_ADS1115=y
|
||||
CONFIG_DRIVERS_ADC_BOARD_ADC=y
|
||||
CONFIG_COMMON_BAROMETERS=y
|
||||
|
||||
@@ -159,7 +159,7 @@
|
||||
|
||||
#define HRT_PPM_CHANNEL /* T3C1 */ 1 /* use capture/compare channel 1 */
|
||||
#define GPIO_PPM_IN /* PB4 T3C1 */ GPIO_TIM3_CH1IN_2
|
||||
#define RC_SERIAL_PORT "/dev/ttyS5"
|
||||
|
||||
#define RC_SERIAL_SINGLEWIRE
|
||||
|
||||
/**
|
||||
|
||||
@@ -4,6 +4,7 @@ CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS0"
|
||||
CONFIG_BOARD_SERIAL_GPS2="/dev/ttyS2"
|
||||
CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS1"
|
||||
CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS3"
|
||||
CONFIG_BOARD_SERIAL_RC="/dev/ttyS5"
|
||||
CONFIG_DRIVERS_ADC_ADS1115=y
|
||||
CONFIG_DRIVERS_ADC_BOARD_ADC=y
|
||||
CONFIG_COMMON_BAROMETERS=y
|
||||
|
||||
@@ -159,7 +159,7 @@
|
||||
|
||||
#define HRT_PPM_CHANNEL /* T3C1 */ 1 /* use capture/compare channel 1 */
|
||||
#define GPIO_PPM_IN /* PB4 T3C1 */ GPIO_TIM3_CH1IN_2
|
||||
#define RC_SERIAL_PORT "/dev/ttyS5"
|
||||
|
||||
#define RC_SERIAL_SINGLEWIRE
|
||||
|
||||
/**
|
||||
|
||||
@@ -6,6 +6,7 @@ CONFIG_BOARD_CONSTRAINED_MEMORY=y
|
||||
CONFIG_BOARD_EXTERNAL_METADATA=y
|
||||
CONFIG_BOARD_SERIAL_URT6="/dev/ttyS2"
|
||||
CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS1"
|
||||
CONFIG_BOARD_SERIAL_RC="/dev/ttyS0"
|
||||
CONFIG_DRIVERS_ADC_BOARD_ADC=y
|
||||
CONFIG_DRIVERS_BAROMETER_BMP280=y
|
||||
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
|
||||
|
||||
@@ -130,7 +130,6 @@
|
||||
#define HRT_PPM_CHANNEL 3 // capture/compare channel 3
|
||||
#define GPIO_PPM_IN (GPIO_ALT|GPIO_AF2|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN8)
|
||||
|
||||
#define RC_SERIAL_PORT "/dev/ttyS0"
|
||||
#define BOARD_SUPPORTS_RC_SERIAL_PORT_OUTPUT
|
||||
|
||||
/*
|
||||
|
||||
@@ -5,6 +5,7 @@ CONFIG_BOARD_NO_HELP=y
|
||||
CONFIG_BOARD_CONSTRAINED_MEMORY=y
|
||||
CONFIG_BOARD_SERIAL_URT6="/dev/ttyS2"
|
||||
CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS1"
|
||||
CONFIG_BOARD_SERIAL_RC="/dev/ttyS0"
|
||||
CONFIG_DRIVERS_ADC_BOARD_ADC=y
|
||||
CONFIG_DRIVERS_BAROMETER_BMP280=y
|
||||
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
|
||||
|
||||
@@ -134,7 +134,6 @@
|
||||
#define HRT_PPM_CHANNEL 3 // capture/compare channel 3
|
||||
#define GPIO_PPM_IN (GPIO_ALT|GPIO_AF2|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN8)
|
||||
|
||||
#define RC_SERIAL_PORT "/dev/ttyS0"
|
||||
#define BOARD_SUPPORTS_RC_SERIAL_PORT_OUTPUT
|
||||
|
||||
/*
|
||||
|
||||
@@ -145,7 +145,6 @@
|
||||
#define HRT_TIMER_CHANNEL 1 /* use capture/compare channel 1 */
|
||||
|
||||
/* RC Serial port */
|
||||
#define RC_SERIAL_PORT "/dev/ttyS4"
|
||||
#define BOARD_SUPPORTS_RC_SERIAL_PORT_OUTPUT
|
||||
|
||||
// #define GPIO_SBUS_INV (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN14)
|
||||
|
||||
@@ -148,7 +148,6 @@
|
||||
#define HRT_TIMER_CHANNEL 1 /* use capture/compare channel 1 */
|
||||
|
||||
/* RC Serial port */
|
||||
#define RC_SERIAL_PORT "/dev/ttyS5"
|
||||
#define BOARD_SUPPORTS_RC_SERIAL_PORT_OUTPUT
|
||||
|
||||
/* SD card bringup does not work if performed on the IDLE thread because it
|
||||
|
||||
@@ -111,8 +111,6 @@
|
||||
#define HRT_TIMER_CHANNEL 1 /* use capture/compare channel 1 */
|
||||
|
||||
/* RC Serial port */
|
||||
|
||||
#define RC_SERIAL_PORT "/dev/ttyS4"
|
||||
#define RC_SERIAL_SINGLEWIRE
|
||||
|
||||
#define GPIO_RSSI_IN /* PC5 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN5)
|
||||
|
||||
@@ -125,7 +125,6 @@
|
||||
|
||||
// So we can run CRSF on ttyS4, which corresponds to the TX6/RX6 pins
|
||||
/* RC Serial port */
|
||||
#define RC_SERIAL_PORT "/dev/ttyS4"
|
||||
#define BOARD_SUPPORTS_RC_SERIAL_PORT_OUTPUT
|
||||
|
||||
/* PWM input driver. Use FMU AUX5 pins attached to timer4 channel 2 */
|
||||
|
||||
@@ -5,6 +5,7 @@ CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS1"
|
||||
CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS2"
|
||||
CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS4"
|
||||
CONFIG_BOARD_SERIAL_TEL4="/dev/ttyS3"
|
||||
CONFIG_BOARD_SERIAL_RC="/dev/ttyS4"
|
||||
CONFIG_DRIVERS_ADC_ADS1115=y
|
||||
CONFIG_DRIVERS_ADC_BOARD_ADC=y
|
||||
CONFIG_COMMON_BAROMETERS=y
|
||||
|
||||
@@ -283,8 +283,6 @@
|
||||
#define GPIO_PPM_IN /* PI5 T8C1 */ GPIO_TIM8_CH1IN_2
|
||||
|
||||
/* RC Serial port */
|
||||
|
||||
#define RC_SERIAL_PORT "/dev/ttyS4"
|
||||
#define RC_SERIAL_SINGLEWIRE
|
||||
|
||||
/* PWM input driver. Use FMU AUX5 pins attached to timer4 channel 2 */
|
||||
|
||||
@@ -5,6 +5,7 @@ CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS2"
|
||||
CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS3"
|
||||
CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS5"
|
||||
CONFIG_BOARD_SERIAL_TEL4="/dev/ttyS6"
|
||||
CONFIG_BOARD_SERIAL_RC="/dev/ttyS4"
|
||||
CONFIG_DRIVERS_ADC_BOARD_ADC=y
|
||||
CONFIG_DRIVERS_BAROMETER_DPS310=y
|
||||
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
|
||||
|
||||
@@ -156,7 +156,6 @@
|
||||
|
||||
|
||||
/* RC Serial port */
|
||||
#define RC_SERIAL_PORT "/dev/ttyS4"
|
||||
#define BOARD_SUPPORTS_RC_SERIAL_PORT_OUTPUT
|
||||
|
||||
// #define GPIO_RSSI_IN /* PC5 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN5)
|
||||
|
||||
@@ -5,6 +5,7 @@ CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS2"
|
||||
CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS3"
|
||||
CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS5"
|
||||
CONFIG_BOARD_SERIAL_TEL4="/dev/ttyS6"
|
||||
CONFIG_BOARD_SERIAL_RC="/dev/ttyS4"
|
||||
CONFIG_BOARD_PARAM_FILE="/fs/microsd/params"
|
||||
CONFIG_DRIVERS_ADC_BOARD_ADC=y
|
||||
CONFIG_DRIVERS_BAROMETER_DPS310=y
|
||||
|
||||
@@ -149,7 +149,6 @@
|
||||
|
||||
|
||||
/* RC Serial port */
|
||||
#define RC_SERIAL_PORT "/dev/ttyS4"
|
||||
#define BOARD_SUPPORTS_RC_SERIAL_PORT_OUTPUT
|
||||
|
||||
// #define GPIO_RSSI_IN /* PC5 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN5)
|
||||
|
||||
@@ -5,6 +5,7 @@ CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS2"
|
||||
CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS3"
|
||||
CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS5"
|
||||
CONFIG_BOARD_SERIAL_TEL4="/dev/ttyS6"
|
||||
CONFIG_BOARD_SERIAL_RC="/dev/ttyS4"
|
||||
CONFIG_DRIVERS_ADC_BOARD_ADC=y
|
||||
CONFIG_DRIVERS_BAROMETER_DPS310=y
|
||||
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
|
||||
|
||||
@@ -156,7 +156,6 @@
|
||||
|
||||
|
||||
/* RC Serial port */
|
||||
#define RC_SERIAL_PORT "/dev/ttyS4"
|
||||
#define BOARD_SUPPORTS_RC_SERIAL_PORT_OUTPUT
|
||||
|
||||
// #define GPIO_RSSI_IN /* PC5 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN5)
|
||||
|
||||
@@ -124,7 +124,6 @@
|
||||
|
||||
|
||||
/* RC Serial port */
|
||||
#define RC_SERIAL_PORT "/dev/ttyS4"
|
||||
#define BOARD_SUPPORTS_RC_SERIAL_PORT_OUTPUT
|
||||
|
||||
/* SD Card */
|
||||
|
||||
@@ -5,6 +5,7 @@ CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS6"
|
||||
CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS4"
|
||||
CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS1"
|
||||
CONFIG_BOARD_SERIAL_TEL4="/dev/ttyS3"
|
||||
CONFIG_BOARD_SERIAL_RC="/dev/ttyS5"
|
||||
CONFIG_DRIVERS_ACTUATORS_VOXL_ESC=y
|
||||
CONFIG_DRIVERS_ADC_ADS1115=y
|
||||
CONFIG_DRIVERS_ADC_BOARD_ADC=y
|
||||
|
||||
@@ -182,8 +182,6 @@
|
||||
#define GPIO_PPM_IN /* PI5 T8C1 */ GPIO_TIM8_CH1IN_2
|
||||
|
||||
/* RC Serial port */
|
||||
|
||||
#define RC_SERIAL_PORT "/dev/ttyS5"
|
||||
#define BOARD_SUPPORTS_RC_SERIAL_PORT_OUTPUT
|
||||
|
||||
/* Safety Switch: Enable the FMU to control it as there is no px4io in ModalAI FC-v1 */
|
||||
|
||||
@@ -3,6 +3,7 @@ CONFIG_BOARD_ARCHITECTURE="cortex-m7"
|
||||
CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS0"
|
||||
CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS6"
|
||||
CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS4"
|
||||
CONFIG_BOARD_SERIAL_RC="/dev/ttyS5"
|
||||
CONFIG_DRIVERS_ACTUATORS_VOXL_ESC=y
|
||||
CONFIG_DRIVERS_ADC_ADS1115=y
|
||||
CONFIG_DRIVERS_ADC_BOARD_ADC=y
|
||||
|
||||
@@ -248,9 +248,6 @@
|
||||
//#define HRT_PPM_CHANNEL /* T8C1 */ 1 /* use capture/compare channel 1 */
|
||||
//#define GPIO_PPM_IN /* PI5 T8C1 */ GPIO_TIM8_CH1IN_2
|
||||
|
||||
/* RC Serial port */
|
||||
|
||||
#define RC_SERIAL_PORT "/dev/ttyS5"
|
||||
|
||||
/* Input Capture Channels. */
|
||||
#define INPUT_CAP1_TIMER 1
|
||||
|
||||
@@ -6,6 +6,7 @@ CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS1"
|
||||
CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS2"
|
||||
CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS5"
|
||||
CONFIG_BOARD_SERIAL_TEL4="/dev/ttyS0"
|
||||
CONFIG_BOARD_SERIAL_RC="/dev/ttyS5"
|
||||
CONFIG_DRIVERS_ADC_ADS1115=y
|
||||
CONFIG_DRIVERS_ADC_BOARD_ADC=y
|
||||
CONFIG_DRIVERS_BAROMETER_DPS310=y
|
||||
|
||||
@@ -126,8 +126,6 @@
|
||||
#define HRT_PPM_CHANNEL /* T3C2 */ 2 /* use capture/compare channel 2 */
|
||||
#define GPIO_PPM_IN /* PC7 T3C2 */ GPIO_TIM3_CH2IN_3
|
||||
|
||||
/* RC Serial port */
|
||||
#define RC_SERIAL_PORT "/dev/ttyS5"
|
||||
|
||||
#define GPIO_RSSI_IN /* PC0 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN0)
|
||||
|
||||
|
||||
@@ -4,6 +4,7 @@ CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS2"
|
||||
CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS0"
|
||||
CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS1"
|
||||
CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS4"
|
||||
CONFIG_BOARD_SERIAL_RC="/dev/ttyS3"
|
||||
CONFIG_DRIVERS_ADC_ADS1115=y
|
||||
CONFIG_DRIVERS_ADC_BOARD_ADC=y
|
||||
CONFIG_DRIVERS_BAROMETER_DPS310=y
|
||||
|
||||
@@ -136,8 +136,6 @@
|
||||
#define HRT_PPM_CHANNEL /* T3C3 */ 3 /* use capture/compare channel 3 */
|
||||
#define GPIO_PPM_IN /* PB0 T3C3 */ GPIO_TIM3_CH3IN_1
|
||||
|
||||
/* RC Serial port */
|
||||
#define RC_SERIAL_PORT "/dev/ttyS3"
|
||||
|
||||
#define GPIO_RSSI_IN /* PC1 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN1)
|
||||
|
||||
|
||||
@@ -3,6 +3,7 @@ CONFIG_BOARD_ARCHITECTURE="cortex-m7"
|
||||
CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS2"
|
||||
CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS0"
|
||||
CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS1"
|
||||
CONFIG_BOARD_SERIAL_RC="/dev/ttyS3"
|
||||
CONFIG_DRIVERS_ADC_ADS1115=y
|
||||
CONFIG_DRIVERS_ADC_BOARD_ADC=y
|
||||
CONFIG_DRIVERS_BAROMETER_DPS310=y
|
||||
|
||||
@@ -135,8 +135,6 @@
|
||||
#define HRT_PPM_CHANNEL /* T3C3 */ 3 /* use capture/compare channel 3 */
|
||||
#define GPIO_PPM_IN /* PB0 T3C3 */ GPIO_TIM3_CH3IN_1
|
||||
|
||||
/* RC Serial port */
|
||||
#define RC_SERIAL_PORT "/dev/ttyS3"
|
||||
|
||||
#define GPIO_RSSI_IN /* PC1 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN1)
|
||||
|
||||
|
||||
@@ -4,6 +4,7 @@ CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS2"
|
||||
CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS0"
|
||||
CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS1"
|
||||
CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS4"
|
||||
CONFIG_BOARD_SERIAL_RC="/dev/ttyS3"
|
||||
CONFIG_DRIVERS_ADC_ADS1115=y
|
||||
CONFIG_DRIVERS_ADC_BOARD_ADC=y
|
||||
CONFIG_DRIVERS_BAROMETER_DPS310=y
|
||||
|
||||
@@ -112,9 +112,6 @@
|
||||
#define HRT_PPM_CHANNEL /* T3C3 */ 3 /* use capture/compare channel 3 */
|
||||
#define GPIO_PPM_IN /* PB0 T3C3 */ GPIO_TIM3_CH3IN_1
|
||||
|
||||
/* RC Serial port */
|
||||
#define RC_SERIAL_PORT "/dev/ttyS3"
|
||||
|
||||
#define GPIO_RSSI_IN /* PC1 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN1)
|
||||
|
||||
/* Safety Switch: Enable the FMU to control it if there is no px4io fixme:This should be BOARD_SAFETY_LED(__ontrue) */
|
||||
|
||||
@@ -4,6 +4,7 @@ CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS2"
|
||||
CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS0"
|
||||
CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS1"
|
||||
CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS4"
|
||||
CONFIG_BOARD_SERIAL_RC="/dev/ttyS3"
|
||||
CONFIG_DRIVERS_ADC_ADS1115=y
|
||||
CONFIG_DRIVERS_ADC_BOARD_ADC=y
|
||||
CONFIG_DRIVERS_BAROMETER_DPS310=y
|
||||
|
||||
@@ -112,8 +112,6 @@
|
||||
#define HRT_PPM_CHANNEL /* T3C3 */ 3 /* use capture/compare channel 3 */
|
||||
#define GPIO_PPM_IN /* PB0 T3C3 */ GPIO_TIM3_CH3IN_1
|
||||
|
||||
/* RC Serial port */
|
||||
#define RC_SERIAL_PORT "/dev/ttyS3"
|
||||
|
||||
#define GPIO_RSSI_IN /* PC1 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN1)
|
||||
|
||||
|
||||
@@ -3,6 +3,7 @@ CONFIG_BOARD_ARCHITECTURE="cortex-m7"
|
||||
CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS3"
|
||||
CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS1"
|
||||
CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS2"
|
||||
CONFIG_BOARD_SERIAL_RC="/dev/ttyS4"
|
||||
CONFIG_DRIVERS_ADC_ADS1115=y
|
||||
CONFIG_DRIVERS_ADC_BOARD_ADC=y
|
||||
CONFIG_DRIVERS_BAROMETER_DPS310=y
|
||||
|
||||
@@ -117,7 +117,6 @@
|
||||
#define GPIO_PPM_IN /* PB0 T3C3 */ GPIO_TIM3_CH3IN_1
|
||||
|
||||
/* RC Serial port */
|
||||
#define RC_SERIAL_PORT "/dev/ttyS4"
|
||||
#define BOARD_SUPPORTS_RC_SERIAL_PORT_OUTPUT
|
||||
|
||||
#define GPIO_RSSI_IN /* PC1 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN1)
|
||||
|
||||
@@ -4,6 +4,7 @@ CONFIG_BOARD_CONSTRAINED_MEMORY=y
|
||||
CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS3"
|
||||
CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS4"
|
||||
CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS1"
|
||||
CONFIG_BOARD_SERIAL_RC="/dev/ttyS2"
|
||||
CONFIG_DRIVERS_ADC_ADS1115=y
|
||||
CONFIG_DRIVERS_ADC_BOARD_ADC=y
|
||||
CONFIG_COMMON_BAROMETERS=y
|
||||
|
||||
@@ -130,9 +130,6 @@ __END_DECLS
|
||||
#define SPEKTRUM_RX_AS_UART() px4_arch_configgpio(PIN_UART1_RX)
|
||||
#define SPEKTRUM_OUT(_one_true) px4_arch_gpiowrite(GPIO_PPM_IN_AS_OUT, (_one_true))
|
||||
|
||||
/* RC input */
|
||||
|
||||
#define RC_SERIAL_PORT "/dev/ttyS2" /* UART1 */
|
||||
#define GPIO_RSSI_IN PIN_ADC1_SE13
|
||||
|
||||
/* Ethernet Control
|
||||
|
||||
@@ -4,6 +4,7 @@ CONFIG_BOARD_CONSTRAINED_MEMORY=y
|
||||
CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS3"
|
||||
CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS4"
|
||||
CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS1"
|
||||
CONFIG_BOARD_SERIAL_RC="/dev/ttyS2"
|
||||
CONFIG_DRIVERS_ADC_ADS1115=y
|
||||
CONFIG_DRIVERS_ADC_BOARD_ADC=y
|
||||
CONFIG_COMMON_BAROMETERS=y
|
||||
|
||||
@@ -130,9 +130,6 @@ __END_DECLS
|
||||
#define SPEKTRUM_RX_AS_UART() px4_arch_configgpio(PIN_UART1_RX)
|
||||
#define SPEKTRUM_OUT(_one_true) px4_arch_gpiowrite(GPIO_PPM_IN_AS_OUT, (_one_true))
|
||||
|
||||
/* RC input */
|
||||
|
||||
#define RC_SERIAL_PORT "/dev/ttyS2" /* UART1 */
|
||||
#define GPIO_RSSI_IN PIN_ADC1_SE13
|
||||
|
||||
/* Ethernet Control
|
||||
|
||||
@@ -87,7 +87,6 @@ __BEGIN_DECLS
|
||||
|
||||
#define DIRECT_PWM_OUTPUT_CHANNELS 8
|
||||
|
||||
#define RC_SERIAL_PORT "/dev/ttyS5"
|
||||
#define RC_SERIAL_SINGLEWIRE_FORCE
|
||||
#define RC_SERIAL_INVERT_RX_ONLY
|
||||
|
||||
|
||||
@@ -5,6 +5,7 @@ CONFIG_BOARD_NO_HELP=y
|
||||
CONFIG_BOARD_CONSTRAINED_MEMORY=y
|
||||
CONFIG_BOARD_SERIAL_URT6="/dev/ttyS2"
|
||||
CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS1"
|
||||
CONFIG_BOARD_SERIAL_RC="/dev/ttyS0"
|
||||
CONFIG_DRIVERS_ADC_BOARD_ADC=y
|
||||
CONFIG_DRIVERS_BAROMETER_BMP280=y
|
||||
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
|
||||
|
||||
@@ -122,7 +122,6 @@
|
||||
#define HRT_PPM_CHANNEL 3 // capture/compare channel 3
|
||||
#define GPIO_PPM_IN (GPIO_ALT|GPIO_AF2|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN8)
|
||||
|
||||
#define RC_SERIAL_PORT "/dev/ttyS0"
|
||||
#define BOARD_SUPPORTS_RC_SERIAL_PORT_OUTPUT
|
||||
|
||||
/*
|
||||
|
||||
@@ -4,6 +4,7 @@ CONFIG_BOARD_CONSTRAINED_MEMORY=y
|
||||
CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS3"
|
||||
CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS1"
|
||||
CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS2"
|
||||
CONFIG_BOARD_SERIAL_RC="/dev/ttyS4"
|
||||
CONFIG_BOARD_SERIAL_WIFI="/dev/ttyS0"
|
||||
CONFIG_DRIVERS_ADC_ADS1115=y
|
||||
CONFIG_DRIVERS_ADC_BOARD_ADC=y
|
||||
|
||||
@@ -113,10 +113,6 @@
|
||||
#define HRT_PPM_CHANNEL 3 /* use capture/compare channel 3 */
|
||||
#define GPIO_PPM_IN (GPIO_ALT|GPIO_AF2|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN0)
|
||||
|
||||
/* RC Serial port */
|
||||
|
||||
#define RC_SERIAL_PORT "/dev/ttyS4"
|
||||
|
||||
/* PWM input driver. Use FMU AUX5 pins attached to timer4 channel 2. */
|
||||
#define PWMIN_TIMER 4
|
||||
#define PWMIN_TIMER_CHANNEL 2
|
||||
|
||||
@@ -4,6 +4,7 @@ CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS0"
|
||||
CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS1"
|
||||
CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS2"
|
||||
CONFIG_BOARD_SERIAL_TEL4="/dev/ttyS3"
|
||||
CONFIG_BOARD_SERIAL_RC="/dev/ttyS4"
|
||||
CONFIG_DRIVERS_ADC_ADS1115=y
|
||||
CONFIG_DRIVERS_ADC_BOARD_ADC=y
|
||||
CONFIG_COMMON_BAROMETERS=y
|
||||
|
||||
@@ -297,8 +297,6 @@
|
||||
#define GPIO_PPM_IN /* PI5 T8C1 */ GPIO_TIM8_CH1IN_2
|
||||
|
||||
/* RC Serial port */
|
||||
|
||||
#define RC_SERIAL_PORT "/dev/ttyS4"
|
||||
#define RC_SERIAL_SINGLEWIRE
|
||||
#define BOARD_SUPPORTS_RC_SERIAL_PORT_OUTPUT
|
||||
|
||||
|
||||
@@ -6,6 +6,7 @@ CONFIG_BOARD_SERIAL_GPS2="/dev/ttyS7"
|
||||
CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS6"
|
||||
CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS4"
|
||||
CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS1"
|
||||
CONFIG_BOARD_SERIAL_RC="/dev/ttyS5"
|
||||
CONFIG_BOARD_SERIAL_EXT2="/dev/ttyS3"
|
||||
CONFIG_DRIVERS_ADC_ADS1115=y
|
||||
CONFIG_DRIVERS_ADC_BOARD_ADC=y
|
||||
@@ -16,6 +17,7 @@ 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_GPIO_MCP23009=y
|
||||
|
||||
@@ -287,7 +287,6 @@
|
||||
#define GPIO_PPM_IN /* PI5 T8C1 */ GPIO_TIM8_CH1IN_2
|
||||
|
||||
/* RC Serial port */
|
||||
#define RC_SERIAL_PORT "/dev/ttyS5"
|
||||
/* Some RC protocols are bi-directional, therefore we need a half-duplex UART */
|
||||
#define RC_SERIAL_SINGLEWIRE
|
||||
/* The STM32 UART by default wires half-duplex mode to the TX pin, but our
|
||||
|
||||
@@ -5,6 +5,7 @@ CONFIG_BOARD_SERIAL_GPS2="/dev/ttyS7"
|
||||
CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS6"
|
||||
CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS4"
|
||||
CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS1"
|
||||
CONFIG_BOARD_SERIAL_RC="/dev/ttyS5"
|
||||
CONFIG_DRIVERS_ADC_ADS1115=y
|
||||
CONFIG_DRIVERS_ADC_BOARD_ADC=y
|
||||
CONFIG_COMMON_BAROMETERS=y
|
||||
|
||||
@@ -257,8 +257,6 @@
|
||||
#define GPIO_PPM_IN /* PI5 T8C1 */ GPIO_TIM8_CH1IN_2
|
||||
|
||||
/* RC Serial port */
|
||||
|
||||
#define RC_SERIAL_PORT "/dev/ttyS5"
|
||||
#define RC_SERIAL_SINGLEWIRE
|
||||
#define RC_SERIAL_SWAP_RXTX
|
||||
|
||||
|
||||
@@ -6,6 +6,7 @@ CONFIG_BOARD_SERIAL_GPS2="/dev/ttyS7"
|
||||
CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS6"
|
||||
CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS4"
|
||||
CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS1"
|
||||
CONFIG_BOARD_SERIAL_RC="/dev/ttyS5"
|
||||
CONFIG_BOARD_SERIAL_EXT2="/dev/ttyS3"
|
||||
CONFIG_DRIVERS_ADC_ADS1115=y
|
||||
CONFIG_DRIVERS_ADC_BOARD_ADC=y
|
||||
@@ -16,6 +17,7 @@ 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
|
||||
|
||||
@@ -324,7 +324,6 @@
|
||||
#define GPIO_PPM_IN /* PI5 T8C1 */ GPIO_TIM8_CH1IN_2
|
||||
|
||||
/* RC Serial port */
|
||||
#define RC_SERIAL_PORT "/dev/ttyS5"
|
||||
/* Some RC protocols are bi-directional, therefore we need a half-duplex UART */
|
||||
#define RC_SERIAL_SINGLEWIRE
|
||||
/* The STM32 UART by default wires half-duplex mode to the TX pin, but our
|
||||
|
||||
@@ -6,6 +6,7 @@ CONFIG_BOARD_SERIAL_GPS2="/dev/ttyS3"
|
||||
CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS2"
|
||||
CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS5"
|
||||
CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS6"
|
||||
CONFIG_BOARD_SERIAL_RC="/dev/ttyS4"
|
||||
CONFIG_DRIVERS_ADC_ADS1115=y
|
||||
CONFIG_DRIVERS_ADC_BOARD_ADC=y
|
||||
CONFIG_DRIVERS_BAROMETER_BMP388=y
|
||||
@@ -15,6 +16,7 @@ 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_DISTANCE_SENSOR_LIGHTWARE_SF45_SERIAL=y
|
||||
CONFIG_DRIVERS_DSHOT=y
|
||||
|
||||
@@ -451,7 +451,6 @@
|
||||
#define HRT_PPM_CHANNEL /* GPIO_EMC_B1_09 GPIO_GPT5_CAPTURE1_1 */ 1 /* use capture/compare channel 1 */
|
||||
#define GPIO_PPM_IN /* GPIO_EMC_B1_09 GPT1_CAPTURE2 */ (GPIO_GPT5_CAPTURE1_1 | GENERAL_INPUT_IOMUX)
|
||||
|
||||
#define RC_SERIAL_PORT "/dev/ttyS4"
|
||||
#define RC_SERIAL_SINGLEWIRE 1 // Suport Single wire wiring
|
||||
#define RC_SERIAL_SWAP_RXTX 1 // Set Swap (but not supported in HW) to use Single wire
|
||||
#define RC_SERIAL_SWAP_USING_SINGLEWIRE 1 // Set to use Single wire swap as HW does not support swap
|
||||
|
||||
@@ -4,6 +4,7 @@ CONFIG_BOARD_CONSTRAINED_FLASH=y
|
||||
CONFIG_BOARD_CONSTRAINED_MEMORY=y
|
||||
CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS2"
|
||||
CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS1"
|
||||
CONFIG_BOARD_SERIAL_RC="/dev/ttyS3"
|
||||
CONFIG_DRIVERS_ADC_BOARD_ADC=y
|
||||
CONFIG_DRIVERS_BAROMETER_BMP280=y
|
||||
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
|
||||
|
||||
@@ -70,7 +70,7 @@
|
||||
#define HRT_TIMER_CHANNEL 1
|
||||
#define HRT_PPM_CHANNEL 1 // Number really doesn't matter for this board
|
||||
#define GPIO_PPM_IN (16 | GPIO_FUN(RP2040_GPIO_FUNC_SIO))
|
||||
#define RC_SERIAL_PORT "/dev/ttyS3"
|
||||
|
||||
#define BOARD_SUPPORTS_RC_SERIAL_PORT_OUTPUT
|
||||
|
||||
/* This board provides a DMA pool and APIs */ // Needs to be figured out
|
||||
|
||||
@@ -6,6 +6,7 @@ CONFIG_BOARD_SERIAL_GPS2="/dev/ttyS7"
|
||||
CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS6"
|
||||
CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS4"
|
||||
CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS1"
|
||||
CONFIG_BOARD_SERIAL_RC="/dev/ttyS5"
|
||||
CONFIG_DRIVERS_ADC_BOARD_ADC=y
|
||||
CONFIG_COMMON_BAROMETERS=y
|
||||
CONFIG_DRIVERS_BATT_SMBUS=y
|
||||
|
||||
@@ -251,8 +251,6 @@
|
||||
#define GPIO_PPM_IN /* PI5 T8C1 */ GPIO_TIM8_CH1IN_2
|
||||
|
||||
/* RC Serial port */
|
||||
|
||||
#define RC_SERIAL_PORT "/dev/ttyS5"
|
||||
#define RC_SERIAL_SINGLEWIRE
|
||||
|
||||
/* Input Capture Channels. */
|
||||
|
||||
@@ -1,5 +1,6 @@
|
||||
CONFIG_BOARD_TOOLCHAIN="arm-none-eabi"
|
||||
CONFIG_BOARD_ARCHITECTURE="cortex-m7"
|
||||
CONFIG_BOARD_SERIAL_RC="/dev/ttyS0"
|
||||
CONFIG_DRIVERS_ADC_BOARD_ADC=y
|
||||
CONFIG_COMMON_BAROMETERS=y
|
||||
CONFIG_DRIVERS_CAMERA_CAPTURE=y
|
||||
|
||||
@@ -107,10 +107,6 @@
|
||||
#define HRT_TIMER_CHANNEL 3 /* use capture/compare channel 3 */
|
||||
|
||||
|
||||
/* RC Serial port */
|
||||
|
||||
#define RC_SERIAL_PORT "/dev/ttyS0"
|
||||
|
||||
#define GPIO_RSSI_IN /* PC5 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN5)
|
||||
|
||||
#define SDIO_SLOTNO 0 /* Only one slot */
|
||||
|
||||
@@ -5,6 +5,7 @@ CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS3"
|
||||
CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS1"
|
||||
CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS2"
|
||||
CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS6"
|
||||
CONFIG_BOARD_SERIAL_RC="/dev/ttyS4"
|
||||
CONFIG_DRIVERS_ADC_BOARD_ADC=y
|
||||
CONFIG_DRIVERS_BAROMETER_MS5611=y
|
||||
CONFIG_DRIVERS_BATT_SMBUS=y
|
||||
|
||||
@@ -111,10 +111,6 @@
|
||||
#define HRT_PPM_CHANNEL 3 /* use capture/compare channel 3 */
|
||||
#define GPIO_PPM_IN (GPIO_ALT|GPIO_AF2|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN0)
|
||||
|
||||
/* RC Serial port */
|
||||
|
||||
#define RC_SERIAL_PORT "/dev/ttyS4"
|
||||
|
||||
/* PWM input driver. Use FMU AUX5 pins attached to timer4 channel 2. */
|
||||
#define PWMIN_TIMER 4
|
||||
#define PWMIN_TIMER_CHANNEL 2
|
||||
|
||||
@@ -136,7 +136,6 @@
|
||||
#define HRT_TIMER_CHANNEL 1 /* use capture/compare channel 1 */
|
||||
|
||||
/* RC Serial port */
|
||||
#define RC_SERIAL_PORT "/dev/ttyS4"
|
||||
#define BOARD_SUPPORTS_RC_SERIAL_PORT_OUTPUT
|
||||
|
||||
// #define GPIO_SBUS_INV (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN14)
|
||||
|
||||
@@ -7,6 +7,7 @@ CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS6"
|
||||
CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS4"
|
||||
CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS1"
|
||||
CONFIG_BOARD_SERIAL_EXT2="/dev/ttyS3"
|
||||
CONFIG_BOARD_SERIAL_RC="/dev/ttyS5"
|
||||
CONFIG_DRIVERS_ADC_ADS1115=y
|
||||
CONFIG_DRIVERS_ADC_BOARD_ADC=y
|
||||
CONFIG_DRIVERS_BAROMETER_INVENSENSE_ICP201XX=y
|
||||
|
||||
@@ -318,8 +318,6 @@
|
||||
#define GPIO_PPM_IN /* PI5 T8C1 */ GPIO_TIM8_CH1IN_2
|
||||
|
||||
/* RC Serial port */
|
||||
|
||||
#define RC_SERIAL_PORT "/dev/ttyS5"
|
||||
#define RC_SERIAL_SINGLEWIRE
|
||||
|
||||
/* Input Capture Channels. */
|
||||
|
||||
@@ -0,0 +1,23 @@
|
||||
# GPS home position in WGS84 coordinates.
|
||||
|
||||
uint32 MESSAGE_VERSION = 0
|
||||
|
||||
uint64 timestamp # time since system start (microseconds)
|
||||
|
||||
float64 lat # Latitude in degrees
|
||||
float64 lon # Longitude in degrees
|
||||
float32 alt # Altitude in meters (AMSL)
|
||||
|
||||
float32 x # X coordinate in meters
|
||||
float32 y # Y coordinate in meters
|
||||
float32 z # Z coordinate in meters
|
||||
|
||||
float32 yaw # Yaw angle in radians
|
||||
|
||||
bool valid_alt # true when the altitude has been set
|
||||
bool valid_hpos # true when the latitude and longitude have been set
|
||||
bool valid_lpos # true when the local position (xyz) has been set
|
||||
|
||||
bool manual_home # true when home position was set manually
|
||||
|
||||
uint32 update_count # update counter of the home position
|
||||
@@ -10,5 +10,6 @@
|
||||
#include "translation_arming_check_reply_v1.h"
|
||||
#include "translation_battery_status_v1.h"
|
||||
#include "translation_event_v1.h"
|
||||
#include "translation_home_position_v1.h"
|
||||
#include "translation_vehicle_attitude_setpoint_v1.h"
|
||||
#include "translation_vehicle_status_v1.h"
|
||||
|
||||
@@ -0,0 +1,65 @@
|
||||
/****************************************************************************
|
||||
* Copyright (c) 2025 PX4 Development Team.
|
||||
* SPDX-License-Identifier: BSD-3-Clause
|
||||
****************************************************************************/
|
||||
#pragma once
|
||||
|
||||
// Translate HomePosition v0 <--> v1
|
||||
#include <px4_msgs_old/msg/home_position_v0.hpp>
|
||||
#include <px4_msgs/msg/home_position.hpp>
|
||||
|
||||
class HomePositionV1Translation {
|
||||
public:
|
||||
using MessageOlder = px4_msgs_old::msg::HomePositionV0;
|
||||
static_assert(MessageOlder::MESSAGE_VERSION == 0);
|
||||
|
||||
using MessageNewer = px4_msgs::msg::HomePosition;
|
||||
static_assert(MessageNewer::MESSAGE_VERSION == 1);
|
||||
|
||||
static constexpr const char* kTopic = "fmu/out/home_position";
|
||||
|
||||
static void fromOlder(const MessageOlder &msg_older, MessageNewer &msg_newer) {
|
||||
|
||||
// Update for HomePosition
|
||||
|
||||
// Set msg_newer from msg_older
|
||||
msg_newer.timestamp = msg_older.timestamp;
|
||||
msg_newer.lat = msg_older.lat;
|
||||
msg_newer.lon = msg_older.lon;
|
||||
msg_newer.alt = msg_older.alt;
|
||||
msg_newer.x = msg_older.x;
|
||||
msg_newer.y = msg_older.y;
|
||||
msg_newer.z = msg_older.z;
|
||||
msg_newer.roll = 0.0f; // New field in v1, set to 0
|
||||
msg_newer.pitch = 0.0f; // New field in v1, set to 0
|
||||
msg_newer.yaw = msg_older.yaw;
|
||||
msg_newer.valid_alt = msg_older.valid_alt;
|
||||
msg_newer.valid_hpos = msg_older.valid_hpos;
|
||||
msg_newer.valid_lpos = msg_older.valid_lpos;
|
||||
msg_newer.manual_home = msg_older.manual_home;
|
||||
msg_newer.update_count = msg_older.update_count;
|
||||
}
|
||||
|
||||
static void toOlder(const MessageNewer &msg_newer, MessageOlder &msg_older) {
|
||||
|
||||
// Update for HomePosition
|
||||
|
||||
// Set msg_older from msg_newer
|
||||
msg_older.timestamp = msg_newer.timestamp;
|
||||
msg_older.lat = msg_newer.lat;
|
||||
msg_older.lon = msg_newer.lon;
|
||||
msg_older.alt = msg_newer.alt;
|
||||
msg_older.x = msg_newer.x;
|
||||
msg_older.y = msg_newer.y;
|
||||
msg_older.z = msg_newer.z;
|
||||
// Note: roll and pitch from v1 are ignored in v0
|
||||
msg_older.yaw = msg_newer.yaw;
|
||||
msg_older.valid_alt = msg_newer.valid_alt;
|
||||
msg_older.valid_hpos = msg_newer.valid_hpos;
|
||||
msg_older.valid_lpos = msg_newer.valid_lpos;
|
||||
msg_older.manual_home = msg_newer.manual_home;
|
||||
msg_older.update_count = msg_newer.update_count;
|
||||
}
|
||||
};
|
||||
|
||||
REGISTER_TOPIC_TRANSLATION_DIRECT(HomePositionV1Translation);
|
||||
@@ -1,6 +1,6 @@
|
||||
# GPS home position in WGS84 coordinates.
|
||||
|
||||
uint32 MESSAGE_VERSION = 0
|
||||
uint32 MESSAGE_VERSION = 1
|
||||
|
||||
uint64 timestamp # time since system start (microseconds)
|
||||
|
||||
@@ -12,6 +12,8 @@ float32 x # X coordinate in meters
|
||||
float32 y # Y coordinate in meters
|
||||
float32 z # Z coordinate in meters
|
||||
|
||||
float32 roll # Pitch angle in radians
|
||||
float32 pitch # Roll angle in radians
|
||||
float32 yaw # Yaw angle in radians
|
||||
|
||||
bool valid_alt # true when the altitude has been set
|
||||
|
||||
@@ -450,7 +450,7 @@ __BEGIN_DECLS
|
||||
* Name: board_rc_singlewire
|
||||
*
|
||||
* Description:
|
||||
* A board may define RC_SERIAL_SINGLEWIRE, so that RC_SERIAL_PORT is configured
|
||||
* A board may define RC_SERIAL_SINGLEWIRE, so that CONFIG_BOARD_SERIAL_RC is configured
|
||||
* as singlewire UART.
|
||||
*
|
||||
* Input Parameters:
|
||||
@@ -463,7 +463,7 @@ __BEGIN_DECLS
|
||||
************************************************************************************/
|
||||
|
||||
#if defined(RC_SERIAL_SINGLEWIRE)
|
||||
static inline bool board_rc_singlewire(const char *device) { return strcmp(device, RC_SERIAL_PORT) == 0; }
|
||||
static inline bool board_rc_singlewire(const char *device) { return strcmp(device, CONFIG_BOARD_SERIAL_RC) == 0; }
|
||||
#elif defined(RC_SERIAL_SINGLEWIRE_FORCE)
|
||||
static inline bool board_rc_singlewire(const char *device) { return true; }
|
||||
#else
|
||||
@@ -474,7 +474,7 @@ static inline bool board_rc_singlewire(const char *device) { return false; }
|
||||
* Name: board_rc_swap_rxtx
|
||||
*
|
||||
* Description:
|
||||
* A board may define RC_SERIAL_SWAP_RXTX, so that RC_SERIAL_PORT is configured
|
||||
* A board may define RC_SERIAL_SWAP_RXTX, so that CONFIG_BOARD_SERIAL_RC is configured
|
||||
* as UART with RX/TX swapped.
|
||||
*
|
||||
* It can optionaly define RC_SERIAL_SWAP_USING_SINGLEWIRE If the board is wired
|
||||
@@ -496,7 +496,7 @@ static inline bool board_rc_singlewire(const char *device) { return false; }
|
||||
************************************************************************************/
|
||||
|
||||
#if defined(RC_SERIAL_SWAP_RXTX)
|
||||
static inline bool board_rc_swap_rxtx(const char *device) { return strcmp(device, RC_SERIAL_PORT) == 0; }
|
||||
static inline bool board_rc_swap_rxtx(const char *device) { return strcmp(device, CONFIG_BOARD_SERIAL_RC) == 0; }
|
||||
#else
|
||||
static inline bool board_rc_swap_rxtx(const char *device) { return false; }
|
||||
#endif
|
||||
@@ -506,7 +506,7 @@ static inline bool board_rc_swap_rxtx(const char *device) { return false; }
|
||||
*
|
||||
* Description:
|
||||
* All boards may optionally define RC_INVERT_INPUT(bool invert) that is
|
||||
* used to invert the RC_SERIAL_PORT RC port (e.g. to toggle an external XOR via
|
||||
* used to invert the CONFIG_BOARD_SERIAL_RC RC port (e.g. to toggle an external XOR via
|
||||
* GPIO).
|
||||
*
|
||||
* Input Parameters:
|
||||
@@ -521,7 +521,7 @@ static inline bool board_rc_swap_rxtx(const char *device) { return false; }
|
||||
#ifdef RC_INVERT_INPUT
|
||||
static inline bool board_rc_invert_input(const char *device, bool invert)
|
||||
{
|
||||
if (strcmp(device, RC_SERIAL_PORT) == 0) { RC_INVERT_INPUT(invert); return true; }
|
||||
if (strcmp(device, CONFIG_BOARD_SERIAL_RC) == 0) { RC_INVERT_INPUT(invert); return true; }
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
@@ -79,7 +79,11 @@
|
||||
# define HRT_TIMER_BASE STM32_TIM1_BASE
|
||||
# define HRT_TIMER_POWER_REG STM32_RCC_APB2ENR
|
||||
# define HRT_TIMER_POWER_BIT RCC_APB2ENR_TIM1EN
|
||||
#if defined(CONFIG_ARCH_CHIP_STM32H7)
|
||||
# define HRT_TIMER_VECTOR STM32_IRQ_TIMCC
|
||||
#else
|
||||
# define HRT_TIMER_VECTOR STM32_IRQ_TIM1CC
|
||||
#endif
|
||||
# define HRT_TIMER_CLOCK STM32_APB2_TIM1_CLKIN
|
||||
# if CONFIG_STM32_TIM1
|
||||
# error must not set CONFIG_STM32_TIM1=y and HRT_TIMER=1
|
||||
|
||||
@@ -136,26 +136,11 @@ RCInput::task_spawn(int argc, char *argv[])
|
||||
int ch;
|
||||
const char *myoptarg = nullptr;
|
||||
const char *device_name = nullptr;
|
||||
bool silent = false;
|
||||
#if defined(RC_SERIAL_PORT)
|
||||
device_name = RC_SERIAL_PORT;
|
||||
#endif // RC_SERIAL_PORT
|
||||
|
||||
#if defined(RC_SERIAL_PORT) && defined(PX4IO_SERIAL_DEVICE)
|
||||
|
||||
// if RC_SERIAL_PORT == PX4IO_SERIAL_DEVICE then don't use it by default if the px4io is running
|
||||
if ((strcmp(RC_SERIAL_PORT, PX4IO_SERIAL_DEVICE) == 0) && (access("/dev/px4io", R_OK) == 0)) {
|
||||
device_name = nullptr;
|
||||
silent = true;
|
||||
}
|
||||
|
||||
#endif // RC_SERIAL_PORT && PX4IO_SERIAL_DEVICE
|
||||
|
||||
while ((ch = px4_getopt(argc, argv, "d:", &myoptind, &myoptarg)) != EOF) {
|
||||
switch (ch) {
|
||||
case 'd':
|
||||
device_name = myoptarg;
|
||||
silent = false;
|
||||
break;
|
||||
|
||||
case '?':
|
||||
@@ -173,6 +158,20 @@ RCInput::task_spawn(int argc, char *argv[])
|
||||
return -1;
|
||||
}
|
||||
|
||||
#if defined(CONFIG_BOARD_SERIAL_RC) && defined(PX4IO_SERIAL_DEVICE)
|
||||
|
||||
// if board has optional RC (CONFIG_BOARD_SERIAL_RC) potentially on same
|
||||
// serial as px4io (PX4IO_SERIAL_DEVICE) don't allow conflict (silently for now)
|
||||
if ((strcmp(device_name, PX4IO_SERIAL_DEVICE) == 0)
|
||||
&& (strcmp(CONFIG_BOARD_SERIAL_RC, PX4IO_SERIAL_DEVICE) == 0)
|
||||
&& (access("/dev/px4io", R_OK) == 0)
|
||||
) {
|
||||
PX4_INFO("unable to start, conflict with PX4IO on %s", device_name);
|
||||
return PX4_OK;
|
||||
}
|
||||
|
||||
#endif // CONFIG_BOARD_SERIAL_RC && PX4IO_SERIAL_DEVICE
|
||||
|
||||
if (device_name && (access(device_name, R_OK | W_OK) == 0)) {
|
||||
RCInput *instance = new RCInput(device_name);
|
||||
|
||||
@@ -188,15 +187,12 @@ RCInput::task_spawn(int argc, char *argv[])
|
||||
|
||||
return PX4_OK;
|
||||
|
||||
} else if (silent) {
|
||||
return PX4_OK;
|
||||
|
||||
} else {
|
||||
if (device_name) {
|
||||
PX4_ERR("invalid device (-d) %s", device_name);
|
||||
|
||||
} else {
|
||||
PX4_INFO("valid device required");
|
||||
PX4_ERR("valid device required");
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
@@ -24,11 +24,8 @@ parameters:
|
||||
default: -1
|
||||
|
||||
serial_config:
|
||||
- command: set RC_INPUT_ARGS "-d ${SERIAL_DEV}"
|
||||
- command: "rc_input start -d ${SERIAL_DEV}"
|
||||
port_config_param:
|
||||
name: RC_PORT_CONFIG
|
||||
group: Serial
|
||||
default: RC
|
||||
description_extended: |
|
||||
Setting this to 'Disabled' will use a board-specific default port
|
||||
for RC input.
|
||||
|
||||
@@ -127,7 +127,10 @@ bool AnalogBattery::is_valid()
|
||||
|
||||
int AnalogBattery::get_voltage_channel()
|
||||
{
|
||||
if (_analog_params.v_channel >= 0) {
|
||||
if (_analog_params.v_channel == V_CHANNEL_DISABLED) {
|
||||
return -1;
|
||||
|
||||
} else if (_analog_params.v_channel >= 0) {
|
||||
return _analog_params.v_channel;
|
||||
|
||||
} else {
|
||||
@@ -135,6 +138,7 @@ int AnalogBattery::get_voltage_channel()
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
int AnalogBattery::get_current_channel()
|
||||
{
|
||||
if (_analog_params.i_channel >= 0) {
|
||||
|
||||
@@ -94,6 +94,9 @@ protected:
|
||||
virtual void updateParams() override;
|
||||
|
||||
private:
|
||||
|
||||
static constexpr int V_CHANNEL_DISABLED = -2;
|
||||
|
||||
uORB::Subscription _vehicle_status_sub{ORB_ID(vehicle_status)};
|
||||
uint8_t _arming_state{0};
|
||||
|
||||
|
||||
@@ -41,7 +41,9 @@ parameters:
|
||||
short: Battery ${i} Voltage ADC Channel
|
||||
long: |
|
||||
This parameter specifies the ADC channel used to monitor voltage of main power battery.
|
||||
A value of -1 means to use the board default.
|
||||
A value of -1 means to use the board default. A value of -2 disables analog monitoring.
|
||||
This is useful when the FMU supports both analog and digital voltage monitoring and you want
|
||||
to use digital monitoring exclusively.
|
||||
|
||||
type: int32
|
||||
reboot_required: true
|
||||
|
||||
@@ -999,6 +999,10 @@ Commander::handle_command(const vehicle_command_s &cmd)
|
||||
}
|
||||
|
||||
} else {
|
||||
float roll = matrix::wrap_2pi(math::radians(cmd.param2));
|
||||
roll = PX4_ISFINITE(roll) ? roll : 0.0f;
|
||||
float pitch = matrix::wrap_2pi(math::radians(cmd.param3));
|
||||
pitch = PX4_ISFINITE(pitch) ? pitch : 0.0f;
|
||||
float yaw = matrix::wrap_2pi(math::radians(cmd.param4));
|
||||
yaw = PX4_ISFINITE(yaw) ? yaw : (float)NAN;
|
||||
const double lat = cmd.param5;
|
||||
@@ -1007,7 +1011,7 @@ Commander::handle_command(const vehicle_command_s &cmd)
|
||||
|
||||
if (PX4_ISFINITE(lat) && PX4_ISFINITE(lon) && PX4_ISFINITE(alt)) {
|
||||
|
||||
if (_home_position.setManually(lat, lon, alt, yaw)) {
|
||||
if (_home_position.setManually(lat, lon, alt, roll, pitch, yaw)) {
|
||||
|
||||
cmd_result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED;
|
||||
|
||||
|
||||
@@ -1,6 +1,6 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2022-2023 PX4 Development Team. All rights reserved.
|
||||
* Copyright (c) 2022-2025 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
|
||||
@@ -99,7 +99,9 @@ bool HomePosition::setHomePosition(bool force)
|
||||
const vehicle_local_position_s &lpos = _local_position_sub.get();
|
||||
_heading_reset_counter = lpos.heading_reset_counter; // TODO: should not be here
|
||||
|
||||
fillLocalHomePos(home, lpos);
|
||||
const vehicle_attitude_s &attitude = _attitude_sub.get();
|
||||
|
||||
fillLocalHomePos(home, lpos, attitude);
|
||||
updated = true;
|
||||
}
|
||||
|
||||
@@ -135,19 +137,25 @@ bool HomePosition::setHomePosition(bool force)
|
||||
return updated;
|
||||
}
|
||||
|
||||
void HomePosition::fillLocalHomePos(home_position_s &home, const vehicle_local_position_s &lpos)
|
||||
void HomePosition::fillLocalHomePos(home_position_s &home, const vehicle_local_position_s &lpos,
|
||||
const vehicle_attitude_s &attitude)
|
||||
{
|
||||
fillLocalHomePos(home, lpos.x, lpos.y, lpos.z, lpos.heading);
|
||||
matrix::Quatf q(attitude.q);
|
||||
matrix::Eulerf euler(q);
|
||||
fillLocalHomePos(home, lpos.x, lpos.y, lpos.z, euler(0), euler(1), euler(2));
|
||||
}
|
||||
|
||||
void HomePosition::fillLocalHomePos(home_position_s &home, float x, float y, float z, float heading)
|
||||
void HomePosition::fillLocalHomePos(home_position_s &home, float x, float y, float z, float roll, float pitch,
|
||||
float yaw)
|
||||
{
|
||||
home.x = x;
|
||||
home.y = y;
|
||||
home.z = z;
|
||||
home.valid_lpos = true;
|
||||
|
||||
home.yaw = heading;
|
||||
home.roll = roll;
|
||||
home.pitch = pitch;
|
||||
home.yaw = yaw;
|
||||
}
|
||||
|
||||
void HomePosition::fillGlobalHomePos(home_position_s &home, const vehicle_global_position_s &gpos)
|
||||
@@ -229,7 +237,7 @@ void HomePosition::setInAirHomePosition()
|
||||
ref_pos.project(home.lat, home.lon, home_x, home_y);
|
||||
|
||||
const float home_z = -(home.alt - lpos.ref_alt);
|
||||
fillLocalHomePos(home, home_x, home_y, home_z, NAN);
|
||||
fillLocalHomePos(home, home_x, home_y, home_z, NAN, NAN, NAN);
|
||||
|
||||
home.timestamp = hrt_absolute_time();
|
||||
home.update_count++;
|
||||
@@ -245,7 +253,7 @@ void HomePosition::setInAirHomePosition()
|
||||
}
|
||||
}
|
||||
|
||||
bool HomePosition::setManually(double lat, double lon, float alt, float yaw)
|
||||
bool HomePosition::setManually(double lat, double lon, float alt, float roll, float pitch, float yaw)
|
||||
{
|
||||
const vehicle_local_position_s &vehicle_local_position = _local_position_sub.get();
|
||||
|
||||
@@ -268,6 +276,8 @@ bool HomePosition::setManually(double lat, double lon, float alt, float yaw)
|
||||
home.z = -(alt - vehicle_local_position.ref_alt);
|
||||
home.valid_lpos = vehicle_local_position.xy_valid && vehicle_local_position.z_valid;
|
||||
|
||||
home.roll = roll;
|
||||
home.pitch = pitch;
|
||||
home.yaw = yaw;
|
||||
|
||||
home.timestamp = hrt_absolute_time();
|
||||
@@ -303,6 +313,7 @@ void HomePosition::update(bool set_automatically, bool check_if_changed)
|
||||
{
|
||||
_local_position_sub.update();
|
||||
_global_position_sub.update();
|
||||
_attitude_sub.update();
|
||||
|
||||
if (_vehicle_air_data_sub.updated()) {
|
||||
vehicle_air_data_s baro_data;
|
||||
|
||||
@@ -1,6 +1,6 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2022-2023 PX4 Development Team. All rights reserved.
|
||||
* Copyright (c) 2022-2025 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
|
||||
@@ -39,6 +39,7 @@
|
||||
#include <uORB/topics/sensor_gps.h>
|
||||
#include <uORB/topics/vehicle_global_position.h>
|
||||
#include <uORB/topics/vehicle_local_position.h>
|
||||
#include <uORB/topics/vehicle_attitude.h>
|
||||
#include <uORB/topics/failsafe_flags.h>
|
||||
#include <uORB/topics/vehicle_air_data.h>
|
||||
#include <lib/mathlib/math/filter/AlphaFilter.hpp>
|
||||
@@ -64,7 +65,7 @@ public:
|
||||
|
||||
bool setHomePosition(bool force = false);
|
||||
void setInAirHomePosition();
|
||||
bool setManually(double lat, double lon, float alt, float yaw);
|
||||
bool setManually(double lat, double lon, float alt, float roll, float pitch, float yaw);
|
||||
void setTakeoffTime(uint64_t takeoff_time) { _takeoff_time = takeoff_time; }
|
||||
|
||||
void update(bool set_automatically, bool check_if_changed);
|
||||
@@ -76,8 +77,9 @@ private:
|
||||
void setHomePosValid();
|
||||
void updateHomePositionYaw(float yaw);
|
||||
|
||||
static void fillLocalHomePos(home_position_s &home, const vehicle_local_position_s &lpos);
|
||||
static void fillLocalHomePos(home_position_s &home, float x, float y, float z, float heading);
|
||||
static void fillLocalHomePos(home_position_s &home, const vehicle_local_position_s &lpos,
|
||||
const vehicle_attitude_s &attitude);
|
||||
static void fillLocalHomePos(home_position_s &home, float x, float y, float z, float roll, float pitch, float yaw);
|
||||
static void fillGlobalHomePos(home_position_s &home, const vehicle_global_position_s &gpos);
|
||||
static void fillGlobalHomePos(home_position_s &home, double lat, double lon, double alt);
|
||||
|
||||
@@ -85,6 +87,7 @@ private:
|
||||
|
||||
uORB::SubscriptionData<vehicle_global_position_s> _global_position_sub{ORB_ID(vehicle_global_position)};
|
||||
uORB::SubscriptionData<vehicle_local_position_s> _local_position_sub{ORB_ID(vehicle_local_position)};
|
||||
uORB::SubscriptionData<vehicle_attitude_s> _attitude_sub{ORB_ID(vehicle_attitude)};
|
||||
uORB::Subscription _vehicle_air_data_sub{ORB_ID(vehicle_air_data)};
|
||||
|
||||
uint64_t _last_gps_timestamp{0};
|
||||
|
||||
@@ -232,6 +232,7 @@ void Ekf::updateVerticalPositionResetStatus(const float delta_z)
|
||||
_state_reset_status.reset_count.posD++;
|
||||
}
|
||||
|
||||
#if defined(CONFIG_EKF2_TERRAIN)
|
||||
void Ekf::updateTerrainResetStatus(const float delta_z)
|
||||
{
|
||||
if (_state_reset_status.reset_count.hagl == _state_reset_count_prev.hagl) {
|
||||
@@ -244,6 +245,7 @@ void Ekf::updateTerrainResetStatus(const float delta_z)
|
||||
|
||||
_state_reset_status.reset_count.hagl++;
|
||||
}
|
||||
#endif // CONFIG_EKF2_TERRAIN
|
||||
|
||||
void Ekf::resetHorizontalPositionToLastKnown()
|
||||
{
|
||||
|
||||
@@ -8,7 +8,7 @@ parameters:
|
||||
description:
|
||||
short: Enable internal combustion engine
|
||||
type: boolean
|
||||
default: true
|
||||
default: false
|
||||
|
||||
ICE_ON_SOURCE:
|
||||
description:
|
||||
|
||||
Some files were not shown because too many files have changed in this diff Show More
Reference in New Issue
Block a user