mirror of
https://gitee.com/xiaohuolufeihua/bizhang_-obav.git
synced 2026-05-21 01:12:11 +00:00
airframes: add config for px4vision devkit drone (#13683)
* Added configuration file for Pixhawk Vision Signed-off-by: RomanBapst <bapstroman@gmail.com>
This commit is contained in:
140
ROMFS/px4fmu_common/init.d/airframes/4016_holybro_px4vision
Normal file
140
ROMFS/px4fmu_common/init.d/airframes/4016_holybro_px4vision
Normal file
@@ -0,0 +1,140 @@
|
||||
#!/bin/sh
|
||||
#
|
||||
# @name PX4 Vision DevKit Platform
|
||||
#
|
||||
# @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
|
||||
#
|
||||
|
||||
sh /etc/init.d/rc.mc_defaults
|
||||
|
||||
set MIXER quad_x
|
||||
set PWM_OUT 1234
|
||||
|
||||
if [ $AUTOCNF = yes ]
|
||||
then
|
||||
# System parameters
|
||||
# use FMU motor outputs for less delay in the rate control loop
|
||||
param set SYS_USE_IO 0
|
||||
|
||||
# Commander Parameters
|
||||
param set COM_OBS_AVOID 1
|
||||
param set COM_DISARM_LAND 0.5
|
||||
|
||||
# EKF2 parameters
|
||||
param set EKF2_AID_MASK 35
|
||||
param set EKF2_IMU_POS_X 0.02
|
||||
param set EKF2_GPS_POS_X 0.055
|
||||
param set EKF2_GPS_POS_Z -0.15
|
||||
param set EKF2_HGT_MODE 0
|
||||
param set EKF2_MIN_RNG 0.03
|
||||
param set EKF2_OF_POS_X 0.055
|
||||
param set EKF2_OF_POS_Y 0.02
|
||||
param set EKF2_OF_POS_Z 0.065
|
||||
param set EKF2_REQ_HDRIFT 0.3
|
||||
param set EKF2_REQ_SACC 1
|
||||
param set EKF2_REQ_VDRIFT 0.3
|
||||
param set EKF2_RNG_AID 1
|
||||
param set EKF2_RNG_A_HMAX 8
|
||||
param set EKF2_RNG_A_VMAX 2
|
||||
param set EKF2_RNG_POS_X 0.055
|
||||
param set EKF2_RNG_POS_Y -0.01
|
||||
param set EKF2_RNG_POS_Z 0.065
|
||||
param set EKF2_PCOEF_XP -0.25
|
||||
param set EKF2_PCOEF_YN -0.55
|
||||
param set EKF2_PCOEF_YP -0.55
|
||||
|
||||
# MAVLink parameters
|
||||
param set MAV_0_CONFIG 101
|
||||
param set MAV_1_CONFIG 102
|
||||
param set MAV_1_RATE 80000
|
||||
param set MAV_1_MODE 9
|
||||
param set SER_TEL1_BAUD 921600
|
||||
|
||||
# Vehicle attitude PID tuning
|
||||
param set MC_ACRO_EXPO 0
|
||||
param set MC_ACRO_EXPO_Y 0
|
||||
param set MC_ACRO_P_MAX 200
|
||||
param set MC_ACRO_R_MAX 200
|
||||
param set MC_ACRO_SUPEXPO 0
|
||||
param set MC_ACRO_SUPEXPOY 0
|
||||
param set MC_ACRO_Y_MAX 150
|
||||
param set MC_DTERM_CUTOFF 30
|
||||
param set MC_PITCHRATE_D 0.0015
|
||||
param set MC_PITCHRATE_I 0.2
|
||||
param set MC_PITCHRATE_K 1
|
||||
param set MC_PITCHRATE_P 0.15
|
||||
param set MC_ROLLRATE_D 0.0015
|
||||
param set MC_ROLLRATE_I 0.2
|
||||
param set MC_ROLLRATE_K 1
|
||||
param set MC_ROLLRATE_P 0.15
|
||||
param set MC_YAWRATE_P 0.3
|
||||
|
||||
# Position Control Tuning
|
||||
param set CP_DIST 6.0
|
||||
param set MPC_ACC_DOWN_MAX 5
|
||||
param set MPC_ACC_HOR_MAX 10
|
||||
param set MPC_ACC_UP_MAX 4
|
||||
param set MPC_MANTHR_MIN 0
|
||||
param set MPC_MAN_Y_MAX 120
|
||||
param set MPC_TILTMAX_AIR 45
|
||||
param set MPC_THR_HOVER 0.3
|
||||
param set MPC_THR_MIN 0.12
|
||||
param set MPC_TKO_SPEED 1
|
||||
param set MPC_VEL_MANUAL 5
|
||||
param set MPC_XY_CRUISE 5
|
||||
param set MPC_XY_VEL_MAX 5
|
||||
param set MPC_XY_VEL_P 0.079
|
||||
param set MPC_XY_TRAJ_P 0.3
|
||||
param set MPC_Z_TRAJ_P 0.3
|
||||
param set MPC_Z_VEL_I 0.15
|
||||
param set MPC_Z_VEL_P 0.25
|
||||
|
||||
# Navigator Parameters
|
||||
param set NAV_ACC_RAD 2
|
||||
|
||||
# PWM and RC Parameters
|
||||
param set PWM_MAX 1950
|
||||
param set PWM_MIN 1075
|
||||
|
||||
# use oneshot motor output protocol
|
||||
param set PWM_RATE 0
|
||||
param set RC_FLT_CUTOFF 0
|
||||
|
||||
# RTL Parameters
|
||||
param set RTL_DESCEND_ALT 5
|
||||
param set RTL_LAND_DELAY 0
|
||||
param set RTL_RETURN_ALT 5
|
||||
param set RTL_CONE_ANG 45
|
||||
|
||||
# Logging Parameters
|
||||
param set SDLOG_PROFILE 131
|
||||
|
||||
# Sensors Parameters
|
||||
param set SENS_BOARD_ROT 0
|
||||
param set SENS_CM8JL65_CFG 104
|
||||
param set SENS_FLOW_MAXHGT 25
|
||||
param set SENS_FLOW_MINHGT 0.5
|
||||
param set SENS_FLOW_ROT 0
|
||||
param set IMU_GYRO_CUTOFF 100
|
||||
param set SENS_EN_PMW3901 1
|
||||
|
||||
# Power Parameters
|
||||
param set BAT_N_CELLS 4
|
||||
param set BAT_A_PER_V 36.3675
|
||||
param set BAT_CNT_V_CURR 0.0008
|
||||
param set BAT_CNT_V_VOLT 0.0008
|
||||
param set BAT_V_DIV 18.40697289
|
||||
|
||||
# Circuit breakers
|
||||
param set CBRK_IO_SAFETY 22027
|
||||
|
||||
param set THR_MDL_FAC 0.3
|
||||
fi
|
||||
@@ -39,7 +39,7 @@ px4_add_romfs_files(
|
||||
1001_rc_quad_x.hil
|
||||
1002_standard_vtol.hil
|
||||
1100_rc_quad_x_sih.hil
|
||||
|
||||
|
||||
# [2000, 2999] Standard planes"
|
||||
2100_standard_plane
|
||||
2105_maja
|
||||
@@ -70,6 +70,7 @@ px4_add_romfs_files(
|
||||
4013_bebop
|
||||
4014_s500
|
||||
4015_holybro_s500
|
||||
4016_holybro_px4vision
|
||||
4020_hk_micro_pcb
|
||||
4030_3dr_solo
|
||||
4031_3dr_quad
|
||||
@@ -142,7 +143,7 @@ px4_add_romfs_files(
|
||||
15001_coax_heli
|
||||
|
||||
16001_helicopter
|
||||
|
||||
|
||||
24001_dodeca_cox
|
||||
|
||||
50000_generic_ground_vehicle
|
||||
|
||||
Reference in New Issue
Block a user