Browse Source

Update LPE sitl init script.

sbg
James Goppert 9 years ago
parent
commit
759b107468
  1. 18
      posix-configs/SITL/init/rcS_lpe_jmavsim_iris

18
posix-configs/SITL/init/rcS_lpe_jmavsim_iris

@ -3,8 +3,10 @@ simulator start -s @@ -3,8 +3,10 @@ simulator start -s
param load
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
param set MC_YAW_P 2.0
param set MC_YAW_P 2.8
param set MC_YAWRATE_P 0.35
param set SYS_AUTOSTART 4010
param set SYS_RESTART_TYPE 2
@ -26,12 +28,22 @@ param set MPC_XY_P 0.4 @@ -26,12 +28,22 @@ 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
param set COM_RC_IN_MODE 1
param set NAV_ACC_RAD 2.0
param set RTL_RETURN_ALT 30.0
param set RTL_DESCEND_ALT 10.0
param set MIS_TAKEOFF_ALT 5.0
param set MPC_HOLD_MAX_Z 2.0
param set MPC_HOLD_XY_DZ 0.1
param set MPC_HOLD_Z_DZ 0.1
param set MPC_Z_VEL_MAX 2.0
param set MPC_Z_VEL_P 0.4
# changes for LPE
param set COM_RC_IN_MODE 1
param set LPE_BETA_MAX 10000
rgbled start
rgbledsim start
tone_alarm start
gyrosim start
accelsim start
@ -49,6 +61,7 @@ mc_pos_control start @@ -49,6 +61,7 @@ mc_pos_control start
mc_att_control start
mixer load /dev/pwm_output0 ../../../../ROMFS/px4fmu_common/mixers/quad_x.main.mix
mavlink start -u 14556 -r 2000000
mavlink start -u 14557 -r 2000000 -m onboard
mavlink stream -r 80 -s POSITION_TARGET_LOCAL_NED -u 14556
mavlink stream -r 80 -s LOCAL_POSITION_NED_COV -u 14556
mavlink stream -r 80 -s GLOBAL_POSITION_INT -u 14556
@ -57,6 +70,7 @@ mavlink stream -r 80 -s ATTITUDE_TARGET -u 14556 @@ -57,6 +70,7 @@ 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
mavlink stream -r 20 -s MANUAL_CONTROL -u 14556
mavlink boot_complete
sdlog2 start -r 100 -e -t -a

Loading…
Cancel
Save