mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
Airframe: IFO-S setup is added.
This commit is contained in:
parent
f0dde45303
commit
15f997d337
@ -117,6 +117,7 @@ then
|
||||
|
||||
# TELEM1 ttyS1 - Wifi module
|
||||
param set MAV_0_CONFIG 101
|
||||
param set MAV_0_RATE 0
|
||||
param set MAV_0_MODE 2 # onboard
|
||||
param set SER_TEL1_BAUD 921600
|
||||
|
||||
|
||||
136
ROMFS/px4fmu_common/init.d/airframes/4073_ifo-s
Normal file
136
ROMFS/px4fmu_common/init.d/airframes/4073_ifo-s
Normal file
@ -0,0 +1,136 @@
|
||||
#!/bin/sh
|
||||
#
|
||||
# @name UVify IFO
|
||||
#
|
||||
# @type Quadrotor x
|
||||
# @class Copter
|
||||
#
|
||||
# @output MAIN1 motor 1
|
||||
# @output MAIN2 motor 2
|
||||
# @output MAIN3 motor 3
|
||||
# @output MAIN4 motor 4
|
||||
#
|
||||
# @board px4_fmu-v2 exclude
|
||||
# @board px4_fmu-v3 exclude
|
||||
# @board px4_fmu-v4pro exclude
|
||||
# @board px4_fmu-v5 exclude
|
||||
# @board px4_fmu-v5x exclude
|
||||
# @board intel_aerofc-v1 exclude
|
||||
#
|
||||
# @maintainer Hyon Lim <lim@uvify.com>
|
||||
#
|
||||
|
||||
set VEHICLE_TYPE mc
|
||||
set MIXER quad_x
|
||||
set PWM_OUT 1234
|
||||
|
||||
if [ $AUTOCNF = yes ]
|
||||
then
|
||||
# Attitude & rate gains
|
||||
#param set MC_ROLL_P 7.00000
|
||||
param set MC_ROLLRATE_P 0.15000
|
||||
#param set MC_ROLLRATE_I 0.90000
|
||||
param set MC_ROLLRATE_D 0.00130
|
||||
|
||||
#param set MC_PITCH_P 7.00000
|
||||
param set MC_PITCHRATE_P 0.15000
|
||||
#param set MC_PITCHRATE_I 1.10000
|
||||
param set MC_PITCHRATE_D 0.00160
|
||||
|
||||
param set MC_YAW_P 2.8
|
||||
param set MC_YAWRATE_P 0.2
|
||||
#param set MC_YAWRATE_I 0.15
|
||||
param set MC_YAWRATE_D 0.0
|
||||
param set MC_YAW_FF 0.5
|
||||
|
||||
#param set MC_ROLL_TC 0.19
|
||||
#param set MC_PITCH_TC 0.16
|
||||
|
||||
# Manual mode settings: Unleash Draco R's power :)
|
||||
#param set MPC_MAN_TILT_MAX 70.00000
|
||||
#param set MC_PITCHRATE_MAX 1600.00000
|
||||
#param set MC_ROLLRATE_MAX 1600.00000
|
||||
#param set MC_YAWRATE_MAX 700.00000
|
||||
param set MPC_MANTHR_MAX 0.90000
|
||||
param set MPC_MANTHR_MIN 0.08000
|
||||
#param set MPC_MAN_TILT_MAX 35.0000
|
||||
#param set MPC_TILTMAX_AIR 20.0000
|
||||
|
||||
# Disable RC filtering
|
||||
param set RC_FLT_CUTOFF 0.00000
|
||||
|
||||
# Filter settings
|
||||
param set MC_DTERM_CUTOFF 90.00000
|
||||
param set IMU_GYRO_CUTOFF 100.00000
|
||||
|
||||
# Thrust curve (avoids the need for TPA)
|
||||
#param set THR_MDL_FAC 0.25
|
||||
|
||||
# System
|
||||
param set PWM_MAX 1950
|
||||
param set PWM_MIN 1100
|
||||
param set PWM_RATE 0
|
||||
|
||||
# Sensors
|
||||
param set SENS_BOARD_ROT 10
|
||||
# Yaw 180
|
||||
param set SENS_FLOW_ROT 4
|
||||
# TELEM3
|
||||
param set SENS_TFMINI_CFG 103
|
||||
param set SENS_EN_PMW3901 1
|
||||
|
||||
# EKF2
|
||||
param set EKF2_AID_MASK 3
|
||||
param set EKF2_GND_EFF_DZ 6.0
|
||||
param set EKF2_HGT_MODE 1
|
||||
param set EKF2_MIN_RNG 0.3
|
||||
param set EKF2_OF_QMIN 50
|
||||
param set EKF2_RNG_AID 1
|
||||
|
||||
# Position control
|
||||
param set MPC_Z_P 1.00000
|
||||
param set MPC_Z_VEL_P 0.20000
|
||||
param set MPC_Z_VEL_I 0.02000
|
||||
param set MPC_Z_VEL_D 0.00000
|
||||
|
||||
param set MPC_THR_MIN 0.06000
|
||||
param set MPC_THR_HOVER 0.3000
|
||||
|
||||
param set MIS_TAKEOFF_ALT 1.1000
|
||||
param set MPC_XY_P 1.7000
|
||||
param set MPC_XY_VEL_P 0.1300
|
||||
param set MPC_XY_VEL_I 0.0600
|
||||
param set MPC_XY_VEL_D 0.0100
|
||||
param set MPC_TKO_RAMP_T 1.0000
|
||||
param set MPC_TKO_SPEED 1.1000
|
||||
param set MPC_VEL_MANUAL 3.0000
|
||||
|
||||
param set BAT_SOURCE 0
|
||||
param set BAT_N_CELLS 4
|
||||
param set BAT_V_DIV 10.14
|
||||
param set BAT_A_PER_V 18.18
|
||||
#param set CBRK_IO_SAFETY 22027
|
||||
param set COM_ARM_EKF_AB 0.00500
|
||||
param set COM_DISARM_LAND 2
|
||||
|
||||
# Filter settings
|
||||
param set IMU_GYRO_CUTOFF 90.00000
|
||||
param set MC_DTERM_CUTOFF 70.00000
|
||||
|
||||
# Don't try to be intelligent on RC loss: just cut the motors
|
||||
param set NAV_RCL_ACT 6
|
||||
|
||||
# enable to use high-rate logging for better rate tracking analysis
|
||||
# param set SDLOG_PROFILE 19
|
||||
|
||||
# TELEM1 ttyS1 - Wifi module
|
||||
param set MAV_0_CONFIG 101
|
||||
param set MAV_0_RATE 0
|
||||
param set MAV_0_MODE 2 # onboard
|
||||
param set SER_TEL1_BAUD 921600
|
||||
|
||||
# TELEM2 ttyS2 - Sub 1-Ghz
|
||||
param set MAV_1_CONFIG 102
|
||||
param set MAV_1_MODE 0 # normal
|
||||
param set SER_TEL2_BAUD 57600
|
||||
fi
|
||||
@ -80,6 +80,7 @@ px4_add_romfs_files(
|
||||
4070_aerofc
|
||||
4071_ifo
|
||||
4072_draco
|
||||
4073_ifo-s
|
||||
4080_zmr250
|
||||
4090_nanomind
|
||||
4100_tiltquadrotor
|
||||
|
||||
@ -12,6 +12,7 @@ px4_add_board(
|
||||
GPS1:/dev/ttyS3
|
||||
TEL1:/dev/ttyS1
|
||||
TEL2:/dev/ttyS2
|
||||
TEL3:/dev/ttyS6
|
||||
DRIVERS
|
||||
adc
|
||||
barometer/ms5611
|
||||
|
||||
@ -42,3 +42,12 @@ then
|
||||
mpu9250 -s -R 2 start
|
||||
lis3mdl -R 2 -X start
|
||||
fi
|
||||
|
||||
# IFO-S
|
||||
if param compare SYS_AUTOSTART 4073
|
||||
then
|
||||
# IFO GPS LED
|
||||
rgbled_ncp5623c start -a 0x38
|
||||
mpu9250 -R 2 start
|
||||
lis3mdl -R 2 -X start
|
||||
fi
|
||||
|
||||
@ -42,7 +42,7 @@ CONFIG_BUILTIN=y
|
||||
CONFIG_C99_BOOL8=y
|
||||
CONFIG_CDCACM=y
|
||||
CONFIG_CDCACM_PRODUCTID=0x0012
|
||||
CONFIG_CDCACM_PRODUCTSTR="Core"
|
||||
CONFIG_CDCACM_PRODUCTSTR="PX4 FMU UVify Core"
|
||||
CONFIG_CDCACM_RXBUFSIZE=600
|
||||
CONFIG_CDCACM_TXBUFSIZE=2000
|
||||
CONFIG_CDCACM_VENDORID=0x26ac
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user