Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Pr vtol hitl #9276

Merged
merged 7 commits into from
Jul 2, 2018
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
64 changes: 64 additions & 0 deletions ROMFS/px4fmu_common/init.d/1002_standard_vtol.hil
Original file line number Diff line number Diff line change
@@ -0,0 +1,64 @@
#!nsh
#
# @name HIL Standard VTOL QuadPlane
#
# @type Standard VTOL
# @class VTOL
#
# @maintainer Roman Bapst <[email protected]>
#

sh /etc/init.d/rc.vtol_defaults

if [ $AUTOCNF == yes ]
then
param set BAT_N_CELLS 3
param set COM_DISARM_LAND 5
param set COM_RC_IN_MODE 1
param set EKF2_AID_MASK 1
param set EKF2_ANGERR_INIT 0.01
param set EKF2_GBIAS_INIT 0.01
param set EKF2_HGT_MODE 0
param set EKF2_MAG_TYPE 1
param set FW_AIRSPD_MAX 25
param set FW_AIRSPD_MIN 14
param set FW_AIRSPD_TRIM 16
param set MAV_TYPE 20
param set MC_PITCH_P 6
param set MC_PITCHRATE_P 0.2
param set MC_ROLL_P 6
param set MC_ROLLRATE_P 0.3
param set MIS_LTRMIN_ALT 10
param set MIS_TAKEOFF_ALT 10
param set MIS_YAW_TMT 10
param set MPC_ACC_HOR_MAX 2
param set MPC_ACC_HOR_MAX 2.0
param set MPC_THR_MIN 0.1
param set MPC_TKO_SPEED 1.0
param set MPC_XY_P 0.8
param set MPC_XY_VEL_D 0.005
param set MPC_XY_VEL_I 0.2
param set MPC_XY_VEL_P 0.15
param set MPC_Z_VEL_I 0.15
param set MPC_Z_VEL_MAX_DN 1.5
param set MPC_Z_VEL_P 0.6
param set NAV_ACC_RAD 5.0
param set NAV_DLL_ACT 2
param set NAV_LOITER_RAD 80
param set RTL_DESCEND_ALT 10.0
param set RTL_LAND_DELAY 0
param set RTL_RETURN_ALT 30.0
param set SDLOG_DIRS_MAX 7
param set SYS_MC_EST_GROUP 2
param set SYS_RESTART_TYPE 2
param set VT_F_TRANS_THR 0.75
param set VT_MOT_COUNT 4
param set VT_TYPE 2
fi

set MIXER standard_vtol_hitl
set MAV_TYPE 22

set PWM_OUT 1234

param set SYS_HITL 1
1 change: 0 additions & 1 deletion ROMFS/px4fmu_common/mixers/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -75,7 +75,6 @@ px4_add_romfs_files(
quad_x_can.main.mix
quad_x.main.mix
quad_x_vtol.main.mix
quad_x_vtol_sim.main.mix
stampede.main.mix
tri_y_yaw-.main.mix
tri_y_yaw+.main.mix
Expand Down
6 changes: 0 additions & 6 deletions ROMFS/px4fmu_common/mixers/quad_x_vtol.main.mix
Original file line number Diff line number Diff line change
Expand Up @@ -6,8 +6,6 @@ are mixed 100%.

R: 4x 10000 10000 10000 0

Z:

# left elevon
M: 2
S: 1 0 5000 5000 0 -10000 10000
Expand All @@ -17,7 +15,3 @@ S: 1 1 5000 5000 0 -10000 10000
M: 2
S: 1 0 5000 5000 0 -10000 10000
S: 1 1 -5000 -5000 0 -10000 10000

# mixer for the virtual elevator
M: 1
S: 1 1 10000 10000 0 -10000 10000
24 changes: 24 additions & 0 deletions ROMFS/px4fmu_common/mixers/standard_vtol_hitl.main.mix
Original file line number Diff line number Diff line change
@@ -0,0 +1,24 @@
Mixer for Standard VTOL (QuadPlane) with motor x configuration (Gazebo HITL)
=============================================================================

R: 4x 10000 10000 10000 0

# mixer for the pusher/puller throttle
M: 1
O: 10000 10000 0 -10000 10000
S: 1 3 0 20000 -10000 -10000 10000

# mixer for the left aileron
M: 1
O: 10000 10000 0 -10000 10000
S: 1 0 10000 10000 0 -10000 10000

# mixer for the right aileron
M: 1
O: 10000 10000 0 -10000 10000
S: 1 0 -10000 -10000 0 -10000 10000

# mixer for the elevator
M: 1
O: 10000 10000 0 -10000 10000
S: 1 1 10000 10000 0 -10000 10000
2 changes: 1 addition & 1 deletion posix-configs/SITL/init/ekf2/tailsitter
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,7 @@ mc_att_control start
fw_pos_control_l1 start
fw_att_control start
wind_estimator start
mixer load /dev/pwm_output0 ROMFS/px4fmu_common/mixers/quad_x_vtol_sim.main.mix
mixer load /dev/pwm_output0 ROMFS/sitl/mixers/quad_x_vtol.main.mix
mavlink start -x -u 14556 -r 2000000
mavlink start -x -u 14557 -r 2000000 -m onboard -o 14540
mavlink stream -r 80 -s POSITION_TARGET_LOCAL_NED -u 14556
Expand Down