mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
boards: align auterion v6x with APX4
This commit is contained in:
parent
9fa4a57c66
commit
0f0fe8f1fa
@ -20,13 +20,11 @@ CONFIG_DRIVERS_DSHOT=y
|
||||
CONFIG_DRIVERS_GNSS_SEPTENTRIO=y
|
||||
CONFIG_DRIVERS_GPIO_MCP23009=y
|
||||
CONFIG_DRIVERS_GPS=y
|
||||
CONFIG_DRIVERS_HEATER=y
|
||||
CONFIG_DRIVERS_IMU_BOSCH_BMI088=y
|
||||
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20602=y
|
||||
CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y
|
||||
CONFIG_COMMON_LIGHT=y
|
||||
CONFIG_COMMON_MAGNETOMETER=y
|
||||
CONFIG_DRIVERS_OSD_MSP_OSD=y
|
||||
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
|
||||
CONFIG_DRIVERS_POWER_MONITOR_INA228=y
|
||||
CONFIG_DRIVERS_POWER_MONITOR_INA238=y
|
||||
@ -34,6 +32,7 @@ CONFIG_DRIVERS_POWER_MONITOR_PM_SELECTOR_AUTERION=y
|
||||
CONFIG_DRIVERS_PWM_INPUT=y
|
||||
CONFIG_DRIVERS_PWM_OUT=y
|
||||
CONFIG_DRIVERS_PX4IO=y
|
||||
CONFIG_DRIVERS_RPM_CAPTURE=y
|
||||
CONFIG_COMMON_RC=y
|
||||
CONFIG_DRIVERS_SAFETY_BUTTON=y
|
||||
CONFIG_DRIVERS_TONE_ALARM=y
|
||||
@ -53,10 +52,12 @@ CONFIG_MODULES_FW_ATT_CONTROL=y
|
||||
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||
CONFIG_MODULES_FW_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y
|
||||
CONFIG_FIGURE_OF_EIGHT=y
|
||||
CONFIG_MODULES_FW_RATE_CONTROL=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_GYRO_CALIBRATION=y
|
||||
CONFIG_MODULES_HARDFAULT_STREAM=y
|
||||
CONFIG_MODULES_INTERNAL_COMBUSTION_ENGINE_CONTROL=y
|
||||
CONFIG_MODULES_LAND_DETECTOR=y
|
||||
CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y
|
||||
CONFIG_MODULES_LOAD_MON=y
|
||||
@ -64,7 +65,6 @@ CONFIG_MODULES_LOGGER=y
|
||||
CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y
|
||||
CONFIG_MODULES_MANUAL_CONTROL=y
|
||||
CONFIG_MODULES_MAVLINK=y
|
||||
CONFIG_MAVLINK_DIALECT="development"
|
||||
CONFIG_MODULES_MC_ATT_CONTROL=y
|
||||
CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
|
||||
@ -74,8 +74,9 @@ CONFIG_MODULES_NAVIGATOR=y
|
||||
CONFIG_MODE_NAVIGATOR_VTOL_TAKEOFF=y
|
||||
CONFIG_NUM_MISSION_ITMES_SUPPORTED=1000
|
||||
CONFIG_MODULES_RC_UPDATE=y
|
||||
CONFIG_MODULES_ROVER_MECANUM=y
|
||||
CONFIG_MODULES_SENSORS=y
|
||||
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
|
||||
CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y
|
||||
CONFIG_MODULES_UXRCE_DDS_CLIENT=y
|
||||
CONFIG_MODULES_VTOL_ATT_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
|
||||
@ -92,6 +93,7 @@ CONFIG_SYSTEMCMDS_PARAM=y
|
||||
CONFIG_SYSTEMCMDS_PERF=y
|
||||
CONFIG_SYSTEMCMDS_REBOOT=y
|
||||
CONFIG_SYSTEMCMDS_SYSTEM_TIME=y
|
||||
CONFIG_SYSTEMCMDS_SD_BENCH=y
|
||||
CONFIG_SYSTEMCMDS_TOP=y
|
||||
CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y
|
||||
CONFIG_SYSTEMCMDS_TUNE_CONTROL=y
|
||||
|
||||
@ -17,6 +17,9 @@ param set-default UXRCE_DDS_CFG 1000
|
||||
# The buzzer draws too much power (0.2A) on the GPS power rail (limit 0.45A).
|
||||
param set-default CBRK_BUZZER 782097
|
||||
|
||||
# Update default IP config if needed
|
||||
netman update_default -i eth0
|
||||
|
||||
safety_button start
|
||||
|
||||
# GPIO Expander driver on external I2C3
|
||||
|
||||
@ -3,8 +3,16 @@
|
||||
# Auterion FMUv6X specific board MAVLink startup script.
|
||||
#------------------------------------------------------------------------------
|
||||
|
||||
# start Mavlink on Telem2
|
||||
mavlink start -d /dev/ttyS4 -b 3000000 -r 290000 -m onboard_low_bandwidth -x -z
|
||||
if param compare MAV_S_FORWARD 1
|
||||
then
|
||||
set S_FORWARD "-f"
|
||||
else
|
||||
set S_FORWARD ""
|
||||
fi
|
||||
|
||||
mavlink start -d /dev/ttyS4 -b 3000000 -r 290000 -m p:MAV_S_MODE -x -z $S_FORWARD
|
||||
|
||||
unset S_FORWARD
|
||||
|
||||
# Ensure nothing else starts on TEL2 (ttyS4)
|
||||
set PRT_TEL2_ 1
|
||||
|
||||
@ -9,5 +9,4 @@ CONFIG_MODULES_FW_RATE_CONTROL=n
|
||||
CONFIG_MODULES_VTOL_ATT_CONTROL=n
|
||||
CONFIG_COMMON_RC=y
|
||||
# CONFIG_EKF2_SIDESLIP is not set
|
||||
CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y
|
||||
# CONFIG_SENSORS_VEHICLE_AIRSPEED is not set
|
||||
|
||||
@ -377,7 +377,11 @@
|
||||
#define GPIO_USART2_RTS GPIO_USART2_RTS_2 /* PD4 */
|
||||
#define GPIO_USART2_CTS GPIO_USART2_CTS_NSS_2 /* PD3 */
|
||||
|
||||
#define GPIO_USART3_RX GPIO_USART3_RX_3 /* PD9 */
|
||||
#ifdef PX4_RESTRICTED_BUILD
|
||||
# define GPIO_USART3_RX 0 /* PD9 */
|
||||
#else
|
||||
# define GPIO_USART3_RX GPIO_USART3_RX_3 /* PD9 */
|
||||
#endif /* PX4_RESTRICTED_BUILD */
|
||||
#define GPIO_USART3_TX GPIO_USART3_TX_3 /* PD8 */
|
||||
|
||||
#define GPIO_UART4_RX GPIO_UART4_RX_6 /* PH14 */
|
||||
|
||||
@ -139,14 +139,13 @@ CONFIG_NETDB_DNSCLIENT=y
|
||||
CONFIG_NETDB_DNSCLIENT_ENTRIES=8
|
||||
CONFIG_NETDB_DNSSERVER_NOADDR=y
|
||||
CONFIG_NETDEV_PHY_IOCTL=y
|
||||
CONFIG_NETINIT_DHCPC=y
|
||||
CONFIG_NETINIT_DNS=y
|
||||
CONFIG_NETINIT_DNSIPADDR=0xA290AFE
|
||||
CONFIG_NETINIT_DRIPADDR=0xA290AFE
|
||||
CONFIG_NETINIT_IPADDR=0xA290A02
|
||||
CONFIG_NETINIT_MONITOR=y
|
||||
CONFIG_NETINIT_THREAD=y
|
||||
CONFIG_NETINIT_THREAD_PRIORITY=49
|
||||
CONFIG_NETUTILS_TELNETD=y
|
||||
CONFIG_NET_ARP_IPIN=y
|
||||
CONFIG_NET_ARP_SEND=y
|
||||
CONFIG_NET_BROADCAST=y
|
||||
@ -155,10 +154,6 @@ CONFIG_NET_ICMP=y
|
||||
CONFIG_NET_ICMP_SOCKET=y
|
||||
CONFIG_NET_NACTIVESOCKETS=16
|
||||
CONFIG_NET_SOLINGER=y
|
||||
CONFIG_NET_TCP=y
|
||||
CONFIG_NET_TCPBACKLOG=y
|
||||
CONFIG_NET_TCP_DELAYED_ACK=y
|
||||
CONFIG_NET_TCP_WRITE_BUFFERS=y
|
||||
CONFIG_NET_UDP=y
|
||||
CONFIG_NET_UDP_CHECKSUMS=y
|
||||
CONFIG_NET_UDP_WRITE_BUFFERS=y
|
||||
@ -174,8 +169,6 @@ CONFIG_NSH_QUOTE=y
|
||||
CONFIG_NSH_ROMFSETC=y
|
||||
CONFIG_NSH_ROMFSSECTSIZE=128
|
||||
CONFIG_NSH_STRERROR=y
|
||||
CONFIG_NSH_TELNET=y
|
||||
CONFIG_NSH_TELNET_LOGIN=y
|
||||
CONFIG_NSH_VARS=y
|
||||
CONFIG_OTG_ID_GPIO_DISABLE=y
|
||||
CONFIG_PIPES=y
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user