mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-06-09 15:50:05 +08:00
Compare commits
6 Commits
| Author | SHA1 | Date | |
|---|---|---|---|
| 7f2f71d99b | |||
| 8edc071e8c | |||
| 2ce745568f | |||
| 2d0eedc71d | |||
| e5b2584da7 | |||
| b23a7fc314 |
@@ -29,6 +29,7 @@ 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
|
||||
@@ -499,6 +500,9 @@ 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
|
||||
@@ -660,6 +664,7 @@ 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,7 +4,6 @@ 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,6 +113,9 @@
|
||||
#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,7 +4,6 @@ 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,6 +110,8 @@
|
||||
#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,7 +15,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_GPS=y
|
||||
|
||||
@@ -322,6 +322,10 @@
|
||||
#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,6 +270,10 @@
|
||||
#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,6 +1,5 @@
|
||||
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,6 +142,7 @@
|
||||
#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,7 +8,6 @@ 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
|
||||
@@ -20,9 +19,6 @@ 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
|
||||
@@ -46,7 +42,6 @@ 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,12 +3,6 @@
|
||||
# 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,48 +23,6 @@ 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,7 +6,6 @@ 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,6 +102,9 @@
|
||||
#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,7 +6,6 @@ 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,6 +227,8 @@
|
||||
#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,7 +4,6 @@ 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,7 +4,6 @@ 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,7 +6,6 @@ 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,6 +130,7 @@
|
||||
#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,7 +5,6 @@ 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,6 +134,7 @@
|
||||
#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,6 +145,7 @@
|
||||
#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,6 +148,7 @@
|
||||
#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,6 +111,8 @@
|
||||
#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,6 +125,7 @@
|
||||
|
||||
// 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,7 +5,6 @@ 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,6 +283,8 @@
|
||||
#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,7 +5,6 @@ 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,6 +156,7 @@
|
||||
|
||||
|
||||
/* 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,7 +5,6 @@ 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,6 +149,7 @@
|
||||
|
||||
|
||||
/* 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,7 +5,6 @@ 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,6 +156,7 @@
|
||||
|
||||
|
||||
/* 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,6 +124,7 @@
|
||||
|
||||
|
||||
/* RC Serial port */
|
||||
#define RC_SERIAL_PORT "/dev/ttyS4"
|
||||
#define BOARD_SUPPORTS_RC_SERIAL_PORT_OUTPUT
|
||||
|
||||
/* SD Card */
|
||||
|
||||
@@ -5,7 +5,6 @@ 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,6 +182,8 @@
|
||||
#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,7 +3,6 @@ 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,6 +248,9 @@
|
||||
//#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,7 +6,6 @@ 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,6 +126,8 @@
|
||||
#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,7 +4,6 @@ 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,6 +136,8 @@
|
||||
#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,7 +3,6 @@ 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,6 +135,8 @@
|
||||
#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,7 +4,6 @@ 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,6 +112,9 @@
|
||||
#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,7 +4,6 @@ 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,6 +112,8 @@
|
||||
#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,7 +3,6 @@ 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,6 +117,7 @@
|
||||
#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,7 +4,6 @@ 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,6 +130,9 @@ __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,7 +4,6 @@ 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,6 +130,9 @@ __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,6 +87,7 @@ __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
|
||||
|
||||
|
||||
@@ -138,6 +138,9 @@
|
||||
#define CONFIG_FLEXIO1_CLK 1
|
||||
#define CONFIG_FLEXIO1_PRED_DIVIDER 5
|
||||
#define CONFIG_FLEXIO1_PODF_DIVIDER 1
|
||||
#define CONFIG_FLEXIO2_CLK 1
|
||||
#define CONFIG_FLEXIO2_PRED_DIVIDER 5
|
||||
#define CONFIG_FLEXIO2_PODF_DIVIDER 1
|
||||
#define CONFIG_PLL3_PFD2_FRAC 16
|
||||
#define BOARD_FLEXIO_PREQ 108000000
|
||||
|
||||
|
||||
@@ -301,6 +301,20 @@ void imxrt_flexio_clocking(void)
|
||||
reg |= CCM_CDCDR_FLEXIO1_CLK_PRED
|
||||
(CCM_PRED_FROM_DIVISOR(CONFIG_FLEXIO1_PRED_DIVIDER));
|
||||
putreg32(reg, IMXRT_CCM_CDCDR);
|
||||
|
||||
reg = getreg32(IMXRT_CCM_CSCMR2);
|
||||
reg &= ~(CCM_CSCMR2_FLEXIO2_CLK_SEL_MASK);
|
||||
reg |= CCM_CSCMR2_FLEXIO2_CLK_SEL(CONFIG_FLEXIO2_CLK);
|
||||
putreg32(reg, IMXRT_CCM_CSCMR2);
|
||||
|
||||
reg = getreg32(IMXRT_CCM_CS1CDR);
|
||||
reg &= ~(CCM_CS1CDR_FLEXIO2_CLK_PRED_MASK |
|
||||
CCM_CS1CDR_FLEXIO2_CLK_PODF_MASK);
|
||||
reg |= CCM_CS1CDR_FLEXIO2_CLK_PODF
|
||||
(CCM_PODF_FROM_DIVISOR(CONFIG_FLEXIO2_PODF_DIVIDER));
|
||||
reg |= CCM_CS1CDR_FLEXIO2_CLK_PRED
|
||||
(CCM_PRED_FROM_DIVISOR(CONFIG_FLEXIO2_PRED_DIVIDER));
|
||||
putreg32(reg, IMXRT_CCM_CS1CDR);
|
||||
}
|
||||
|
||||
|
||||
|
||||
@@ -77,19 +77,22 @@
|
||||
constexpr io_timers_t io_timers[MAX_IO_TIMERS] = {
|
||||
initIOPWMDshot(PWM::FlexPWM2, PWM::Submodule0), // PWM_1, PMW_5
|
||||
initIOPWMDshot(PWM::FlexPWM2, PWM::Submodule1), // PWM_0
|
||||
initIOPWM(PWM::FlexPWM2, PWM::Submodule2), // PWM_4
|
||||
initIOPWMDshot(PWM::FlexPWM2, PWM::Submodule2), // PWM_4
|
||||
initIOPWMDshot(PWM::FlexPWM4, PWM::Submodule2), // PWM_2, PWM_3
|
||||
};
|
||||
|
||||
#define FXIO_IOMUX (IOMUX_SLEW_FAST | IOMUX_DRIVE_130OHM | IOMUX_PULL_UP_47K | IOMUX_SCHMITT_TRIGGER)
|
||||
|
||||
//TODO: distinguish between the different FlexIO instances
|
||||
//
|
||||
constexpr timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = {
|
||||
initIOTimerChannelDshot(io_timers, {PWM::PWM2_PWM_A, PWM::Submodule0}, IOMUX::Pad::GPIO_EMC_06, GPIO_FLEXIO1_FLEXIO06_1 | FXIO_IOMUX, 6), /* RevA. PWM_1 RevB. PWM1 */
|
||||
initIOTimerChannelDshot(io_timers, {PWM::PWM2_PWM_B, PWM::Submodule0}, IOMUX::Pad::GPIO_EMC_07, GPIO_FLEXIO1_FLEXIO07_1 | FXIO_IOMUX, 7), /* RevA. PWM_5 RevB. PWM2 */
|
||||
initIOTimerChannelDshot(io_timers, {PWM::PWM2_PWM_A, PWM::Submodule1}, IOMUX::Pad::GPIO_EMC_08, GPIO_FLEXIO1_FLEXIO08_1 | FXIO_IOMUX, 8), /* RevA. PWM_0 RevB. PWM3 */
|
||||
initIOTimerChannel(io_timers, {PWM::PWM2_PWM_B, PWM::Submodule2}, IOMUX::Pad::GPIO_B0_11), /* RevA. PWM_4 RevB. PWM4 */
|
||||
initIOTimerChannelDshot(io_timers, {PWM::PWM4_PWM_A, PWM::Submodule2}, IOMUX::Pad::GPIO_EMC_04, GPIO_FLEXIO1_FLEXIO04_1 | FXIO_IOMUX, 4), /* RevA. PWM_3 RevB. PWM5 */
|
||||
initIOTimerChannelDshot(io_timers, {PWM::PWM4_PWM_B, PWM::Submodule2}, IOMUX::Pad::GPIO_EMC_05, GPIO_FLEXIO1_FLEXIO05_1 | FXIO_IOMUX, 5), /* RevA. PWM_2 RevB. PWM6 */
|
||||
initIOTimerChannelDshot(io_timers, {PWM::PWM2_PWM_A, PWM::Submodule0}, IOMUX::Pad::GPIO_EMC_06, GPIO_FLEXIO1_FLEXIO06_1 | FXIO_IOMUX, IMXRT_FLEXIO1_BASE, 6), /* RevA. PWM_1 RevB. PWM1 */
|
||||
initIOTimerChannelDshot(io_timers, {PWM::PWM2_PWM_B, PWM::Submodule0}, IOMUX::Pad::GPIO_EMC_07, GPIO_FLEXIO1_FLEXIO07_1 | FXIO_IOMUX, IMXRT_FLEXIO1_BASE, 7), /* RevA. PWM_5 RevB. PWM2 */
|
||||
initIOTimerChannelDshot(io_timers, {PWM::PWM2_PWM_A, PWM::Submodule1}, IOMUX::Pad::GPIO_EMC_08, GPIO_FLEXIO1_FLEXIO08_1 | FXIO_IOMUX, IMXRT_FLEXIO1_BASE, 8), /* RevA. PWM_0 RevB. PWM3 */
|
||||
initIOTimerChannelDshot(io_timers, {PWM::PWM2_PWM_B, PWM::Submodule2}, IOMUX::Pad::GPIO_B0_11, GPIO_FLEXIO2_FLEXIO11_1 | FXIO_IOMUX, IMXRT_FLEXIO2_BASE, 11), /* RevA. PWM_4 RevB. PWM4 */
|
||||
initIOTimerChannelDshot(io_timers, {PWM::PWM4_PWM_A, PWM::Submodule2}, IOMUX::Pad::GPIO_EMC_04, GPIO_FLEXIO1_FLEXIO04_1 | FXIO_IOMUX, IMXRT_FLEXIO1_BASE, 4), /* RevA. PWM_3 RevB. PWM5 */
|
||||
initIOTimerChannelDshot(io_timers, {PWM::PWM4_PWM_B, PWM::Submodule2}, IOMUX::Pad::GPIO_EMC_05, GPIO_FLEXIO1_FLEXIO05_1 | FXIO_IOMUX, IMXRT_FLEXIO1_BASE, 5), /* RevA. PWM_2 RevB. PWM6 */
|
||||
|
||||
};
|
||||
|
||||
constexpr io_timers_channel_mapping_t io_timers_channel_mapping =
|
||||
|
||||
@@ -5,7 +5,6 @@ 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,6 +122,7 @@
|
||||
#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,7 +4,6 @@ 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,6 +113,10 @@
|
||||
#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,7 +4,6 @@ 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,6 +297,8 @@
|
||||
#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,7 +6,6 @@ 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
|
||||
@@ -17,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_GPIO_MCP23009=y
|
||||
|
||||
@@ -287,6 +287,7 @@
|
||||
#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,7 +5,6 @@ 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,6 +257,8 @@
|
||||
#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,7 +6,6 @@ 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
|
||||
@@ -17,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
|
||||
|
||||
@@ -324,6 +324,7 @@
|
||||
#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,7 +6,6 @@ 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
|
||||
@@ -16,7 +15,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_DISTANCE_SENSOR_LIGHTWARE_SF45_SERIAL=y
|
||||
CONFIG_DRIVERS_DSHOT=y
|
||||
|
||||
@@ -451,6 +451,7 @@
|
||||
#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,7 +4,6 @@ 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,7 +6,6 @@ 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,6 +251,8 @@
|
||||
#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,6 +1,5 @@
|
||||
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,6 +107,10 @@
|
||||
#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,7 +5,6 @@ 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,6 +111,10 @@
|
||||
#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,6 +136,7 @@
|
||||
#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,7 +7,6 @@ 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,6 +318,8 @@
|
||||
#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,23 +0,0 @@
|
||||
# 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,6 +10,5 @@
|
||||
#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"
|
||||
|
||||
@@ -1,65 +0,0 @@
|
||||
/****************************************************************************
|
||||
* 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 = 1
|
||||
uint32 MESSAGE_VERSION = 0
|
||||
|
||||
uint64 timestamp # time since system start (microseconds)
|
||||
|
||||
@@ -12,8 +12,6 @@ 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 CONFIG_BOARD_SERIAL_RC is configured
|
||||
* A board may define RC_SERIAL_SINGLEWIRE, so that RC_SERIAL_PORT 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, CONFIG_BOARD_SERIAL_RC) == 0; }
|
||||
static inline bool board_rc_singlewire(const char *device) { return strcmp(device, RC_SERIAL_PORT) == 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 CONFIG_BOARD_SERIAL_RC is configured
|
||||
* A board may define RC_SERIAL_SWAP_RXTX, so that RC_SERIAL_PORT 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, CONFIG_BOARD_SERIAL_RC) == 0; }
|
||||
static inline bool board_rc_swap_rxtx(const char *device) { return strcmp(device, RC_SERIAL_PORT) == 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 CONFIG_BOARD_SERIAL_RC RC port (e.g. to toggle an external XOR via
|
||||
* used to invert the RC_SERIAL_PORT 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, CONFIG_BOARD_SERIAL_RC) == 0) { RC_INVERT_INPUT(invert); return true; }
|
||||
if (strcmp(device, RC_SERIAL_PORT) == 0) { RC_INVERT_INPUT(invert); return true; }
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
@@ -45,7 +45,9 @@
|
||||
|
||||
#include "arm_internal.h"
|
||||
|
||||
#define FLEXIO_BASE IMXRT_FLEXIO1_BASE
|
||||
#define FLEXIO1_BASE IMXRT_FLEXIO1_BASE
|
||||
#define FLEXIO2_BASE IMXRT_FLEXIO2_BASE
|
||||
|
||||
#define DSHOT_TIMERS FLEXIO_SHIFTBUFNIS_COUNT
|
||||
#define DSHOT_THROTTLE_POSITION 5u
|
||||
#define DSHOT_TELEMETRY_POSITION 4u
|
||||
@@ -98,77 +100,80 @@ static uint32_t dshot_mask;
|
||||
static uint32_t bdshot_recv_mask;
|
||||
static uint32_t bdshot_parsed_recv_mask;
|
||||
|
||||
static inline uint32_t flexio_getreg32(uint32_t offset)
|
||||
static uint32_t flexio1_base_addr = FLEXIO1_BASE;
|
||||
static uint32_t flexio2_base_addr = FLEXIO2_BASE;
|
||||
|
||||
static inline uint32_t flexio_getreg32(uint32_t flexio_base, uint32_t offset)
|
||||
{
|
||||
return getreg32(FLEXIO_BASE + offset);
|
||||
return getreg32(flexio_base + offset);
|
||||
}
|
||||
|
||||
static inline void flexio_modifyreg32(unsigned int offset,
|
||||
static inline void flexio_modifyreg32(uint32_t flexio_base, unsigned int offset,
|
||||
uint32_t clearbits,
|
||||
uint32_t setbits)
|
||||
{
|
||||
modifyreg32(FLEXIO_BASE + offset, clearbits, setbits);
|
||||
modifyreg32(flexio_base + offset, clearbits, setbits);
|
||||
}
|
||||
|
||||
static inline void flexio_putreg32(uint32_t value, uint32_t offset)
|
||||
static inline void flexio_putreg32(uint32_t flexio_base, uint32_t value, uint32_t offset)
|
||||
{
|
||||
putreg32(value, FLEXIO_BASE + offset);
|
||||
putreg32(value, flexio_base + offset);
|
||||
}
|
||||
|
||||
static inline void enable_shifter_status_interrupts(uint32_t mask)
|
||||
static inline void enable_shifter_status_interrupts(uint32_t flexio_base, uint32_t mask)
|
||||
{
|
||||
flexio_modifyreg32(IMXRT_FLEXIO_SHIFTSIEN_OFFSET, 0, mask);
|
||||
flexio_modifyreg32(flexio_base, IMXRT_FLEXIO_SHIFTSIEN_OFFSET, 0, mask);
|
||||
}
|
||||
|
||||
static inline void disable_shifter_status_interrupts(uint32_t mask)
|
||||
static inline void disable_shifter_status_interrupts(uint32_t flexio_base, uint32_t mask)
|
||||
{
|
||||
flexio_modifyreg32(IMXRT_FLEXIO_SHIFTSIEN_OFFSET, mask, 0);
|
||||
flexio_modifyreg32(flexio_base, IMXRT_FLEXIO_SHIFTSIEN_OFFSET, mask, 0);
|
||||
}
|
||||
|
||||
static inline uint32_t get_shifter_status_flags(void)
|
||||
static inline uint32_t get_shifter_status_flags(uint32_t flexio_base)
|
||||
{
|
||||
return flexio_getreg32(IMXRT_FLEXIO_SHIFTSTAT_OFFSET);
|
||||
return flexio_getreg32(flexio_base, IMXRT_FLEXIO_SHIFTSTAT_OFFSET);
|
||||
}
|
||||
|
||||
static inline void clear_shifter_status_flags(uint32_t mask)
|
||||
static inline void clear_shifter_status_flags(uint32_t flexio_base, uint32_t mask)
|
||||
{
|
||||
flexio_putreg32(mask, IMXRT_FLEXIO_SHIFTSTAT_OFFSET);
|
||||
flexio_putreg32(flexio_base, mask, IMXRT_FLEXIO_SHIFTSTAT_OFFSET);
|
||||
}
|
||||
|
||||
static inline void enable_timer_status_interrupts(uint32_t mask)
|
||||
static inline void enable_timer_status_interrupts(uint32_t flexio_base, uint32_t mask)
|
||||
{
|
||||
flexio_modifyreg32(IMXRT_FLEXIO_TIMIEN_OFFSET, 0, mask);
|
||||
flexio_modifyreg32(flexio_base, IMXRT_FLEXIO_TIMIEN_OFFSET, 0, mask);
|
||||
}
|
||||
|
||||
static inline void disable_timer_status_interrupts(uint32_t mask)
|
||||
static inline void disable_timer_status_interrupts(uint32_t flexio_base, uint32_t mask)
|
||||
{
|
||||
flexio_modifyreg32(IMXRT_FLEXIO_TIMIEN_OFFSET, mask, 0);
|
||||
flexio_modifyreg32(flexio_base, IMXRT_FLEXIO_TIMIEN_OFFSET, mask, 0);
|
||||
}
|
||||
|
||||
static inline uint32_t get_timer_status_flags(void)
|
||||
static inline uint32_t get_timer_status_flags(uint32_t flexio_base)
|
||||
{
|
||||
return flexio_getreg32(IMXRT_FLEXIO_TIMSTAT_OFFSET);
|
||||
return flexio_getreg32(flexio_base, IMXRT_FLEXIO_TIMSTAT_OFFSET);
|
||||
}
|
||||
|
||||
static inline void clear_timer_status_flags(uint32_t mask)
|
||||
static inline void clear_timer_status_flags(uint32_t flexio_base, uint32_t mask)
|
||||
{
|
||||
flexio_putreg32(mask, IMXRT_FLEXIO_TIMSTAT_OFFSET);
|
||||
flexio_putreg32(flexio_base, mask, IMXRT_FLEXIO_TIMSTAT_OFFSET);
|
||||
}
|
||||
|
||||
static void flexio_dshot_output(uint32_t channel, uint32_t pin, uint32_t timcmp, bool inverted)
|
||||
static void flexio_dshot_output(uint32_t flexio_base, uint32_t channel, uint32_t pin, uint32_t timcmp, bool inverted)
|
||||
{
|
||||
/* Disable Shifter */
|
||||
flexio_putreg32(0, IMXRT_FLEXIO_SHIFTCTL0_OFFSET + channel * 0x4);
|
||||
flexio_putreg32(flexio_base, 0, IMXRT_FLEXIO_SHIFTCTL0_OFFSET + channel * 0x4);
|
||||
|
||||
/* No start bit, stop bit low */
|
||||
flexio_putreg32(FLEXIO_SHIFTCFG_INSRC(FLEXIO_SHIFTER_INPUT_FROM_PIN) |
|
||||
flexio_putreg32(flexio_base, FLEXIO_SHIFTCFG_INSRC(FLEXIO_SHIFTER_INPUT_FROM_PIN) |
|
||||
FLEXIO_SHIFTCFG_PWIDTH(0) |
|
||||
FLEXIO_SHIFTCFG_SSTOP(FLEXIO_SHIFTER_STOP_BIT_LOW) |
|
||||
FLEXIO_SHIFTCFG_SSTART(FLEXIO_SHIFTER_START_BIT_DISABLED_LOAD_DATA_ON_ENABLE),
|
||||
IMXRT_FLEXIO_SHIFTCFG0_OFFSET + channel * 0x4);
|
||||
|
||||
/* Transmit mode, output to FXIO pin, inverted output for bdshot */
|
||||
flexio_putreg32(FLEXIO_SHIFTCTL_TIMSEL(channel) |
|
||||
flexio_putreg32(flexio_base, FLEXIO_SHIFTCTL_TIMSEL(channel) |
|
||||
FLEXIO_SHIFTCTL_TIMPOL(FLEXIO_SHIFTER_TIMER_POLARITY_ON_POSITIVE) |
|
||||
FLEXIO_SHIFTCTL_PINCFG(FLEXIO_PIN_CONFIG_OUTPUT) |
|
||||
FLEXIO_SHIFTCTL_PINSEL(pin) |
|
||||
@@ -177,7 +182,7 @@ static void flexio_dshot_output(uint32_t channel, uint32_t pin, uint32_t timcmp,
|
||||
IMXRT_FLEXIO_SHIFTCTL0_OFFSET + channel * 0x4);
|
||||
|
||||
/* Start transmitting on trigger, disable on compare */
|
||||
flexio_putreg32(FLEXIO_TIMCFG_TIMOUT(FLEXIO_TIMER_OUTPUT_ONE_NOT_AFFECTED_BY_RESET) |
|
||||
flexio_putreg32(flexio_base, FLEXIO_TIMCFG_TIMOUT(FLEXIO_TIMER_OUTPUT_ONE_NOT_AFFECTED_BY_RESET) |
|
||||
FLEXIO_TIMCFG_TIMDEC(FLEXIO_TIMER_DEC_SRC_ON_FLEX_IO_CLOCK_SHIFT_TIMER_OUTPUT) |
|
||||
FLEXIO_TIMCFG_TIMRST(FLEXIO_TIMER_RESET_NEVER) |
|
||||
FLEXIO_TIMCFG_TIMDIS(FLEXIO_TIMER_DISABLE_ON_TIMER_COMPARE) |
|
||||
@@ -186,10 +191,10 @@ static void flexio_dshot_output(uint32_t channel, uint32_t pin, uint32_t timcmp,
|
||||
FLEXIO_TIMCFG_TSTART(FLEXIO_TIMER_START_BIT_DISABLED),
|
||||
IMXRT_FLEXIO_TIMCFG0_OFFSET + channel * 0x4);
|
||||
|
||||
flexio_putreg32(timcmp, IMXRT_FLEXIO_TIMCMP0_OFFSET + channel * 0x4);
|
||||
flexio_putreg32(flexio_base, timcmp, IMXRT_FLEXIO_TIMCMP0_OFFSET + channel * 0x4);
|
||||
|
||||
/* Baud mode, Trigger on shifter write */
|
||||
flexio_putreg32(FLEXIO_TIMCTL_TRGSEL((4 * channel) + 1) |
|
||||
flexio_putreg32(flexio_base, FLEXIO_TIMCTL_TRGSEL((4 * channel) + 1) |
|
||||
FLEXIO_TIMCTL_TRGPOL(FLEXIO_TIMER_TRIGGER_POLARITY_ACTIVE_LOW) |
|
||||
FLEXIO_TIMCTL_TRGSRC(FLEXIO_TIMER_TRIGGER_SOURCE_INTERNAL) |
|
||||
FLEXIO_TIMCTL_PINCFG(FLEXIO_PIN_CONFIG_OUTPUT_DISABLED) |
|
||||
@@ -202,20 +207,22 @@ static void flexio_dshot_output(uint32_t channel, uint32_t pin, uint32_t timcmp,
|
||||
|
||||
static int flexio_irq_handler(int irq, void *context, void *arg)
|
||||
{
|
||||
uint32_t flags = get_shifter_status_flags();
|
||||
uint32_t flexio_base = *(uint32_t *) arg;
|
||||
|
||||
uint32_t flags = get_shifter_status_flags(flexio_base);
|
||||
uint32_t channel;
|
||||
|
||||
for (channel = 0; flags && channel < DSHOT_TIMERS; channel++) {
|
||||
if (flags & (1 << channel)) {
|
||||
disable_shifter_status_interrupts(1 << channel);
|
||||
if ((flags & (1 << channel)) && timer_io_channels[channel].flex_io_base == flexio_base) {
|
||||
disable_shifter_status_interrupts(flexio_base, 1 << channel);
|
||||
|
||||
if (dshot_inst[channel].state == DSHOT_START) {
|
||||
dshot_inst[channel].state = DSHOT_12BIT_FIFO;
|
||||
flexio_putreg32(dshot_inst[channel].irq_data, IMXRT_FLEXIO_SHIFTBUF0_OFFSET + channel * 0x4);
|
||||
flexio_putreg32(flexio_base, dshot_inst[channel].irq_data, IMXRT_FLEXIO_SHIFTBUF0_OFFSET + channel * 0x4);
|
||||
|
||||
} else if (dshot_inst[channel].state == BDSHOT_RECEIVE) {
|
||||
dshot_inst[channel].state = BDSHOT_RECEIVE_COMPLETE;
|
||||
dshot_inst[channel].raw_response = flexio_getreg32(IMXRT_FLEXIO_SHIFTBUFBIS0_OFFSET + channel * 0x4);
|
||||
dshot_inst[channel].raw_response = flexio_getreg32(flexio_base, IMXRT_FLEXIO_SHIFTBUFBIS0_OFFSET + channel * 0x4);
|
||||
|
||||
bdshot_recv_mask |= (1 << channel);
|
||||
|
||||
@@ -227,13 +234,13 @@ static int flexio_irq_handler(int irq, void *context, void *arg)
|
||||
}
|
||||
}
|
||||
|
||||
flags = get_timer_status_flags();
|
||||
flags = get_timer_status_flags(flexio_base);
|
||||
|
||||
for (channel = 0; flags; (channel = (channel + 1) % DSHOT_TIMERS)) {
|
||||
flags = get_timer_status_flags();
|
||||
flags = get_timer_status_flags(flexio_base);
|
||||
|
||||
if (flags & (1 << channel)) {
|
||||
clear_timer_status_flags(1 << channel);
|
||||
if ((flags & (1 << channel)) && timer_io_channels[channel].flex_io_base == flexio_base) {
|
||||
clear_timer_status_flags(flexio_base, 1 << channel);
|
||||
|
||||
if (dshot_inst[channel].state == DSHOT_12BIT_FIFO) {
|
||||
dshot_inst[channel].state = DSHOT_12BIT_TRANSFERRED;
|
||||
@@ -242,21 +249,21 @@ static int flexio_irq_handler(int irq, void *context, void *arg)
|
||||
dshot_inst[channel].state = DSHOT_TRANSMIT_COMPLETE;
|
||||
|
||||
} else if (dshot_inst[channel].bdshot && dshot_inst[channel].state == DSHOT_12BIT_TRANSFERRED) {
|
||||
disable_shifter_status_interrupts(1 << channel);
|
||||
disable_shifter_status_interrupts(flexio_base, 1 << channel);
|
||||
dshot_inst[channel].state = BDSHOT_RECEIVE;
|
||||
|
||||
/* Transmit done, disable timer and reconfigure to receive*/
|
||||
flexio_putreg32(0x0, IMXRT_FLEXIO_TIMCTL0_OFFSET + channel * 0x4);
|
||||
flexio_putreg32(flexio_base, 0x0, IMXRT_FLEXIO_TIMCTL0_OFFSET + channel * 0x4);
|
||||
|
||||
/* Input data from pin, no start/stop bit*/
|
||||
flexio_putreg32(FLEXIO_SHIFTCFG_INSRC(FLEXIO_SHIFTER_INPUT_FROM_PIN) |
|
||||
flexio_putreg32(flexio_base, FLEXIO_SHIFTCFG_INSRC(FLEXIO_SHIFTER_INPUT_FROM_PIN) |
|
||||
FLEXIO_SHIFTCFG_PWIDTH(0) |
|
||||
FLEXIO_SHIFTCFG_SSTOP(FLEXIO_SHIFTER_STOP_BIT_DISABLE) |
|
||||
FLEXIO_SHIFTCFG_SSTART(FLEXIO_SHIFTER_START_BIT_DISABLED_LOAD_DATA_ON_SHIFT),
|
||||
IMXRT_FLEXIO_SHIFTCFG0_OFFSET + channel * 0x4);
|
||||
|
||||
/* Shifter receive mdoe, on FXIO pin input */
|
||||
flexio_putreg32(FLEXIO_SHIFTCTL_TIMSEL(channel) |
|
||||
flexio_putreg32(flexio_base, FLEXIO_SHIFTCTL_TIMSEL(channel) |
|
||||
FLEXIO_SHIFTCTL_TIMPOL(FLEXIO_SHIFTER_TIMER_POLARITY_ON_POSITIVE) |
|
||||
FLEXIO_SHIFTCTL_PINCFG(FLEXIO_PIN_CONFIG_OUTPUT_DISABLED) |
|
||||
FLEXIO_SHIFTCTL_PINSEL(timer_io_channels[channel].dshot.flexio_pin) |
|
||||
@@ -265,10 +272,10 @@ static int flexio_irq_handler(int irq, void *context, void *arg)
|
||||
IMXRT_FLEXIO_SHIFTCTL0_OFFSET + channel * 0x4);
|
||||
|
||||
/* Make sure there no shifter flags high from transmission */
|
||||
clear_shifter_status_flags(1 << channel);
|
||||
clear_shifter_status_flags(flexio_base, 1 << channel);
|
||||
|
||||
/* Enable on pin transition, resychronize through reset on rising edge */
|
||||
flexio_putreg32(FLEXIO_TIMCFG_TIMOUT(FLEXIO_TIMER_OUTPUT_ONE_AFFECTED_BY_RESET) |
|
||||
flexio_putreg32(flexio_base, FLEXIO_TIMCFG_TIMOUT(FLEXIO_TIMER_OUTPUT_ONE_AFFECTED_BY_RESET) |
|
||||
FLEXIO_TIMCFG_TIMDEC(FLEXIO_TIMER_DEC_SRC_ON_FLEX_IO_CLOCK_SHIFT_TIMER_OUTPUT) |
|
||||
FLEXIO_TIMCFG_TIMRST(FLEXIO_TIMER_RESET_ON_TIMER_PIN_RISING_EDGE) |
|
||||
FLEXIO_TIMCFG_TIMDIS(FLEXIO_TIMER_DISABLE_ON_TIMER_COMPARE) |
|
||||
@@ -278,10 +285,10 @@ static int flexio_irq_handler(int irq, void *context, void *arg)
|
||||
IMXRT_FLEXIO_TIMCFG0_OFFSET + channel * 0x4);
|
||||
|
||||
/* Enable on pin transition, resychronize through reset on rising edge */
|
||||
flexio_putreg32(bdshot_tcmp, IMXRT_FLEXIO_TIMCMP0_OFFSET + channel * 0x4);
|
||||
flexio_putreg32(flexio_base, bdshot_tcmp, IMXRT_FLEXIO_TIMCMP0_OFFSET + channel * 0x4);
|
||||
|
||||
/* Trigger on FXIO pin transition, Baud mode */
|
||||
flexio_putreg32(FLEXIO_TIMCTL_TRGSEL(2 * timer_io_channels[channel].dshot.flexio_pin) |
|
||||
flexio_putreg32(flexio_base, FLEXIO_TIMCTL_TRGSEL(2 * timer_io_channels[channel].dshot.flexio_pin) |
|
||||
FLEXIO_TIMCTL_TRGPOL(FLEXIO_TIMER_TRIGGER_POLARITY_ACTIVE_HIGH) |
|
||||
FLEXIO_TIMCTL_TRGSRC(FLEXIO_TIMER_TRIGGER_SOURCE_INTERNAL) |
|
||||
FLEXIO_TIMCTL_PINCFG(FLEXIO_PIN_CONFIG_OUTPUT_DISABLED) |
|
||||
@@ -291,7 +298,7 @@ static int flexio_irq_handler(int irq, void *context, void *arg)
|
||||
IMXRT_FLEXIO_TIMCTL0_OFFSET + channel * 0x4);
|
||||
|
||||
/* Enable shifter interrupt for receiving data */
|
||||
enable_shifter_status_interrupts(1 << channel);
|
||||
enable_shifter_status_interrupts(flexio_base, 1 << channel);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -300,34 +307,72 @@ static int flexio_irq_handler(int irq, void *context, void *arg)
|
||||
return OK;
|
||||
}
|
||||
|
||||
|
||||
int up_dshot_init(uint32_t channel_mask, unsigned dshot_pwm_freq, bool enable_bidirectional_dshot)
|
||||
{
|
||||
/* Calculate dshot timings based on dshot_pwm_freq */
|
||||
dshot_tcmp = 0x2F00 | (((BOARD_FLEXIO_PREQ / (dshot_pwm_freq * 3) / 2) - 1) & 0xFF);
|
||||
bdshot_tcmp = 0x2900 | (((BOARD_FLEXIO_PREQ / (dshot_pwm_freq * 5 / 4) / 2) - 3) & 0xFF);
|
||||
|
||||
/* Clock FlexIO peripheral */
|
||||
imxrt_clockall_flexio1();
|
||||
bool flexio1_channels = false;
|
||||
bool flexio2_channels = false;
|
||||
|
||||
/* Reset FlexIO peripheral */
|
||||
flexio_modifyreg32(IMXRT_FLEXIO_CTRL_OFFSET, 0,
|
||||
FLEXIO_CTRL_SWRST_MASK);
|
||||
flexio_putreg32(0, IMXRT_FLEXIO_CTRL_OFFSET);
|
||||
for (unsigned i = 0; (channel_mask != 0) && (i < DSHOT_TIMERS); i++) {
|
||||
if (channel_mask & (1 << i)) {
|
||||
if (timer_io_channels[i].flex_io_base == FLEXIO1_BASE) {
|
||||
PX4_INFO("Flexio1 channel found");
|
||||
flexio1_channels = true;
|
||||
|
||||
/* Initialize FlexIO peripheral */
|
||||
flexio_modifyreg32(IMXRT_FLEXIO_CTRL_OFFSET,
|
||||
(FLEXIO_CTRL_DOZEN_MASK |
|
||||
FLEXIO_CTRL_DBGE_MASK |
|
||||
FLEXIO_CTRL_FASTACC_MASK |
|
||||
FLEXIO_CTRL_FLEXEN_MASK),
|
||||
(FLEXIO_CTRL_DBGE(1) |
|
||||
FLEXIO_CTRL_FASTACC(1) |
|
||||
FLEXIO_CTRL_FLEXEN(0)));
|
||||
} else if (timer_io_channels[i].flex_io_base == FLEXIO2_BASE) {
|
||||
PX4_INFO("Flexio2 channel found");
|
||||
flexio2_channels = true;
|
||||
|
||||
/* FlexIO IRQ handling */
|
||||
up_enable_irq(IMXRT_IRQ_FLEXIO1);
|
||||
irq_attach(IMXRT_IRQ_FLEXIO1, flexio_irq_handler, 0);
|
||||
} else {PX4_ERR("Invalid flexio base defined");}
|
||||
}
|
||||
}
|
||||
|
||||
if (flexio1_channels) { // FlexIO peripheral 1
|
||||
/* Clock FlexIO peripheral */
|
||||
imxrt_clockall_flexio1();
|
||||
/* Reset FlexIO 1 peripheral */
|
||||
flexio_modifyreg32(FLEXIO1_BASE, IMXRT_FLEXIO_CTRL_OFFSET, 0,
|
||||
FLEXIO_CTRL_SWRST_MASK);
|
||||
flexio_putreg32(FLEXIO1_BASE, 0, IMXRT_FLEXIO_CTRL_OFFSET);
|
||||
|
||||
/* Initialize FlexIO 1 peripheral */
|
||||
flexio_modifyreg32(FLEXIO1_BASE, IMXRT_FLEXIO_CTRL_OFFSET,
|
||||
(FLEXIO_CTRL_DOZEN_MASK |
|
||||
FLEXIO_CTRL_DBGE_MASK |
|
||||
FLEXIO_CTRL_FASTACC_MASK |
|
||||
FLEXIO_CTRL_FLEXEN_MASK),
|
||||
(FLEXIO_CTRL_DBGE(1) |
|
||||
FLEXIO_CTRL_FASTACC(1) |
|
||||
FLEXIO_CTRL_FLEXEN(0)));
|
||||
/* FlexIO IRQ handling */
|
||||
up_enable_irq(IMXRT_IRQ_FLEXIO1);
|
||||
irq_attach(IMXRT_IRQ_FLEXIO1, flexio_irq_handler, &flexio1_base_addr);
|
||||
}
|
||||
|
||||
if (flexio2_channels) { // FlexIO peripheral 2
|
||||
/* Clock FlexIO peripheral */
|
||||
imxrt_clockall_flexio2();
|
||||
/* Reset FlexIO 2 peripheral */
|
||||
flexio_modifyreg32(FLEXIO2_BASE, IMXRT_FLEXIO_CTRL_OFFSET, 0,
|
||||
FLEXIO_CTRL_SWRST_MASK);
|
||||
flexio_putreg32(FLEXIO2_BASE, 0, IMXRT_FLEXIO_CTRL_OFFSET);
|
||||
|
||||
/* Initialize FlexIO 2 peripheral */
|
||||
flexio_modifyreg32(FLEXIO2_BASE, IMXRT_FLEXIO_CTRL_OFFSET,
|
||||
(FLEXIO_CTRL_DOZEN_MASK |
|
||||
FLEXIO_CTRL_DBGE_MASK |
|
||||
FLEXIO_CTRL_FASTACC_MASK |
|
||||
FLEXIO_CTRL_FLEXEN_MASK),
|
||||
(FLEXIO_CTRL_DBGE(1) |
|
||||
FLEXIO_CTRL_FASTACC(1) |
|
||||
FLEXIO_CTRL_FLEXEN(0)));
|
||||
|
||||
up_enable_irq(IMXRT_IRQ_FLEXIO2);
|
||||
irq_attach(IMXRT_IRQ_FLEXIO2, flexio_irq_handler, &flexio2_base_addr);
|
||||
}
|
||||
|
||||
dshot_mask = 0x0;
|
||||
|
||||
@@ -342,7 +387,9 @@ int up_dshot_init(uint32_t channel_mask, unsigned dshot_pwm_freq, bool enable_bi
|
||||
|
||||
dshot_inst[channel].bdshot = enable_bidirectional_dshot;
|
||||
|
||||
flexio_dshot_output(channel, timer_io_channels[channel].dshot.flexio_pin, dshot_tcmp, dshot_inst[channel].bdshot);
|
||||
flexio_dshot_output(timer_io_channels[channel].flex_io_base, channel, timer_io_channels[channel].dshot.flexio_pin,
|
||||
dshot_tcmp,
|
||||
dshot_inst[channel].bdshot);
|
||||
|
||||
dshot_inst[channel].init = true;
|
||||
|
||||
@@ -351,8 +398,16 @@ int up_dshot_init(uint32_t channel_mask, unsigned dshot_pwm_freq, bool enable_bi
|
||||
}
|
||||
}
|
||||
|
||||
flexio_modifyreg32(IMXRT_FLEXIO_CTRL_OFFSET, 0,
|
||||
FLEXIO_CTRL_FLEXEN_MASK);
|
||||
if (flexio1_channels) {
|
||||
flexio_modifyreg32(FLEXIO1_BASE, IMXRT_FLEXIO_CTRL_OFFSET, 0,
|
||||
FLEXIO_CTRL_FLEXEN_MASK);
|
||||
}
|
||||
|
||||
if (flexio2_channels) {
|
||||
flexio_modifyreg32(FLEXIO2_BASE, IMXRT_FLEXIO_CTRL_OFFSET, 0,
|
||||
FLEXIO_CTRL_FLEXEN_MASK);
|
||||
|
||||
}
|
||||
|
||||
return channel_mask;
|
||||
}
|
||||
@@ -417,7 +472,6 @@ void up_bdshot_erpm(void)
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
int up_bdshot_num_erpm_ready(void)
|
||||
{
|
||||
int num_ready = 0;
|
||||
@@ -470,12 +524,36 @@ void up_bdshot_status(void)
|
||||
|
||||
void up_dshot_trigger(void)
|
||||
{
|
||||
bool flexio1_channels = false;
|
||||
bool flexio2_channels = false;
|
||||
|
||||
|
||||
for (unsigned i = 0; (i < DSHOT_TIMERS); i++) {
|
||||
if (dshot_inst[i].init && dshot_inst[i].data_seg1 != 0) {
|
||||
|
||||
if (timer_io_channels[i].flex_io_base == FLEXIO1_BASE) {
|
||||
flexio1_channels = true;
|
||||
|
||||
} else if (timer_io_channels[i].flex_io_base == FLEXIO2_BASE) {
|
||||
flexio2_channels = true;
|
||||
|
||||
} else {PX4_ERR("Invalid flexio base defined");}
|
||||
}
|
||||
}
|
||||
|
||||
// Calc data now since we're not event driven
|
||||
if (bdshot_recv_mask != 0x0) {
|
||||
up_bdshot_erpm();
|
||||
}
|
||||
|
||||
clear_timer_status_flags(0xFF);
|
||||
if (flexio1_channels) {
|
||||
clear_timer_status_flags(FLEXIO1_BASE, 0xFF);
|
||||
}
|
||||
|
||||
if (flexio2_channels) {
|
||||
clear_timer_status_flags(FLEXIO2_BASE, 0xFF);
|
||||
}
|
||||
|
||||
|
||||
for (uint8_t channel = 0; (channel < DSHOT_TIMERS); channel++) {
|
||||
if (dshot_inst[channel].bdshot && (bdshot_recv_mask & (1 << channel)) == 0) {
|
||||
@@ -483,15 +561,26 @@ void up_dshot_trigger(void)
|
||||
}
|
||||
|
||||
if (dshot_inst[channel].init && dshot_inst[channel].data_seg1 != 0) {
|
||||
flexio_putreg32(dshot_inst[channel].data_seg1, IMXRT_FLEXIO_SHIFTBUF0_OFFSET + channel * 0x4);
|
||||
flexio_putreg32(timer_io_channels[channel].flex_io_base, dshot_inst[channel].data_seg1,
|
||||
IMXRT_FLEXIO_SHIFTBUF0_OFFSET + channel * 0x4);
|
||||
}
|
||||
}
|
||||
|
||||
bdshot_recv_mask = 0x0;
|
||||
|
||||
clear_timer_status_flags(0xFF);
|
||||
enable_shifter_status_interrupts(0xFF);
|
||||
enable_timer_status_interrupts(0xFF);
|
||||
if (flexio1_channels) {
|
||||
clear_timer_status_flags(FLEXIO1_BASE, 0xFF);
|
||||
enable_shifter_status_interrupts(FLEXIO1_BASE, 0xFF);
|
||||
enable_timer_status_interrupts(FLEXIO1_BASE, 0xFF);
|
||||
}
|
||||
|
||||
if (flexio2_channels) {
|
||||
clear_timer_status_flags(FLEXIO2_BASE, 0xFF);
|
||||
enable_shifter_status_interrupts(FLEXIO2_BASE, 0xFF);
|
||||
enable_timer_status_interrupts(FLEXIO2_BASE, 0xFF);
|
||||
}
|
||||
|
||||
|
||||
}
|
||||
|
||||
/* Expand packet from 16 bits 48 to get T0H and T1H timing */
|
||||
@@ -522,6 +611,7 @@ uint64_t dshot_expand_data(uint16_t packet)
|
||||
**/
|
||||
void dshot_motor_data_set(unsigned channel, uint16_t throttle, bool telemetry)
|
||||
{
|
||||
|
||||
if (channel < DSHOT_TIMERS && dshot_inst[channel].init) {
|
||||
uint16_t csum_data;
|
||||
uint16_t packet = 0;
|
||||
@@ -554,13 +644,14 @@ void dshot_motor_data_set(unsigned channel, uint16_t throttle, bool telemetry)
|
||||
dshot_inst[channel].state = DSHOT_START;
|
||||
|
||||
if (dshot_inst[channel].bdshot) {
|
||||
flexio_putreg32(timer_io_channels[channel].flex_io_base, 0x0, IMXRT_FLEXIO_TIMCTL0_OFFSET + channel * 0x4);
|
||||
disable_shifter_status_interrupts(timer_io_channels[channel].flex_io_base, 1 << channel);
|
||||
|
||||
flexio_putreg32(0x0, IMXRT_FLEXIO_TIMCTL0_OFFSET + channel * 0x4);
|
||||
disable_shifter_status_interrupts(1 << channel);
|
||||
flexio_dshot_output(timer_io_channels[channel].flex_io_base, channel, timer_io_channels[channel].dshot.flexio_pin,
|
||||
dshot_tcmp,
|
||||
dshot_inst[channel].bdshot);
|
||||
|
||||
flexio_dshot_output(channel, timer_io_channels[channel].dshot.flexio_pin, dshot_tcmp, dshot_inst[channel].bdshot);
|
||||
|
||||
clear_timer_status_flags(0xFF);
|
||||
clear_timer_status_flags(timer_io_channels[channel].flex_io_base, 0xFF);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@@ -107,11 +107,12 @@ typedef struct timer_io_channels_t {
|
||||
uint32_t gpio_out; /* The timer valn_offset GPIO for PWM (this is the IOMUX Pad, e.g. PWM_IOMUX | GPIO_FLEXPWM2_PWMA00_2) */
|
||||
uint32_t gpio_in; /* The timer valn_offset GPIO for Capture */
|
||||
uint32_t gpio_portpin; /* The GPIO Port + Pin (e.g. GPIO_PORT2 | GPIO_PIN6) */
|
||||
uint32_t flex_io_base;
|
||||
uint8_t timer_index; /* 0 based index in the io_timers_t table */
|
||||
uint8_t val_offset; /* IMXRT_FLEXPWM_SM0VAL3_OFFSET or IMXRT_FLEXPWM_SM0VAL5_OFFSET */
|
||||
uint8_t sub_module; /* 0 based sub module offset */
|
||||
uint8_t sub_module_bits; /* LDOK and CLDOK bits */
|
||||
uint8_t timer_channel; /* Unused */
|
||||
uint8_t timer_channel;/* Unused */
|
||||
dshot_conf_t dshot;
|
||||
} timer_io_channels_t;
|
||||
|
||||
|
||||
@@ -600,14 +600,13 @@ static inline constexpr timer_io_channels_t initIOTimerChannel(const io_timers_t
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
static inline constexpr timer_io_channels_t initIOTimerChannelDshot(const io_timers_t io_timers_conf[MAX_IO_TIMERS],
|
||||
PWM::FlexPWMConfig pwm_config, IOMUX::Pad pad, uint32_t dshot_pinmux, uint32_t flexio_pin)
|
||||
PWM::FlexPWMConfig pwm_config, IOMUX::Pad pad, uint32_t dshot_pinmux, uint32_t flexio, uint32_t flexio_pin)
|
||||
{
|
||||
timer_io_channels_t ret = initIOTimerChannel(io_timers_conf, pwm_config, pad);
|
||||
|
||||
ret.dshot.pinmux = dshot_pinmux;
|
||||
ret.dshot.flexio_pin = flexio_pin;
|
||||
ret.flex_io_base = flexio;
|
||||
return ret;
|
||||
}
|
||||
|
||||
|
||||
@@ -79,11 +79,7 @@
|
||||
# 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,11 +136,26 @@ 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 '?':
|
||||
@@ -158,20 +173,6 @@ 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);
|
||||
|
||||
@@ -187,12 +188,15 @@ 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_ERR("valid device required");
|
||||
PX4_INFO("valid device required");
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
@@ -24,8 +24,11 @@ parameters:
|
||||
default: -1
|
||||
|
||||
serial_config:
|
||||
- command: "rc_input start -d ${SERIAL_DEV}"
|
||||
- command: set RC_INPUT_ARGS "-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,10 +127,7 @@ bool AnalogBattery::is_valid()
|
||||
|
||||
int AnalogBattery::get_voltage_channel()
|
||||
{
|
||||
if (_analog_params.v_channel == V_CHANNEL_DISABLED) {
|
||||
return -1;
|
||||
|
||||
} else if (_analog_params.v_channel >= 0) {
|
||||
if (_analog_params.v_channel >= 0) {
|
||||
return _analog_params.v_channel;
|
||||
|
||||
} else {
|
||||
@@ -138,7 +135,6 @@ int AnalogBattery::get_voltage_channel()
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
int AnalogBattery::get_current_channel()
|
||||
{
|
||||
if (_analog_params.i_channel >= 0) {
|
||||
|
||||
@@ -94,9 +94,6 @@ 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};
|
||||
|
||||
|
||||
Some files were not shown because too many files have changed in this diff Show More
Reference in New Issue
Block a user