3 <!-- Load joint controller configurations from YAML file to parameter server -->
4 <rosparam file="$(find wild_thumper)/config/control.yaml" command="load" />
6 <include file="$(find gazebo_ros)/launch/empty_world.launch" >
7 <arg name="world_name" value="$(find wild_thumper)/worlds/test.world" />
8 <arg name="gui" value="false" />
11 <param name="robot_description" command="$(find xacro)/xacro.py $(find wild_thumper)/urdf/wild_thumper.urdf.xacro"/>
13 <node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher" output="screen"/>
15 <!-- Spawn a robot into Gazebo -->
16 <node name="spawn_urdf" pkg="gazebo_ros" type="spawn_model" args="-param robot_description -urdf -model wild_thumper" output="screen" />
18 <!-- load the controllers -->
19 <node name="controller_spawner" pkg="controller_manager" type="spawner" output="screen" ns="/" args="joint_state_controller diff_drive_controller"/>
21 <node name="relay_cmd_vel" pkg="topic_tools" type="relay" output="screen" args="/cmd_vel /diff_drive_controller/cmd_vel" />
22 <node name="relay_odom" pkg="topic_tools" type="relay" output="screen" args="/diff_drive_controller/odom /odom" />
24 <node pkg="depthimage_to_laserscan" type="depthimage_to_laserscan" name="depthimage_to_laserscan" output="screen">
25 <remap from="/image" to="/camera/depth/image_raw"/>
28 <node pkg="robot_pose_ekf" type="robot_pose_ekf" name="robot_pose_ekf" output="screen">
29 <remap from="imu_data" to="imu"/>
30 <remap from="robot_pose_ekf/odom_combined" to="odom_combined"/>
31 <param name="output_frame" value="odom"/>
32 <param name="freq" value="20.0"/>
33 <param name="vo_used" value="false"/>
34 <param name="debug" value="true"/>
35 <param name="sensor_timeout" value="2.0"/>