forked from Archive/PX4-Autopilot
boards: sync
This commit is contained in:
parent
72ca6902f0
commit
d8148c8e3b
|
@ -15,6 +15,7 @@ px4_add_board(
|
|||
TEL1:/dev/ttyS1
|
||||
TEL2:/dev/ttyS2
|
||||
DRIVERS
|
||||
adc/ads1115
|
||||
adc/board_adc
|
||||
barometer # all available barometer drivers
|
||||
batt_smbus
|
||||
|
@ -31,13 +32,12 @@ px4_add_board(
|
|||
imu/invensense/mpu6000
|
||||
imu/invensense/mpu6500
|
||||
irlock
|
||||
lights/blinkm
|
||||
lights/rgbled
|
||||
#lights/rgbled_ncp5623c
|
||||
lights # all available light drivers
|
||||
magnetometer # all available magnetometer drivers
|
||||
optical_flow # all available optical flow drivers
|
||||
#osd
|
||||
osd
|
||||
pca9685
|
||||
pca9685_pwm_out
|
||||
power_monitor/ina226
|
||||
#protocol_splitter
|
||||
pwm_input
|
||||
|
@ -45,6 +45,7 @@ px4_add_board(
|
|||
pwm_out
|
||||
rc_input
|
||||
roboclaw
|
||||
rpm
|
||||
telemetry # all available telemetry drivers
|
||||
test_ppm
|
||||
tone_alarm
|
||||
|
@ -57,6 +58,7 @@ px4_add_board(
|
|||
commander
|
||||
dataman
|
||||
ekf2
|
||||
esc_battery
|
||||
events
|
||||
flight_mode_manager
|
||||
fw_att_control
|
||||
|
@ -72,12 +74,15 @@ px4_add_board(
|
|||
mc_hover_thrust_estimator
|
||||
mc_pos_control
|
||||
mc_rate_control
|
||||
#micrortps_bridge
|
||||
navigator
|
||||
rc_update
|
||||
rover_pos_control
|
||||
sensors
|
||||
sih
|
||||
temperature_compensation
|
||||
uuv_att_control
|
||||
uuv_pos_control
|
||||
vmount
|
||||
vtol_att_control
|
||||
SYSTEMCMDS
|
||||
|
@ -85,6 +90,7 @@ px4_add_board(
|
|||
#dmesg
|
||||
dumpfile
|
||||
esc_calib
|
||||
gpio
|
||||
hardfault_log
|
||||
i2cdetect
|
||||
led_control
|
||||
|
@ -111,6 +117,8 @@ px4_add_board(
|
|||
work_queue
|
||||
EXAMPLES
|
||||
fake_gps
|
||||
fake_gyro
|
||||
fake_magnetometer
|
||||
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
hello
|
||||
hwtest # Hardware test
|
||||
|
|
|
@ -31,13 +31,12 @@ px4_add_board(
|
|||
imu/adis16477
|
||||
imu/adis16497
|
||||
irlock
|
||||
lights/blinkm
|
||||
#lights/rgbled
|
||||
#lights/rgbled_ncp5623c
|
||||
lights # all available light drivers
|
||||
magnetometer # all available magnetometer drivers
|
||||
optical_flow # all available optical flow drivers
|
||||
#osd
|
||||
pca9685
|
||||
#pca9685_pwm_out
|
||||
power_monitor/ina226
|
||||
#protocol_splitter
|
||||
#pwm_input
|
||||
|
@ -45,6 +44,7 @@ px4_add_board(
|
|||
pwm_out
|
||||
rc_input
|
||||
roboclaw
|
||||
rpm
|
||||
telemetry # all available telemetry drivers
|
||||
test_ppm
|
||||
#tone_alarm
|
||||
|
@ -57,6 +57,7 @@ px4_add_board(
|
|||
commander
|
||||
dataman
|
||||
ekf2
|
||||
esc_battery
|
||||
events
|
||||
flight_mode_manager
|
||||
fw_att_control
|
||||
|
@ -72,19 +73,23 @@ px4_add_board(
|
|||
mc_hover_thrust_estimator
|
||||
mc_pos_control
|
||||
mc_rate_control
|
||||
#micrortps_bridge
|
||||
navigator
|
||||
rc_update
|
||||
rover_pos_control
|
||||
sensors
|
||||
sih
|
||||
temperature_compensation
|
||||
uuv_att_control
|
||||
uuv_pos_control
|
||||
vmount
|
||||
vtol_att_control
|
||||
SYSTEMCMDS
|
||||
#bl_update
|
||||
bl_update
|
||||
dmesg
|
||||
dumpfile
|
||||
esc_calib
|
||||
gpio
|
||||
hardfault_log
|
||||
i2cdetect
|
||||
led_control
|
||||
|
@ -108,6 +113,8 @@ px4_add_board(
|
|||
work_queue
|
||||
EXAMPLES
|
||||
fake_gps
|
||||
fake_gyro
|
||||
fake_magnetometer
|
||||
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
hello
|
||||
hwtest # Hardware test
|
||||
|
|
|
@ -19,6 +19,7 @@ px4_add_board(
|
|||
# CONSOLE: /dev/ttyS4
|
||||
# RC: /dev/ttyS5
|
||||
DRIVERS
|
||||
adc/ads1115
|
||||
adc/board_adc
|
||||
barometer # all available barometer drivers
|
||||
batt_smbus
|
||||
|
@ -30,24 +31,24 @@ px4_add_board(
|
|||
gps
|
||||
heater
|
||||
#imu # all available imu drivers
|
||||
imu/analog_devices/adis16448
|
||||
imu/bosch/bmi088
|
||||
imu/invensense/icm20649
|
||||
imu/invensense/icm20689
|
||||
irlock
|
||||
lights/blinkm
|
||||
lights/rgbled
|
||||
lights/rgbled_ncp5623c
|
||||
lights/rgbled_pwm
|
||||
lights # all available light drivers
|
||||
magnetometer # all available magnetometer drivers
|
||||
optical_flow # all available optical flow drivers
|
||||
#osd
|
||||
osd
|
||||
pca9685
|
||||
pca9685_pwm_out
|
||||
power_monitor/ina226
|
||||
#protocol_splitter
|
||||
pwm_out_sim
|
||||
pwm_out
|
||||
rc_input
|
||||
roboclaw
|
||||
rpm
|
||||
safety_button
|
||||
telemetry # all available telemetry drivers
|
||||
test_ppm
|
||||
|
@ -61,6 +62,7 @@ px4_add_board(
|
|||
commander
|
||||
dataman
|
||||
ekf2
|
||||
esc_battery
|
||||
events
|
||||
flight_mode_manager
|
||||
fw_att_control
|
||||
|
@ -76,12 +78,15 @@ px4_add_board(
|
|||
mc_hover_thrust_estimator
|
||||
mc_pos_control
|
||||
mc_rate_control
|
||||
#micrortps_bridge
|
||||
navigator
|
||||
rc_update
|
||||
rover_pos_control
|
||||
sensors
|
||||
sih
|
||||
temperature_compensation
|
||||
uuv_att_control
|
||||
uuv_pos_control
|
||||
vmount
|
||||
vtol_att_control
|
||||
SYSTEMCMDS
|
||||
|
@ -89,6 +94,7 @@ px4_add_board(
|
|||
dmesg
|
||||
dumpfile
|
||||
esc_calib
|
||||
gpio
|
||||
hardfault_log
|
||||
i2cdetect
|
||||
led_control
|
||||
|
@ -104,6 +110,7 @@ px4_add_board(
|
|||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
serial_test
|
||||
system_time
|
||||
tests # tests and test runner
|
||||
top
|
||||
|
@ -115,6 +122,7 @@ px4_add_board(
|
|||
work_queue
|
||||
EXAMPLES
|
||||
fake_gps
|
||||
fake_gyro
|
||||
fake_magnetometer
|
||||
#fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
#hello
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
#!/bin/sh
|
||||
#
|
||||
# board specific board MAVLink startup script.
|
||||
# board specific MAVLink startup script.
|
||||
#------------------------------------------------------------------------------
|
||||
|
||||
# Start MAVLink on the USB port
|
||||
|
|
|
@ -220,55 +220,61 @@
|
|||
|
||||
#define STM32_SDMMC_CLKCR_EDGE STM32_SDMMC_CLKCR_NEGEDGE
|
||||
|
||||
|
||||
/* UART/USART */
|
||||
#define GPIO_USART1_RX GPIO_USART1_RX_3 /* PB7 */
|
||||
#define GPIO_USART1_TX GPIO_USART1_TX_3 /* PB6 */
|
||||
#define GPIO_USART1_TX GPIO_USART1_TX_3 /* PB6 */
|
||||
#define GPIO_USART1_RX GPIO_USART1_RX_3 /* PB7 */
|
||||
|
||||
#define GPIO_USART2_RX GPIO_USART2_RX_2 /* PD6 */
|
||||
#define GPIO_USART2_TX GPIO_USART2_TX_2 /* PD5 */
|
||||
#define GPIO_USART2_RTS GPIO_USART2_RTS_2 /* PD4 */
|
||||
#define GPIO_USART2_CTS GPIO_USART2_CTS_NSS_2 /* PD3 */
|
||||
#define GPIO_USART2_CTS GPIO_USART2_CTS_NSS_2 /* PD3 */
|
||||
#define GPIO_USART2_RTS GPIO_USART2_RTS_2 /* PD4 */
|
||||
#define GPIO_USART2_TX GPIO_USART2_TX_2 /* PD5 */
|
||||
#define GPIO_USART2_RX GPIO_USART2_RX_2 /* PD6 */
|
||||
|
||||
#define GPIO_UART4_RX GPIO_UART4_RX_5 /* PD0 */
|
||||
#define GPIO_UART4_TX GPIO_UART4_TX_5 /* PD1 */
|
||||
#define GPIO_UART4_TX GPIO_UART4_TX_5 /* PD1 */
|
||||
#define GPIO_UART4_RX GPIO_UART4_RX_5 /* PD0 */
|
||||
|
||||
#define GPIO_USART6_RX GPIO_USART6_RX_2 /* PG9 */
|
||||
#define GPIO_USART6_TX GPIO_USART6_TX_2 /* PG14 */
|
||||
#define GPIO_USART6_RX GPIO_USART6_RX_2 /* PG9 */
|
||||
#define GPIO_USART6_RTS GPIO_USART6_RTS_2 /* PG8 */
|
||||
#define GPIO_USART6_CTS GPIO_USART6_CTS_NSS_2 /* PG15 */
|
||||
|
||||
#define GPIO_UART7_RX GPIO_UART7_RX_4 /* PF6 */
|
||||
#define GPIO_UART7_TX GPIO_UART7_TX_3 /* PE8 */
|
||||
#define GPIO_UART7_TX GPIO_UART7_TX_3 /* PE8 */
|
||||
#define GPIO_UART7_RX GPIO_UART7_RX_4 /* PF6 */
|
||||
|
||||
#define GPIO_UART8_TX GPIO_UART8_TX_1 /* PE1 */
|
||||
#define GPIO_UART8_RX GPIO_UART8_RX_1 /* PE0 */
|
||||
|
||||
#define GPIO_UART8_RX GPIO_UART8_RX_1 /* PE0 */
|
||||
#define GPIO_UART8_TX GPIO_UART8_TX_1 /* PE1 */
|
||||
|
||||
/* CAN */
|
||||
#define GPIO_CAN1_RX GPIO_CAN1_RX_5 /* PI9 */
|
||||
#define GPIO_CAN1_TX GPIO_CAN1_TX_4 /* PH13 */
|
||||
#define GPIO_CAN1_RX GPIO_CAN1_RX_5 /* PI9 */
|
||||
#define GPIO_CAN2_RX GPIO_CAN2_RX_1 /* PB12 */
|
||||
#define GPIO_CAN2_TX GPIO_CAN2_TX_1 /* PB13 */
|
||||
|
||||
|
||||
/* SPI */
|
||||
#define GPIO_SPI1_SCK GPIO_SPI1_SCK_3 /* PG11 */
|
||||
#define GPIO_SPI1_MISO GPIO_SPI1_MISO_1 /* PA6 */
|
||||
#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_3 /* PD7 */
|
||||
#define ADJ_SLEW_RATE(p) (((p) & ~GPIO_SPEED_MASK) | (GPIO_SPEED_2MHz))
|
||||
|
||||
#define GPIO_SPI2_SCK GPIO_SPI2_SCK_6 /* PI1 */
|
||||
#define GPIO_SPI2_MISO GPIO_SPI2_MISO_3 /* PI2 */
|
||||
#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_4 /* PI3 */
|
||||
#define GPIO_SPI1_SCK ADJ_SLEW_RATE(GPIO_SPI1_SCK_3) /* PG11 */
|
||||
#define GPIO_SPI1_MISO GPIO_SPI1_MISO_1 /* PA6 */
|
||||
#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_3 /* PD7 */
|
||||
|
||||
#define GPIO_SPI4_SCK GPIO_SPI4_SCK_2 /* PE2 */
|
||||
#define GPIO_SPI4_MISO GPIO_SPI4_MISO_1 /* PE13 */
|
||||
#define GPIO_SPI4_MOSI GPIO_SPI4_MOSI_2 /* PE6 */
|
||||
#define GPIO_SPI2_SCK ADJ_SLEW_RATE(GPIO_SPI2_SCK_6) /* PI1 */
|
||||
#define GPIO_SPI2_MISO GPIO_SPI2_MISO_3 /* PI2 */
|
||||
#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_4 /* PI3 */
|
||||
|
||||
#define GPIO_SPI5_SCK GPIO_SPI5_SCK_1 /* PF7 */
|
||||
#define GPIO_SPI5_MISO GPIO_SPI5_MISO_1 /* PF8 */
|
||||
#define GPIO_SPI5_MOSI GPIO_SPI5_MOSI_2 /* PF9 */
|
||||
#define GPIO_SPI4_SCK ADJ_SLEW_RATE(GPIO_SPI4_SCK_2) /* PE2 */
|
||||
#define GPIO_SPI4_MISO GPIO_SPI4_MISO_1 /* PE13 */
|
||||
#define GPIO_SPI4_MOSI GPIO_SPI4_MOSI_2 /* PE6 */
|
||||
|
||||
#define GPIO_SPI5_SCK ADJ_SLEW_RATE(GPIO_SPI5_SCK_1) /* PF7 */
|
||||
#define GPIO_SPI5_MISO GPIO_SPI5_MISO_1 /* PF8 */
|
||||
#define GPIO_SPI5_MOSI GPIO_SPI5_MOSI_2 /* PF9 */
|
||||
|
||||
#define GPIO_SPI6_SCK ADJ_SLEW_RATE(GPIO_SPI6_SCK_1) /* PG13 */
|
||||
#define GPIO_SPI6_MISO GPIO_SPI6_MISO_1 /* PG12 */
|
||||
#define GPIO_SPI6_MOSI GPIO_SPI6_MOSI_2 /* PA7 */
|
||||
|
||||
#define GPIO_SPI6_SCK GPIO_SPI6_SCK_1 /* PG13 */
|
||||
#define GPIO_SPI6_MISO GPIO_SPI6_MISO_1 /* PG12 */
|
||||
#define GPIO_SPI6_MOSI GPIO_SPI6_MOSI_2 /* PA7 */
|
||||
|
||||
/* I2C */
|
||||
#define GPIO_I2C1_SCL GPIO_I2C1_SCL_2 /* PB8 */
|
||||
|
|
|
@ -19,6 +19,7 @@ px4_add_board(
|
|||
# CONSOLE: /dev/ttyS4
|
||||
# RC: /dev/ttyS5
|
||||
DRIVERS
|
||||
adc/ads1115
|
||||
adc/board_adc
|
||||
barometer # all available barometer drivers
|
||||
batt_smbus
|
||||
|
@ -31,26 +32,23 @@ px4_add_board(
|
|||
heater
|
||||
#imu # all available imu drivers
|
||||
imu/analog_devices/adis16448
|
||||
imu/adis16477
|
||||
imu/adis16497
|
||||
imu/bosch/bmi088
|
||||
imu/invensense/icm20649
|
||||
imu/invensense/icm20689
|
||||
irlock
|
||||
lights/blinkm
|
||||
lights/rgbled
|
||||
lights/rgbled_ncp5623c
|
||||
lights/rgbled_pwm
|
||||
lights # all available light drivers
|
||||
magnetometer # all available magnetometer drivers
|
||||
optical_flow # all available optical flow drivers
|
||||
#osd
|
||||
osd
|
||||
pca9685
|
||||
pca9685_pwm_out
|
||||
power_monitor/ina226
|
||||
#protocol_splitter
|
||||
pwm_out_sim
|
||||
pwm_out
|
||||
rc_input
|
||||
roboclaw
|
||||
rpm
|
||||
safety_button
|
||||
telemetry # all available telemetry drivers
|
||||
test_ppm
|
||||
|
@ -64,6 +62,7 @@ px4_add_board(
|
|||
commander
|
||||
dataman
|
||||
ekf2
|
||||
esc_battery
|
||||
events
|
||||
flight_mode_manager
|
||||
fw_att_control
|
||||
|
@ -79,12 +78,15 @@ px4_add_board(
|
|||
mc_hover_thrust_estimator
|
||||
mc_pos_control
|
||||
mc_rate_control
|
||||
#micrortps_bridge
|
||||
navigator
|
||||
rc_update
|
||||
rover_pos_control
|
||||
sensors
|
||||
sih
|
||||
temperature_compensation
|
||||
uuv_att_control
|
||||
uuv_pos_control
|
||||
vmount
|
||||
vtol_att_control
|
||||
SYSTEMCMDS
|
||||
|
@ -92,6 +94,7 @@ px4_add_board(
|
|||
dmesg
|
||||
dumpfile
|
||||
esc_calib
|
||||
gpio
|
||||
hardfault_log
|
||||
i2cdetect
|
||||
led_control
|
||||
|
@ -107,6 +110,7 @@ px4_add_board(
|
|||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
serial_test
|
||||
system_time
|
||||
tests # tests and test runner
|
||||
top
|
||||
|
@ -118,6 +122,7 @@ px4_add_board(
|
|||
work_queue
|
||||
EXAMPLES
|
||||
fake_gps
|
||||
fake_gyro
|
||||
fake_magnetometer
|
||||
#fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
#hello
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
#!/bin/sh
|
||||
#
|
||||
# board specific board MAVLink startup script.
|
||||
# board specific MAVLink startup script.
|
||||
#------------------------------------------------------------------------------
|
||||
|
||||
# Start MAVLink on the USB port
|
||||
|
|
|
@ -220,55 +220,61 @@
|
|||
|
||||
#define STM32_SDMMC_CLKCR_EDGE STM32_SDMMC_CLKCR_NEGEDGE
|
||||
|
||||
|
||||
/* UART/USART */
|
||||
#define GPIO_USART1_RX GPIO_USART1_RX_3 /* PB7 */
|
||||
#define GPIO_USART1_TX GPIO_USART1_TX_3 /* PB6 */
|
||||
#define GPIO_USART1_TX GPIO_USART1_TX_3 /* PB6 */
|
||||
#define GPIO_USART1_RX GPIO_USART1_RX_3 /* PB7 */
|
||||
|
||||
#define GPIO_USART2_RX GPIO_USART2_RX_2 /* PD6 */
|
||||
#define GPIO_USART2_TX GPIO_USART2_TX_2 /* PD5 */
|
||||
#define GPIO_USART2_RTS GPIO_USART2_RTS_2 /* PD4 */
|
||||
#define GPIO_USART2_CTS GPIO_USART2_CTS_NSS_2 /* PD3 */
|
||||
#define GPIO_USART2_CTS GPIO_USART2_CTS_NSS_2 /* PD3 */
|
||||
#define GPIO_USART2_RTS GPIO_USART2_RTS_2 /* PD4 */
|
||||
#define GPIO_USART2_TX GPIO_USART2_TX_2 /* PD5 */
|
||||
#define GPIO_USART2_RX GPIO_USART2_RX_2 /* PD6 */
|
||||
|
||||
#define GPIO_UART4_RX GPIO_UART4_RX_5 /* PD0 */
|
||||
#define GPIO_UART4_TX GPIO_UART4_TX_5 /* PD1 */
|
||||
#define GPIO_UART4_TX GPIO_UART4_TX_5 /* PD1 */
|
||||
#define GPIO_UART4_RX GPIO_UART4_RX_5 /* PD0 */
|
||||
|
||||
#define GPIO_USART6_RX GPIO_USART6_RX_2 /* PG9 */
|
||||
#define GPIO_USART6_TX GPIO_USART6_TX_2 /* PG14 */
|
||||
#define GPIO_USART6_RX GPIO_USART6_RX_2 /* PG9 */
|
||||
#define GPIO_USART6_RTS GPIO_USART6_RTS_2 /* PG8 */
|
||||
#define GPIO_USART6_CTS GPIO_USART6_CTS_NSS_2 /* PG15 */
|
||||
|
||||
#define GPIO_UART7_RX GPIO_UART7_RX_4 /* PF6 */
|
||||
#define GPIO_UART7_TX GPIO_UART7_TX_3 /* PE8 */
|
||||
#define GPIO_UART7_TX GPIO_UART7_TX_3 /* PE8 */
|
||||
#define GPIO_UART7_RX GPIO_UART7_RX_4 /* PF6 */
|
||||
|
||||
#define GPIO_UART8_TX GPIO_UART8_TX_1 /* PE1 */
|
||||
#define GPIO_UART8_RX GPIO_UART8_RX_1 /* PE0 */
|
||||
|
||||
#define GPIO_UART8_RX GPIO_UART8_RX_1 /* PE0 */
|
||||
#define GPIO_UART8_TX GPIO_UART8_TX_1 /* PE1 */
|
||||
|
||||
/* CAN */
|
||||
#define GPIO_CAN1_RX GPIO_CAN1_RX_5 /* PI9 */
|
||||
#define GPIO_CAN1_TX GPIO_CAN1_TX_4 /* PH13 */
|
||||
#define GPIO_CAN1_RX GPIO_CAN1_RX_5 /* PI9 */
|
||||
#define GPIO_CAN2_RX GPIO_CAN2_RX_1 /* PB12 */
|
||||
#define GPIO_CAN2_TX GPIO_CAN2_TX_1 /* PB13 */
|
||||
|
||||
|
||||
/* SPI */
|
||||
#define GPIO_SPI1_SCK GPIO_SPI1_SCK_3 /* PG11 */
|
||||
#define GPIO_SPI1_MISO GPIO_SPI1_MISO_1 /* PA6 */
|
||||
#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_3 /* PD7 */
|
||||
#define ADJ_SLEW_RATE(p) (((p) & ~GPIO_SPEED_MASK) | (GPIO_SPEED_2MHz))
|
||||
|
||||
#define GPIO_SPI2_SCK GPIO_SPI2_SCK_6 /* PI1 */
|
||||
#define GPIO_SPI2_MISO GPIO_SPI2_MISO_3 /* PI2 */
|
||||
#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_4 /* PI3 */
|
||||
#define GPIO_SPI1_SCK ADJ_SLEW_RATE(GPIO_SPI1_SCK_3) /* PG11 */
|
||||
#define GPIO_SPI1_MISO GPIO_SPI1_MISO_1 /* PA6 */
|
||||
#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_3 /* PD7 */
|
||||
|
||||
#define GPIO_SPI4_SCK GPIO_SPI4_SCK_2 /* PE2 */
|
||||
#define GPIO_SPI4_MISO GPIO_SPI4_MISO_1 /* PE13 */
|
||||
#define GPIO_SPI4_MOSI GPIO_SPI4_MOSI_2 /* PE6 */
|
||||
#define GPIO_SPI2_SCK ADJ_SLEW_RATE(GPIO_SPI2_SCK_6) /* PI1 */
|
||||
#define GPIO_SPI2_MISO GPIO_SPI2_MISO_3 /* PI2 */
|
||||
#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_4 /* PI3 */
|
||||
|
||||
#define GPIO_SPI5_SCK GPIO_SPI5_SCK_1 /* PF7 */
|
||||
#define GPIO_SPI5_MISO GPIO_SPI5_MISO_1 /* PF8 */
|
||||
#define GPIO_SPI5_MOSI GPIO_SPI5_MOSI_2 /* PF9 */
|
||||
#define GPIO_SPI4_SCK ADJ_SLEW_RATE(GPIO_SPI4_SCK_2) /* PE2 */
|
||||
#define GPIO_SPI4_MISO GPIO_SPI4_MISO_1 /* PE13 */
|
||||
#define GPIO_SPI4_MOSI GPIO_SPI4_MOSI_2 /* PE6 */
|
||||
|
||||
#define GPIO_SPI5_SCK ADJ_SLEW_RATE(GPIO_SPI5_SCK_1) /* PF7 */
|
||||
#define GPIO_SPI5_MISO GPIO_SPI5_MISO_1 /* PF8 */
|
||||
#define GPIO_SPI5_MOSI GPIO_SPI5_MOSI_2 /* PF9 */
|
||||
|
||||
#define GPIO_SPI6_SCK ADJ_SLEW_RATE(GPIO_SPI6_SCK_1) /* PG13 */
|
||||
#define GPIO_SPI6_MISO GPIO_SPI6_MISO_1 /* PG12 */
|
||||
#define GPIO_SPI6_MOSI GPIO_SPI6_MOSI_2 /* PA7 */
|
||||
|
||||
#define GPIO_SPI6_SCK GPIO_SPI6_SCK_1 /* PG13 */
|
||||
#define GPIO_SPI6_MISO GPIO_SPI6_MISO_1 /* PG12 */
|
||||
#define GPIO_SPI6_MOSI GPIO_SPI6_MOSI_2 /* PA7 */
|
||||
|
||||
/* I2C */
|
||||
#define GPIO_I2C1_SCL GPIO_I2C1_SCL_2 /* PB8 */
|
||||
|
|
|
@ -107,6 +107,8 @@ px4_add_board(
|
|||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
serial_test
|
||||
system_time
|
||||
#tests # tests and test runner
|
||||
top
|
||||
topic_listener
|
||||
|
|
|
@ -30,8 +30,6 @@ px4_add_board(
|
|||
#heater
|
||||
#imu # all available imu drivers
|
||||
imu/analog_devices/adis16448
|
||||
imu/adis16477
|
||||
imu/adis16497
|
||||
imu/invensense/icm20602
|
||||
imu/invensense/icm20649
|
||||
imu/invensense/icm20948
|
||||
|
@ -51,7 +49,7 @@ px4_add_board(
|
|||
roboclaw
|
||||
rpm
|
||||
telemetry # all available telemetry drivers
|
||||
test_ppm
|
||||
#test_ppm
|
||||
tone_alarm
|
||||
uavcan
|
||||
MODULES
|
||||
|
@ -108,7 +106,9 @@ px4_add_board(
|
|||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
tests # tests and test runner
|
||||
serial_test
|
||||
system_time
|
||||
#tests # tests and test runner
|
||||
top
|
||||
topic_listener
|
||||
tune_control
|
||||
|
|
|
@ -10,7 +10,7 @@ px4_add_board(
|
|||
BUILD_BOOTLOADER
|
||||
IO px4_io-v2_default
|
||||
TESTING
|
||||
# UAVCAN_INTERFACES 2 - No H7 or FD can support in UAVCAN
|
||||
UAVCAN_INTERFACES 2
|
||||
SERIAL_PORTS
|
||||
GPS1:/dev/ttyS0
|
||||
TEL1:/dev/ttyS1
|
||||
|
@ -30,30 +30,26 @@ px4_add_board(
|
|||
heater
|
||||
#imu # all available imu drivers
|
||||
imu/analog_devices/adis16448
|
||||
imu/adis16477
|
||||
imu/adis16497
|
||||
imu/bosch/bmi088
|
||||
imu/invensense/icm20689
|
||||
irlock
|
||||
lights/blinkm
|
||||
lights/rgbled
|
||||
lights/rgbled_ncp5623c
|
||||
lights # all available light drivers
|
||||
magnetometer # all available magnetometer drivers
|
||||
optical_flow # all available optical flow drivers
|
||||
#osd
|
||||
pca9685
|
||||
pca9685_pwm_out
|
||||
power_monitor/ina226
|
||||
#protocol_splitter
|
||||
# pwm_input - Need to create arch/stm32 arch/stm32h7 arch/kinetis and reloacate
|
||||
# all arch dependant code there
|
||||
pwm_out_sim
|
||||
pwm_out
|
||||
px4io
|
||||
roboclaw
|
||||
rpm
|
||||
telemetry # all available telemetry drivers
|
||||
test_ppm
|
||||
tone_alarm
|
||||
# uavcan - No H7 or FD can support in UAVCAN yet
|
||||
#uavcan
|
||||
MODULES
|
||||
airspeed_selector
|
||||
attitude_estimator_q
|
||||
|
@ -62,6 +58,7 @@ px4_add_board(
|
|||
commander
|
||||
dataman
|
||||
ekf2
|
||||
esc_battery
|
||||
events
|
||||
flight_mode_manager
|
||||
fw_att_control
|
||||
|
@ -77,12 +74,15 @@ px4_add_board(
|
|||
mc_hover_thrust_estimator
|
||||
mc_pos_control
|
||||
mc_rate_control
|
||||
#micrortps_bridge
|
||||
navigator
|
||||
rc_update
|
||||
rover_pos_control
|
||||
sensors
|
||||
sih
|
||||
temperature_compensation
|
||||
uuv_att_control
|
||||
uuv_pos_control
|
||||
vmount
|
||||
vtol_att_control
|
||||
SYSTEMCMDS
|
||||
|
@ -90,6 +90,7 @@ px4_add_board(
|
|||
dmesg
|
||||
dumpfile
|
||||
esc_calib
|
||||
gpio
|
||||
hardfault_log
|
||||
i2cdetect
|
||||
led_control
|
||||
|
@ -116,6 +117,8 @@ px4_add_board(
|
|||
work_queue
|
||||
EXAMPLES
|
||||
fake_gps
|
||||
fake_gyro
|
||||
fake_magnetometer
|
||||
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
hello
|
||||
hwtest # Hardware test
|
||||
|
|
|
@ -28,7 +28,7 @@ px4_add_board(
|
|||
imu/invensense/icm20602
|
||||
imu/invensense/icm42688p
|
||||
irlock
|
||||
lights/blinkm
|
||||
#lights/blinkm
|
||||
lights/rgbled
|
||||
lights/rgbled_ncp5623c
|
||||
magnetometer # all available magnetometer drivers
|
||||
|
@ -43,6 +43,7 @@ px4_add_board(
|
|||
pwm_out
|
||||
rc_input
|
||||
roboclaw
|
||||
rpm
|
||||
safety_button
|
||||
telemetry # all available telemetry drivers
|
||||
test_ppm
|
||||
|
@ -71,12 +72,15 @@ px4_add_board(
|
|||
mc_hover_thrust_estimator
|
||||
mc_pos_control
|
||||
mc_rate_control
|
||||
#micrortps_bridge
|
||||
navigator
|
||||
rc_update
|
||||
rover_pos_control
|
||||
sensors
|
||||
sih
|
||||
temperature_compensation
|
||||
uuv_att_control
|
||||
uuv_pos_control
|
||||
vmount
|
||||
vtol_att_control
|
||||
SYSTEMCMDS
|
||||
|
@ -84,6 +88,7 @@ px4_add_board(
|
|||
dmesg
|
||||
dumpfile
|
||||
esc_calib
|
||||
gpio
|
||||
hardfault_log
|
||||
i2cdetect
|
||||
led_control
|
||||
|
@ -110,6 +115,8 @@ px4_add_board(
|
|||
work_queue
|
||||
EXAMPLES
|
||||
fake_gps
|
||||
fake_gyro
|
||||
fake_magnetometer
|
||||
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
hello
|
||||
hwtest # Hardware test
|
||||
|
|
|
@ -17,6 +17,7 @@ px4_add_board(
|
|||
TEL3:/dev/ttyS4
|
||||
#FRSKY:/dev/ttyS5
|
||||
DRIVERS
|
||||
adc/ads1115
|
||||
adc/board_adc
|
||||
#barometer # all available barometer drivers
|
||||
barometer/dps310
|
||||
|
@ -25,7 +26,7 @@ px4_add_board(
|
|||
camera_trigger
|
||||
differential_pressure # all available differential pressure drivers
|
||||
distance_sensor # all available distance sensor drivers
|
||||
#dshot
|
||||
dshot
|
||||
gps
|
||||
#heater
|
||||
#imu # all available imu drivers
|
||||
|
@ -33,13 +34,12 @@ px4_add_board(
|
|||
imu/invensense/icm20602
|
||||
imu/invensense/icm20948
|
||||
irlock
|
||||
lights/blinkm
|
||||
lights/rgbled
|
||||
lights/rgbled_ncp5623c
|
||||
lights # all available light drivers
|
||||
magnetometer # all available magnetometer drivers
|
||||
#optical_flow # all available optical flow drivers
|
||||
#osd
|
||||
optical_flow # all available optical flow drivers
|
||||
osd
|
||||
pca9685
|
||||
pca9685_pwm_out
|
||||
power_monitor/ina226
|
||||
#protocol_splitter
|
||||
#pwm_input
|
||||
|
@ -47,6 +47,7 @@ px4_add_board(
|
|||
pwm_out
|
||||
rc_input
|
||||
roboclaw
|
||||
rpm
|
||||
safety_button
|
||||
telemetry # all available telemetry drivers
|
||||
test_ppm
|
||||
|
@ -60,6 +61,7 @@ px4_add_board(
|
|||
commander
|
||||
dataman
|
||||
ekf2
|
||||
esc_battery
|
||||
events
|
||||
flight_mode_manager
|
||||
fw_att_control
|
||||
|
@ -82,6 +84,8 @@ px4_add_board(
|
|||
sensors
|
||||
sih
|
||||
temperature_compensation
|
||||
uuv_att_control
|
||||
uuv_pos_control
|
||||
vmount
|
||||
vtol_att_control
|
||||
SYSTEMCMDS
|
||||
|
@ -89,6 +93,7 @@ px4_add_board(
|
|||
dmesg
|
||||
dumpfile
|
||||
esc_calib
|
||||
gpio
|
||||
hardfault_log
|
||||
i2cdetect
|
||||
led_control
|
||||
|
@ -115,6 +120,8 @@ px4_add_board(
|
|||
work_queue
|
||||
EXAMPLES
|
||||
fake_gps
|
||||
fake_gyro
|
||||
fake_magnetometer
|
||||
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
hello
|
||||
hwtest # Hardware test
|
||||
|
|
|
@ -17,6 +17,7 @@ px4_add_board(
|
|||
#CONSOLE:/dev/ttyS4
|
||||
#FRSKY:/dev/ttyS5
|
||||
DRIVERS
|
||||
adc/ads1115
|
||||
adc/board_adc
|
||||
#barometer # all available barometer drivers
|
||||
barometer/dps310
|
||||
|
@ -25,7 +26,7 @@ px4_add_board(
|
|||
camera_trigger
|
||||
differential_pressure # all available differential pressure drivers
|
||||
distance_sensor # all available distance sensor drivers
|
||||
#dshot
|
||||
dshot
|
||||
gps
|
||||
#heater
|
||||
#imu # all available imu drivers
|
||||
|
@ -33,13 +34,12 @@ px4_add_board(
|
|||
imu/invensense/icm20602
|
||||
imu/invensense/icm20948
|
||||
irlock
|
||||
lights/blinkm
|
||||
lights/rgbled
|
||||
lights/rgbled_ncp5623c
|
||||
lights # all available light drivers
|
||||
magnetometer # all available magnetometer drivers
|
||||
#optical_flow # all available optical flow drivers
|
||||
#osd
|
||||
optical_flow # all available optical flow drivers
|
||||
osd
|
||||
pca9685
|
||||
pca9685_pwm_out
|
||||
power_monitor/ina226
|
||||
#protocol_splitter
|
||||
#pwm_input
|
||||
|
@ -47,6 +47,7 @@ px4_add_board(
|
|||
pwm_out
|
||||
rc_input
|
||||
roboclaw
|
||||
rpm
|
||||
safety_button
|
||||
telemetry # all available telemetry drivers
|
||||
test_ppm
|
||||
|
@ -60,6 +61,7 @@ px4_add_board(
|
|||
commander
|
||||
dataman
|
||||
ekf2
|
||||
esc_battery
|
||||
events
|
||||
flight_mode_manager
|
||||
fw_att_control
|
||||
|
@ -82,6 +84,8 @@ px4_add_board(
|
|||
sensors
|
||||
sih
|
||||
temperature_compensation
|
||||
uuv_att_control
|
||||
uuv_pos_control
|
||||
vmount
|
||||
vtol_att_control
|
||||
SYSTEMCMDS
|
||||
|
@ -89,6 +93,7 @@ px4_add_board(
|
|||
dmesg
|
||||
dumpfile
|
||||
esc_calib
|
||||
gpio
|
||||
hardfault_log
|
||||
i2cdetect
|
||||
led_control
|
||||
|
@ -115,6 +120,8 @@ px4_add_board(
|
|||
work_queue
|
||||
EXAMPLES
|
||||
fake_gps
|
||||
fake_gyro
|
||||
fake_magnetometer
|
||||
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
hello
|
||||
hwtest # Hardware test
|
||||
|
|
|
@ -48,7 +48,6 @@ px4_add_board(
|
|||
rc_input
|
||||
roboclaw
|
||||
rpm
|
||||
#safety_button TODO
|
||||
telemetry # all available telemetry drivers
|
||||
test_ppm
|
||||
tone_alarm
|
||||
|
@ -107,23 +106,26 @@ px4_add_board(
|
|||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
serial_test
|
||||
system_time
|
||||
tests # tests and test runner
|
||||
top
|
||||
topic_listener
|
||||
tune_control
|
||||
uorb
|
||||
usb_connected
|
||||
ver
|
||||
work_queue
|
||||
EXAMPLES
|
||||
fake_gps
|
||||
fake_magnetometer
|
||||
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
hello
|
||||
hwtest # Hardware test
|
||||
#fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
#hello
|
||||
#hwtest # Hardware test
|
||||
#matlab_csv_serial
|
||||
px4_mavlink_debug # Tutorial code from http://dev.px4.io/en/debug/debug_values.html
|
||||
px4_simple_app # Tutorial code from http://dev.px4.io/en/apps/hello_sky.html
|
||||
rover_steering_control # Rover example app
|
||||
uuv_example_app
|
||||
work_item
|
||||
#px4_mavlink_debug # Tutorial code from http://dev.px4.io/en/debug/debug_values.html
|
||||
#px4_simple_app # Tutorial code from http://dev.px4.io/en/apps/hello_sky.html
|
||||
#rover_steering_control # Rover example app
|
||||
#uuv_example_app
|
||||
#work_item
|
||||
)
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
#!/bin/sh
|
||||
#
|
||||
# Board specific MAVLink startup script.
|
||||
# board specific MAVLink startup script.
|
||||
#------------------------------------------------------------------------------
|
||||
|
||||
# Start MAVLink on the USB port
|
||||
|
|
|
@ -187,7 +187,7 @@
|
|||
* Note: look at Table 54 in ST Manual
|
||||
*/
|
||||
#define STM32_RCC_D2CCIP2R_I2C123SRC RCC_D2CCIP2R_I2C123SEL_HSI /* I2C123 clock source */
|
||||
#define STM32_RCC_D3CCIPR_I2C4SRC RCC_D3CCIPR_I2C4SEL_HSI /* I2C4 clock source */
|
||||
#define STM32_RCC_D3CCIPR_I2C4SRC RCC_D3CCIPR_I2C4SEL_HSI /* I2C4 clock source */
|
||||
#define STM32_RCC_D2CCIP1R_SPI123SRC RCC_D2CCIP1R_SPI123SEL_PLL2 /* SPI123 clock source */
|
||||
#define STM32_RCC_D2CCIP1R_SPI45SRC RCC_D2CCIP1R_SPI45SEL_PLL2 /* SPI45 clock source */
|
||||
#define STM32_RCC_D3CCIPR_SPI6SRC RCC_D3CCIPR_SPI6SEL_PLL2 /* SPI6 clock source */
|
||||
|
@ -222,34 +222,35 @@
|
|||
|
||||
|
||||
/* UART/USART */
|
||||
#define GPIO_USART2_RX GPIO_USART2_RX_2 /* PD6 */
|
||||
#define GPIO_USART2_TX GPIO_USART2_TX_2 /* PD5 */
|
||||
#define GPIO_USART2_RTS GPIO_USART2_RTS_2 /* PD4 */
|
||||
#define GPIO_USART2_CTS GPIO_USART2_CTS_NSS_2 /* PD3 */
|
||||
#define GPIO_USART2_TX GPIO_USART2_TX_2 /* PD5 */
|
||||
#define GPIO_USART2_RX GPIO_USART2_RX_2 /* PD6 */
|
||||
#define GPIO_USART2_CTS GPIO_USART2_CTS_NSS_2 /* PD3 */
|
||||
#define GPIO_USART2_RTS GPIO_USART2_RTS_2 /* PD4 */
|
||||
|
||||
#define GPIO_USART3_RX GPIO_USART3_RX_3 /* PD9 */
|
||||
#define GPIO_USART3_TX GPIO_USART3_TX_3 /* PD8 */
|
||||
#define GPIO_USART3_RTS GPIO_USART3_RTS_2 /* PD12 */
|
||||
#define GPIO_USART3_CTS GPIO_USART3_CTS_NSS_2 /* PD11 */
|
||||
#define GPIO_USART3_TX GPIO_USART3_TX_3 /* PD8 */
|
||||
#define GPIO_USART3_RX GPIO_USART3_RX_3 /* PD9 */
|
||||
#define GPIO_USART3_CTS GPIO_USART3_CTS_NSS_2 /* PD11 */
|
||||
#define GPIO_USART3_RTS GPIO_USART3_RTS_2 /* PD12 */
|
||||
|
||||
#define GPIO_UART4_RX GPIO_UART4_RX_1 /* PA1 */
|
||||
#define GPIO_UART4_TX GPIO_UART4_TX_1 /* PA0 */
|
||||
#define GPIO_UART4_TX GPIO_UART4_TX_2 /* PA0 */
|
||||
#define GPIO_UART4_RX GPIO_UART4_RX_2 /* PA1 */
|
||||
|
||||
#define GPIO_USART6_RX GPIO_USART6_RX_1 /* PC7 */
|
||||
#define GPIO_USART6_TX GPIO_USART6_TX_2 /* PG14 */
|
||||
#define GPIO_USART6_TX 0
|
||||
#define GPIO_USART6_RX GPIO_USART6_RX_1 /* PC7 */
|
||||
|
||||
#define GPIO_UART7_RX GPIO_UART7_RX_1 /* PE7 */
|
||||
#define GPIO_UART7_TX GPIO_UART7_TX_1 /* PE8 */
|
||||
#define GPIO_UART7_TX GPIO_UART7_TX_3 /* PE8 */
|
||||
#define GPIO_UART7_RX GPIO_UART7_RX_3 /* PE7 */
|
||||
|
||||
#define GPIO_UART8_RX GPIO_UART8_RX_1 /* PE0 */
|
||||
#define GPIO_UART8_TX GPIO_UART8_TX_1 /* PE1 */
|
||||
#define GPIO_UART8_TX GPIO_UART8_TX_1 /* PE1 */
|
||||
#define GPIO_UART8_RX GPIO_UART8_RX_1 /* PE0 */
|
||||
|
||||
|
||||
/* CAN */
|
||||
#define GPIO_CAN1_RX GPIO_CAN1_RX_3 /* PD0 */
|
||||
#define GPIO_CAN1_TX GPIO_CAN1_TX_3 /* PD1 */
|
||||
#define GPIO_CAN2_RX GPIO_CAN2_RX_1 /* PB12 */
|
||||
#define GPIO_CAN2_TX GPIO_CAN2_TX_1 /* PB13 */
|
||||
#define GPIO_CAN1_RX GPIO_CAN1_RX_3 /* PD0 */
|
||||
#define GPIO_CAN1_TX GPIO_CAN1_TX_3 /* PD1 */
|
||||
|
||||
#define GPIO_CAN2_RX GPIO_CAN2_RX_1 /* PB12 */
|
||||
#define GPIO_CAN2_TX GPIO_CAN2_TX_1 /* PB13 */
|
||||
|
||||
|
||||
/* SPI */
|
||||
|
@ -265,15 +266,15 @@
|
|||
|
||||
#define GPIO_SPI5_SCK ADJ_SLEW_RATE(GPIO_SPI5_SCK_1) /* PF7 */
|
||||
#define GPIO_SPI5_MISO GPIO_SPI5_MISO_1 /* PF8 */
|
||||
#define GPIO_SPI5_MOSI GPIO_SPI5_MOSI_1 /* PF9 */
|
||||
#define GPIO_SPI5_MOSI GPIO_SPI5_MOSI_2 /* PF9 */
|
||||
|
||||
|
||||
/* I2C */
|
||||
#define GPIO_I2C1_SCL GPIO_I2C1_SCL_2 /* PB8 */
|
||||
#define GPIO_I2C1_SDA GPIO_I2C1_SDA_2 /* PB9 */
|
||||
|
||||
#define GPIO_I2C3_SCL GPIO_I2C3_SCL_2 /* PH7 */
|
||||
#define GPIO_I2C3_SDA GPIO_I2C3_SDA_2 /* PH8 */
|
||||
#define GPIO_I2C3_SCL GPIO_I2C3_SCL_2 /* PH7 */
|
||||
#define GPIO_I2C3_SDA GPIO_I2C3_SDA_2 /* PH8 */
|
||||
|
||||
#define GPIO_I2C4_SCL GPIO_I2C4_SCL_4 /* PB6 */
|
||||
#define GPIO_I2C4_SDA GPIO_I2C4_SDA_4 /* PB7 */
|
||||
#define GPIO_I2C4_SCL GPIO_I2C4_SCL_4 /* PB6 */
|
||||
#define GPIO_I2C4_SDA GPIO_I2C4_SDA_4 /* PB7 */
|
||||
|
|
|
@ -37,8 +37,5 @@
|
|||
#define DMAMAP_SPI1_RX DMAMAP_DMA12_SPI1RX_0 /* DMA1:37 */
|
||||
#define DMAMAP_SPI1_TX DMAMAP_DMA12_SPI1TX_0 /* DMA1:38 */
|
||||
|
||||
#define DMAMAP_USART6_RX DMAMAP_DMA12_USART6RX_1 /* DMA1:71 */
|
||||
#define DMAMAP_USART6_TX DMAMAP_DMA12_USART6TX_1 /* DMA1:72 */
|
||||
|
||||
#define DMAMAP_SPI5_RX DMAMAP_DMA12_SPI5RX_0 /* DMA1:83 */
|
||||
#define DMAMAP_SPI5_TX DMAMAP_DMA12_SPI5TX_0 /* DMA1:84 */
|
||||
#define DMAMAP_SPI5_RX DMAMAP_DMA12_SPI5RX_0 /* DMA1:85 */
|
||||
#define DMAMAP_SPI5_TX DMAMAP_DMA12_SPI5TX_0 /* DMA1:86 */
|
||||
|
|
|
@ -196,6 +196,11 @@ SECTIONS
|
|||
_ebss = ABSOLUTE(.);
|
||||
} > AXI_SRAM
|
||||
|
||||
/* Emit the the D3 power domain section for locating BDMA data */
|
||||
.SRAM4 (NOLOAD) :
|
||||
{
|
||||
} > SRAM4
|
||||
|
||||
/* Stabs debugging sections. */
|
||||
.stab 0 : { *(.stab) }
|
||||
.stabstr 0 : { *(.stabstr) }
|
||||
|
|
|
@ -77,14 +77,14 @@
|
|||
|
||||
/* CAN Silence: Silent mode control */
|
||||
#define GPIO_CAN1_SILENT_S0 /* PF5 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTF|GPIO_PIN5)
|
||||
#define GPIO_CAN2_SILENT_S0 /* PF5 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTF|GPIO_PIN5)
|
||||
//#define GPIO_CAN2_SILENT_S0 /* PF5 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTF|GPIO_PIN5)
|
||||
|
||||
/* PWM */
|
||||
#define DIRECT_PWM_OUTPUT_CHANNELS 8
|
||||
#define DIRECT_INPUT_TIMER_CHANNELS 8
|
||||
|
||||
/* Power supply control and monitoring GPIOs */
|
||||
#define GPIO_nPOWER_IN_A /* PB5 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN5)
|
||||
#define GPIO_nPOWER_IN_A /* PB5 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTB|GPIO_PIN5)
|
||||
|
||||
#define GPIO_VDD_BRICK1_VALID GPIO_nPOWER_IN_A /* Brick 1 Is Chosen */
|
||||
#define BOARD_NUMBER_BRICKS 1
|
||||
|
@ -109,7 +109,7 @@
|
|||
|
||||
/* High-resolution timer */
|
||||
#define HRT_TIMER 3 /* use timer3 for the HRT */
|
||||
#define HRT_TIMER_CHANNEL 1 /* use capture/compare channel 1 */
|
||||
#define HRT_TIMER_CHANNEL 2 /* use capture/compare channel 2 */
|
||||
|
||||
#define HRT_PPM_CHANNEL /* T3C3 */ 3 /* use capture/compare channel 3 */
|
||||
#define GPIO_PPM_IN /* PB0 T3C3 */ GPIO_TIM3_CH3IN_1
|
||||
|
@ -148,20 +148,11 @@
|
|||
#define BOARD_ADC_SERVO_VALID (1) /* never powers off the Servo rail */
|
||||
#define BOARD_ADC_BRICK_VALID (px4_arch_gpioread(GPIO_VDD_BRICK1_VALID))
|
||||
|
||||
/* This board provides a DMA pool and APIs */
|
||||
#define BOARD_DMA_ALLOC_POOL_SIZE 5120
|
||||
|
||||
/* This board provides the board_on_reset interface */
|
||||
#define BOARD_HAS_ON_RESET 1
|
||||
|
||||
#define BOARD_HAS_STATIC_MANIFEST 1
|
||||
|
||||
#define BOARD_HAS_PWM DIRECT_PWM_OUTPUT_CHANNELS
|
||||
|
||||
#define BOARD_NUM_IO_TIMERS 3
|
||||
|
||||
#define BOARD_DSHOT_MOTOR_ASSIGNMENT {3, 2, 1, 0, 4, 5, 6, 7};
|
||||
|
||||
#define BOARD_DMA_ALLOC_POOL_SIZE 5120 /* This board provides a DMA pool and APIs */
|
||||
#define BOARD_HAS_ON_RESET 1 /* This board provides the board_on_reset interface */
|
||||
#define BOARD_ENABLE_CONSOLE_BUFFER
|
||||
|
||||
#define PX4_GPIO_INIT_LIST { \
|
||||
|
@ -171,9 +162,15 @@
|
|||
GPIO_CAN2_TX, \
|
||||
GPIO_CAN2_RX, \
|
||||
GPIO_CAN1_SILENT_S0, \
|
||||
GPIO_CAN2_SILENT_S0, \
|
||||
GPIO_LEVEL_SHIFTER_OE, \
|
||||
GPIO_PWM_VOLT_SEL, \
|
||||
GPIO_nPOWER_IN_A, \
|
||||
GPIO_VDD_3V3_SPEKTRUM_POWER_EN, \
|
||||
PX4_GPIO_PIN_OFF(GPIO_SDMMC1_D0), \
|
||||
PX4_GPIO_PIN_OFF(GPIO_SDMMC1_D1), \
|
||||
PX4_GPIO_PIN_OFF(GPIO_SDMMC1_D2), \
|
||||
PX4_GPIO_PIN_OFF(GPIO_SDMMC1_D3), \
|
||||
PX4_GPIO_PIN_OFF(GPIO_SDMMC1_CMD),\
|
||||
GPIO_TONE_ALARM_IDLE, \
|
||||
GPIO_SAFETY_SWITCH_IN, \
|
||||
GPIO_OTGFS_VBUS, \
|
||||
|
|
|
@ -164,7 +164,6 @@ __EXPORT int board_app_initialize(uintptr_t arg)
|
|||
syslog(LOG_ERR, "[boot] DMA alloc FAILED\n");
|
||||
}
|
||||
|
||||
|
||||
/* initial LED state */
|
||||
drv_led_start();
|
||||
led_off(LED_RED);
|
||||
|
@ -195,7 +194,6 @@ __EXPORT int board_app_initialize(uintptr_t arg)
|
|||
#endif /* CONFIG_MMCSD */
|
||||
|
||||
/* Configure the HW based on the manifest */
|
||||
|
||||
px4_platform_configure();
|
||||
|
||||
return OK;
|
||||
|
|
|
@ -37,21 +37,10 @@
|
|||
* Board-specific USB functions.
|
||||
*/
|
||||
|
||||
#include <px4_platform_common/px4_config.h>
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
#include <debug.h>
|
||||
|
||||
#include "board_config.h"
|
||||
#include <nuttx/usb/usbdev.h>
|
||||
#include <nuttx/usb/usbdev_trace.h>
|
||||
|
||||
#include <arm_arch.h>
|
||||
#include <chip.h>
|
||||
#include <stm32_gpio.h>
|
||||
#include <stm32_otg.h>
|
||||
#include "board_config.h"
|
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_usbsuspend
|
||||
|
@ -63,19 +52,6 @@
|
|||
* while the USB is suspended.
|
||||
*
|
||||
************************************************************************************/
|
||||
__EXPORT void stm32_usbinitialize(void)
|
||||
{
|
||||
/* The OTG FS has an internal soft pull-up */
|
||||
|
||||
/* Configure the OTG FS VBUS sensing GPIO, Power On, and Overcurrent GPIOs */
|
||||
|
||||
#ifdef CONFIG_STM32H7_OTGFS
|
||||
stm32_configgpio(GPIO_OTGFS_VBUS);
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
|
||||
__EXPORT void stm32_usbsuspend(FAR struct usbdev_s *dev, bool resume)
|
||||
{
|
||||
uinfo("resume: %d\n", resume);
|
||||
|
|
|
@ -48,7 +48,6 @@ px4_add_board(
|
|||
rc_input
|
||||
roboclaw
|
||||
rpm
|
||||
#safety_button TODO
|
||||
telemetry # all available telemetry drivers
|
||||
test_ppm
|
||||
tone_alarm
|
||||
|
@ -107,23 +106,26 @@ px4_add_board(
|
|||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
serial_test
|
||||
system_time
|
||||
tests # tests and test runner
|
||||
top
|
||||
topic_listener
|
||||
tune_control
|
||||
uorb
|
||||
usb_connected
|
||||
ver
|
||||
work_queue
|
||||
EXAMPLES
|
||||
fake_gps
|
||||
fake_magnetometer
|
||||
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
hello
|
||||
hwtest # Hardware test
|
||||
#fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
#hello
|
||||
#hwtest # Hardware test
|
||||
#matlab_csv_serial
|
||||
px4_mavlink_debug # Tutorial code from http://dev.px4.io/en/debug/debug_values.html
|
||||
px4_simple_app # Tutorial code from http://dev.px4.io/en/apps/hello_sky.html
|
||||
rover_steering_control # Rover example app
|
||||
uuv_example_app
|
||||
work_item
|
||||
#px4_mavlink_debug # Tutorial code from http://dev.px4.io/en/debug/debug_values.html
|
||||
#px4_simple_app # Tutorial code from http://dev.px4.io/en/apps/hello_sky.html
|
||||
#rover_steering_control # Rover example app
|
||||
#uuv_example_app
|
||||
#work_item
|
||||
)
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
#!/bin/sh
|
||||
#
|
||||
# Board specific MAVLink startup script.
|
||||
# board specific MAVLink startup script.
|
||||
#------------------------------------------------------------------------------
|
||||
|
||||
# Start MAVLink on the USB port
|
||||
|
|
|
@ -187,6 +187,7 @@
|
|||
* Note: look at Table 54 in ST Manual
|
||||
*/
|
||||
#define STM32_RCC_D2CCIP2R_I2C123SRC RCC_D2CCIP2R_I2C123SEL_HSI /* I2C123 clock source */
|
||||
#define STM32_RCC_D3CCIPR_I2C4SRC RCC_D3CCIPR_I2C4SEL_HSI /* I2C4 clock source */
|
||||
#define STM32_RCC_D2CCIP1R_SPI123SRC RCC_D2CCIP1R_SPI123SEL_PLL2 /* SPI123 clock source */
|
||||
#define STM32_RCC_D2CCIP1R_SPI45SRC RCC_D2CCIP1R_SPI45SEL_PLL2 /* SPI45 clock source */
|
||||
#define STM32_RCC_D3CCIPR_SPI6SRC RCC_D3CCIPR_SPI6SEL_PLL2 /* SPI6 clock source */
|
||||
|
@ -221,32 +222,32 @@
|
|||
|
||||
|
||||
/* UART/USART */
|
||||
#define GPIO_USART2_RX GPIO_USART2_RX_2 /* PD6 */
|
||||
#define GPIO_USART2_TX GPIO_USART2_TX_2 /* PD5 */
|
||||
#define GPIO_USART2_RTS GPIO_USART2_RTS_2 /* PD4 */
|
||||
#define GPIO_USART2_CTS GPIO_USART2_CTS_NSS_2 /* PD3 */
|
||||
#define GPIO_USART2_TX GPIO_USART2_TX_2 /* PD5 */
|
||||
#define GPIO_USART2_RX GPIO_USART2_RX_2 /* PD6 */
|
||||
#define GPIO_USART2_CTS GPIO_USART2_CTS_NSS_2 /* PD3 */
|
||||
#define GPIO_USART2_RTS GPIO_USART2_RTS_2 /* PD4 */
|
||||
|
||||
#define GPIO_USART3_RX GPIO_USART3_RX_3 /* PD9 */
|
||||
#define GPIO_USART3_TX GPIO_USART3_TX_3 /* PD8 */
|
||||
#define GPIO_USART3_RTS GPIO_USART3_RTS_2 /* PD12 */
|
||||
#define GPIO_USART3_CTS GPIO_USART3_CTS_NSS_2 /* PD11 */
|
||||
#define GPIO_USART3_TX GPIO_USART3_TX_3 /* PD8 */
|
||||
#define GPIO_USART3_RX GPIO_USART3_RX_3 /* PD9 */
|
||||
#define GPIO_USART3_CTS GPIO_USART3_CTS_NSS_2 /* PD11 */
|
||||
#define GPIO_USART3_RTS GPIO_USART3_RTS_2 /* PD12 */
|
||||
|
||||
#define GPIO_UART4_RX GPIO_UART4_RX_1 /* PA1 */
|
||||
#define GPIO_UART4_TX GPIO_UART4_TX_1 /* PA0 */
|
||||
#define GPIO_UART4_TX GPIO_UART4_TX_2 /* PA0 */
|
||||
#define GPIO_UART4_RX GPIO_UART4_RX_2 /* PA1 */
|
||||
|
||||
#define GPIO_USART6_RX GPIO_USART6_RX_1 /* PC7 */
|
||||
#define GPIO_USART6_TX GPIO_USART6_TX_2 /* PG14 */
|
||||
#define GPIO_USART6_TX 0
|
||||
#define GPIO_USART6_RX GPIO_USART6_RX_1 /* PC7 */
|
||||
|
||||
#define GPIO_UART7_RX GPIO_UART7_RX_1 /* PE7 */
|
||||
#define GPIO_UART7_TX GPIO_UART7_TX_1 /* PE8 */
|
||||
#define GPIO_UART7_TX GPIO_UART7_TX_3 /* PE8 */
|
||||
#define GPIO_UART7_RX GPIO_UART7_RX_3 /* PE7 */
|
||||
|
||||
#define GPIO_UART8_RX GPIO_UART8_RX_1 /* PE0 */
|
||||
#define GPIO_UART8_TX GPIO_UART8_TX_1 /* PE1 */
|
||||
#define GPIO_UART8_TX GPIO_UART8_TX_1 /* PE1 */
|
||||
#define GPIO_UART8_RX GPIO_UART8_RX_1 /* PE0 */
|
||||
|
||||
|
||||
/* CAN */
|
||||
#define GPIO_CAN1_RX GPIO_CAN1_RX_3 /* PD0 */
|
||||
#define GPIO_CAN1_TX GPIO_CAN1_TX_3 /* PD1 */
|
||||
#define GPIO_CAN1_RX GPIO_CAN1_RX_3 /* PD0 */
|
||||
#define GPIO_CAN1_TX GPIO_CAN1_TX_3 /* PD1 */
|
||||
|
||||
|
||||
/* SPI */
|
||||
|
@ -262,7 +263,7 @@
|
|||
|
||||
#define GPIO_SPI5_SCK ADJ_SLEW_RATE(GPIO_SPI5_SCK_1) /* PF7 */
|
||||
#define GPIO_SPI5_MISO GPIO_SPI5_MISO_1 /* PF8 */
|
||||
#define GPIO_SPI5_MOSI GPIO_SPI5_MOSI_1 /* PF9 */
|
||||
#define GPIO_SPI5_MOSI GPIO_SPI5_MOSI_2 /* PF9 */
|
||||
|
||||
|
||||
/* I2C */
|
||||
|
|
|
@ -37,8 +37,5 @@
|
|||
#define DMAMAP_SPI1_RX DMAMAP_DMA12_SPI1RX_0 /* DMA1:37 */
|
||||
#define DMAMAP_SPI1_TX DMAMAP_DMA12_SPI1TX_0 /* DMA1:38 */
|
||||
|
||||
#define DMAMAP_USART6_RX DMAMAP_DMA12_USART6RX_1 /* DMA1:71 */
|
||||
#define DMAMAP_USART6_TX DMAMAP_DMA12_USART6TX_1 /* DMA1:72 */
|
||||
|
||||
#define DMAMAP_SPI5_RX DMAMAP_DMA12_SPI5RX_0 /* DMA1:83 */
|
||||
#define DMAMAP_SPI5_TX DMAMAP_DMA12_SPI5TX_0 /* DMA1:84 */
|
||||
#define DMAMAP_SPI5_RX DMAMAP_DMA12_SPI5RX_0 /* DMA1:85 */
|
||||
#define DMAMAP_SPI5_TX DMAMAP_DMA12_SPI5TX_0 /* DMA1:86 */
|
||||
|
|
|
@ -196,6 +196,11 @@ SECTIONS
|
|||
_ebss = ABSOLUTE(.);
|
||||
} > AXI_SRAM
|
||||
|
||||
/* Emit the the D3 power domain section for locating BDMA data */
|
||||
.SRAM4 (NOLOAD) :
|
||||
{
|
||||
} > SRAM4
|
||||
|
||||
/* Stabs debugging sections. */
|
||||
.stab 0 : { *(.stab) }
|
||||
.stabstr 0 : { *(.stabstr) }
|
||||
|
|
|
@ -76,14 +76,17 @@
|
|||
#define BOARD_ADC_OPEN_CIRCUIT_V (5.6f)
|
||||
|
||||
/* CAN Silence: Silent mode control */
|
||||
#define GPIO_CAN1_SILENT_S0 /* PF5 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTF|GPIO_PIN5)
|
||||
#define GPIO_CAN1_SILENT_S0 /* PF5 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTF|GPIO_PIN5)
|
||||
|
||||
#define GPIO_LEVEL_SHIFTER_OE /* PI3 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTI|GPIO_PIN3)
|
||||
#define GPIO_PWM_VOLT_SEL /* PG6 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN6)
|
||||
|
||||
/* PWM */
|
||||
#define DIRECT_PWM_OUTPUT_CHANNELS 8
|
||||
#define DIRECT_INPUT_TIMER_CHANNELS 8
|
||||
|
||||
/* Power supply control and monitoring GPIOs */
|
||||
#define GPIO_nPOWER_IN_A /* PB5 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN5)
|
||||
#define GPIO_nPOWER_IN_A /* PB5 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTB|GPIO_PIN5)
|
||||
|
||||
#define GPIO_VDD_BRICK1_VALID GPIO_nPOWER_IN_A /* Brick 1 Is Chosen */
|
||||
#define BOARD_NUMBER_BRICKS 1
|
||||
|
@ -108,7 +111,7 @@
|
|||
|
||||
/* High-resolution timer */
|
||||
#define HRT_TIMER 3 /* use timer3 for the HRT */
|
||||
#define HRT_TIMER_CHANNEL 1 /* use capture/compare channel 1 */
|
||||
#define HRT_TIMER_CHANNEL 2 /* use capture/compare channel 2 */
|
||||
|
||||
#define HRT_PPM_CHANNEL /* T3C3 */ 3 /* use capture/compare channel 3 */
|
||||
#define GPIO_PPM_IN /* PB0 T3C3 */ GPIO_TIM3_CH3IN_1
|
||||
|
@ -147,20 +150,11 @@
|
|||
#define BOARD_ADC_SERVO_VALID (1) /* never powers off the Servo rail */
|
||||
#define BOARD_ADC_BRICK_VALID (px4_arch_gpioread(GPIO_VDD_BRICK1_VALID))
|
||||
|
||||
/* This board provides a DMA pool and APIs */
|
||||
#define BOARD_DMA_ALLOC_POOL_SIZE 5120
|
||||
|
||||
/* This board provides the board_on_reset interface */
|
||||
#define BOARD_HAS_ON_RESET 1
|
||||
|
||||
#define BOARD_HAS_STATIC_MANIFEST 1
|
||||
|
||||
#define BOARD_HAS_PWM DIRECT_PWM_OUTPUT_CHANNELS
|
||||
|
||||
#define BOARD_NUM_IO_TIMERS 3
|
||||
|
||||
#define BOARD_DSHOT_MOTOR_ASSIGNMENT {3, 2, 1, 0, 4, 5, 6, 7};
|
||||
|
||||
#define BOARD_DMA_ALLOC_POOL_SIZE 5120 /* This board provides a DMA pool and APIs */
|
||||
#define BOARD_HAS_ON_RESET 1 /* This board provides the board_on_reset interface */
|
||||
#define BOARD_ENABLE_CONSOLE_BUFFER
|
||||
|
||||
#define PX4_GPIO_INIT_LIST { \
|
||||
|
@ -168,8 +162,15 @@
|
|||
GPIO_CAN1_TX, \
|
||||
GPIO_CAN1_RX, \
|
||||
GPIO_CAN1_SILENT_S0, \
|
||||
GPIO_LEVEL_SHIFTER_OE, \
|
||||
GPIO_PWM_VOLT_SEL, \
|
||||
GPIO_nPOWER_IN_A, \
|
||||
GPIO_VDD_3V3_SPEKTRUM_POWER_EN, \
|
||||
PX4_GPIO_PIN_OFF(GPIO_SDMMC1_D0), \
|
||||
PX4_GPIO_PIN_OFF(GPIO_SDMMC1_D1), \
|
||||
PX4_GPIO_PIN_OFF(GPIO_SDMMC1_D2), \
|
||||
PX4_GPIO_PIN_OFF(GPIO_SDMMC1_D3), \
|
||||
PX4_GPIO_PIN_OFF(GPIO_SDMMC1_CMD),\
|
||||
GPIO_TONE_ALARM_IDLE, \
|
||||
GPIO_SAFETY_SWITCH_IN, \
|
||||
GPIO_OTGFS_VBUS, \
|
||||
|
|
|
@ -164,7 +164,6 @@ __EXPORT int board_app_initialize(uintptr_t arg)
|
|||
syslog(LOG_ERR, "[boot] DMA alloc FAILED\n");
|
||||
}
|
||||
|
||||
|
||||
/* initial LED state */
|
||||
drv_led_start();
|
||||
led_off(LED_RED);
|
||||
|
@ -195,7 +194,6 @@ __EXPORT int board_app_initialize(uintptr_t arg)
|
|||
#endif /* CONFIG_MMCSD */
|
||||
|
||||
/* Configure the HW based on the manifest */
|
||||
|
||||
px4_platform_configure();
|
||||
|
||||
return OK;
|
||||
|
|
|
@ -37,21 +37,10 @@
|
|||
* Board-specific USB functions.
|
||||
*/
|
||||
|
||||
#include <px4_platform_common/px4_config.h>
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
#include <debug.h>
|
||||
|
||||
#include "board_config.h"
|
||||
#include <nuttx/usb/usbdev.h>
|
||||
#include <nuttx/usb/usbdev_trace.h>
|
||||
|
||||
#include <arm_arch.h>
|
||||
#include <chip.h>
|
||||
#include <stm32_gpio.h>
|
||||
#include <stm32_otg.h>
|
||||
#include "board_config.h"
|
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_usbsuspend
|
||||
|
@ -63,19 +52,6 @@
|
|||
* while the USB is suspended.
|
||||
*
|
||||
************************************************************************************/
|
||||
__EXPORT void stm32_usbinitialize(void)
|
||||
{
|
||||
/* The OTG FS has an internal soft pull-up */
|
||||
|
||||
/* Configure the OTG FS VBUS sensing GPIO, Power On, and Overcurrent GPIOs */
|
||||
|
||||
#ifdef CONFIG_STM32H7_OTGFS
|
||||
stm32_configgpio(GPIO_OTGFS_VBUS);
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
|
||||
__EXPORT void stm32_usbsuspend(FAR struct usbdev_s *dev, bool resume)
|
||||
{
|
||||
uinfo("resume: %d\n", resume);
|
||||
|
|
|
@ -11,12 +11,13 @@ px4_add_board(
|
|||
TESTING
|
||||
UAVCAN_INTERFACES 2
|
||||
SERIAL_PORTS
|
||||
TEL1:/dev/ttyS0
|
||||
TEL2:/dev/ttyS1
|
||||
GPS1:/dev/ttyS2
|
||||
#RC:/dev/ttyS3
|
||||
#CONSOLE:/dev/ttyS4
|
||||
#FRSKY:/dev/ttyS5
|
||||
#SPARE:/dev/ttyS0
|
||||
TEL1:/dev/ttyS1
|
||||
TEL2:/dev/ttyS2
|
||||
GPS1:/dev/ttyS3
|
||||
#RC:/dev/ttyS4
|
||||
#CONSOLE:/dev/ttyS5
|
||||
#FRSKY:/dev/ttyS6
|
||||
DRIVERS
|
||||
adc/board_adc
|
||||
#barometer # all available barometer drivers
|
||||
|
@ -94,6 +95,7 @@ px4_add_board(
|
|||
hardfault_log
|
||||
i2cdetect
|
||||
led_control
|
||||
mft
|
||||
mixer
|
||||
motor_ramp
|
||||
motor_test
|
||||
|
@ -105,6 +107,7 @@ px4_add_board(
|
|||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
serial_test
|
||||
system_time
|
||||
tests # tests and test runner
|
||||
top
|
||||
|
@ -116,14 +119,15 @@ px4_add_board(
|
|||
work_queue
|
||||
EXAMPLES
|
||||
fake_gps
|
||||
fake_gyro
|
||||
fake_magnetometer
|
||||
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
hello
|
||||
hwtest # Hardware test
|
||||
#fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
#hello
|
||||
#hwtest # Hardware test
|
||||
#matlab_csv_serial
|
||||
px4_mavlink_debug # Tutorial code from http://dev.px4.io/en/debug/debug_values.html
|
||||
px4_simple_app # Tutorial code from http://dev.px4.io/en/apps/hello_sky.html
|
||||
rover_steering_control # Rover example app
|
||||
uuv_example_app
|
||||
work_item
|
||||
#px4_mavlink_debug # Tutorial code from http://dev.px4.io/en/debug/debug_values.html
|
||||
#px4_simple_app # Tutorial code from http://dev.px4.io/en/apps/hello_sky.html
|
||||
#rover_steering_control # Rover example app
|
||||
#uuv_example_app
|
||||
#work_item
|
||||
)
|
||||
|
|
|
@ -0,0 +1,10 @@
|
|||
#!/bin/sh
|
||||
#
|
||||
# board specific extras init
|
||||
#------------------------------------------------------------------------------
|
||||
|
||||
# Run FrSky Telemetry on Pixracer on the FrSky port if not enabled already
|
||||
if param compare TEL_FRSKY_CONFIG 0
|
||||
then
|
||||
frsky_telemetry start -d /dev/ttyS6 -t 15
|
||||
fi
|
|
@ -1,6 +1,6 @@
|
|||
#!/bin/sh
|
||||
#
|
||||
# Board specific MAVLink startup script.
|
||||
# board specific MAVLink startup script.
|
||||
#------------------------------------------------------------------------------
|
||||
|
||||
# Start MAVLink on the USB port
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
#!/bin/sh
|
||||
#
|
||||
# Board specific sensors init
|
||||
# board specific sensors init
|
||||
#------------------------------------------------------------------------------
|
||||
board_adc start
|
||||
|
||||
|
|
|
@ -25,7 +25,7 @@ CONFIG_ARMV7M_USEBASEPRI=y
|
|||
CONFIG_BOARDCTL_RESET=y
|
||||
CONFIG_BOARD_INITTHREAD_PRIORITY=254
|
||||
CONFIG_BOARD_LATE_INITIALIZE=y
|
||||
CONFIG_BOARD_LOOPSPERMSEC=22114
|
||||
CONFIG_BOARD_LOOPSPERMSEC=95150
|
||||
CONFIG_BOARD_RESET_ON_ASSERT=2
|
||||
CONFIG_C99_BOOL8=y
|
||||
CONFIG_CDCACM=y
|
||||
|
|
|
@ -237,8 +237,8 @@
|
|||
#define GPIO_UART4_TX GPIO_UART4_TX_2 /* PA0 */
|
||||
#define GPIO_UART4_RX GPIO_UART4_RX_2 /* PA1 */
|
||||
|
||||
//#define GPIO_USART6_TX GPIO_USART6_TX_2 /* PG14 */
|
||||
//#define GPIO_USART6_RX GPIO_USART6_RX_1 /* PC7 */
|
||||
#define GPIO_USART6_TX 0
|
||||
#define GPIO_USART6_RX GPIO_USART6_RX_1 /* PC7 */
|
||||
|
||||
#define GPIO_UART7_TX GPIO_UART7_TX_3 /* PE8 */
|
||||
#define GPIO_UART7_RX GPIO_UART7_RX_3 /* PE7 */
|
||||
|
@ -252,7 +252,7 @@
|
|||
#define GPIO_CAN1_TX GPIO_CAN1_TX_3 /* PD1 */
|
||||
|
||||
#define GPIO_CAN2_RX GPIO_CAN2_RX_1 /* PB12 */
|
||||
#define GPIO_CAN2_TX GPIO_CAN2_TX_1 /* PB13 */
|
||||
#define GPIO_CAN2_TX GPIO_CAN2_TX_1 /* PB13 */
|
||||
|
||||
|
||||
/* SPI */
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2020 PX4 Development Team. All rights reserved.
|
||||
* Copyright (c) 2020-2021 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
@ -37,9 +37,6 @@
|
|||
#define DMAMAP_SPI1_RX DMAMAP_DMA12_SPI1RX_0 /* DMA1:37 */
|
||||
#define DMAMAP_SPI1_TX DMAMAP_DMA12_SPI1TX_0 /* DMA1:38 */
|
||||
|
||||
#define DMAMAP_SPI2_RX DMAMAP_DMA12_SPI2RX_0 /* DMA1:39 */
|
||||
#define DMAMAP_SPI2_TX DMAMAP_DMA12_SPI2TX_0 /* DMA1:40 */
|
||||
|
||||
#define DMAMAP_SPI5_RX DMAMAP_DMA12_SPI5RX_0 /* DMA1:85 */
|
||||
#define DMAMAP_SPI5_TX DMAMAP_DMA12_SPI5TX_0 /* DMA1:86 */
|
||||
|
||||
|
|
|
@ -141,7 +141,7 @@ CONFIG_SCHED_LPWORKPRIORITY=50
|
|||
CONFIG_SCHED_LPWORKSTACKSIZE=1632
|
||||
CONFIG_SCHED_WAITPID=y
|
||||
CONFIG_SDCLONE_DISABLE=y
|
||||
CONFIG_SDMMC1_SDIO_MODE=y
|
||||
CONFIG_SDMMC1_SDIO_PULLUP=y
|
||||
CONFIG_SEM_NNESTPRIO=8
|
||||
CONFIG_SEM_PREALLOCHOLDERS=0
|
||||
CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y
|
||||
|
@ -198,6 +198,7 @@ CONFIG_STM32H7_UART8=y
|
|||
CONFIG_STM32H7_USART1=y
|
||||
CONFIG_STM32H7_USART2=y
|
||||
CONFIG_STM32H7_USART3=y
|
||||
CONFIG_STM32H7_USART6=y
|
||||
CONFIG_STM32H7_USART_BREAKS=y
|
||||
CONFIG_STM32H7_USART_INVERT=y
|
||||
CONFIG_STM32H7_USART_SINGLEWIRE=y
|
||||
|
@ -227,6 +228,9 @@ CONFIG_USART3_IFLOWCONTROL=y
|
|||
CONFIG_USART3_OFLOWCONTROL=y
|
||||
CONFIG_USART3_RXBUFSIZE=600
|
||||
CONFIG_USART3_TXBUFSIZE=3000
|
||||
CONFIG_USART6_BAUD=57600
|
||||
CONFIG_USART6_RXBUFSIZE=600
|
||||
CONFIG_USART6_TXBUFSIZE=1500
|
||||
CONFIG_USBDEV=y
|
||||
CONFIG_USBDEV_BUSPOWERED=y
|
||||
CONFIG_USBDEV_MAXPOWER=500
|
||||
|
|
|
@ -111,6 +111,7 @@ MEMORY
|
|||
{
|
||||
ITCM_RAM (rwx) : ORIGIN = 0x00000000, LENGTH = 64K
|
||||
FLASH (rx) : ORIGIN = 0x08020000, LENGTH = 1920K
|
||||
|
||||
DTCM1_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 64K
|
||||
DTCM2_RAM (rwx) : ORIGIN = 0x20010000, LENGTH = 64K
|
||||
AXI_SRAM (rwx) : ORIGIN = 0x24000000, LENGTH = 512K /* D1 domain AXI bus */
|
||||
|
@ -167,6 +168,7 @@ SECTIONS
|
|||
_einit = ABSOLUTE(.);
|
||||
} > FLASH
|
||||
|
||||
|
||||
.ARM.extab : {
|
||||
*(.ARM.extab*)
|
||||
} > FLASH
|
||||
|
@ -201,6 +203,7 @@ SECTIONS
|
|||
{
|
||||
} > SRAM4
|
||||
|
||||
|
||||
/* Stabs debugging sections. */
|
||||
.stab 0 : { *(.stab) }
|
||||
.stabstr 0 : { *(.stabstr) }
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2020 PX4 Development Team. All rights reserved.
|
||||
* Copyright (c) 2020-2021 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
@ -58,29 +58,30 @@
|
|||
/* PA2 */ GPIO_ADC12_INP14, \
|
||||
/* PA3 */ GPIO_ADC12_INP15, \
|
||||
/* PA4 */ GPIO_ADC12_INP18, \
|
||||
/* PC1 */ GPIO_ADC123_INN10
|
||||
/* PC1 */ GPIO_ADC123_INP11
|
||||
|
||||
/* Define Channel numbers must match above GPIO pin */
|
||||
#define ADC_BATTERY_VOLTAGE_CHANNEL 14 /* PA2 BATT_VOLT_SENS */
|
||||
#define ADC_BATTERY_CURRENT_CHANNEL 15 /* PA3 BATT_CURRENT_SENS */
|
||||
#define ADC_SCALED_V5_CHANNEL 18 /* PA4 VDD_5V_SENS */
|
||||
#define ADC_RSSI_IN_CHANNEL 10 /* PC1 */
|
||||
/* Define Channel numbers must match above GPIO pins */
|
||||
#define ADC_BATTERY_VOLTAGE_CHANNEL 14 /* PA2 BATT_VOLT_SENS */
|
||||
#define ADC_BATTERY_CURRENT_CHANNEL 15 /* PA3 BATT_CURRENT_SENS */
|
||||
#define ADC_SCALED_V5_CHANNEL 18 /* PA4 VDD_5V_SENS */
|
||||
#define ADC_RC_RSSI_CHANNEL 11 /* PC1 */
|
||||
|
||||
#define ADC_CHANNELS \
|
||||
((1 << ADC_BATTERY_VOLTAGE_CHANNEL) | \
|
||||
(1 << ADC_BATTERY_CURRENT_CHANNEL) | \
|
||||
(1 << ADC_SCALED_V5_CHANNEL) | \
|
||||
(1 << ADC_RSSI_IN_CHANNEL))
|
||||
(1 << ADC_RC_RSSI_CHANNEL))
|
||||
|
||||
/* HW has to large of R termination on ADC todo:change when HW value is chosen */
|
||||
#define BOARD_ADC_OPEN_CIRCUIT_V (5.6f)
|
||||
|
||||
/* CAN Silence: Silent mode control */
|
||||
#define GPIO_CAN1_SILENT_S0 /* PF11 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTF|GPIO_PIN11)
|
||||
#define GPIO_CAN2_SILENT_S0 /* PF14 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTF|GPIO_PIN14)
|
||||
#define GPIO_CAN1_SILENT_S0 /* PF11 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTF|GPIO_PIN11)
|
||||
#define GPIO_CAN2_SILENT_S0 /* PF14 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTF|GPIO_PIN14)
|
||||
|
||||
#define GPIO_LEVEL_SHIFTER_OE /* PI3 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTI|GPIO_PIN3)
|
||||
#define GPIO_PWM_VOLT_SEL /* PG6 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN6)
|
||||
#define GPIO_LEVEL_SHIFTER_OE /* PI3 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTI|GPIO_PIN3)
|
||||
#define GPIO_VDD_3V3_SENSORS_EN /* PE3 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN3)
|
||||
#define GPIO_PWM_VOLT_SEL /* PG6 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN6)
|
||||
|
||||
/* PWM */
|
||||
#define DIRECT_PWM_OUTPUT_CHANNELS 8
|
||||
|
@ -118,7 +119,7 @@
|
|||
#define GPIO_PPM_IN /* PB0 T3C3 */ GPIO_TIM3_CH3IN_1
|
||||
|
||||
/* RC Serial port */
|
||||
#define RC_SERIAL_PORT "/dev/ttyS3"
|
||||
#define RC_SERIAL_PORT "/dev/ttyS4"
|
||||
|
||||
#define GPIO_RSSI_IN /* PC1 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN1)
|
||||
|
||||
|
@ -148,7 +149,7 @@
|
|||
|
||||
#define BOARD_HAS_PWM DIRECT_PWM_OUTPUT_CHANNELS
|
||||
#define BOARD_NUM_IO_TIMERS 3
|
||||
#define BOARD_DSHOT_MOTOR_ASSIGNMENT {3, 2, 1, 0, 4, 5};
|
||||
#define BOARD_DSHOT_MOTOR_ASSIGNMENT {3, 2, 1, 0, 4, 5, 6, 7};
|
||||
#define BOARD_DMA_ALLOC_POOL_SIZE 5120 /* This board provides a DMA pool and APIs */
|
||||
#define BOARD_HAS_ON_RESET 1 /* This board provides the board_on_reset interface */
|
||||
#define BOARD_ENABLE_CONSOLE_BUFFER
|
||||
|
@ -162,6 +163,7 @@
|
|||
GPIO_CAN1_SILENT_S0, \
|
||||
GPIO_CAN2_SILENT_S0, \
|
||||
GPIO_LEVEL_SHIFTER_OE, \
|
||||
GPIO_VDD_3V3_SENSORS_EN, \
|
||||
GPIO_PWM_VOLT_SEL, \
|
||||
GPIO_nPOWER_IN_A, \
|
||||
GPIO_VDD_3V3_SPEKTRUM_POWER_EN, \
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2020 PX4 Development Team. All rights reserved.
|
||||
* Copyright (c) 2021 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
@ -193,5 +193,8 @@ __EXPORT int board_app_initialize(uintptr_t arg)
|
|||
sdio_mediachange(sdio_dev, true);
|
||||
#endif /* CONFIG_MMCSD */
|
||||
|
||||
/* Configure the HW based on the manifest */
|
||||
px4_platform_configure();
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2020 PX4 Development Team. All rights reserved.
|
||||
* Copyright (C) 2020-2021 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
@ -39,7 +39,7 @@ constexpr px4_spi_bus_t px4_spi_buses[SPI_BUS_MAX_BUS_ITEMS] = {
|
|||
initSPIBus(SPI::Bus::SPI1, {
|
||||
initSPIDevice(DRV_IMU_DEVTYPE_ICM20602, SPI::CS{GPIO::PortC, GPIO::Pin2}, SPI::DRDY{GPIO::PortD, GPIO::Pin15}),
|
||||
initSPIDevice(DRV_IMU_DEVTYPE_ICM20948, SPI::CS{GPIO::PortE, GPIO::Pin15}, SPI::DRDY{GPIO::PortE, GPIO::Pin12}),
|
||||
}, {GPIO::PortE, GPIO::Pin3}),
|
||||
}),
|
||||
initSPIBus(SPI::Bus::SPI2, {
|
||||
initSPIDevice(SPIDEV_FLASH(0), SPI::CS{GPIO::PortD, GPIO::Pin10}),
|
||||
initSPIDevice(DRV_BARO_DEVTYPE_DPS310, SPI::CS{GPIO::PortD, GPIO::Pin7}),
|
||||
|
|
|
@ -19,6 +19,7 @@ px4_add_board(
|
|||
# CONSOLE:/dev/tty5
|
||||
# OSD:/dev/tty6
|
||||
DRIVERS
|
||||
adc/ads1115
|
||||
adc/board_adc
|
||||
barometer # all available barometer drivers
|
||||
batt_smbus
|
||||
|
@ -33,13 +34,12 @@ px4_add_board(
|
|||
imu/invensense/icm20608g
|
||||
imu/invensense/mpu9250
|
||||
irlock
|
||||
lights/blinkm
|
||||
lights/rgbled
|
||||
lights/rgbled_ncp5623c
|
||||
lights # all available light drivers
|
||||
magnetometer # all available magnetometer drivers
|
||||
#optical_flow # all available optical flow drivers
|
||||
#osd
|
||||
optical_flow # all available optical flow drivers
|
||||
osd
|
||||
pca9685
|
||||
pca9685_pwm_out
|
||||
power_monitor/ina226
|
||||
#protocol_splitter
|
||||
pwm_input
|
||||
|
@ -83,6 +83,8 @@ px4_add_board(
|
|||
sensors
|
||||
sih
|
||||
temperature_compensation
|
||||
uuv_att_control
|
||||
uuv_pos_control
|
||||
vmount
|
||||
vtol_att_control
|
||||
SYSTEMCMDS
|
||||
|
@ -117,6 +119,7 @@ px4_add_board(
|
|||
work_queue
|
||||
EXAMPLES
|
||||
fake_gps
|
||||
fake_gyro
|
||||
fake_magnetometer
|
||||
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
hello
|
||||
|
|
|
@ -16,6 +16,7 @@ px4_add_board(
|
|||
TEL1:/dev/ttyS1
|
||||
TEL2:/dev/ttyS2
|
||||
DRIVERS
|
||||
adc/ads1115
|
||||
adc/board_adc
|
||||
barometer # all available barometer drivers
|
||||
batt_smbus
|
||||
|
@ -23,7 +24,7 @@ px4_add_board(
|
|||
camera_trigger
|
||||
differential_pressure # all available differential pressure drivers
|
||||
distance_sensor # all available distance sensor drivers
|
||||
#dshot
|
||||
dshot
|
||||
gps
|
||||
#heater
|
||||
#imu # all available imu drivers
|
||||
|
@ -31,14 +32,12 @@ px4_add_board(
|
|||
imu/invensense/icm20608g
|
||||
imu/invensense/mpu9250
|
||||
irlock
|
||||
lights/blinkm
|
||||
lights/rgbled
|
||||
#lights/rgbled_ncp5623c
|
||||
lights # all available light drivers
|
||||
magnetometer # all available magnetometer drivers
|
||||
#optical_flow # all available optical flow drivers
|
||||
optical_flow/px4flow
|
||||
#osd
|
||||
optical_flow # all available optical flow drivers
|
||||
osd
|
||||
pca9685
|
||||
pca9685_pwm_out
|
||||
#power_monitor/ina226
|
||||
#protocol_splitter
|
||||
pwm_input
|
||||
|
@ -46,6 +45,7 @@ px4_add_board(
|
|||
pwm_out
|
||||
px4io
|
||||
roboclaw
|
||||
rpm
|
||||
telemetry # all available telemetry drivers
|
||||
test_ppm
|
||||
tone_alarm
|
||||
|
@ -58,6 +58,7 @@ px4_add_board(
|
|||
commander
|
||||
dataman
|
||||
ekf2
|
||||
esc_battery
|
||||
events
|
||||
flight_mode_manager
|
||||
fw_att_control
|
||||
|
@ -80,6 +81,8 @@ px4_add_board(
|
|||
sensors
|
||||
sih
|
||||
temperature_compensation
|
||||
uuv_att_control
|
||||
uuv_pos_control
|
||||
vmount
|
||||
vtol_att_control
|
||||
SYSTEMCMDS
|
||||
|
@ -87,6 +90,7 @@ px4_add_board(
|
|||
#dmesg
|
||||
dumpfile
|
||||
esc_calib
|
||||
gpio
|
||||
hardfault_log
|
||||
i2cdetect
|
||||
led_control
|
||||
|
@ -113,6 +117,8 @@ px4_add_board(
|
|||
work_queue
|
||||
EXAMPLES
|
||||
fake_gps
|
||||
fake_gyro
|
||||
fake_magnetometer
|
||||
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
hello
|
||||
hwtest # Hardware test
|
||||
|
|
|
@ -15,6 +15,7 @@ px4_add_board(
|
|||
TEL1:/dev/ttyS4
|
||||
TEL2:/dev/ttyS1
|
||||
DRIVERS
|
||||
adc/ads1115
|
||||
adc/board_adc
|
||||
barometer # all available barometer drivers
|
||||
barometer/mpl3115a2
|
||||
|
@ -30,21 +31,20 @@ px4_add_board(
|
|||
imu/fxas21002c
|
||||
imu/fxos8701cq
|
||||
irlock
|
||||
lights/blinkm
|
||||
lights/rgbled
|
||||
lights/rgbled_ncp5623c
|
||||
lights # all available light drivers
|
||||
lights/rgbled_pwm
|
||||
magnetometer # all available magnetometer drivers
|
||||
#optical_flow # all available optical flow drivers
|
||||
optical_flow/px4flow
|
||||
#osd
|
||||
optical_flow # all available optical flow drivers
|
||||
osd
|
||||
pca9685
|
||||
pca9685_pwm_out
|
||||
power_monitor/ina226
|
||||
#protocol_splitter
|
||||
pwm_out_sim
|
||||
pwm_out
|
||||
rc_input
|
||||
roboclaw
|
||||
rpm
|
||||
safety_button
|
||||
telemetry # all available telemetry drivers
|
||||
#test_ppm # NOT Portable YET
|
||||
|
@ -58,6 +58,7 @@ px4_add_board(
|
|||
commander
|
||||
dataman
|
||||
ekf2
|
||||
esc_battery
|
||||
events
|
||||
flight_mode_manager
|
||||
fw_att_control
|
||||
|
@ -73,12 +74,15 @@ px4_add_board(
|
|||
mc_hover_thrust_estimator
|
||||
mc_pos_control
|
||||
mc_rate_control
|
||||
#micrortps_bridge
|
||||
navigator
|
||||
rc_update
|
||||
rover_pos_control
|
||||
sensors
|
||||
sih
|
||||
temperature_compensation
|
||||
uuv_att_control
|
||||
uuv_pos_control
|
||||
vmount
|
||||
vtol_att_control
|
||||
SYSTEMCMDS
|
||||
|
@ -86,7 +90,7 @@ px4_add_board(
|
|||
#dmesg
|
||||
dumpfile
|
||||
esc_calib
|
||||
#hardfault_log # Needs bbsrm
|
||||
gpio
|
||||
i2cdetect
|
||||
led_control
|
||||
mft
|
||||
|
@ -112,6 +116,8 @@ px4_add_board(
|
|||
work_queue
|
||||
EXAMPLES
|
||||
fake_gps
|
||||
fake_gyro
|
||||
fake_magnetometer
|
||||
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
hello
|
||||
hwtest # Hardware test
|
||||
|
|
|
@ -3,6 +3,7 @@ px4_add_board(
|
|||
PLATFORM nuttx
|
||||
VENDOR omnibus
|
||||
MODEL f4sd
|
||||
LABEL default
|
||||
TOOLCHAIN arm-none-eabi
|
||||
ARCHITECTURE cortex-m4
|
||||
CONSTRAINED_MEMORY
|
||||
|
@ -24,7 +25,6 @@ px4_add_board(
|
|||
imu/invensense/icm20602
|
||||
imu/invensense/mpu6000
|
||||
#irlock
|
||||
#lights/blinkm
|
||||
lights/rgbled
|
||||
#magnetometer # all available magnetometer drivers
|
||||
magnetometer/hmc5883
|
||||
|
@ -46,6 +46,7 @@ px4_add_board(
|
|||
commander
|
||||
dataman
|
||||
ekf2
|
||||
#esc_battery
|
||||
events
|
||||
flight_mode_manager
|
||||
#fw_att_control
|
||||
|
@ -61,12 +62,15 @@ px4_add_board(
|
|||
mc_hover_thrust_estimator
|
||||
mc_pos_control
|
||||
mc_rate_control
|
||||
#micrortps_bridge
|
||||
navigator
|
||||
rc_update
|
||||
#rover_pos_control
|
||||
sensors
|
||||
#sih
|
||||
#temperature_compensation
|
||||
#uuv_att_control
|
||||
#uuv_pos_control
|
||||
#vmount
|
||||
#vtol_att_control
|
||||
SYSTEMCMDS
|
||||
|
@ -74,6 +78,7 @@ px4_add_board(
|
|||
dmesg
|
||||
dumpfile
|
||||
esc_calib
|
||||
#gpio
|
||||
hardfault_log
|
||||
i2cdetect
|
||||
led_control
|
||||
|
@ -89,6 +94,7 @@ px4_add_board(
|
|||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
#system_time
|
||||
#tests # tests and test runner
|
||||
top
|
||||
#topic_listener
|
||||
|
@ -99,6 +105,8 @@ px4_add_board(
|
|||
work_queue
|
||||
EXAMPLES
|
||||
#fake_gps
|
||||
#fake_gyro
|
||||
#fake_magnetometer
|
||||
#fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
#hello
|
||||
#hwtest # Hardware test
|
||||
|
|
|
@ -33,25 +33,21 @@ px4_add_board(
|
|||
gps
|
||||
#heater
|
||||
#imu # all available imu drivers
|
||||
#imu/analog_devices/adis16448
|
||||
#imu/adis16477
|
||||
#imu/adis16497
|
||||
imu/l3gd20
|
||||
imu/lsm303d
|
||||
#imu/invensense/icm20608g
|
||||
#imu/invensense/icm20948
|
||||
imu/invensense/mpu6000
|
||||
#imu/invensense/mpu9250
|
||||
#iridiumsbd
|
||||
#irlock
|
||||
#lights/blinkm
|
||||
#lights # all available light drivers
|
||||
lights/rgbled
|
||||
#magnetometer # all available magnetometer drivers
|
||||
magnetometer/hmc5883
|
||||
#optical_flow # all available optical flow drivers
|
||||
#optical_flow/px4flow
|
||||
#osd
|
||||
#pca9685
|
||||
#pca9685_pwm_out
|
||||
#power_monitor/ina226
|
||||
#protocol_splitter
|
||||
#pwm_input
|
||||
|
@ -59,6 +55,7 @@ px4_add_board(
|
|||
pwm_out
|
||||
px4io
|
||||
#roboclaw
|
||||
#rpm
|
||||
#telemetry # all available telemetry drivers
|
||||
#test_ppm
|
||||
tone_alarm
|
||||
|
@ -94,6 +91,8 @@ px4_add_board(
|
|||
sensors
|
||||
#sih
|
||||
#temperature_compensation
|
||||
#uuv_att_control
|
||||
#uuv_pos_control
|
||||
#vmount
|
||||
#vtol_att_control
|
||||
SYSTEMCMDS
|
||||
|
@ -101,6 +100,7 @@ px4_add_board(
|
|||
#dmesg
|
||||
#dumpfile
|
||||
#esc_calib
|
||||
#gpio
|
||||
hardfault_log
|
||||
#i2cdetect
|
||||
#led_control
|
||||
|
@ -116,7 +116,7 @@ px4_add_board(
|
|||
reboot
|
||||
#reflect
|
||||
#sd_bench
|
||||
#shutdown
|
||||
#system_time
|
||||
#tests # tests and test runner
|
||||
top
|
||||
#topic_listener
|
||||
|
@ -127,6 +127,8 @@ px4_add_board(
|
|||
#work_queue
|
||||
EXAMPLES
|
||||
#fake_gps
|
||||
#fake_gyro
|
||||
#fake_magnetometer
|
||||
#fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
#hello
|
||||
#hwtest # Hardware test
|
||||
|
|
|
@ -1,6 +1,4 @@
|
|||
|
||||
# FMUv3 is FMUv2 with access to the full 2MB flash
|
||||
|
||||
px4_add_board(
|
||||
PLATFORM nuttx
|
||||
VENDOR px4
|
||||
|
@ -19,8 +17,8 @@ px4_add_board(
|
|||
TEL2:/dev/ttyS2
|
||||
TEL4:/dev/ttyS6
|
||||
DRIVERS
|
||||
adc/board_adc
|
||||
adc/ads1115
|
||||
adc/board_adc
|
||||
barometer # all available barometer drivers
|
||||
batt_smbus
|
||||
camera_capture
|
||||
|
@ -32,8 +30,6 @@ px4_add_board(
|
|||
#heater
|
||||
#imu # all available imu drivers
|
||||
imu/analog_devices/adis16448
|
||||
imu/adis16477
|
||||
imu/adis16497
|
||||
imu/l3gd20
|
||||
imu/lsm303d
|
||||
imu/invensense/icm20608g
|
||||
|
@ -41,13 +37,10 @@ px4_add_board(
|
|||
imu/invensense/mpu6000
|
||||
imu/invensense/mpu9250
|
||||
irlock
|
||||
lights/blinkm
|
||||
lights/rgbled
|
||||
lights/rgbled_ncp5623c
|
||||
lights # all available light drivers
|
||||
magnetometer # all available magnetometer drivers
|
||||
#optical_flow # all available optical flow drivers
|
||||
optical_flow/px4flow
|
||||
#osd
|
||||
optical_flow # all available optical flow drivers
|
||||
osd
|
||||
pca9685
|
||||
pca9685_pwm_out
|
||||
#power_monitor/ina226
|
||||
|
@ -57,6 +50,7 @@ px4_add_board(
|
|||
pwm_out
|
||||
px4io
|
||||
roboclaw
|
||||
rpm
|
||||
telemetry # all available telemetry drivers
|
||||
test_ppm
|
||||
tone_alarm
|
||||
|
@ -92,6 +86,8 @@ px4_add_board(
|
|||
sensors
|
||||
sih
|
||||
temperature_compensation
|
||||
uuv_att_control
|
||||
uuv_pos_control
|
||||
vmount
|
||||
vtol_att_control
|
||||
SYSTEMCMDS
|
||||
|
@ -126,6 +122,8 @@ px4_add_board(
|
|||
work_queue
|
||||
EXAMPLES
|
||||
fake_gps
|
||||
fake_gyro
|
||||
fake_magnetometer
|
||||
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
hello
|
||||
hwtest # Hardware test
|
||||
|
|
|
@ -15,10 +15,9 @@ px4_add_board(
|
|||
TEL1:/dev/ttyS1
|
||||
TEL2:/dev/ttyS2
|
||||
WIFI:/dev/ttyS0
|
||||
|
||||
DRIVERS
|
||||
adc/board_adc
|
||||
adc/ads1115
|
||||
adc/board_adc
|
||||
barometer # all available barometer drivers
|
||||
batt_smbus
|
||||
camera_capture
|
||||
|
@ -30,28 +29,24 @@ px4_add_board(
|
|||
heater
|
||||
#imu # all available imu drivers
|
||||
imu/analog_devices/adis16448
|
||||
imu/adis16477
|
||||
imu/adis16497
|
||||
imu/invensense/icm20602
|
||||
imu/invensense/icm20608g
|
||||
imu/invensense/icm40609d
|
||||
imu/invensense/mpu6500
|
||||
imu/invensense/mpu9250
|
||||
irlock
|
||||
lights/blinkm
|
||||
lights/rgbled
|
||||
lights/rgbled_ncp5623c
|
||||
lights # all available light drivers
|
||||
magnetometer # all available magnetometer drivers
|
||||
optical_flow # all available optical flow drivers
|
||||
#osd
|
||||
osd
|
||||
pca9685
|
||||
pca9685_pwm_out
|
||||
power_monitor/ina226
|
||||
#protocol_splitter
|
||||
pwm_input
|
||||
pwm_out_sim
|
||||
pwm_out
|
||||
rc_input
|
||||
roboclaw
|
||||
rpm
|
||||
safety_button
|
||||
telemetry # all available telemetry drivers
|
||||
test_ppm
|
||||
|
|
|
@ -18,8 +18,8 @@ px4_add_board(
|
|||
TEL3:/dev/ttyS0
|
||||
TEL4:/dev/ttyS6
|
||||
DRIVERS
|
||||
adc/board_adc
|
||||
adc/ads1115
|
||||
adc/board_adc
|
||||
barometer # all available barometer drivers
|
||||
batt_smbus
|
||||
camera_capture
|
||||
|
@ -30,26 +30,25 @@ px4_add_board(
|
|||
gps
|
||||
#heater
|
||||
#imu # all available imu drivers
|
||||
imu/analog_devices/adis16448
|
||||
imu/invensense/icm20602
|
||||
imu/invensense/icm20608g
|
||||
imu/invensense/mpu9250
|
||||
irlock
|
||||
lights/blinkm
|
||||
lights/rgbled
|
||||
lights/rgbled_ncp5623c
|
||||
lights # all available light drivers
|
||||
magnetometer # all available magnetometer drivers
|
||||
#optical_flow # all available optical flow drivers
|
||||
optical_flow/px4flow
|
||||
#osd
|
||||
optical_flow # all available optical flow drivers
|
||||
osd
|
||||
pca9685
|
||||
pca9685_pwm_out
|
||||
power_monitor/ina226
|
||||
#power_monitor/ina226
|
||||
#protocol_splitter
|
||||
pwm_input
|
||||
pwm_out_sim
|
||||
pwm_out
|
||||
px4io
|
||||
roboclaw
|
||||
rpm
|
||||
telemetry # all available telemetry drivers
|
||||
test_ppm
|
||||
tone_alarm
|
||||
|
@ -94,6 +93,7 @@ px4_add_board(
|
|||
#dmesg
|
||||
dumpfile
|
||||
esc_calib
|
||||
gpio
|
||||
hardfault_log
|
||||
i2cdetect
|
||||
led_control
|
||||
|
@ -120,6 +120,8 @@ px4_add_board(
|
|||
work_queue
|
||||
EXAMPLES
|
||||
fake_gps
|
||||
fake_gyro
|
||||
fake_magnetometer
|
||||
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
hello
|
||||
hwtest # Hardware test
|
||||
|
|
|
@ -16,8 +16,8 @@ px4_add_board(
|
|||
TEL2:/dev/ttyS2
|
||||
TEL4:/dev/ttyS3
|
||||
DRIVERS
|
||||
adc/board_adc
|
||||
adc/ads1115
|
||||
adc/board_adc
|
||||
barometer # all available barometer drivers
|
||||
batt_smbus
|
||||
camera_capture
|
||||
|
@ -29,19 +29,14 @@ px4_add_board(
|
|||
#heater
|
||||
#imu # all available imu drivers
|
||||
imu/analog_devices/adis16448
|
||||
imu/adis16477
|
||||
imu/adis16497
|
||||
imu/bosch/bmi055
|
||||
imu/invensense/icm20602
|
||||
imu/invensense/icm20689
|
||||
irlock
|
||||
lights/blinkm
|
||||
lights/rgbled
|
||||
lights/rgbled_ncp5623c
|
||||
lights/rgbled_pwm
|
||||
lights # all available light drivers
|
||||
magnetometer # all available magnetometer drivers
|
||||
optical_flow # all available optical flow drivers
|
||||
#osd
|
||||
osd
|
||||
pca9685
|
||||
pca9685_pwm_out
|
||||
power_monitor/ina226
|
||||
|
|
|
@ -18,8 +18,8 @@ px4_add_board(
|
|||
TEL3:/dev/ttyS1
|
||||
GPS2:/dev/ttyS7
|
||||
DRIVERS
|
||||
adc/board_adc
|
||||
adc/ads1115
|
||||
adc/board_adc
|
||||
barometer # all available barometer drivers
|
||||
batt_smbus
|
||||
camera_capture
|
||||
|
@ -31,19 +31,15 @@ px4_add_board(
|
|||
#heater
|
||||
#imu # all available imu drivers
|
||||
imu/analog_devices/adis16448
|
||||
imu/adis16477
|
||||
imu/adis16497
|
||||
imu/bosch/bmi088
|
||||
imu/invensense/icm20602
|
||||
imu/invensense/icm42688p
|
||||
irlock
|
||||
#lights/blinkm
|
||||
lights/rgbled
|
||||
lights/rgbled_ncp5623c
|
||||
lights # all available light drivers
|
||||
magnetometer # all available magnetometer drivers
|
||||
optical_flow # all available optical flow drivers
|
||||
#osd
|
||||
#pca9685
|
||||
osd
|
||||
pca9685
|
||||
pca9685_pwm_out
|
||||
power_monitor/ina226
|
||||
#protocol_splitter
|
||||
|
@ -89,6 +85,8 @@ px4_add_board(
|
|||
sensors
|
||||
sih
|
||||
temperature_compensation
|
||||
uuv_att_control
|
||||
uuv_pos_control
|
||||
vmount
|
||||
vtol_att_control
|
||||
SYSTEMCMDS
|
||||
|
@ -124,6 +122,8 @@ px4_add_board(
|
|||
work_queue
|
||||
EXAMPLES
|
||||
fake_gps
|
||||
fake_gyro
|
||||
fake_magnetometer
|
||||
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
hello
|
||||
hwtest # Hardware test
|
||||
|
|
|
@ -28,6 +28,7 @@ px4_add_board(
|
|||
gps
|
||||
heater
|
||||
#imu # all available imu drivers
|
||||
imu/analog_devices/adis16448
|
||||
imu/bosch/bmi088
|
||||
imu/invensense/icm20602
|
||||
imu/invensense/icm42605
|
||||
|
@ -117,7 +118,8 @@ px4_add_board(
|
|||
work_queue
|
||||
EXAMPLES
|
||||
fake_gps
|
||||
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
fake_magnetometer
|
||||
#fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
#hello
|
||||
#hwtest # Hardware test
|
||||
#matlab_csv_serial
|
||||
|
|
|
@ -10,7 +10,7 @@ px4_add_board(
|
|||
BUILD_BOOTLOADER
|
||||
IO px4_io-v2_default
|
||||
TESTING
|
||||
# UAVCAN_INTERFACES 2 - No H7 or FD can support in UAVCAN
|
||||
UAVCAN_INTERFACES 2
|
||||
SERIAL_PORTS
|
||||
GPS1:/dev/ttyS0
|
||||
TEL1:/dev/ttyS6
|
||||
|
@ -30,8 +30,6 @@ px4_add_board(
|
|||
heater
|
||||
#imu # all available imu drivers
|
||||
imu/analog_devices/adis16448
|
||||
imu/adis16477
|
||||
imu/adis16497
|
||||
imu/bosch/bmi088
|
||||
imu/invensense/icm20649
|
||||
irlock
|
||||
|
@ -44,8 +42,7 @@ px4_add_board(
|
|||
pca9685
|
||||
power_monitor/ina226
|
||||
#protocol_splitter
|
||||
# pwm_input - Need to create arch/stm32 arch/stm32h7 arch/kinetis and reloacate
|
||||
# all arch dependant code there
|
||||
#pwm_input - Need to create arch/stm32 arch/stm32h7
|
||||
pwm_out_sim
|
||||
pwm_out
|
||||
px4io
|
||||
|
@ -56,10 +53,11 @@ px4_add_board(
|
|||
telemetry # all available telemetry drivers
|
||||
test_ppm
|
||||
tone_alarm
|
||||
# uavcan - No H7 or FD can support in UAVCAN yet
|
||||
uavcan
|
||||
MODULES
|
||||
airspeed_selector
|
||||
attitude_estimator_q
|
||||
#battery_status
|
||||
camera_feedback
|
||||
commander
|
||||
dataman
|
||||
|
@ -94,6 +92,7 @@ px4_add_board(
|
|||
dmesg
|
||||
dumpfile
|
||||
esc_calib
|
||||
gpio
|
||||
hardfault_log
|
||||
i2cdetect
|
||||
led_control
|
||||
|
@ -109,6 +108,7 @@ px4_add_board(
|
|||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
serial_test
|
||||
system_time
|
||||
tests # tests and test runner
|
||||
top
|
||||
|
@ -118,7 +118,6 @@ px4_add_board(
|
|||
usb_connected
|
||||
ver
|
||||
work_queue
|
||||
serial_test
|
||||
EXAMPLES
|
||||
fake_gps
|
||||
fake_magnetometer
|
||||
|
|
|
@ -88,6 +88,7 @@ px4_add_board(
|
|||
EXAMPLES
|
||||
dyn_hello # dynamically loading modules example
|
||||
fake_gps
|
||||
fake_gyro
|
||||
fake_magnetometer
|
||||
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
hello
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2018 PX4 Development Team. All rights reserved.
|
||||
# Copyright (c) 2018-2021 PX4 Development Team. All rights reserved.
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
|
@ -32,6 +32,7 @@
|
|||
############################################################################
|
||||
|
||||
add_subdirectory(blinkm)
|
||||
#add_subdirectory(neopixel) # requiers board support (BOARD_HAS_N_S_RGB_LED)
|
||||
add_subdirectory(rgbled)
|
||||
add_subdirectory(rgbled_ncp5623c)
|
||||
#add_subdirectory(rgbled_pwm) # requires board support (BOARD_HAS_LED_PWM/BOARD_HAS_UI_LED_PWM)
|
||||
|
|
Loading…
Reference in New Issue