]> defiant.homedns.org Git - ros_wild_thumper.git/blob - launch/gazebo.launch
-reenable range layer
[ros_wild_thumper.git] / launch / gazebo.launch
1 <?xml version="1.0"?>
2 <launch>
3         <arg name="use_imu" default="true"/>
4
5         <!-- Load joint controller configurations from YAML file to parameter server -->
6         <rosparam file="$(find wild_thumper)/config/control.yaml" command="load" />
7         <rosparam param="/diff_drive_controller/enable_odom_tf" unless="$(arg use_imu)">true</rosparam>
8
9         <include file="$(find gazebo_ros)/launch/empty_world.launch" >
10                 <arg name="world_name" value="$(find wild_thumper)/worlds/test.world" />
11                 <arg name="gui" value="false" />
12         </include>
13
14         <param name="robot_description" command="$(find xacro)/xacro.py $(find wild_thumper)/urdf/wild_thumper.urdf.xacro"/>
15
16         <node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher" output="screen"/>
17
18         <!-- Spawn a robot into Gazebo -->
19         <node name="spawn_urdf" pkg="gazebo_ros" type="spawn_model" args="-param robot_description -urdf -model wild_thumper" output="screen" />
20
21         <!-- load the controllers -->
22         <node name="controller_spawner" pkg="controller_manager" type="spawner" output="screen" ns="/" args="joint_state_controller diff_drive_controller"/>
23
24         <node name="relay_cmd_vel" pkg="topic_tools" type="relay" output="screen" args="/cmd_vel /diff_drive_controller/cmd_vel" />
25         <node name="relay_odom" pkg="topic_tools" type="relay" output="screen" args="/diff_drive_controller/odom /odom" />
26
27         <node pkg="depthimage_to_laserscan" type="depthimage_to_laserscan" name="depthimage_to_laserscan" output="screen">
28                 <remap from="/image" to="/camera/depth/image_raw"/>
29         </node>
30
31         <node pkg="robot_pose_ekf" type="robot_pose_ekf" name="robot_pose_ekf" output="screen" if="$(arg use_imu)">
32                 <remap from="imu_data" to="imu"/>
33                 <remap from="robot_pose_ekf/odom_combined" to="odom_combined"/>
34                 <param name="output_frame" value="odom"/>
35                 <param name="freq" value="20.0"/>
36                 <param name="vo_used" value="false"/>
37                 <param name="debug" value="true"/>
38                 <param name="sensor_timeout" value="2.0"/>
39         </node>
40 </launch>