4 changed files with 151 additions and 4 deletions
@ -0,0 +1,5 @@ |
|||||||
|
include(cmake/configs/posix_sitl_default.cmake) |
||||||
|
|
||||||
|
set(config_sitl_rcS_dir |
||||||
|
posix-configs/SITL/init/test |
||||||
|
) |
@ -0,0 +1,132 @@ |
|||||||
|
uorb start |
||||||
|
param load |
||||||
|
param set MAV_TYPE 22 |
||||||
|
param set VT_TYPE 2 |
||||||
|
param set VT_MOT_COUNT 4 |
||||||
|
param set VT_TRANS_THR 0.75 |
||||||
|
param set SYS_AUTOSTART 13006 |
||||||
|
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 MC_ROLLRATE_P 0.3 |
||||||
|
param set MC_PITCHRATE_P 0.2 |
||||||
|
param set MC_PITCH_P 6 |
||||||
|
param set MC_ROLL_P 6 |
||||||
|
param set MPC_XY_P 0.8 |
||||||
|
param set MPC_ACC_HOR_MAX 2.0 |
||||||
|
param set MPC_XY_VEL_P 0.15 |
||||||
|
param set MPC_XY_VEL_I 0.2 |
||||||
|
param set MPC_XY_VEL_D 0.005 |
||||||
|
param set MPC_XY_FF 0.1 |
||||||
|
param set MPC_Z_VEL_MAX 1.5 |
||||||
|
param set MPC_Z_VEL_P 0.6 |
||||||
|
param set MPC_Z_VEL_I 0.15 |
||||||
|
param set FW_AIRSPD_MIN 14 |
||||||
|
param set FW_AIRSPD_TRIM 16 |
||||||
|
param set FW_AIRSPD_MAX 25 |
||||||
|
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 5.0 |
||||||
|
param set NAV_LOITER_RAD 80 |
||||||
|
param set MPC_TKO_SPEED 1.0 |
||||||
|
param set MIS_LTRMIN_ALT 10 |
||||||
|
param set MIS_TAKEOFF_ALT 10 |
||||||
|
param set MIS_YAW_TMT 10 |
||||||
|
param set RTL_RETURN_ALT 30.0 |
||||||
|
param set RTL_DESCEND_ALT 10.0 |
||||||
|
param set RTL_LAND_DELAY 0 |
||||||
|
param set COM_DISARM_LAND 2 |
||||||
|
param set MPC_ACC_HOR_MAX 2 |
||||||
|
param set EKF2_GBIAS_INIT 0.01 |
||||||
|
param set EKF2_ANGERR_INIT 0.01 |
||||||
|
param set EKF2_MAG_TYPE 1 |
||||||
|
simulator start -s |
||||||
|
rgbledsim start |
||||||
|
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 |
||||||
|
land_detector start multicopter |
||||||
|
navigator start |
||||||
|
ekf2 start |
||||||
|
vtol_att_control start |
||||||
|
mc_pos_control start |
||||||
|
mc_att_control start |
||||||
|
fw_pos_control_l1 start |
||||||
|
fw_att_control start |
||||||
|
mixer load /dev/pwm_output0 ROMFS/sitl/mixers/standard_vtol_sitl.main.mix |
||||||
|
mavlink start -u 14556 -r 2000000 |
||||||
|
mavlink start -u 14557 -r 2000000 -m onboard -o 14540 |
||||||
|
mavlink stream -r 20 -s EXTENDED_SYS_STATE -u 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 |
||||||
|
logger start -e -t |
||||||
|
mavlink boot_complete |
||||||
|
ver all |
||||||
|
|
||||||
|
sleep 13 |
||||||
|
commander takeoff |
||||||
|
sleep 2 |
||||||
|
commander land |
||||||
|
sleep 5 |
||||||
|
|
||||||
|
listener vehicle_status |
||||||
|
|
||||||
|
logger stop |
||||||
|
mavlink stop-all |
||||||
|
vtol_att_control stop |
||||||
|
mc_pos_control stop |
||||||
|
mc_att_control stop |
||||||
|
fw_pos_control_l1 stop |
||||||
|
fw_att_control stop |
||||||
|
|
||||||
|
commander stop |
||||||
|
navigator stop |
||||||
|
land_detector stop |
||||||
|
ekf2 stop |
||||||
|
sensors stop |
||||||
|
|
||||||
|
rgbledsim stop |
||||||
|
tone_alarm stop |
||||||
|
gyrosim stop |
||||||
|
accelsim stop |
||||||
|
barosim stop |
||||||
|
adcsim stop |
||||||
|
gpssim stop |
||||||
|
measairspeedsim stop |
||||||
|
|
||||||
|
dataman stop |
||||||
|
uorb stop |
||||||
|
|
||||||
|
shutdown |
Loading…
Reference in new issue