Skip to content

Commit

Permalink
we have swarms
Browse files Browse the repository at this point in the history
  • Loading branch information
lukvacek committed Mar 31, 2017
1 parent 58d8156 commit fc348ed
Show file tree
Hide file tree
Showing 5 changed files with 166 additions and 2 deletions.
2 changes: 1 addition & 1 deletion Tools/sitl_gazebo
2 changes: 1 addition & 1 deletion launch/posix_sitl.launch
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@
<arg name="Y" default="0"/>

<arg name="est" default="lpe"/>
<arg name="vehicle" default="iris"/>
<arg name="vehicle" default="f450"/>
<arg name="world" default="$(find mavlink_sitl_gazebo)/worlds/empty.world"/>
<arg name="sdf" default="$(find mavlink_sitl_gazebo)/models/$(arg vehicle)/$(arg vehicle).sdf"/>
<arg name="rcS" default="$(find px4)/posix-configs/SITL/init/$(arg est)/$(arg vehicle)"/>
Expand Down
82 changes: 82 additions & 0 deletions launch/posix_sitl_two.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,82 @@
<launch>

<!-- Posix SITL environment launch script -->
<arg name="x" default="0"/>
<arg name="y" default="0"/>
<arg name="z" default="0"/>
<arg name="R" default="0"/>
<arg name="P" default="0"/>
<arg name="Y" default="0"/>

<arg name="x2" default="-1"/>
<arg name="y2" default="-3"/>

<arg name="est" default="lpe"/>
<arg name="vehicle" default="f450"/>
<arg name="vehicle2" default="f450-1"/>
<arg name="world" default="$(find mavlink_sitl_gazebo)/worlds/empty.world"/>
<arg name="sdf" default="$(find mavlink_sitl_gazebo)/models/$(arg vehicle)/$(arg vehicle).sdf"/>
<arg name="sdf2" default="$(find mavlink_sitl_gazebo)/models/$(arg vehicle2)/$(arg vehicle2).sdf"/>
<arg name="rcS" default="$(find px4)/posix-configs/SITL/init/$(arg est)/$(arg vehicle)"/>
<arg name="rcS2" default="$(find px4)/posix-configs/SITL/init/$(arg est)/$(arg vehicle2)"/>

<arg name="headless" default="false"/>
<arg name="gui" default="true"/>
<arg name="ns" default="/"/>

<arg name="debug" default="false"/>
<arg name="verbose" default="false"/>
<arg name="paused" default="false"/>

<arg name="log_output" default="screen" />

<arg name="pluginlists_yaml" value="$(find mavros)/launch/px4_pluginlists.yaml" />
<arg name="config_yaml" value="$(find mavros)/launch/px4_config.yaml" />

<node name="sitl" pkg="px4" type="px4" output="screen"
args="$(find px4) $(arg rcS)">
</node>

<node name="sitl2" pkg="px4" type="px4" output="screen"
args="$(find px4) $(arg rcS2)">
</node>

<include file="$(find gazebo_ros)/launch/empty_world.launch">
<arg name="headless" value="$(arg headless)"/>
<arg name="gui" value="$(arg gui)"/>
<arg name="world_name" value="$(arg world)" />
<arg name="debug" value="$(arg debug)" />
<arg name="verbose" value="$(arg verbose)" />
<arg name="paused" value="$(arg paused)" />
</include>

<node name="$(anon vehicle_spawn)" output="screen" pkg="gazebo_ros" type="spawn_model"
args="-sdf -file $(arg sdf) -model $(arg vehicle) -x $(arg x) -y $(arg y) -z $(arg z) -R $(arg R) -P $(arg P) -Y $(arg Y)"/>-->

<node name="$(anon vehicle_spawn_2)" output="screen" pkg="gazebo_ros" type="spawn_model"
args="-sdf -file $(arg sdf2) -model $(arg vehicle2) -x $(arg x2) -y $(arg y2) -z $(arg z) -R $(arg R) -P $(arg P) -Y $(arg Y)"/>

<node pkg="mavros" type="mavros_node" name="mavros1" required="true" clear_params="true" output="$(arg log_output)">
<param name="fcu_url" value="udp://:14540@localhost:14557"/>
<param name="gcs_url" value="" />
<param name="target_system_id" value="1" />
<param name="target_component_id" value="1" />
<param name="system_id" value="34" />
<rosparam command="load" file="$(arg pluginlists_yaml)" />
<rosparam command="load" file="$(arg config_yaml)" />
</node>

<node pkg="mavros" type="mavros_node" name="mavros2" required="true" clear_params="true" output="$(arg log_output)">
<param name="fcu_url" value="udp://:14640@localhost:14657"/>
<param name="gcs_url" value="" />
<param name="target_system_id" value="2" />
<param name="target_component_id" value="2" />
<param name="system_id" value="48" />
<!-- load blacklist, config -->
<rosparam command="load" file="$(arg pluginlists_yaml)" />
<rosparam command="load" file="$(arg config_yaml)" />
</node>

</launch>

<!-- vim: set et ft=xml fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : -->
2 changes: 2 additions & 0 deletions posix-configs/SITL/init/lpe/f450
Original file line number Diff line number Diff line change
@@ -1,5 +1,7 @@
uorb start
param load
param set MAV_SYS_ID 1
param set MAV_COMP_ID 1
param set MAV_TYPE 2
param set SYS_AUTOSTART 4010
param set SYS_RESTART_TYPE 2
Expand Down
80 changes: 80 additions & 0 deletions posix-configs/SITL/init/lpe/f450-1
Original file line number Diff line number Diff line change
@@ -0,0 +1,80 @@
uorb start
param load
param set MAV_SYS_ID 2
param set MAV_COMP_ID 2
param set MAV_TYPE 2
param set SYS_AUTOSTART 4010
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 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 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
replay tryapplyparams
simulator start -s -u 14660
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/quad_w.main.mix
mavlink start -u 14656 -r 4000000
mavlink start -u 14657 -r 4000000 -m onboard -o 14640
mavlink stream -r 50 -s POSITION_TARGET_LOCAL_NED -u 14656
mavlink stream -r 100 -s LOCAL_POSITION_NED -u 14656
mavlink stream -r 50 -s GLOBAL_POSITION_INT -u 14656
mavlink stream -r 50 -s ATTITUDE -u 14656
mavlink stream -r 50 -s ATTITUDE_QUATERNION -u 14656
mavlink stream -r 50 -s ATTITUDE_TARGET -u 14656
mavlink stream -r 50 -s SERVO_OUTPUT_RAW_0 -u 14656
mavlink stream -r 20 -s RC_CHANNELS -u 14656
mavlink stream -r 50 -s HIGHRES_IMU -u 14656
mavlink stream -r 10 -s OPTICAL_FLOW_RAD -u 14656
logger start -e -t
mavlink boot_complete
replay trystart

0 comments on commit fc348ed

Please sign in to comment.