mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-24 04:07:35 +08:00
Compare commits
1 Commits
| Author | SHA1 | Date | |
|---|---|---|---|
| ad7b74847e |
@@ -29,7 +29,6 @@ set LOGGER_ARGS ""
|
||||
set LOGGER_BUF 8
|
||||
set PARAM_FILE ""
|
||||
set PARAM_BACKUP_FILE ""
|
||||
set RC_INPUT_ARGS ""
|
||||
set SDCARD_AVAILABLE no
|
||||
set SDCARD_EXT_PATH /fs/microsd/ext_autostart
|
||||
set SDCARD_FORMAT no
|
||||
@@ -411,8 +410,10 @@ else
|
||||
#
|
||||
. ${R}etc/init.d/rc.serial
|
||||
|
||||
# Must be started after the serial config is read
|
||||
rc_input start $RC_INPUT_ARGS
|
||||
if param compare -s RC_PPM_EN 1
|
||||
then
|
||||
ppm_in start
|
||||
fi
|
||||
|
||||
#
|
||||
# Play the startup tune (if not disabled or there is an error)
|
||||
@@ -544,7 +545,6 @@ unset LOGGER_ARGS
|
||||
unset LOGGER_BUF
|
||||
unset PARAM_FILE
|
||||
unset PARAM_BACKUP_FILE
|
||||
unset RC_INPUT_ARGS
|
||||
unset SDCARD_AVAILABLE
|
||||
unset SDCARD_EXT_PATH
|
||||
unset SDCARD_FORMAT
|
||||
|
||||
@@ -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
|
||||
@@ -28,7 +29,8 @@ CONFIG_DRIVERS_PCA9685_PWM_OUT=y
|
||||
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
|
||||
CONFIG_DRIVERS_PWM_INPUT=y
|
||||
CONFIG_DRIVERS_PWM_OUT=y
|
||||
CONFIG_DRIVERS_RC_INPUT=y
|
||||
CONFIG_COMMON_RC=y
|
||||
CONFIG_DRIVERS_RC_PPM_IN=y
|
||||
CONFIG_DRIVERS_ROBOCLAW=y
|
||||
CONFIG_DRIVERS_RPM=y
|
||||
CONFIG_DRIVERS_SMART_BATTERY_BATMON=y
|
||||
|
||||
@@ -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_TEL4="/dev/ttyS3"
|
||||
CONFIG_BOARD_SERIAL_RC="/dev/ttyS5"
|
||||
CONFIG_DRIVERS_ADC_BOARD_ADC=y
|
||||
CONFIG_DRIVERS_BAROMETER_BMP388=y
|
||||
CONFIG_DRIVERS_BATT_SMBUS=y
|
||||
@@ -27,7 +28,8 @@ CONFIG_DRIVERS_POWER_MONITOR_INA228=y
|
||||
CONFIG_DRIVERS_POWER_MONITOR_INA238=y
|
||||
CONFIG_DRIVERS_PWM_OUT=y
|
||||
CONFIG_DRIVERS_PX4IO=y
|
||||
CONFIG_DRIVERS_RC_INPUT=y
|
||||
CONFIG_COMMON_RC=y
|
||||
CONFIG_DRIVERS_RC_PPM_IN=y
|
||||
CONFIG_DRIVERS_SAFETY_BUTTON=y
|
||||
CONFIG_DRIVERS_TONE_ALARM=y
|
||||
CONFIG_DRIVERS_UAVCAN=y
|
||||
|
||||
Binary file not shown.
@@ -323,7 +323,6 @@
|
||||
#define GPIO_PPM_IN /* PI5 T8C1 */ GPIO_TIM8_CH1IN_2
|
||||
|
||||
/* RC Serial port */
|
||||
|
||||
#define RC_SERIAL_PORT "/dev/ttyS5"
|
||||
|
||||
/* Input Capture Channels. */
|
||||
|
||||
@@ -145,10 +145,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/ttyS5"
|
||||
#define RC_SERIAL_SINGLEWIRE
|
||||
|
||||
/* power on/off */
|
||||
#define MS_PWR_BUTTON_DOWN 750
|
||||
#define KEY_AD_GPIO (GPIO_INPUT|GPIO_PULLUP|GPIO_EXTI|GPIO_PORTC|GPIO_PIN4)
|
||||
|
||||
@@ -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
|
||||
@@ -22,14 +23,12 @@ CONFIG_DRIVERS_IRLOCK=y
|
||||
CONFIG_COMMON_LIGHT=y
|
||||
CONFIG_COMMON_MAGNETOMETER=y
|
||||
CONFIG_COMMON_OPTICAL_FLOW=y
|
||||
CONFIG_DRIVERS_OSD=y
|
||||
CONFIG_DRIVERS_PCA9685=y
|
||||
CONFIG_DRIVERS_PCA9685_PWM_OUT=y
|
||||
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
|
||||
CONFIG_DRIVERS_PWM_OUT=y
|
||||
CONFIG_DRIVERS_RC_INPUT=y
|
||||
CONFIG_COMMON_RC=y
|
||||
CONFIG_DRIVERS_ROBOCLAW=y
|
||||
CONFIG_DRIVERS_RPM=y
|
||||
CONFIG_DRIVERS_SMART_BATTERY_BATMON=y
|
||||
CONFIG_COMMON_TELEMETRY=y
|
||||
CONFIG_DRIVERS_UAVCAN=y
|
||||
@@ -38,6 +37,7 @@ CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y
|
||||
CONFIG_MODULES_BATTERY_STATUS=y
|
||||
CONFIG_MODULES_CAMERA_FEEDBACK=y
|
||||
CONFIG_MODULES_COMMANDER=y
|
||||
CONFIG_MODULES_CONTROL_ALLOCATOR=y
|
||||
CONFIG_MODULES_DATAMAN=y
|
||||
CONFIG_MODULES_EKF2=y
|
||||
CONFIG_MODULES_ESC_BATTERY=y
|
||||
@@ -46,6 +46,7 @@ CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_ATT_CONTROL=y
|
||||
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||
CONFIG_MODULES_FW_POS_CONTROL_L1=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_GYRO_CALIBRATION=y
|
||||
CONFIG_MODULES_GYRO_FFT=y
|
||||
CONFIG_MODULES_LAND_DETECTOR=y
|
||||
@@ -61,7 +62,6 @@ CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
|
||||
CONFIG_MODULES_MC_POS_CONTROL=y
|
||||
CONFIG_MODULES_MC_RATE_CONTROL=y
|
||||
CONFIG_MODULES_CONTROL_ALLOCATOR=y
|
||||
CONFIG_MODULES_NAVIGATOR=y
|
||||
CONFIG_MODULES_RC_UPDATE=y
|
||||
CONFIG_MODULES_ROVER_POS_CONTROL=y
|
||||
@@ -74,7 +74,6 @@ CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y
|
||||
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
|
||||
CONFIG_MODULES_UUV_ATT_CONTROL=y
|
||||
CONFIG_MODULES_UUV_POS_CONTROL=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_VTOL_ATT_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
|
||||
CONFIG_SYSTEMCMDS_BL_UPDATE=y
|
||||
|
||||
@@ -103,7 +103,6 @@
|
||||
#define HRT_TIMER_CHANNEL 1 /* use capture/compare channel 3 */
|
||||
|
||||
/* RC Serial port */
|
||||
|
||||
#define RC_SERIAL_PORT "/dev/ttyS4"
|
||||
|
||||
/* Power switch controls ******************************************************/
|
||||
|
||||
@@ -3,6 +3,7 @@ CONFIG_BOARD_LINUX_TARGET=y
|
||||
CONFIG_BOARD_TOOLCHAIN="arm-linux-gnueabihf"
|
||||
CONFIG_BOARD_ARCHITECTURE="cortex-a8"
|
||||
CONFIG_BOARD_TESTING=y
|
||||
CONFIG_BOARD_SERIAL_RC="/dev/ttyS4"
|
||||
CONFIG_DRIVERS_ADC_ADS1115=y
|
||||
CONFIG_DRIVERS_ADC_BOARD_ADC=y
|
||||
CONFIG_DRIVERS_BAROMETER_BMP280=y
|
||||
@@ -16,7 +17,7 @@ CONFIG_DRIVERS_IMU_INVENSENSE_ICM20948=y
|
||||
CONFIG_DRIVERS_IMU_INVENSENSE_MPU9250=y
|
||||
CONFIG_DRIVERS_LINUX_PWM_OUT=y
|
||||
CONFIG_DRIVERS_MAGNETOMETER_HMC5883=y
|
||||
CONFIG_DRIVERS_RC_INPUT=y
|
||||
CONFIG_COMMON_RC=y
|
||||
CONFIG_DRIVERS_SMART_BATTERY_BATMON=y
|
||||
CONFIG_MODULES_AIRSPEED_SELECTOR=y
|
||||
CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y
|
||||
|
||||
@@ -31,7 +31,9 @@ CONFIG_DRIVERS_PCA9685=y
|
||||
CONFIG_DRIVERS_PCA9685_PWM_OUT=y
|
||||
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
|
||||
CONFIG_DRIVERS_PWM_OUT=y
|
||||
CONFIG_DRIVERS_RC_INPUT=y
|
||||
CONFIG_COMMON_RC=y
|
||||
CONFIG_BOARD_SERIAL_RC="/dev/ttyS5"
|
||||
CONFIG_DRIVERS_RC_PPM_IN=y
|
||||
CONFIG_DRIVERS_ROBOCLAW=y
|
||||
CONFIG_DRIVERS_RPM=y
|
||||
CONFIG_DRIVERS_SAFETY_BUTTON=y
|
||||
|
||||
@@ -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
|
||||
@@ -31,7 +32,8 @@ CONFIG_DRIVERS_PCA9685=y
|
||||
CONFIG_DRIVERS_PCA9685_PWM_OUT=y
|
||||
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
|
||||
CONFIG_DRIVERS_PWM_OUT=y
|
||||
CONFIG_DRIVERS_RC_INPUT=y
|
||||
CONFIG_COMMON_RC=y
|
||||
CONFIG_DRIVERS_RC_PPM_IN=y
|
||||
CONFIG_DRIVERS_ROBOCLAW=y
|
||||
CONFIG_DRIVERS_SAFETY_BUTTON=y
|
||||
CONFIG_DRIVERS_SMART_BATTERY_BATMON=y
|
||||
|
||||
Binary file not shown.
Binary file not shown.
@@ -16,7 +16,9 @@ CONFIG_DRIVERS_IMU_INVENSENSE_MPU9250=y
|
||||
CONFIG_DRIVERS_MAGNETOMETER_AKM_AK8963=y
|
||||
CONFIG_DRIVERS_MAGNETOMETER_HMC5883=y
|
||||
CONFIG_DRIVERS_PWM_OUT=y
|
||||
CONFIG_DRIVERS_RC_INPUT=y
|
||||
CONFIG_COMMON_RC=y
|
||||
CONFIG_BOARD_SERIAL_RC="/dev/ttyS0"
|
||||
CONFIG_DRIVERS_RC_PPM_IN=y
|
||||
CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y
|
||||
CONFIG_MODULES_BATTERY_STATUS=y
|
||||
CONFIG_MODULES_COMMANDER=y
|
||||
|
||||
@@ -132,7 +132,6 @@
|
||||
#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
|
||||
|
||||
/*
|
||||
* One RC_IN
|
||||
|
||||
@@ -3,6 +3,7 @@ CONFIG_BOARD_LINUX_TARGET=y
|
||||
CONFIG_BOARD_TOOLCHAIN="arm-linux-gnueabihf"
|
||||
CONFIG_BOARD_ARCHITECTURE="cortex-a53"
|
||||
CONFIG_BOARD_TESTING=y
|
||||
CONFIG_BOARD_SERIAL_RC="/dev/ttyS4"
|
||||
CONFIG_DRIVERS_ADC_ADS1115=y
|
||||
CONFIG_DRIVERS_ADC_BOARD_ADC=y
|
||||
CONFIG_DRIVERS_BAROMETER_MS5611=y
|
||||
@@ -18,7 +19,7 @@ CONFIG_DRIVERS_IMU_ST_LSM9DS1=y
|
||||
CONFIG_DRIVERS_LINUX_PWM_OUT=y
|
||||
CONFIG_DRIVERS_MAGNETOMETER_HMC5883=y
|
||||
CONFIG_DRIVERS_MAGNETOMETER_LSM9DS1_MAG=y
|
||||
CONFIG_DRIVERS_RC_INPUT=y
|
||||
CONFIG_COMMON_RC=y
|
||||
CONFIG_DRIVERS_SMART_BATTERY_BATMON=y
|
||||
CONFIG_MODULES_AIRSPEED_SELECTOR=y
|
||||
CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y
|
||||
|
||||
@@ -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_DSHOT=y
|
||||
|
||||
@@ -135,7 +135,6 @@
|
||||
#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
|
||||
|
||||
/*
|
||||
* One RC_IN
|
||||
|
||||
Binary file not shown.
@@ -12,9 +12,8 @@ CONFIG_DRIVERS_BAROMETER_BMP280=y
|
||||
CONFIG_DRIVERS_DSHOT=y
|
||||
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20689=y
|
||||
CONFIG_DRIVERS_IMU_INVENSENSE_MPU6000=y
|
||||
CONFIG_DRIVERS_OSD=y
|
||||
CONFIG_DRIVERS_PWM_OUT=y
|
||||
CONFIG_DRIVERS_RC_INPUT=y
|
||||
CONFIG_COMMON_RC=y
|
||||
CONFIG_DRIVERS_TELEMETRY_FRSKY_TELEMETRY=y
|
||||
CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y
|
||||
CONFIG_MODULES_BATTERY_STATUS=y
|
||||
|
||||
@@ -111,7 +111,6 @@
|
||||
#define HRT_TIMER_CHANNEL 1 /* use capture/compare channel 1 */
|
||||
|
||||
/* RC Serial port */
|
||||
|
||||
#define RC_SERIAL_PORT "/dev/ttyS4"
|
||||
|
||||
#define GPIO_RSSI_IN /* PC5 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN5)
|
||||
|
||||
@@ -18,12 +18,10 @@ CONFIG_DRIVERS_IMU_INVENSENSE_MPU6000=y
|
||||
CONFIG_COMMON_LIGHT=y
|
||||
CONFIG_COMMON_MAGNETOMETER=y
|
||||
CONFIG_COMMON_OPTICAL_FLOW=y
|
||||
CONFIG_DRIVERS_OSD=y
|
||||
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
|
||||
CONFIG_DRIVERS_PWM_OUT=y
|
||||
CONFIG_DRIVERS_RC_INPUT=y
|
||||
CONFIG_COMMON_RC=y
|
||||
CONFIG_DRIVERS_ROBOCLAW=y
|
||||
CONFIG_DRIVERS_RPM=y
|
||||
CONFIG_DRIVERS_SMART_BATTERY_BATMON=y
|
||||
CONFIG_COMMON_TELEMETRY=y
|
||||
CONFIG_DRIVERS_TONE_ALARM=y
|
||||
|
||||
@@ -34,7 +34,9 @@ CONFIG_DRIVERS_PWM_INPUT=y
|
||||
CONFIG_DRIVERS_PWM_OUT=y
|
||||
CONFIG_MODULES_SIMULATION_PWM_OUT_SIM=y
|
||||
CONFIG_DRIVERS_PX4IO=y
|
||||
CONFIG_DRIVERS_RC_INPUT=y
|
||||
CONFIG_COMMON_RC=y
|
||||
CONFIG_BOARD_SERIAL_RC="/dev/ttyS4"
|
||||
CONFIG_DRIVERS_RC_PPM_IN=y
|
||||
CONFIG_DRIVERS_ROBOCLAW=y
|
||||
CONFIG_DRIVERS_RPM=y
|
||||
CONFIG_DRIVERS_SAFETY_BUTTON=y
|
||||
|
||||
Binary file not shown.
@@ -283,7 +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
|
||||
|
||||
|
||||
@@ -22,7 +22,8 @@ CONFIG_COMMON_OPTICAL_FLOW=y
|
||||
CONFIG_DRIVERS_OSD=y
|
||||
CONFIG_DRIVERS_PWM_OUT=y
|
||||
CONFIG_DRIVERS_PWM_OUT_SIM=n
|
||||
CONFIG_DRIVERS_RC_INPUT=y
|
||||
CONFIG_COMMON_RC=y
|
||||
CONFIG_BOARD_SERIAL_RC="/dev/ttyS4"
|
||||
CONFIG_DRIVERS_RPM=n
|
||||
CONFIG_COMMON_TELEMETRY=y
|
||||
CONFIG_DRIVERS_TONE_ALARM=y
|
||||
|
||||
@@ -159,7 +159,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)
|
||||
|
||||
|
||||
@@ -21,7 +21,8 @@ CONFIG_COMMON_OPTICAL_FLOW=y
|
||||
CONFIG_DRIVERS_OSD=y
|
||||
CONFIG_DRIVERS_PWM_OUT=y
|
||||
CONFIG_DRIVERS_PWM_OUT_SIM=n
|
||||
CONFIG_DRIVERS_RC_INPUT=y
|
||||
CONFIG_COMMON_RC=y
|
||||
CONFIG_BOARD_SERIAL_RC="/dev/ttyS4"
|
||||
CONFIG_DRIVERS_RPM=n
|
||||
CONFIG_COMMON_TELEMETRY=y
|
||||
CONFIG_DRIVERS_TONE_ALARM=y
|
||||
|
||||
@@ -150,7 +150,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)
|
||||
|
||||
|
||||
@@ -22,7 +22,8 @@ CONFIG_COMMON_OPTICAL_FLOW=y
|
||||
CONFIG_DRIVERS_OSD=y
|
||||
CONFIG_DRIVERS_PWM_OUT=y
|
||||
CONFIG_DRIVERS_PWM_OUT_SIM=n
|
||||
CONFIG_DRIVERS_RC_INPUT=y
|
||||
CONFIG_COMMON_RC=y
|
||||
CONFIG_BOARD_SERIAL_RC="/dev/ttyS4"
|
||||
CONFIG_DRIVERS_RPM=n
|
||||
CONFIG_COMMON_TELEMETRY=y
|
||||
CONFIG_DRIVERS_TONE_ALARM=y
|
||||
|
||||
@@ -159,7 +159,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)
|
||||
|
||||
|
||||
@@ -30,7 +30,9 @@ CONFIG_DRIVERS_PCA9685_PWM_OUT=y
|
||||
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
|
||||
CONFIG_DRIVERS_POWER_MONITOR_VOXLPM=y
|
||||
CONFIG_DRIVERS_PWM_OUT=y
|
||||
CONFIG_DRIVERS_RC_INPUT=y
|
||||
CONFIG_COMMON_RC=y
|
||||
CONFIG_BOARD_SERIAL_RC="/dev/ttyS5"
|
||||
CONFIG_DRIVERS_RC_PPM_IN=y
|
||||
CONFIG_DRIVERS_ROBOCLAW=y
|
||||
CONFIG_DRIVERS_SAFETY_BUTTON=y
|
||||
CONFIG_DRIVERS_SMART_BATTERY_BATMON=y
|
||||
|
||||
@@ -182,9 +182,7 @@
|
||||
#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 */
|
||||
#define GPIO_SAFETY_SWITCH_IN /* PF3 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTF|GPIO_PIN3)
|
||||
|
||||
@@ -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_MODALAI_ESC=y
|
||||
CONFIG_DRIVERS_ADC_ADS1115=y
|
||||
CONFIG_DRIVERS_ADC_BOARD_ADC=y
|
||||
@@ -29,7 +30,7 @@ CONFIG_DRIVERS_PCA9685_PWM_OUT=y
|
||||
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
|
||||
CONFIG_DRIVERS_POWER_MONITOR_VOXLPM=y
|
||||
CONFIG_DRIVERS_PWM_OUT=y
|
||||
CONFIG_DRIVERS_RC_INPUT=y
|
||||
CONFIG_COMMON_RC=y
|
||||
CONFIG_DRIVERS_ROBOCLAW=y
|
||||
CONFIG_COMMON_TELEMETRY=y
|
||||
CONFIG_DRIVERS_UAVCAN=y
|
||||
|
||||
@@ -237,7 +237,6 @@
|
||||
//#define GPIO_PPM_IN /* PI5 T8C1 */ GPIO_TIM8_CH1IN_2
|
||||
|
||||
/* RC Serial port */
|
||||
|
||||
#define RC_SERIAL_PORT "/dev/ttyS5"
|
||||
|
||||
/* Input Capture Channels. */
|
||||
|
||||
@@ -26,7 +26,9 @@ CONFIG_DRIVERS_PCA9685=y
|
||||
CONFIG_DRIVERS_PCA9685_PWM_OUT=y
|
||||
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
|
||||
CONFIG_DRIVERS_PWM_OUT=y
|
||||
CONFIG_DRIVERS_RC_INPUT=y
|
||||
CONFIG_COMMON_RC=y
|
||||
CONFIG_BOARD_SERIAL_RC="/dev/ttyS3"
|
||||
CONFIG_DRIVERS_RC_PPM_IN=y
|
||||
CONFIG_DRIVERS_ROBOCLAW=y
|
||||
CONFIG_DRIVERS_RPM=y
|
||||
CONFIG_DRIVERS_SMART_BATTERY_BATMON=y
|
||||
|
||||
@@ -26,7 +26,9 @@ CONFIG_DRIVERS_PCA9685=y
|
||||
CONFIG_DRIVERS_PCA9685_PWM_OUT=y
|
||||
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
|
||||
CONFIG_DRIVERS_PWM_OUT=y
|
||||
CONFIG_DRIVERS_RC_INPUT=y
|
||||
CONFIG_COMMON_RC=y
|
||||
CONFIG_BOARD_SERIAL_RC="/dev/ttyS3"
|
||||
CONFIG_DRIVERS_RC_PPM_IN=y
|
||||
CONFIG_DRIVERS_ROBOCLAW=y
|
||||
CONFIG_DRIVERS_RPM=y
|
||||
CONFIG_DRIVERS_SAFETY_BUTTON=y
|
||||
|
||||
@@ -25,7 +25,9 @@ CONFIG_DRIVERS_PCA9685=y
|
||||
CONFIG_DRIVERS_PCA9685_PWM_OUT=y
|
||||
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
|
||||
CONFIG_DRIVERS_PWM_OUT=y
|
||||
CONFIG_DRIVERS_RC_INPUT=y
|
||||
CONFIG_COMMON_RC=y
|
||||
CONFIG_BOARD_SERIAL_RC="/dev/ttyS3"
|
||||
CONFIG_DRIVERS_RC_PPM_IN=y
|
||||
CONFIG_DRIVERS_ROBOCLAW=y
|
||||
CONFIG_DRIVERS_RPM=y
|
||||
CONFIG_DRIVERS_SAFETY_BUTTON=y
|
||||
|
||||
@@ -26,7 +26,9 @@ CONFIG_DRIVERS_PCA9685=y
|
||||
CONFIG_DRIVERS_PCA9685_PWM_OUT=y
|
||||
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
|
||||
CONFIG_DRIVERS_PWM_OUT=y
|
||||
CONFIG_DRIVERS_RC_INPUT=y
|
||||
CONFIG_COMMON_RC=y
|
||||
CONFIG_BOARD_SERIAL_RC="/dev/ttyS3"
|
||||
CONFIG_DRIVERS_RC_PPM_IN=y
|
||||
CONFIG_DRIVERS_ROBOCLAW=y
|
||||
CONFIG_DRIVERS_SMART_BATTERY_BATMON=y
|
||||
CONFIG_COMMON_TELEMETRY=y
|
||||
|
||||
@@ -25,7 +25,9 @@ CONFIG_DRIVERS_PCA9685=y
|
||||
CONFIG_DRIVERS_PCA9685_PWM_OUT=y
|
||||
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
|
||||
CONFIG_DRIVERS_PWM_OUT=y
|
||||
CONFIG_DRIVERS_RC_INPUT=y
|
||||
CONFIG_COMMON_RC=y
|
||||
CONFIG_BOARD_SERIAL_RC="/dev/ttyS3"
|
||||
CONFIG_DRIVERS_RC_PPM_IN=y
|
||||
CONFIG_DRIVERS_ROBOCLAW=y
|
||||
CONFIG_DRIVERS_SMART_BATTERY_BATMON=y
|
||||
CONFIG_COMMON_TELEMETRY=y
|
||||
|
||||
@@ -26,7 +26,9 @@ CONFIG_DRIVERS_PCA9685=y
|
||||
CONFIG_DRIVERS_PCA9685_PWM_OUT=y
|
||||
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
|
||||
CONFIG_DRIVERS_PWM_OUT=y
|
||||
CONFIG_DRIVERS_RC_INPUT=y
|
||||
CONFIG_COMMON_RC=y
|
||||
CONFIG_BOARD_SERIAL_RC="/dev/ttyS4"
|
||||
CONFIG_DRIVERS_RC_PPM_IN=y
|
||||
CONFIG_DRIVERS_ROBOCLAW=y
|
||||
CONFIG_DRIVERS_SMART_BATTERY_BATMON=y
|
||||
CONFIG_COMMON_TELEMETRY=y
|
||||
|
||||
@@ -118,7 +118,6 @@
|
||||
|
||||
/* 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)
|
||||
|
||||
|
||||
Binary file not shown.
Binary file not shown.
@@ -27,7 +27,9 @@ CONFIG_DRIVERS_PCA9685=y
|
||||
CONFIG_DRIVERS_PCA9685_PWM_OUT=y
|
||||
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
|
||||
CONFIG_DRIVERS_PWM_OUT=y
|
||||
CONFIG_DRIVERS_RC_INPUT=y
|
||||
CONFIG_COMMON_RC=y
|
||||
CONFIG_BOARD_SERIAL_RC="/dev/ttyS2"
|
||||
CONFIG_DRIVERS_RC_PPM_IN=y
|
||||
CONFIG_DRIVERS_ROBOCLAW=y
|
||||
CONFIG_DRIVERS_SAFETY_BUTTON=y
|
||||
CONFIG_DRIVERS_SMART_BATTERY_BATMON=y
|
||||
|
||||
@@ -131,7 +131,6 @@ __END_DECLS
|
||||
#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
|
||||
|
||||
|
||||
@@ -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
|
||||
@@ -28,7 +29,8 @@ CONFIG_DRIVERS_PCA9685=y
|
||||
CONFIG_DRIVERS_PCA9685_PWM_OUT=y
|
||||
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
|
||||
CONFIG_DRIVERS_PWM_OUT=y
|
||||
CONFIG_DRIVERS_RC_INPUT=y
|
||||
CONFIG_COMMON_RC=y
|
||||
CONFIG_DRIVERS_RC_PPM_IN=y
|
||||
CONFIG_DRIVERS_ROBOCLAW=y
|
||||
CONFIG_DRIVERS_SAFETY_BUTTON=y
|
||||
CONFIG_DRIVERS_SMART_BATTERY_BATMON=y
|
||||
|
||||
@@ -131,7 +131,6 @@ __END_DECLS
|
||||
#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
|
||||
|
||||
|
||||
@@ -19,7 +19,9 @@ CONFIG_DRIVERS_LIGHTS_RGBLED_PWM=y
|
||||
CONFIG_DRIVERS_MAGNETOMETER_HMC5883=y
|
||||
CONFIG_DRIVERS_MAGNETOMETER_ISENTEK_IST8310=y
|
||||
CONFIG_DRIVERS_PWM_OUT=y
|
||||
CONFIG_DRIVERS_RC_INPUT=y
|
||||
CONFIG_COMMON_RC=y
|
||||
CONFIG_BOARD_SERIAL_RC="/dev/ttyS5"
|
||||
CONFIG_DRIVERS_RC_PPM_IN=y
|
||||
CONFIG_DRIVERS_SAFETY_BUTTON=y
|
||||
CONFIG_DRIVERS_TONE_ALARM=y
|
||||
CONFIG_COMMON_UWB=y
|
||||
|
||||
@@ -14,7 +14,9 @@ CONFIG_DRIVERS_IMU_INVENSENSE_MPU6000=y
|
||||
CONFIG_DRIVERS_MAGNETOMETER_HMC5883=y
|
||||
CONFIG_DRIVERS_OSD=y
|
||||
CONFIG_DRIVERS_PWM_OUT=y
|
||||
CONFIG_DRIVERS_RC_INPUT=y
|
||||
CONFIG_COMMON_RC=y
|
||||
CONFIG_BOARD_SERIAL_RC="/dev/ttyS0"
|
||||
CONFIG_DRIVERS_RC_PPM_IN=y
|
||||
CONFIG_DRIVERS_TELEMETRY_FRSKY_TELEMETRY=y
|
||||
CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y
|
||||
CONFIG_MODULES_BATTERY_STATUS=y
|
||||
|
||||
@@ -123,7 +123,6 @@
|
||||
#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
|
||||
|
||||
/*
|
||||
* One RC_IN
|
||||
|
||||
Binary file not shown.
Binary file not shown.
@@ -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
|
||||
@@ -30,7 +31,8 @@ CONFIG_DRIVERS_PCA9685_PWM_OUT=y
|
||||
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
|
||||
CONFIG_DRIVERS_PWM_INPUT=y
|
||||
CONFIG_DRIVERS_PWM_OUT=y
|
||||
CONFIG_DRIVERS_RC_INPUT=y
|
||||
CONFIG_COMMON_RC=y
|
||||
CONFIG_DRIVERS_RC_PPM_IN=y
|
||||
CONFIG_DRIVERS_ROBOCLAW=y
|
||||
CONFIG_DRIVERS_SAFETY_BUTTON=y
|
||||
CONFIG_DRIVERS_SMART_BATTERY_BATMON=y
|
||||
|
||||
@@ -114,7 +114,6 @@
|
||||
#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. */
|
||||
|
||||
Binary file not shown.
@@ -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
|
||||
@@ -35,7 +36,8 @@ CONFIG_DRIVERS_PWM_INPUT=y
|
||||
CONFIG_DRIVERS_PWM_OUT=y
|
||||
CONFIG_DRIVERS_PX4IO=y
|
||||
CONFIG_COMMON_RC=y
|
||||
CONFIG_DRIVERS_RC_INPUT=y
|
||||
CONFIG_COMMON_RC=y
|
||||
CONFIG_DRIVERS_RC_PPM_IN=y
|
||||
CONFIG_DRIVERS_ROBOCLAW=y
|
||||
CONFIG_DRIVERS_SAFETY_BUTTON=y
|
||||
CONFIG_DRIVERS_SMART_BATTERY_BATMON=y
|
||||
|
||||
Binary file not shown.
@@ -297,10 +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
|
||||
|
||||
/* PWM input driver. Use FMU AUX5 pins attached to timer4 channel 2 */
|
||||
#define PWMIN_TIMER 4
|
||||
|
||||
@@ -18,8 +18,10 @@ CONFIG_EXAMPLES_FAKE_GPS=n
|
||||
CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=n
|
||||
CONFIG_MODULES_CAMERA_FEEDBACK=n
|
||||
CONFIG_MODULES_ESC_BATTERY=n
|
||||
CONFIG_MODULES_GYRO_FFT=n
|
||||
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=n
|
||||
# CONFIG_MODULES_GYRO_FFT is not set
|
||||
CONFIG_MODULES_LOCAL_POSITION_ESTIMATOR=n
|
||||
CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=n
|
||||
CONFIG_MODULES_MICRODDS_CLIENT=n
|
||||
CONFIG_MODULES_ROVER_POS_CONTROL=n
|
||||
CONFIG_MODULES_TEMPERATURE_COMPENSATION=n
|
||||
|
||||
@@ -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_ADS1115=y
|
||||
CONFIG_DRIVERS_ADC_BOARD_ADC=y
|
||||
CONFIG_DRIVERS_BAROMETER_BMP388=y
|
||||
@@ -36,7 +37,6 @@ CONFIG_DRIVERS_POWER_MONITOR_INA238=y
|
||||
CONFIG_DRIVERS_PWM_OUT=y
|
||||
CONFIG_DRIVERS_PX4IO=y
|
||||
CONFIG_COMMON_RC=y
|
||||
CONFIG_DRIVERS_RC_INPUT=y
|
||||
CONFIG_DRIVERS_ROBOCLAW=y
|
||||
CONFIG_DRIVERS_SAFETY_BUTTON=y
|
||||
CONFIG_DRIVERS_SMART_BATTERY_BATMON=y
|
||||
@@ -59,7 +59,6 @@ CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||
CONFIG_MODULES_FW_POS_CONTROL_L1=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_GYRO_CALIBRATION=y
|
||||
CONFIG_MODULES_GYRO_FFT=n
|
||||
CONFIG_MODULES_LAND_DETECTOR=y
|
||||
CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y
|
||||
CONFIG_MODULES_LOAD_MON=y
|
||||
|
||||
Binary file not shown.
@@ -301,7 +301,6 @@
|
||||
#define GPIO_PPM_IN /* PI5 T8C1 */ GPIO_TIM8_CH1IN_2
|
||||
|
||||
/* RC Serial port */
|
||||
|
||||
#define RC_SERIAL_PORT "/dev/ttyS5"
|
||||
#define RC_SERIAL_SINGLEWIRE
|
||||
|
||||
|
||||
Binary file not shown.
@@ -29,7 +29,9 @@ CONFIG_DRIVERS_PCA9685=y
|
||||
CONFIG_DRIVERS_PCA9685_PWM_OUT=y
|
||||
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
|
||||
CONFIG_DRIVERS_PWM_OUT=y
|
||||
CONFIG_DRIVERS_RC_INPUT=y
|
||||
CONFIG_COMMON_RC=y
|
||||
CONFIG_BOARD_SERIAL_RC="/dev/ttyS5"
|
||||
CONFIG_DRIVERS_RC_PPM_IN=y
|
||||
CONFIG_DRIVERS_ROBOCLAW=y
|
||||
CONFIG_DRIVERS_SAFETY_BUTTON=y
|
||||
CONFIG_DRIVERS_SMART_BATTERY_BATMON=y
|
||||
|
||||
@@ -257,7 +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,7 +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_EXT2="/dev/ttyS3"
|
||||
CONFIG_BOARD_SERIAL_RC="/dev/ttyS5"
|
||||
CONFIG_DRIVERS_ADC_BOARD_ADC=y
|
||||
CONFIG_DRIVERS_BAROMETER_BMP388=y
|
||||
CONFIG_DRIVERS_BAROMETER_INVENSENSE_ICP201XX=y
|
||||
@@ -28,13 +28,13 @@ CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y
|
||||
CONFIG_COMMON_LIGHT=y
|
||||
CONFIG_COMMON_MAGNETOMETER=y
|
||||
CONFIG_COMMON_OPTICAL_FLOW=y
|
||||
CONFIG_COMMON_OSD=y
|
||||
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
|
||||
CONFIG_DRIVERS_POWER_MONITOR_INA228=y
|
||||
CONFIG_DRIVERS_POWER_MONITOR_INA238=y
|
||||
CONFIG_DRIVERS_PWM_OUT=y
|
||||
CONFIG_DRIVERS_PX4IO=y
|
||||
CONFIG_DRIVERS_RC_INPUT=y
|
||||
CONFIG_COMMON_RC=y
|
||||
CONFIG_DRIVERS_RC_PPM_IN=y
|
||||
CONFIG_DRIVERS_SAFETY_BUTTON=y
|
||||
CONFIG_DRIVERS_TONE_ALARM=y
|
||||
CONFIG_DRIVERS_UAVCAN=y
|
||||
|
||||
Binary file not shown.
@@ -333,7 +333,6 @@
|
||||
#define GPIO_PPM_IN /* PI5 T8C1 */ GPIO_TIM8_CH1IN_2
|
||||
|
||||
/* RC Serial port */
|
||||
|
||||
#define RC_SERIAL_PORT "/dev/ttyS5"
|
||||
#define RC_SERIAL_SINGLEWIRE
|
||||
|
||||
|
||||
@@ -3,6 +3,7 @@ CONFIG_BOARD_LINUX_TARGET=y
|
||||
CONFIG_BOARD_TOOLCHAIN="arm-linux-gnueabihf"
|
||||
CONFIG_BOARD_ARCHITECTURE="cortex-a53"
|
||||
CONFIG_BOARD_TESTING=y
|
||||
CONFIG_BOARD_SERIAL_RC="/dev/ttyS4"
|
||||
CONFIG_DRIVERS_ADC_ADS1115=y
|
||||
CONFIG_DRIVERS_BAROMETER_MS5611=y
|
||||
CONFIG_DRIVERS_BATT_SMBUS=y
|
||||
@@ -14,7 +15,7 @@ CONFIG_DRIVERS_IMU_INVENSENSE_ICM20948=y
|
||||
CONFIG_DRIVERS_IMU_INVENSENSE_MPU9250=y
|
||||
CONFIG_DRIVERS_MAGNETOMETER_HMC5883=y
|
||||
CONFIG_DRIVERS_PCA9685_PWM_OUT=y
|
||||
CONFIG_DRIVERS_RC_INPUT=y
|
||||
CONFIG_COMMON_RC=y
|
||||
CONFIG_DRIVERS_RPI_RC_IN=y
|
||||
CONFIG_DRIVERS_SMART_BATTERY_BATMON=y
|
||||
CONFIG_MODULES_AIRSPEED_SELECTOR=y
|
||||
|
||||
@@ -4,13 +4,14 @@ 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_GPS=y
|
||||
CONFIG_DRIVERS_IMU_INVENSENSE_MPU9250=y
|
||||
CONFIG_DRIVERS_MAGNETOMETER_HMC5883=y
|
||||
CONFIG_DRIVERS_PWM_OUT=y
|
||||
CONFIG_DRIVERS_RC_INPUT=y
|
||||
CONFIG_COMMON_RC=y
|
||||
CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y
|
||||
CONFIG_MODULES_BATTERY_STATUS=y
|
||||
CONFIG_MODULES_COMMANDER=y
|
||||
|
||||
@@ -71,7 +71,6 @@
|
||||
#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
|
||||
#define BOARD_DMA_ALLOC_POOL_SIZE 2048
|
||||
|
||||
@@ -3,6 +3,7 @@ CONFIG_BOARD_LINUX_TARGET=y
|
||||
CONFIG_BOARD_TOOLCHAIN="arm-linux-gnueabihf"
|
||||
CONFIG_BOARD_ARCHITECTURE="cortex-a53"
|
||||
CONFIG_BOARD_TESTING=y
|
||||
CONFIG_BOARD_SERIAL_RC="/dev/ttyS4"
|
||||
CONFIG_DRIVERS_ADC_ADS1115=y
|
||||
CONFIG_DRIVERS_BAROMETER_MS5611=y
|
||||
CONFIG_DRIVERS_BATT_SMBUS=y
|
||||
@@ -16,14 +17,14 @@ CONFIG_DRIVERS_MAGNETOMETER_HMC5883=y
|
||||
CONFIG_DRIVERS_MAGNETOMETER_ISENTEK_IST8310=y
|
||||
CONFIG_DRIVERS_MAGNETOMETER_QMC5883L=y
|
||||
CONFIG_DRIVERS_PCA9685_PWM_OUT=y
|
||||
CONFIG_MODULES_SIMULATION_PWM_OUT_SIM=y
|
||||
CONFIG_DRIVERS_RC_INPUT=y
|
||||
CONFIG_COMMON_RC=y
|
||||
CONFIG_DRIVERS_SMART_BATTERY_BATMON=y
|
||||
CONFIG_MODULES_AIRSPEED_SELECTOR=y
|
||||
CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y
|
||||
CONFIG_MODULES_BATTERY_STATUS=y
|
||||
CONFIG_MODULES_CAMERA_FEEDBACK=y
|
||||
CONFIG_MODULES_COMMANDER=y
|
||||
CONFIG_MODULES_CONTROL_ALLOCATOR=y
|
||||
CONFIG_MODULES_DATAMAN=y
|
||||
CONFIG_MODULES_EKF2=y
|
||||
CONFIG_MODULES_EVENTS=y
|
||||
@@ -31,6 +32,7 @@ CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_ATT_CONTROL=y
|
||||
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||
CONFIG_MODULES_FW_POS_CONTROL_L1=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_GYRO_CALIBRATION=y
|
||||
CONFIG_MODULES_GYRO_FFT=y
|
||||
CONFIG_MODULES_LAND_DETECTOR=y
|
||||
@@ -46,7 +48,6 @@ CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
|
||||
CONFIG_MODULES_MC_POS_CONTROL=y
|
||||
CONFIG_MODULES_MC_RATE_CONTROL=y
|
||||
CONFIG_MODULES_CONTROL_ALLOCATOR=y
|
||||
CONFIG_MODULES_NAVIGATOR=y
|
||||
CONFIG_MODULES_RC_UPDATE=y
|
||||
CONFIG_MODULES_ROVER_POS_CONTROL=y
|
||||
@@ -57,7 +58,6 @@ CONFIG_MODULES_SIMULATION_SENSOR_GPS_SIM=y
|
||||
CONFIG_MODULES_SIMULATION_SENSOR_MAG_SIM=y
|
||||
CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y
|
||||
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_VTOL_ATT_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_BSONDUMP=y
|
||||
CONFIG_SYSTEMCMDS_DYN=y
|
||||
|
||||
@@ -31,7 +31,9 @@ CONFIG_DRIVERS_PWM_INPUT=y
|
||||
CONFIG_DRIVERS_PWM_OUT=y
|
||||
CONFIG_MODULES_SIMULATION_PWM_OUT_SIM=y
|
||||
CONFIG_DRIVERS_PX4IO=y
|
||||
CONFIG_DRIVERS_RC_INPUT=y
|
||||
CONFIG_COMMON_RC=y
|
||||
CONFIG_BOARD_SERIAL_RC="/dev/ttyS5"
|
||||
CONFIG_DRIVERS_RC_PPM_IN=y
|
||||
CONFIG_DRIVERS_ROBOCLAW=y
|
||||
CONFIG_DRIVERS_RPM=y
|
||||
CONFIG_DRIVERS_SAFETY_BUTTON=y
|
||||
|
||||
@@ -251,7 +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
|
||||
|
||||
|
||||
@@ -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
|
||||
@@ -13,9 +14,8 @@ CONFIG_DRIVERS_IMU_INVENSENSE_MPU6000=y
|
||||
CONFIG_COMMON_LIGHT=y
|
||||
CONFIG_COMMON_MAGNETOMETER=y
|
||||
CONFIG_COMMON_OPTICAL_FLOW=y
|
||||
CONFIG_DRIVERS_OSD=y
|
||||
CONFIG_DRIVERS_PWM_OUT=y
|
||||
CONFIG_DRIVERS_RC_INPUT=y
|
||||
CONFIG_COMMON_RC=y
|
||||
CONFIG_COMMON_TELEMETRY=y
|
||||
CONFIG_DRIVERS_TONE_ALARM=y
|
||||
CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y
|
||||
|
||||
@@ -25,7 +25,9 @@ CONFIG_COMMON_OPTICAL_FLOW=y
|
||||
CONFIG_DRIVERS_PCA9685=y
|
||||
CONFIG_DRIVERS_PWM_INPUT=y
|
||||
CONFIG_DRIVERS_PWM_OUT=y
|
||||
CONFIG_DRIVERS_RC_INPUT=y
|
||||
CONFIG_COMMON_RC=y
|
||||
CONFIG_BOARD_SERIAL_RC="/dev/ttyS4"
|
||||
CONFIG_DRIVERS_RC_PPM_IN=y
|
||||
CONFIG_DRIVERS_TONE_ALARM=y
|
||||
CONFIG_DRIVERS_UAVCAN=y
|
||||
CONFIG_BOARD_UAVCAN_INTERFACES=1
|
||||
|
||||
@@ -58,7 +58,7 @@
|
||||
#include <lib/mixer_module/mixer_module.hpp>
|
||||
#include <lib/parameters/param.h>
|
||||
#include <lib/perf/perf_counter.h>
|
||||
#include <lib/rc/dsm.h>
|
||||
#include <lib/rc/dsm/dsm.h>
|
||||
#include <lib/systemlib/mavlink_log.h>
|
||||
#include <lib/button/ButtonPublisher.hpp>
|
||||
|
||||
|
||||
@@ -1,9 +1,15 @@
|
||||
menu "RC"
|
||||
menuconfig COMMON_RC
|
||||
bool "Common RC"
|
||||
bool "Common RC drivers"
|
||||
default n
|
||||
select DRIVERS_RC_CRSF_RC
|
||||
select DRIVERS_RC_CRSF
|
||||
select DRIVERS_RC_SPEKTRUM_DSM
|
||||
select DRIVERS_RC_GHST_RC
|
||||
#select DRIVERS_RC_PPM_IN
|
||||
select DRIVERS_RC_SBUS
|
||||
#select DRIVERS_RC_ST24_RC
|
||||
#select DRIVERS_RC_SUMD_RC
|
||||
---help---
|
||||
Enable default set of magnetometer drivers
|
||||
Enable default set of RC drivers
|
||||
rsource "*/Kconfig"
|
||||
endmenu
|
||||
|
||||
@@ -31,8 +31,8 @@
|
||||
#
|
||||
############################################################################
|
||||
px4_add_module(
|
||||
MODULE drivers__rc__crsf_rc
|
||||
MAIN crsf_rc
|
||||
MODULE drivers__rc__crsf
|
||||
MAIN crsf
|
||||
COMPILE_FLAGS
|
||||
SRCS
|
||||
CrsfRc.cpp
|
||||
@@ -47,5 +47,5 @@ px4_add_module(
|
||||
MODULE_CONFIG
|
||||
module.yaml
|
||||
DEPENDS
|
||||
rc
|
||||
px4_work_queue
|
||||
)
|
||||
@@ -500,12 +500,12 @@ int CrsfRc::print_status()
|
||||
perf_print_counter(_cycle_interval_perf);
|
||||
perf_print_counter(_publish_interval_perf);
|
||||
|
||||
PX4_INFO("Disposed bytes: %li", _packet_parser_statistics.disposed_bytes);
|
||||
PX4_INFO("Valid known packet CRCs: %li", _packet_parser_statistics.crcs_valid_known_packets);
|
||||
PX4_INFO("Valid unknown packet CRCs: %li", _packet_parser_statistics.crcs_valid_unknown_packets);
|
||||
PX4_INFO("Invalid CRCs: %li", _packet_parser_statistics.crcs_invalid);
|
||||
PX4_INFO("Invalid known packet sizes: %li", _packet_parser_statistics.invalid_known_packet_sizes);
|
||||
PX4_INFO("Invalid unknown packet sizes: %li", _packet_parser_statistics.invalid_unknown_packet_sizes);
|
||||
PX4_INFO("Disposed bytes: %" PRIu32, _packet_parser_statistics.disposed_bytes);
|
||||
PX4_INFO("Valid known packet CRCs: %" PRIu32, _packet_parser_statistics.crcs_valid_known_packets);
|
||||
PX4_INFO("Valid unknown packet CRCs: %" PRIu32, _packet_parser_statistics.crcs_valid_unknown_packets);
|
||||
PX4_INFO("Invalid CRCs: %" PRIu32, _packet_parser_statistics.crcs_invalid);
|
||||
PX4_INFO("Invalid known packet sizes: %" PRIu32, _packet_parser_statistics.invalid_known_packet_sizes);
|
||||
PX4_INFO("Invalid unknown packet sizes: %" PRIu32, _packet_parser_statistics.invalid_unknown_packet_sizes);
|
||||
|
||||
return 0;
|
||||
}
|
||||
@@ -528,7 +528,7 @@ This module parses the CRSF RC uplink protocol and generates CRSF downlink telem
|
||||
|
||||
)DESCR_STR");
|
||||
|
||||
PRINT_MODULE_USAGE_NAME("crsf_rc", "driver");
|
||||
PRINT_MODULE_USAGE_NAME("crsf", "driver");
|
||||
PRINT_MODULE_USAGE_COMMAND("start");
|
||||
PRINT_MODULE_USAGE_PARAM_STRING('d', "/dev/ttyS3", "<file:dev>", "RC device", true);
|
||||
|
||||
@@ -537,7 +537,7 @@ This module parses the CRSF RC uplink protocol and generates CRSF downlink telem
|
||||
return 0;
|
||||
}
|
||||
|
||||
extern "C" __EXPORT int crsf_rc_main(int argc, char *argv[])
|
||||
extern "C" __EXPORT int crsf_main(int argc, char *argv[])
|
||||
{
|
||||
return CrsfRc::main(argc, argv);
|
||||
}
|
||||
@@ -1,5 +1,5 @@
|
||||
menuconfig DRIVERS_RC_CRSF_RC
|
||||
bool "crsf_rc"
|
||||
menuconfig DRIVERS_RC_CRSF
|
||||
bool "crsf"
|
||||
default n
|
||||
---help---
|
||||
Enable support for crsf rc
|
||||
@@ -1,6 +1,6 @@
|
||||
module_name: CRSF RC Input Driver
|
||||
serial_config:
|
||||
- command: "crsf_rc start -d ${SERIAL_DEV}"
|
||||
- command: "crsf start -d ${SERIAL_DEV}"
|
||||
port_config_param:
|
||||
name: RC_CRSF_PRT_CFG
|
||||
group: Serial
|
||||
@@ -0,0 +1,51 @@
|
||||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2015-2022 PX4 Development Team. All rights reserved.
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
# are met:
|
||||
#
|
||||
# 1. Redistributions of source code must retain the above copyright
|
||||
# notice, this list of conditions and the following disclaimer.
|
||||
# 2. Redistributions in binary form must reproduce the above copyright
|
||||
# notice, this list of conditions and the following disclaimer in
|
||||
# the documentation and/or other materials provided with the
|
||||
# distribution.
|
||||
# 3. Neither the name PX4 nor the names of its contributors may be
|
||||
# used to endorse or promote products derived from this software
|
||||
# without specific prior written permission.
|
||||
#
|
||||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
if(PX4_TESTING AND (${PX4_PLATFORM} MATCHES "posix"))
|
||||
add_subdirectory(test)
|
||||
endif()
|
||||
|
||||
px4_add_module(
|
||||
MODULE drivers__rc__ghst
|
||||
MAIN rc_ghst
|
||||
COMPILE_FLAGS
|
||||
SRCS
|
||||
RCInput.cpp
|
||||
RCInput.hpp
|
||||
ghst_parser.cpp
|
||||
ghst_parser.hpp
|
||||
MODULE_CONFIG
|
||||
module.yaml
|
||||
DEPENDS
|
||||
px4_work_queue
|
||||
)
|
||||
@@ -0,0 +1,5 @@
|
||||
menuconfig DRIVERS_RC_GHST_RC
|
||||
bool "rc_ghst"
|
||||
default n
|
||||
---help---
|
||||
Enable support for rc_ghst
|
||||
@@ -0,0 +1,427 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012-2022 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#include "RCInput.hpp"
|
||||
|
||||
#include <termios.h>
|
||||
|
||||
using namespace time_literals;
|
||||
|
||||
RcGhst::RcGhst(const char *device) :
|
||||
ModuleParams(nullptr),
|
||||
ScheduledWorkItem(MODULE_NAME, px4::serial_port_to_wq(device))
|
||||
{
|
||||
// initialize raw_rc values and count
|
||||
for (unsigned i = 0; i < input_rc_s::RC_INPUT_MAX_CHANNELS; i++) {
|
||||
_raw_rc_values[i] = UINT16_MAX;
|
||||
}
|
||||
|
||||
if (device) {
|
||||
strncpy(_device, device, sizeof(_device) - 1);
|
||||
_device[sizeof(_device) - 1] = '\0';
|
||||
}
|
||||
}
|
||||
|
||||
RcGhst::~RcGhst()
|
||||
{
|
||||
perf_free(_cycle_perf);
|
||||
perf_free(_publish_interval_perf);
|
||||
}
|
||||
|
||||
int RcGhst::init()
|
||||
{
|
||||
_rcs_fd = ::open(_device, O_RDWR | O_NONBLOCK);
|
||||
|
||||
if (_rcs_fd >= 0) {
|
||||
ghst_config(_rcs_fd);
|
||||
}
|
||||
|
||||
if (_rcs_fd < 0) {
|
||||
return -errno;
|
||||
}
|
||||
|
||||
if (board_rc_swap_rxtx(_device)) {
|
||||
#if defined(TIOCSSWAP)
|
||||
ioctl(_rcs_fd, TIOCSSWAP, SER_SWAP_ENABLED);
|
||||
#endif // TIOCSSWAP
|
||||
}
|
||||
|
||||
rc_io_invert(false);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int RcGhst::task_spawn(int argc, char *argv[])
|
||||
{
|
||||
bool error_flag = false;
|
||||
|
||||
int myoptind = 1;
|
||||
int ch;
|
||||
const char *myoptarg = nullptr;
|
||||
const char *device_name = nullptr;
|
||||
#if defined(RC_SERIAL_PORT)
|
||||
device_name = RC_SERIAL_PORT;
|
||||
#endif // RC_SERIAL_PORT
|
||||
|
||||
while ((ch = px4_getopt(argc, argv, "d:", &myoptind, &myoptarg)) != EOF) {
|
||||
switch (ch) {
|
||||
case 'd':
|
||||
device_name = myoptarg;
|
||||
break;
|
||||
|
||||
case '?':
|
||||
error_flag = true;
|
||||
break;
|
||||
|
||||
default:
|
||||
PX4_WARN("unrecognized flag");
|
||||
error_flag = true;
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
if (error_flag) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
if (device_name && (access(device_name, R_OK | W_OK) == 0)) {
|
||||
RcGhst *instance = new RcGhst(device_name);
|
||||
|
||||
if (instance == nullptr) {
|
||||
PX4_ERR("alloc failed");
|
||||
return PX4_ERROR;
|
||||
}
|
||||
|
||||
_object.store(instance);
|
||||
_task_id = task_id_is_work_queue;
|
||||
|
||||
instance->ScheduleOnInterval(_current_update_interval);
|
||||
|
||||
return PX4_OK;
|
||||
|
||||
} else {
|
||||
if (device_name) {
|
||||
PX4_ERR("invalid device (-d) %s", device_name);
|
||||
|
||||
} else {
|
||||
PX4_INFO("valid device required");
|
||||
}
|
||||
}
|
||||
|
||||
return PX4_ERROR;
|
||||
}
|
||||
|
||||
void RcGhst::fill_rc_in(uint16_t raw_rc_count_local,
|
||||
uint16_t raw_rc_values_local[input_rc_s::RC_INPUT_MAX_CHANNELS],
|
||||
hrt_abstime now, bool frame_drop, bool failsafe,
|
||||
unsigned frame_drops, int rssi = -1)
|
||||
{
|
||||
// fill rc_in struct for publishing
|
||||
_rc_in.channel_count = raw_rc_count_local;
|
||||
|
||||
if (_rc_in.channel_count > input_rc_s::RC_INPUT_MAX_CHANNELS) {
|
||||
_rc_in.channel_count = input_rc_s::RC_INPUT_MAX_CHANNELS;
|
||||
}
|
||||
|
||||
unsigned valid_chans = 0;
|
||||
|
||||
for (unsigned i = 0; i < _rc_in.channel_count; i++) {
|
||||
_rc_in.values[i] = raw_rc_values_local[i];
|
||||
|
||||
if (raw_rc_values_local[i] != UINT16_MAX) {
|
||||
valid_chans++;
|
||||
}
|
||||
|
||||
// once filled, reset values back to default
|
||||
_raw_rc_values[i] = UINT16_MAX;
|
||||
}
|
||||
|
||||
_rc_in.timestamp = now;
|
||||
_rc_in.timestamp_last_signal = _rc_in.timestamp;
|
||||
_rc_in.rc_ppm_frame_length = 0;
|
||||
|
||||
if (valid_chans == 0) {
|
||||
_rc_in.rssi = 0;
|
||||
}
|
||||
|
||||
_rc_in.rc_failsafe = failsafe;
|
||||
_rc_in.rc_lost = (valid_chans == 0);
|
||||
_rc_in.rc_lost_frame_count = frame_drops;
|
||||
_rc_in.rc_total_frame_count = 0;
|
||||
}
|
||||
|
||||
void RcGhst::rc_io_invert(bool invert)
|
||||
{
|
||||
// First check if the board provides a board-specific inversion method (e.g. via GPIO),
|
||||
// and if not use an IOCTL
|
||||
if (!board_rc_invert_input(_device, invert)) {
|
||||
#if defined(TIOCSINVERT)
|
||||
|
||||
if (invert) {
|
||||
ioctl(_rcs_fd, TIOCSINVERT, SER_INVERT_ENABLED_RX | SER_INVERT_ENABLED_TX);
|
||||
|
||||
} else {
|
||||
ioctl(_rcs_fd, TIOCSINVERT, 0);
|
||||
}
|
||||
|
||||
#endif // TIOCSINVERT
|
||||
}
|
||||
}
|
||||
|
||||
void RcGhst::Run()
|
||||
{
|
||||
if (should_exit()) {
|
||||
exit_and_cleanup();
|
||||
return;
|
||||
}
|
||||
|
||||
if (!_initialized) {
|
||||
if (init() == PX4_OK) {
|
||||
_initialized = true;
|
||||
|
||||
} else {
|
||||
PX4_ERR("init failed");
|
||||
exit_and_cleanup();
|
||||
}
|
||||
|
||||
} else {
|
||||
|
||||
perf_begin(_cycle_perf);
|
||||
|
||||
const hrt_abstime cycle_timestamp = hrt_absolute_time();
|
||||
|
||||
bool rc_updated = false;
|
||||
|
||||
// This block scans for a supported serial RC input and locks onto the first one found
|
||||
// Scan for 500 msec, then switch protocol
|
||||
constexpr hrt_abstime rc_scan_max = 500_ms;
|
||||
|
||||
// TODO: needs work (poll _rcs_fd)
|
||||
// int ret = poll(fds, sizeof(fds) / sizeof(fds[0]), 100);
|
||||
// then update priority to SCHED_PRIORITY_FAST_DRIVER
|
||||
// read all available data from the serial RC input UART
|
||||
|
||||
// read all available data from the serial RC input UART
|
||||
int newBytes = ::read(_rcs_fd, &_rcs_buf[0], RC_MAX_BUFFER_SIZE);
|
||||
|
||||
if (newBytes > 0) {
|
||||
_bytes_rx += newBytes;
|
||||
}
|
||||
|
||||
const bool rc_scan_locked = _rc_scan_locked;
|
||||
|
||||
if (_rc_scan_begin == 0) {
|
||||
_rc_scan_begin = cycle_timestamp;
|
||||
// Configure serial port for GHST
|
||||
ghst_config(_rcs_fd);
|
||||
|
||||
// flush serial buffer and any existing buffered data
|
||||
tcflush(_rcs_fd, TCIOFLUSH);
|
||||
memset(_rcs_buf, 0, sizeof(_rcs_buf));
|
||||
|
||||
} else if (_rc_scan_locked
|
||||
|| cycle_timestamp - _rc_scan_begin < rc_scan_max) {
|
||||
|
||||
// parse new data
|
||||
if (newBytes > 0) {
|
||||
int8_t ghst_rssi = -1;
|
||||
rc_updated = ghst_parse(cycle_timestamp, &_rcs_buf[0], newBytes, &_raw_rc_values[0], &ghst_rssi,
|
||||
&_raw_rc_count, input_rc_s::RC_INPUT_MAX_CHANNELS);
|
||||
|
||||
if (rc_updated) {
|
||||
// we have a new GHST frame. Publish it.
|
||||
_rc_in.input_source = input_rc_s::RC_INPUT_SOURCE_PX4FMU_GHST;
|
||||
fill_rc_in(_raw_rc_count, _raw_rc_values, cycle_timestamp, false, false, 0, ghst_rssi);
|
||||
|
||||
_rc_scan_locked = true;
|
||||
|
||||
// telemetry
|
||||
if ((cycle_timestamp - _last_update) > (1_s / (UPDATE_RATE_HZ * NUM_DATA_TYPES))) {
|
||||
|
||||
switch (_next_type) {
|
||||
case 0U:
|
||||
send_battery_status();
|
||||
break;
|
||||
|
||||
case 1U:
|
||||
send_gps1_status();
|
||||
break;
|
||||
|
||||
case 2U:
|
||||
send_gps2_status();
|
||||
break;
|
||||
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
||||
_last_update = cycle_timestamp;
|
||||
_next_type = (_next_type + 1U) % NUM_DATA_TYPES;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
perf_end(_cycle_perf);
|
||||
|
||||
if (rc_updated) {
|
||||
perf_count(_publish_interval_perf);
|
||||
|
||||
_to_input_rc.publish(_rc_in);
|
||||
|
||||
} else if (!rc_updated && (hrt_elapsed_time(&_rc_in.timestamp_last_signal) > 1_s)) {
|
||||
_rc_scan_locked = false;
|
||||
}
|
||||
|
||||
if (!rc_scan_locked && _rc_scan_locked) {
|
||||
PX4_INFO("RC input locked");
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
bool RcGhst::send_battery_status()
|
||||
{
|
||||
battery_status_s battery_status;
|
||||
|
||||
if (_battery_status_sub.update(&battery_status)) {
|
||||
|
||||
float voltage_in_10mV = battery_status.voltage_filtered_v * FACTOR_VOLTS_TO_10MV;
|
||||
float current_in_10mA = battery_status.current_filtered_a * FACTOR_AMPS_TO_10MA;
|
||||
float fuel_in_10mAh = battery_status.discharged_mah * FACTOR_MAH_TO_10MAH;
|
||||
return ghst_send_telemetry_battery_status(_rcs_fd,
|
||||
static_cast<uint16_t>(voltage_in_10mV),
|
||||
static_cast<uint16_t>(current_in_10mA),
|
||||
static_cast<uint16_t>(fuel_in_10mAh));
|
||||
}
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
bool RcGhst::send_gps1_status()
|
||||
{
|
||||
sensor_gps_s vehicle_gps_position;
|
||||
|
||||
if (_vehicle_gps_position_sub.update(&vehicle_gps_position)) {
|
||||
int32_t latitude = vehicle_gps_position.lat; // 1e-7 degrees
|
||||
int32_t longitude = vehicle_gps_position.lon; // 1e-7 degrees
|
||||
uint16_t altitude = vehicle_gps_position.alt / 1000; // mm -> m
|
||||
|
||||
return ghst_send_telemetry_gps1_status(_rcs_fd, latitude, longitude, altitude);
|
||||
}
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
bool RcGhst::send_gps2_status()
|
||||
{
|
||||
sensor_gps_s vehicle_gps_position;
|
||||
|
||||
if (_vehicle_gps_position_sub.update(&vehicle_gps_position)) {
|
||||
|
||||
uint16_t ground_speed = (uint16_t)(vehicle_gps_position.vel_d_m_s / 3.6f * 10.f);
|
||||
uint16_t ground_course = (uint16_t)(math::degrees(vehicle_gps_position.cog_rad) * 100.f);
|
||||
uint8_t num_sats = vehicle_gps_position.satellites_used;
|
||||
|
||||
// TBD: Can these be computed in a RC telemetry driver?
|
||||
uint16_t home_dist = 0;
|
||||
uint16_t home_dir = 0;
|
||||
uint8_t flags = 0;
|
||||
|
||||
return ghst_send_telemetry_gps2_status(_rcs_fd, ground_speed, ground_course, num_sats, home_dist, home_dir, flags);
|
||||
}
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
int RcGhst::custom_command(int argc, char *argv[])
|
||||
{
|
||||
if (!is_running()) {
|
||||
int ret = RcGhst::task_spawn(argc, argv);
|
||||
|
||||
if (ret) {
|
||||
return ret;
|
||||
}
|
||||
}
|
||||
|
||||
return print_usage("unknown command");
|
||||
}
|
||||
|
||||
int RcGhst::print_status()
|
||||
{
|
||||
PX4_INFO("Max update rate: %u Hz", 1000000 / _current_update_interval);
|
||||
|
||||
if (_device[0] != '\0') {
|
||||
PX4_INFO("UART device: %s", _device);
|
||||
PX4_INFO("UART RX bytes: %" PRIu32, _bytes_rx);
|
||||
}
|
||||
|
||||
PX4_INFO("RC state: %s", _rc_scan_locked ? "found" : "searching for signal");
|
||||
// PX4_INFO("GHST Telemetry: %s", _ghst_telemetry ? "yes" : "no");
|
||||
|
||||
perf_print_counter(_cycle_perf);
|
||||
perf_print_counter(_publish_interval_perf);
|
||||
|
||||
if (hrt_elapsed_time(&_rc_in.timestamp) < 1_s) {
|
||||
print_message(ORB_ID(input_rc), _rc_in);
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int RcGhst::print_usage(const char *reason)
|
||||
{
|
||||
if (reason) {
|
||||
PX4_WARN("%s\n", reason);
|
||||
}
|
||||
|
||||
PRINT_MODULE_DESCRIPTION(
|
||||
R"DESCR_STR(
|
||||
### Description
|
||||
This module does the RC input parsing and auto-selecting the method. Supported methods are:
|
||||
- GHST
|
||||
|
||||
)DESCR_STR");
|
||||
|
||||
PRINT_MODULE_USAGE_NAME("rc_ghst", "driver");
|
||||
PRINT_MODULE_USAGE_COMMAND("start");
|
||||
PRINT_MODULE_USAGE_PARAM_STRING('d', "/dev/ttyS3", "<file:dev>", "RC device", false);
|
||||
|
||||
PRINT_MODULE_USAGE_DEFAULT_COMMANDS();
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
extern "C" __EXPORT int rc_ghst_main(int argc, char *argv[])
|
||||
{
|
||||
return RcGhst::main(argc, argv);
|
||||
}
|
||||
@@ -1,6 +1,6 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2021 PX4 Development Team. All rights reserved.
|
||||
* Copyright (c) 2012-2022 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
@@ -31,44 +31,83 @@
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file ghst_telemetry.cpp
|
||||
*
|
||||
* IRC Ghost (Immersion RC Ghost) telemetry.
|
||||
*
|
||||
* @author Igor Misic <igy1000mb@gmail.com>
|
||||
* @author Juraj Ciberlin <jciberlin1@gmail.com>
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <uORB/Subscription.hpp>
|
||||
#include <uORB/topics/battery_status.h>
|
||||
#include <uORB/topics/sensor_gps.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <float.h>
|
||||
|
||||
/**
|
||||
* High-level class that handles sending of GHST telemetry data
|
||||
*/
|
||||
class GHSTTelemetry
|
||||
#include "ghst_parser.hpp"
|
||||
|
||||
#include <board_config.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <lib/perf/perf_counter.h>
|
||||
#include <px4_platform_common/px4_config.h>
|
||||
#include <px4_platform_common/getopt.h>
|
||||
#include <px4_platform_common/log.h>
|
||||
#include <px4_platform_common/module.h>
|
||||
#include <px4_platform_common/module_params.h>
|
||||
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
|
||||
#include <uORB/PublicationMulti.hpp>
|
||||
#include <uORB/Subscription.hpp>
|
||||
#include <uORB/SubscriptionInterval.hpp>
|
||||
#include <uORB/topics/battery_status.h>
|
||||
#include <uORB/topics/input_rc.h>
|
||||
#include <uORB/topics/sensor_gps.h>
|
||||
|
||||
class RcGhst : public ModuleBase<RcGhst>, public ModuleParams, public px4::ScheduledWorkItem
|
||||
{
|
||||
public:
|
||||
/**
|
||||
* @param uart_fd file descriptor for the UART to use. It is expected to be configured
|
||||
* already.
|
||||
*/
|
||||
explicit GHSTTelemetry(int uart_fd);
|
||||
RcGhst(const char *device);
|
||||
virtual ~RcGhst();
|
||||
|
||||
~GHSTTelemetry() = default;
|
||||
/** @see ModuleBase */
|
||||
static int task_spawn(int argc, char *argv[]);
|
||||
|
||||
/**
|
||||
* Send telemetry data. Call this regularly (i.e. at 100Hz), it will automatically
|
||||
* limit the sending rate.
|
||||
* @return true if new data sent
|
||||
*/
|
||||
bool update(const hrt_abstime &now);
|
||||
/** @see ModuleBase */
|
||||
static int custom_command(int argc, char *argv[]);
|
||||
|
||||
/** @see ModuleBase */
|
||||
static int print_usage(const char *reason = nullptr);
|
||||
|
||||
/** @see ModuleBase::print_status() */
|
||||
int print_status() override;
|
||||
|
||||
int init();
|
||||
|
||||
private:
|
||||
void Run() override;
|
||||
|
||||
void fill_rc_in(uint16_t raw_rc_count_local,
|
||||
uint16_t raw_rc_values_local[input_rc_s::RC_INPUT_MAX_CHANNELS],
|
||||
hrt_abstime now, bool frame_drop, bool failsafe,
|
||||
unsigned frame_drops, int rssi);
|
||||
|
||||
void rc_io_invert(bool invert);
|
||||
|
||||
hrt_abstime _rc_scan_begin{0};
|
||||
|
||||
bool _initialized{false};
|
||||
bool _rc_scan_locked{false};
|
||||
|
||||
static constexpr unsigned _current_update_interval{4000}; // 250 Hz
|
||||
|
||||
input_rc_s _rc_in{};
|
||||
|
||||
uORB::PublicationMulti<input_rc_s> _to_input_rc{ORB_ID(input_rc)};
|
||||
|
||||
int _rcs_fd{-1};
|
||||
char _device[20] {}; ///< device / serial port path
|
||||
|
||||
static constexpr size_t RC_MAX_BUFFER_SIZE{sizeof(ghst_frame_t)};
|
||||
uint8_t _rcs_buf[RC_MAX_BUFFER_SIZE] {};
|
||||
|
||||
uint16_t _raw_rc_values[input_rc_s::RC_INPUT_MAX_CHANNELS] {};
|
||||
uint16_t _raw_rc_count{};
|
||||
|
||||
perf_counter_t _cycle_perf{perf_alloc(PC_ELAPSED, MODULE_NAME": cycle time")};
|
||||
perf_counter_t _publish_interval_perf{perf_alloc(PC_INTERVAL, MODULE_NAME": publish interval")};
|
||||
uint32_t _bytes_rx{0};
|
||||
|
||||
// telemetry
|
||||
bool send_battery_status();
|
||||
bool send_gps1_status();
|
||||
bool send_gps2_status();
|
||||
@@ -76,9 +115,8 @@ private:
|
||||
uORB::Subscription _vehicle_gps_position_sub{ORB_ID(vehicle_gps_position)};
|
||||
uORB::Subscription _battery_status_sub{ORB_ID(battery_status)};
|
||||
|
||||
int _uart_fd;
|
||||
hrt_abstime _last_update {0U};
|
||||
uint32_t _next_type {0U};
|
||||
hrt_abstime _last_update{};
|
||||
uint32_t _next_type{};
|
||||
|
||||
static constexpr uint32_t NUM_DATA_TYPES {3U}; // number of different telemetry data types
|
||||
static constexpr uint32_t UPDATE_RATE_HZ {10U}; // update rate [Hz]
|
||||
@@ -87,5 +125,4 @@ private:
|
||||
static constexpr float FACTOR_VOLTS_TO_10MV {100.0F};
|
||||
static constexpr float FACTOR_AMPS_TO_10MA {100.0F};
|
||||
static constexpr float FACTOR_MAH_TO_10MAH {0.1F};
|
||||
|
||||
};
|
||||
@@ -53,15 +53,12 @@
|
||||
#endif
|
||||
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <limits.h>
|
||||
#include <termios.h>
|
||||
#include <string.h>
|
||||
#include <unistd.h>
|
||||
|
||||
// TODO: include RSSI dBm to percentage conversion for ghost receiver
|
||||
#include "spektrum_rssi.h"
|
||||
|
||||
#include "ghst.hpp"
|
||||
#include "common_rc.h"
|
||||
#include "ghst_parser.hpp"
|
||||
|
||||
#define MIN(a,b) (((a)<(b))?(a):(b))
|
||||
|
||||
@@ -79,12 +76,59 @@ enum class ghst_parser_state_t : uint8_t {
|
||||
// only RSSI frame contains value of RSSI, if it is not received, send last received RSSI
|
||||
static int8_t ghst_rssi = -1;
|
||||
|
||||
static ghst_frame_t &ghst_frame = rc_decode_buf.ghst_frame;
|
||||
static ghst_frame_t ghst_frame;
|
||||
static uint32_t current_frame_position = 0U;
|
||||
static ghst_parser_state_t parser_state = ghst_parser_state_t::unsynced;
|
||||
|
||||
static uint16_t prev_rc_vals[GHST_MAX_NUM_CHANNELS];
|
||||
|
||||
static uint8_t crc8_dvb_s2(uint8_t crc, uint8_t a)
|
||||
{
|
||||
crc ^= a;
|
||||
|
||||
for (int i = 0; i < 8; ++i) {
|
||||
if (crc & 0x80) {
|
||||
crc = (crc << 1) ^ 0xD5;
|
||||
|
||||
} else {
|
||||
crc = crc << 1;
|
||||
}
|
||||
}
|
||||
|
||||
return crc;
|
||||
}
|
||||
|
||||
static uint8_t crc8_dvb_s2_buf(uint8_t *buf, int len)
|
||||
{
|
||||
uint8_t crc = 0;
|
||||
|
||||
for (int i = 0; i < len; ++i) {
|
||||
crc = crc8_dvb_s2(crc, buf[i]);
|
||||
}
|
||||
|
||||
return crc;
|
||||
}
|
||||
|
||||
static constexpr int8_t lu_dbm_percent[] {
|
||||
100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100,
|
||||
100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100,
|
||||
100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 99, 98, 98, 97, 96,
|
||||
95, 94, 93, 92, 91, 90, 89, 88, 87, 86, 85, 84, 83, 82, 81, 79,
|
||||
78, 77, 75, 74, 73, 71, 70, 68, 66, 65, 63, 61, 59, 57, 55, 52,
|
||||
50, 47, 45, 42, 39, 35, 32, 28, 24, 19, 13, 7, 0, 0, 0, 0,
|
||||
0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
|
||||
0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
|
||||
0,
|
||||
};
|
||||
|
||||
#define MASK(n) (n >> (sizeof(n) * CHAR_BIT - 1))
|
||||
|
||||
/* constexpr-compatible version of abs() */
|
||||
static constexpr unsigned c_abs(int n) { return (n + MASK(n)) ^ MASK(n); }
|
||||
|
||||
/* convert signed dbm (-92 to -42) to percentage */
|
||||
static constexpr int8_t dbm_to_percent(int8_t dbm) { return lu_dbm_percent[c_abs(dbm)]; }
|
||||
|
||||
/**
|
||||
* parse the current ghst_frame buffer
|
||||
*/
|
||||
@@ -104,14 +148,6 @@ int ghst_config(int uart_fd)
|
||||
return ret_val;
|
||||
}
|
||||
|
||||
/**
|
||||
* Convert from RC to PWM value
|
||||
* @param chan_value channel value in [172, 1811]
|
||||
* @return PWM channel value in [1000, 2000]
|
||||
*/
|
||||
static uint16_t convert_channel_value(unsigned chan_value);
|
||||
|
||||
|
||||
bool ghst_parse(const uint64_t now, const uint8_t *frame, unsigned len, uint16_t *values,
|
||||
int8_t *rssi, uint16_t *num_values, uint16_t max_channels)
|
||||
{
|
||||
@@ -164,7 +200,12 @@ uint8_t ghst_frame_CRC(const ghst_frame_t &frame)
|
||||
return crc;
|
||||
}
|
||||
|
||||
static uint16_t convert_channel_value(unsigned int chan_value)
|
||||
/**
|
||||
* Convert from RC to PWM value
|
||||
* @param chan_value channel value in [172, 1811]
|
||||
* @return PWM channel value in [1000, 2000]
|
||||
*/
|
||||
static uint16_t convert_channel_value(unsigned chan_value)
|
||||
{
|
||||
/*
|
||||
* RC PWM
|
||||
@@ -297,7 +338,7 @@ static bool ghst_parse_buffer(uint16_t *values, int8_t *rssi, uint16_t *num_valu
|
||||
} else if (ghst_frame.type == static_cast<uint8_t>(ghstFrameType::frameTypeRssi)) {
|
||||
const ghstPayloadRssi_t *const rssiValues = (ghstPayloadRssi_t *)&ghst_frame.payload;
|
||||
// TODO: call function for RSSI dBm to percentage conversion for ghost receiver
|
||||
ghst_rssi = spek_dbm_to_percent(static_cast<int8_t>(rssiValues->rssidBm));
|
||||
ghst_rssi = dbm_to_percent(static_cast<int8_t>(rssiValues->rssidBm));
|
||||
|
||||
} else {
|
||||
GHST_DEBUG("Frame type: %u", ghst_frame.type);
|
||||
@@ -428,4 +469,3 @@ bool ghst_send_telemetry_gps2_status(int uart_fd, uint16_t ground_speed, uint16_
|
||||
|
||||
return write(uart_fd, buf, offset) == offset;
|
||||
}
|
||||
|
||||
@@ -0,0 +1,7 @@
|
||||
module_name: RC GHST input driver
|
||||
serial_config:
|
||||
- command: "rc_ghst start -d ${SERIAL_DEV}"
|
||||
port_config_param:
|
||||
name: RC_GHST_PRT_CFG
|
||||
group: Serial
|
||||
#default: RC
|
||||
+7
-6
@@ -1,6 +1,6 @@
|
||||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2016 PX4 Development Team. All rights reserved.
|
||||
# Copyright (c) 2016-2022 PX4 Development Team. All rights reserved.
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
@@ -32,10 +32,11 @@
|
||||
############################################################################
|
||||
|
||||
px4_add_module(
|
||||
MODULE drivers__snapdragon_spektrum_rc
|
||||
MAIN spektrum_rc
|
||||
MODULE drivers__rc__ghst__test
|
||||
MAIN rc_ghst_test
|
||||
COMPILE_FLAGS
|
||||
-Wno-unused-result
|
||||
SRCS
|
||||
spektrum_rc.cpp
|
||||
DEPENDS
|
||||
rc
|
||||
RcGhstTest.cpp
|
||||
../ghst_parser.cpp
|
||||
)
|
||||
@@ -0,0 +1,123 @@
|
||||
#include <unit_test.h>
|
||||
|
||||
#include <systemlib/err.h>
|
||||
|
||||
#include <stdio.h>
|
||||
#include <string.h>
|
||||
#include <unistd.h>
|
||||
|
||||
#include <drivers/drv_hrt.h>
|
||||
|
||||
#include "../ghst_parser.hpp"
|
||||
|
||||
#if defined(CONFIG_ARCH_BOARD_PX4_SITL)
|
||||
#define TEST_DATA_PATH "./test_data/"
|
||||
#else
|
||||
#define TEST_DATA_PATH "/fs/microsd"
|
||||
#endif
|
||||
|
||||
class RcGhstTest : public UnitTest
|
||||
{
|
||||
public:
|
||||
bool run_tests() override;
|
||||
|
||||
private:
|
||||
bool ghstTest();
|
||||
};
|
||||
|
||||
bool RcGhstTest::run_tests()
|
||||
{
|
||||
ut_run_test(ghstTest);
|
||||
|
||||
return (_tests_failed == 0);
|
||||
}
|
||||
|
||||
bool RcGhstTest::ghstTest()
|
||||
{
|
||||
const char *filepath = TEST_DATA_PATH "ghst_rc_channels.txt";
|
||||
|
||||
FILE *fp = fopen(filepath, "rt");
|
||||
|
||||
ut_test(fp);
|
||||
|
||||
int uart_fd = -1;
|
||||
const int line_size = 500;
|
||||
char line[line_size];
|
||||
bool has_decoded_values = false;
|
||||
const int max_channels = 16;
|
||||
uint16_t rc_values[max_channels];
|
||||
uint16_t num_values = 0;
|
||||
int line_counter = 1;
|
||||
int8_t ghst_rssi = -1;
|
||||
ghst_config(uart_fd);
|
||||
|
||||
while (fgets(line, line_size, fp) != nullptr) {
|
||||
|
||||
if (strncmp(line, "INPUT ", 6) == 0) {
|
||||
|
||||
if (has_decoded_values) {
|
||||
PX4_ERR("Parser decoded values that are not in the test file (line=%i)", line_counter);
|
||||
return false;
|
||||
}
|
||||
|
||||
// read the values
|
||||
const char *file_buffer = line + 6;
|
||||
int frame_len = 0;
|
||||
uint8_t frame[300];
|
||||
int offset;
|
||||
int number;
|
||||
|
||||
while (sscanf(file_buffer, "%x, %n", &number, &offset) > 0) {
|
||||
frame[frame_len++] = number;
|
||||
file_buffer += offset;
|
||||
}
|
||||
|
||||
// Pipe the data into the parser
|
||||
hrt_abstime now = hrt_absolute_time();
|
||||
|
||||
bool result = ghst_parse(now, frame, frame_len, rc_values, &ghst_rssi, &num_values, max_channels);
|
||||
|
||||
if (result) {
|
||||
has_decoded_values = true;
|
||||
}
|
||||
|
||||
} else if (strncmp(line, "DECODED ", 8) == 0) {
|
||||
|
||||
if (!has_decoded_values) {
|
||||
PX4_ERR("Test file contains decoded values but the parser did not decode anything (line=%i)", line_counter);
|
||||
return false;
|
||||
}
|
||||
|
||||
// read the values
|
||||
const char *file_buffer = line + 8;
|
||||
int offset;
|
||||
int expected_rc_value;
|
||||
int expected_num_channels = 0;
|
||||
|
||||
while (sscanf(file_buffer, "%x, %n", &expected_rc_value, &offset) > 0) {
|
||||
|
||||
// allow a small difference
|
||||
if (abs(expected_rc_value - (int)rc_values[expected_num_channels]) > 10) {
|
||||
PX4_ERR("File line: %i, channel: %i", line_counter, expected_num_channels);
|
||||
ut_compare("Wrong decoded channel", expected_rc_value, rc_values[expected_num_channels]);
|
||||
}
|
||||
|
||||
file_buffer += offset;
|
||||
++expected_num_channels;
|
||||
}
|
||||
|
||||
if (expected_num_channels != num_values) {
|
||||
PX4_ERR("File line: %d", line_counter);
|
||||
ut_compare("Unexpected number of decoded channels", expected_num_channels, num_values);
|
||||
}
|
||||
|
||||
has_decoded_values = false;
|
||||
}
|
||||
|
||||
++line_counter;
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
ut_declare_test_c(rc_ghst_test_main, RcGhstTest)
|
||||
@@ -1,6 +1,6 @@
|
||||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2015 PX4 Development Team. All rights reserved.
|
||||
# Copyright (c) 2015-2022 PX4 Development Team. All rights reserved.
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
@@ -31,15 +31,14 @@
|
||||
#
|
||||
############################################################################
|
||||
px4_add_module(
|
||||
MODULE drivers__rc_input
|
||||
MAIN rc_input
|
||||
MODULE drivers__rc__ppm_in
|
||||
MAIN ppm_in
|
||||
COMPILE_FLAGS
|
||||
SRCS
|
||||
RCInput.cpp
|
||||
crsf_telemetry.cpp
|
||||
ghst_telemetry.cpp
|
||||
RCInput.hpp
|
||||
MODULE_CONFIG
|
||||
module.yaml
|
||||
DEPENDS
|
||||
rc
|
||||
px4_work_queue
|
||||
)
|
||||
Some files were not shown because too many files have changed in this diff Show More
Reference in New Issue
Block a user