Files
bizhang_-obav/posix-configs/SITL/init/rcS_jmavsim_iris

75 lines
2.1 KiB
Plaintext
Raw Normal View History

uorb start
2015-06-14 03:17:33 -07:00
param load
2015-06-19 10:44:36 -07:00
param set MAV_TYPE 2
param set MC_PITCHRATE_P 0.15
param set MC_PITCH_P 7
param set MC_ROLL_P 7
param set MC_ROLLRATE_P 0.15
2015-12-01 12:42:57 +01:00
param set MC_YAW_P 2.8
2015-07-02 00:04:06 -07:00
param set MC_YAWRATE_P 0.35
param set SYS_AUTOSTART 4010
param set SYS_RESTART_TYPE 2
2015-06-18 14:24:35 -07:00
dataman start
2015-11-22 15:56:01 +01:00
param set CAL_GYRO0_ID 2293768
param set CAL_ACC0_ID 1376264
param set CAL_ACC1_ID 1310728
param set CAL_MAG0_ID 196616
2015-06-19 10:44:36 -07:00
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 MPC_XY_P 0.4
param set MPC_XY_VEL_P 0.2
param set MPC_XY_VEL_D 0.005
param set SENS_BOARD_ROT 0
2016-03-11 16:42:07 +01:00
param set SENS_BOARD_X_OFF 0.000001
2015-12-01 20:46:51 +01:00
param set COM_RC_IN_MODE 1
param set COM_DL_LOSS_EN 1
2016-04-08 22:15:37 -07:00
param set COM_DISARM_LAND 3
param set NAV_ACC_RAD 2.0
param set RTL_RETURN_ALT 30.0
param set RTL_DESCEND_ALT 10.0
2016-04-08 22:36:07 -07:00
param set RTL_LAND_DELAY 0
param set MIS_TAKEOFF_ALT 2.5
param set MPC_HOLD_MAX_Z 2.0
param set MPC_HOLD_XY_DZ 0.1
param set MPC_Z_VEL_MAX 2.0
param set MPC_Z_VEL_P 0.4
simulator start -s
rgbledsim start
tone_alarm start
gyrosim start
accelsim start
barosim start
adcsim start
gpssim start
pwm_out_sim mode_pwm
sleep 1
sensors start
2015-09-04 19:58:23 +02:00
commander start
2015-06-26 15:01:53 +02:00
land_detector start multicopter
2015-06-26 00:40:02 +02:00
navigator start
2016-01-25 22:42:53 +01:00
ekf2 start
mc_pos_control start
mc_att_control start
2015-09-20 16:41:34 +02:00
mixer load /dev/pwm_output0 ../../../../ROMFS/px4fmu_common/mixers/quad_x.main.mix
mavlink start -u 14556 -r 2000000 -t 127.0.0.1
mavlink start -u 14557 -r 2000000 -m onboard -o 14540 -t 127.0.0.1
2015-07-09 00:49:40 +02:00
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
2016-04-06 11:16:14 -07:00
mavlink stream -r 80 -s ATTITUDE_QUATERNION -u 14556
2015-07-09 00:49:40 +02:00
mavlink stream -r 80 -s ATTITUDE_TARGET -u 14556
mavlink stream -r 20 -s RC_CHANNELS -u 14556
2015-07-23 18:54:58 +02:00
mavlink stream -r 250 -s HIGHRES_IMU -u 14556
mavlink stream -r 10 -s OPTICAL_FLOW_RAD -u 14556
mavlink stream -r 20 -s MANUAL_CONTROL -u 14556
2015-08-01 16:58:02 +02:00
mavlink boot_complete
2015-09-03 09:47:14 +02:00
sdlog2 start -r 100 -e -t -a