Add Rover SITL config

This commit is contained in:
Lorenz Meier 2017-02-18 15:39:48 +01:00
parent 63a84900e6
commit bbd1906dfb
4 changed files with 106 additions and 2 deletions

View File

@ -0,0 +1,37 @@
Mixer for SITL rover
=========================================================
# mixer for the rudder
M: 1
O: 10000 10000 0 -10000 10000
S: 0 0 10000 10000 0 -10000 10000
# mixer for the rudder
M: 1
O: 10000 10000 0 -10000 10000
S: 0 0 10000 10000 0 -10000 10000
# mixer for the elevator
M: 1
O: 10000 10000 0 -10000 10000
S: 0 1 10000 10000 0 -10000 10000
# mixer for throttle
M: 1
O: 10000 10000 0 -10000 10000
S: 0 3 0 20000 -10000 -10000 10000
# mixer for throttle
M: 1
O: 10000 10000 0 -10000 10000
S: 0 3 0 20000 -10000 -10000 10000
# mixer for throttle
M: 1
O: 10000 10000 0 -10000 10000
S: 0 3 0 20000 -10000 -10000 10000
# mixer for throttle
M: 1
O: 10000 10000 0 -10000 10000
S: 0 3 0 20000 -10000 -10000 10000

View File

@ -33,7 +33,7 @@ set(config_module_list
#systemcmds/nshterm
systemcmds/param
systemcmds/perf
#systemcmds/pwm
systemcmds/pwm
systemcmds/reboot
systemcmds/sd_bench
systemcmds/top

View File

@ -0,0 +1,67 @@
uorb start
param load
param set MAV_TYPE 1
param set SYS_AUTOSTART 3033
param set SYS_RESTART_TYPE 2
param set SYS_MC_EST_GROUP 2
dataman start
param set BAT_N_CELLS 3
param set CAL_GYRO0_ID 2293768
param set CAL_ACC0_ID 1376264
param set CAL_ACC1_ID 1310728
param set CAL_MAG0_ID 196616
param set CAL_GYRO0_XOFF 0.01
param set CAL_ACC0_XOFF 0.01
param set CAL_ACC0_YOFF -0.01
param set CAL_ACC0_ZOFF 0.01
param set CAL_ACC0_XSCALE 1.01
param set CAL_ACC0_YSCALE 1.01
param set CAL_ACC0_ZSCALE 1.01
param set CAL_ACC1_XOFF 0.01
param set CAL_MAG0_XOFF 0.01
param set SENS_BOARD_ROT 0
param set SENS_DPRES_OFF 0.001
param set SENS_BOARD_X_OFF 0.000001
param set COM_RC_IN_MODE 1
param set NAV_DLL_ACT 2
param set NAV_ACC_RAD 15.0
param set NAV_LOITER_RAD 50
param set MIS_LTRMIN_ALT 30
param set MIS_TAKEOFF_ALT 30
param set FW_THR_IDLE 0.8
param set EKF2_GBIAS_INIT 0.01
param set EKF2_ANGERR_INIT 0.01
param set EKF2_MAG_TYPE 1
replay tryapplyparams
simulator start -s
tone_alarm start
gyrosim start
accelsim start
barosim start
adcsim start
gpssim start
measairspeedsim start
pwm_out_sim mode_pwm
sleep 1
sensors start
commander start
navigator start
ekf2 start
fw_pos_control_l1 start
fw_att_control start
land_detector start rover
mixer load /dev/pwm_output0 ROMFS/sitl/mixers/rover_sitl.main.mix
mavlink start -u 14556 -r 2000000
mavlink start -u 14557 -r 2000000 -m onboard -o 14540
mavlink stream -r 80 -s POSITION_TARGET_LOCAL_NED -u 14556
mavlink stream -r 80 -s LOCAL_POSITION_NED -u 14556
mavlink stream -r 80 -s GLOBAL_POSITION_INT -u 14556
mavlink stream -r 80 -s ATTITUDE -u 14556
mavlink stream -r 80 -s ATTITUDE_QUATERNION -u 14556
mavlink stream -r 80 -s ATTITUDE_TARGET -u 14556
mavlink stream -r 20 -s RC_CHANNELS -u 14556
mavlink stream -r 250 -s HIGHRES_IMU -u 14556
mavlink stream -r 10 -s OPTICAL_FLOW_RAD -u 14556
sdlog2 start -r 200 -e -t -a
mavlink boot_complete
replay trystart

View File

@ -74,7 +74,7 @@ ExternalProject_Add_Step(sitl_gazebo forceconfigure
# create targets for each viewer/model/debugger combination
set(viewers none jmavsim gazebo replay)
set(debuggers none ide gdb lldb ddd valgrind callgrind)
set(models none iris iris_opt_flow standard_vtol plane solo tailsitter typhoon_h480)
set(models none iris iris_opt_flow standard_vtol plane solo tailsitter typhoon_h480 rover)
set(all_posix_vmd_make_targets)
foreach(viewer ${viewers})
foreach(debugger ${debuggers})