<launch>
- <arg name="paused" default="false"/>
+ <arg name="paused" default="true"/>
<arg name="headless" default="false"/>
<arg name="use_sim_time" default="true"/>
<arg name="wam" default="false"/>
- <arg name="world" default ="/home/gabriel/Navega/src/twil/twil_description/world/centenario.world"/>
+ <arg name="world" default ="$(find twil_description)/world/centenario.world"/>
<arg name="controller" default="twist_mrac_linearizing_controller"/>
<arg name="config" default="$(find twil_bringup)/config/$(arg controller).yaml"/>
</include>
<include file="$(find twil_bringup)/launch/$(arg controller).launch" />
-
<node pkg="tf2_ros" type="static_transform_publisher" name="odom_frame_publisher" args="0 0 0 0 0 0 1 map odom" />
- <node name="robot_state_publisher" pkg="robot_state_publisher" type="state_publisher" />
+ <node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" />
- <node name="rviz" pkg="rviz" type="rviz" args="-d $(find twil_bringup)/rviz/gazebo_rviz.rviz" required="true"/>
+ <node name="rviz" pkg="rviz" type="rviz" args="-d $(find twil_2dnav)/rviz/twil_2dnav.rviz" required="true"/>
- <node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" />
+ <include file="$(find twil_2dnav)/launch/move_base.launch" />
</launch>
<launch>
+ <node name="map_server" pkg="map_server" type="map_server" args="$(find twil_2dnav)/map/centenario1.yaml"/>
- <master auto="start"/>
- <!-- Run the map server -->
- <node name="map_server" pkg="map_server" type="map_server" args="$(find twil_2dnav)/map/map.yaml"/>
-
- <!--- Run AMCL -->
- <!--include file="$(find amcl)/examples/amcl_omni.launch" /-->
-
- <node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
- <rosparam file="$(find twil_2dnav)/config/costmap_common_params.yaml" command="load" ns="global_costmap" />
- <rosparam file="$(find twil_2dnav)/config/costmap_common_params.yaml" command="load" ns="local_costmap" />
- <rosparam file="$(find twil_2dnav)/config/local_costmap_params.yaml" command="load" />
- <rosparam file="$(find twil_2dnav)/config/global_costmap_params.yaml" command="load" />
- <rosparam file="$(find twil_2dnav)/config/base_local_planner_params.yaml" command="load" />
-
- </node>
+ <!--include file="$(find amcl)/examples/amcl_omni.launch" /-->
+ <node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
+ <rosparam file="$(find twil_2dnav)/config/costmap_common_params.yaml" command="load" ns="global_costmap" />
+ <rosparam file="$(find twil_2dnav)/config/costmap_common_params.yaml" command="load" ns="local_costmap" />
+ <rosparam file="$(find twil_2dnav)/config/local_costmap_params.yaml" command="load" />
+ <rosparam file="$(find twil_2dnav)/config/global_costmap_params.yaml" command="load" />
+ <rosparam file="$(find twil_2dnav)/config/base_local_planner_params.yaml" command="load" />
+ </node>
</launch>