From 4241e526aac9fad483949ce6b7cf03597acbd9b6 Mon Sep 17 00:00:00 2001 From: jgoppert Date: Mon, 26 Oct 2015 16:03:22 -0400 Subject: [PATCH] Updated sitl scripts for LPE. --- Tools/sitl_run.sh | 2 +- posix-configs/SITL/init/rcS_lpe_gazebo | 66 +++++++++++++++++++ .../SITL/init/{rcS_lpe => rcS_lpe_jmavsim} | 0 3 files changed, 67 insertions(+), 1 deletion(-) create mode 100644 posix-configs/SITL/init/rcS_lpe_gazebo rename posix-configs/SITL/init/{rcS_lpe => rcS_lpe_jmavsim} (100%) diff --git a/Tools/sitl_run.sh b/Tools/sitl_run.sh index fff0080ca9..6eb69eb46b 100755 --- a/Tools/sitl_run.sh +++ b/Tools/sitl_run.sh @@ -38,7 +38,7 @@ then cd Tools/jMAVSim ant java -Djava.ext.dirs= -cp lib/*:out/production/jmavsim.jar me.drton.jmavsim.Simulator -udp 127.0.0.1:14560 & - SIM_PID=echo $! + SIM_PID=`echo $!` elif [ "$3" == "gazebo" ] then if [ -x "$(command -v gazebo)" ] diff --git a/posix-configs/SITL/init/rcS_lpe_gazebo b/posix-configs/SITL/init/rcS_lpe_gazebo new file mode 100644 index 0000000000..6093991c13 --- /dev/null +++ b/posix-configs/SITL/init/rcS_lpe_gazebo @@ -0,0 +1,66 @@ +uorb start +simulator start -s +param load +param set MAV_TYPE 2 +param set MC_PITCHRATE_P 0.3 +param set MC_ROLLRATE_P 0.3 +param set MC_YAW_P 2.0 +param set MC_YAWRATE_P 0.35 +param set SYS_AUTOSTART 4010 +param set SYS_RESTART_TYPE 2 +dataman start +param set CAL_GYRO0_ID 2293760 +param set CAL_ACC0_ID 1376256 +param set CAL_ACC1_ID 1310720 +param set CAL_MAG0_ID 196608 +param set CAL_GYRO0_XOFF 0.01 +param set CAL_ACC0_XOFF 1 +param set CAL_ACC0_YOFF 2 +param set CAL_ACC0_ZOFF 3 +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.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 8 + +# changes for LPE +param set COM_RC_IN_MODE 1 +param set LPE_BETA_MAX 10000 + +rgbled start +tone_alarm start +gyrosim start +accelsim start +barosim start +adcsim start +gpssim start +pwm_out_sim mode_pwm +sleep 1 +sensors start +commander start +land_detector start multicopter +navigator start +attitude_estimator_q start +mc_pos_control start +mc_att_control start +mixer load /dev/pwm_output0 ../../../../ROMFS/px4fmu_common/mixers/quad_w.main.mix +mavlink start -u 14556 -r 2000000 +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 +mavlink stream -r 80 -s ATTITUDE -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 +mavlink boot_complete +sdlog2 start -r 100 -e -t -a + +# start LPE at end, when we know it is ok to init sensors +sleep 5 +local_position_estimator start diff --git a/posix-configs/SITL/init/rcS_lpe b/posix-configs/SITL/init/rcS_lpe_jmavsim similarity index 100% rename from posix-configs/SITL/init/rcS_lpe rename to posix-configs/SITL/init/rcS_lpe_jmavsim