4 changed files with 95 additions and 1 deletions
@ -0,0 +1,23 @@ |
|||||||
|
<launch> |
||||||
|
|
||||||
|
<arg name="headless" default="false"/> |
||||||
|
<arg name="gui" default="true"/> |
||||||
|
<arg name="enable_logging" default="false"/> |
||||||
|
<arg name="enable_ground_truth" default="true"/> |
||||||
|
<arg name="ns" default="iris"/> |
||||||
|
<arg name="log_file" default="$(arg ns)"/> |
||||||
|
<arg name="mavlink_bridge_url" default="udp://localhost:14553@localhost:14560" /> |
||||||
|
|
||||||
|
<include file="$(find rotors_gazebo)/launch/iris_empty_world.launch"> |
||||||
|
<arg name="headless" value="$(arg headless)"/> |
||||||
|
<arg name="gui" value="$(arg gui)"/> |
||||||
|
<arg name="enable_logging" value="$(arg enable_logging)" /> |
||||||
|
<arg name="enable_ground_truth" value="$(arg enable_ground_truth)" /> |
||||||
|
<arg name="log_file" value="$(arg log_file)"/> |
||||||
|
</include> |
||||||
|
<include file="$(find mavros)/launch/mavlink_bridge.launch"> |
||||||
|
<arg name="mavlink_bridge_url" value="$(arg mavlink_bridge_url)" /> |
||||||
|
<arg name="ns" value="$(arg ns)"/> |
||||||
|
</include> |
||||||
|
|
||||||
|
</launch> |
@ -0,0 +1,69 @@ |
|||||||
|
uorb start |
||||||
|
simulator start -s |
||||||
|
param load |
||||||
|
param set MAV_TYPE 2 |
||||||
|
param set MC_PITCHRATE_P 0.15 |
||||||
|
param set MC_ROLLRATE_P 0.15 |
||||||
|
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 |
||||||
|
param set COM_RC_IN_MODE 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 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 MPP_XY_P 1.0 |
||||||
|
param set MPP_XY_FF 0.0 |
||||||
|
param set MPP_XY_VEL_P 0.01 |
||||||
|
param set MPP_XY_VEL_I 0.0 |
||||||
|
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 MP_ROLL_P 3 |
||||||
|
param set MP_ROLLRATE_P 0.3 |
||||||
|
param set MP_ROLLRATE_I 0.001 |
||||||
|
param set MP_ROLLRATE_D 0.001 |
||||||
|
param set MP_PITCH_P 4 |
||||||
|
param set MP_PITCHRATE_P 0.3 |
||||||
|
rgbled start |
||||||
|
tone_alarm start |
||||||
|
gyrosim start |
||||||
|
accelsim start |
||||||
|
barosim start |
||||||
|
adcsim start |
||||||
|
gpssim start |
||||||
|
hil mode_pwm |
||||||
|
commander start |
||||||
|
sensors start |
||||||
|
land_detector start multicopter |
||||||
|
navigator start |
||||||
|
attitude_estimator_q start |
||||||
|
position_estimator_inav start |
||||||
|
mc_pos_control_m start |
||||||
|
mc_att_control_m start |
||||||
|
mixer load /dev/pwm_output0 ../../ROMFS/px4fmu_common/mixers/quad_x.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 -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 |
||||||
|
|
Loading…
Reference in new issue