@ -1,5 +1,4 @@
@@ -1,5 +1,4 @@
uorb start
simulator start -s -u _SIMPORT_
param load
param set MAV_TYPE 2
param set SYS_AUTOSTART 4010
@ -19,23 +18,32 @@ param set CAL_ACC0_YSCALE 1.01
@@ -19,23 +18,32 @@ 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.2
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.15
param set MPC_XY_VEL_P 0.05
param set MPC_XY_VEL_D 0.005
param set MPC_XY_FF 0.1
param set SENS_BOARD_ROT 0
param set SENS_BOARD_X_OFF 0.000001
param set COM_RC_IN_MODE 1
param set NAV_DLL_ACT 2
param set COM_DISARM_LAND 3
param set NAV_ACC_RAD 2.0
param set COM_OF_LOSS_T 5
param set COM_OBL_ACT 2
param set COM_OBL_RC_ACT 0
param set RTL_RETURN_ALT 30.0
param set RTL_DESCEND_ALT 10.0
param set RTL_DESCEND_ALT 5.0
param set RTL_LAND_DELAY 5
param set MIS_TAKEOFF_ALT 2.5
param set MC_ROLLRATE_P 0.2
param set MC_PITCHRATE_P 0.2
param set MC_PITCH_P 6
param set MC_ROLL_P 6
param set MPC_HOLD_MAX_Z 2.0
param set MPC_HOLD_XY_DZ 0.1
param set MPC_Z_VEL_P 0.6
param set MPC_Z_VEL_I 0.15
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 -u _SIMPORT_
rgbledsim start
tone_alarm start
gyrosim start
@ -52,14 +60,15 @@ navigator start
@@ -52,14 +60,15 @@ navigator start
ekf2 start
mc_pos_control start
mc_att_control start
mixer load /dev/pwm_output0 quad_w.main.mix
mavlink start -u _MAVPORT_ -r 2000000 -o _MAVOPORT_
mavlink start -u _MAVPORT2_ -r 2000000 -m onboard -o _MAVOPORT2_
mavlink stream -r 80 -s POSITION_TARGET_LOCAL_NED -u _MAVPORT_
mavlink stream -r 80 -s LOCAL_POSITION_NED -u _MAVPORT_
mavlink stream -r 80 -s GLOBAL_POSITION_INT -u _MAVPORT_
mavlink stream -r 80 -s ATTITUDE -u _MAVPORT_
mavlink stream -r 80 -s ATTITUDE_TARGET -u _MAVPORT_
mixer load /dev/pwm_output0 ROMFS/px4fmu_common/mixers/quad_w.main.mix
mavlink start -u _MAVPORT_ -r 4000000 -o _MAVOPORT_
mavlink start -u _MAVPORT2_ -r 4000000 -m onboard -o _MAVOPORT2_
mavlink stream -r 50 -s POSITION_TARGET_LOCAL_NED -u _MAVPORT_
mavlink stream -r 50 -s LOCAL_POSITION_NED -u _MAVPORT_
mavlink stream -r 50 -s GLOBAL_POSITION_INT -u _MAVPORT_
mavlink stream -r 50 -s ATTITUDE -u _MAVPORT_
mavlink stream -r 50 -s ATTITUDE_QUATERNION -u _MAVPORT_
mavlink stream -r 50 -s ATTITUDE_TARGET -u _MAVPORT_
mavlink stream -r 20 -s RC_CHANNELS -u _MAVPORT_
mavlink stream -r 250 -s HIGHRES_IMU -u _MAVPORT_
mavlink stream -r 10 -s OPTICAL_FLOW_RAD -u _MAVPORT_