Browse Source

Change to sitl to allow no board rotation for gazebo. (#5400)

* Change to sitl to allow no board rotation for gazebo.

* Fix typo in typhoon launch file and create config for lpe.

* Exit early on test failures
sbg
James Goppert 9 years ago committed by GitHub
parent
commit
dbc5e90993
  1. 2
      Tools/sitl_gazebo
  2. 4
      integrationtests/run_tests.bash
  3. 2
      posix-configs/SITL/init/ekf2/gazebo_tailsitter
  4. 2
      posix-configs/SITL/init/ekf2/iris
  5. 2
      posix-configs/SITL/init/ekf2/multiple_iris
  6. 2
      posix-configs/SITL/init/ekf2/plane
  7. 2
      posix-configs/SITL/init/ekf2/solo
  8. 2
      posix-configs/SITL/init/ekf2/standard_vtol
  9. 2
      posix-configs/SITL/init/ekf2/typhoon_h480
  10. 2
      posix-configs/SITL/init/inav/iris
  11. 2
      posix-configs/SITL/init/inav/iris_opt_flow
  12. 2
      posix-configs/SITL/init/lpe/iris_opt_flow
  13. 2
      posix-configs/SITL/init/lpe/standard_vtol
  14. 78
      posix-configs/SITL/init/lpe/typhoon_h480

2
Tools/sitl_gazebo

@ -1 +1 @@ @@ -1 +1 @@
Subproject commit 800b12aff9bed3bc145f800184f83c6e9b070a29
Subproject commit 2ae68838fff2fcaf02e95f7d27a0cafae58d9b89

4
integrationtests/run_tests.bash

@ -83,8 +83,8 @@ echo -e "ROS_LOG_DIR\t\t: $ROS_LOG_DIR" @@ -83,8 +83,8 @@ echo -e "ROS_LOG_DIR\t\t: $ROS_LOG_DIR"
echo -e "PX4_LOG_DIR\t\t: $PX4_LOG_DIR"
echo -e "TEST_RESULT_TARGET_DIR\t: $TEST_RESULT_TARGET_DIR"
# don't exit on error anymore from here on (because single tests or exports might fail)
set +e
# Exit on first error as we cannot afford to wait forever
set -e
echo "=====> run tests"
rostest px4 mavros_posix_tests_iris.launch
rostest px4 mavros_posix_tests_standard_vtol.launch

2
posix-configs/SITL/init/ekf2/gazebo_tailsitter

@ -30,7 +30,7 @@ param set MPC_XY_FF 0.1 @@ -30,7 +30,7 @@ param set MPC_XY_FF 0.1
param set MPC_Z_VEL_MAX 1.0
param set MPC_Z_VEL_P 0.8
param set MPC_Z_VEL_I 0.15
param set SENS_BOARD_ROT 8
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

2
posix-configs/SITL/init/ekf2/iris

@ -18,7 +18,7 @@ param set CAL_ACC0_YSCALE 1.01 @@ -18,7 +18,7 @@ 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 SENS_BOARD_ROT 8
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

2
posix-configs/SITL/init/ekf2/multiple_iris

@ -27,7 +27,7 @@ param set MPC_XY_P 0.15 @@ -27,7 +27,7 @@ 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
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

2
posix-configs/SITL/init/ekf2/plane

@ -18,7 +18,7 @@ param set CAL_ACC0_YSCALE 1.01 @@ -18,7 +18,7 @@ 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 SENS_BOARD_ROT 8
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

2
posix-configs/SITL/init/ekf2/solo

@ -18,7 +18,7 @@ param set CAL_ACC0_YSCALE 1.01 @@ -18,7 +18,7 @@ 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 SENS_BOARD_ROT 8
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

2
posix-configs/SITL/init/ekf2/standard_vtol

@ -30,7 +30,7 @@ param set MPC_XY_FF 0.1 @@ -30,7 +30,7 @@ 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 SENS_BOARD_ROT 8
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

2
posix-configs/SITL/init/ekf2/typohoon_h480 → posix-configs/SITL/init/ekf2/typhoon_h480

@ -18,7 +18,7 @@ param set CAL_ACC0_YSCALE 1.01 @@ -18,7 +18,7 @@ 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 SENS_BOARD_ROT 8
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

2
posix-configs/SITL/init/inav/iris

@ -32,7 +32,7 @@ param set MPP_XY_VEL_D 0.01 @@ -32,7 +32,7 @@ param set MPP_XY_VEL_D 0.01
param set MPP_XY_VEL_MAX 2.0
param set MPP_Z_VEL_P 0.3
param set MPP_Z_P 2
param set SENS_BOARD_ROT 8
param set SENS_BOARD_ROT 0
param set SENS_BOARD_X_OFF 0.000001
param set MP_ROLL_P 3
param set MP_ROLLRATE_P 0.3

2
posix-configs/SITL/init/inav/iris_opt_flow

@ -18,7 +18,7 @@ param set CAL_ACC0_YSCALE 1.01 @@ -18,7 +18,7 @@ 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 SENS_BOARD_ROT 8
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

2
posix-configs/SITL/init/lpe/iris_opt_flow

@ -18,7 +18,7 @@ param set CAL_ACC0_YSCALE 1.01 @@ -18,7 +18,7 @@ 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 SENS_BOARD_ROT 8
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

2
posix-configs/SITL/init/lpe/standard_vtol

@ -30,7 +30,7 @@ param set MPC_XY_FF 0.1 @@ -30,7 +30,7 @@ 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 SENS_BOARD_ROT 8
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

78
posix-configs/SITL/init/lpe/typhoon_h480

@ -0,0 +1,78 @@ @@ -0,0 +1,78 @@
uorb start
param load
param set MAV_TYPE 13
param set SYS_AUTOSTART 6001
param set SYS_RESTART_TYPE 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 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 RTL_RETURN_ALT 30.0
param set RTL_DESCEND_ALT 10.0
param set RTL_LAND_DELAY 0
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 MPC_XY_VEL_P 0.15
param set MPC_XY_VEL_I 0.2
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
rgbledsim 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
local_position_estimator start
mc_pos_control start
mc_att_control start
mixer load /dev/pwm_output0 ROMFS/px4fmu_common/mixers/hexa_x.main.mix
mavlink start -u 14556 -r 4000000
mavlink start -u 14557 -r 4000000 -m onboard -o 14540
mavlink stream -r 50 -s POSITION_TARGET_LOCAL_NED -u 14556
mavlink stream -r 50 -s LOCAL_POSITION_NED -u 14556
mavlink stream -r 50 -s GLOBAL_POSITION_INT -u 14556
mavlink stream -r 50 -s ATTITUDE -u 14556
mavlink stream -r 50 -s ATTITUDE_QUATERNION -u 14556
mavlink stream -r 50 -s ATTITUDE_TARGET -u 14556
mavlink stream -r 50 -s SERVO_OUTPUT_RAW_0 -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
sdlog2 start -r 100 -e -t -a
mavlink boot_complete
replay trystart
Loading…
Cancel
Save