ROS navigation with Asus xtion pro live (no transform from error)
Ubuntu : 14.04 LTS Trusty tahr (on desktop PC, laptop) ROS : Indigo Robot : Turtlebot
Hello, I'm doing an navigation with asus xtion pro live on turtlebot. I successfully made a map (SLAM), but I have a problem when I do navigation using the map. At, /home/catkin_ws/src folder, I downloaded packages for SLAM, Navigation from here: and because this packages stand for LRF (not xtion), so I fix some codes. here are my fixed codes:
kobuki_navigation.launch
<launch>
<!-- kobuki model -->
<arg name="urdf_file" default="$(find xacro)/xacro.py '$(find kobuki_description)/urdf/kobuki_standalone.urdf.xacro'" />
<param name="robot_description" command="$(arg urdf_file)" />
<node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher" output="screen">
<param name="publish_frequency" type="double" value="5.0" />
</node>
<!-- kobuki control option
<include file="$(find kobuki_navigation)/launch/velocity_smoother.launch.xml"/>
<include file="$(find kobuki_navigation)/launch/safety_controller.launch.xml"/>
-->
<!-- sensor -->
<node pkg="depthimage_to_laserscan" type="depthimage_to_laserscan" name="kobuki_d2l_node" output="screen">
<remap from="output_frame_id" to="/base_scan"/>
<remap from="image" to="/camera/depth/image_raw" />
</node>
<!-- tf -->
<node pkg="kobuki_tf" type="kobuki_tf" name="kobuki_tf" output="screen">
</node>
<!-- Map server -->
<arg name="map_file" default="$(find kobuki_navigation)/maps/map.yaml"/>
<node name="map_server" pkg="map_server" type="map_server" args="$(arg map_file)">
</node>
<!-- AMCL -->
<include file="$(find kobuki_navigation)/launch/amcl.launch.xml"/>
<!-- move_base -->
<arg name="cmd_vel_topic" default="/mobile_base/commands/velocity" />
<arg name="odom_topic" default="odom" />
<node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
<rosparam file="$(find kobuki_navigation)/param/costmap_common_params.yaml" command="load" ns="global_costmap" />
<rosparam file="$(find kobuki_navigation)/param/costmap_common_params.yaml" command="load" ns="local_costmap" />
<rosparam file="$(find kobuki_navigation)/param/local_costmap_params.yaml" command="load" />
<rosparam file="$(find kobuki_navigation)/param/global_costmap_params.yaml" command="load" />
<rosparam file="$(find kobuki_navigation)/param/dwa_local_planner_params.yaml" command="load" />
<rosparam file="$(find kobuki_navigation)/param/move_base_params.yaml" command="load" />
<remap from="cmd_vel" to="$(arg cmd_vel_topic)"/>
<remap from="odom" to="$(arg odom_topic)"/>
</node>
</launch>
kobuki_navigation_base.launch
<launch>
<!-- kobuki model -->
<arg name="urdf_file" default="$(find xacro)/xacro.py '$(find kobuki_description)/urdf/kobuki_standalone.urdf.xacro'" />
<param name="robot_description" command="$(arg urdf_file)" />
<node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher" output="screen">
<param name="publish_frequency" type="double" value="5.0" />
</node>
<!-- kobuki control option
<include file="$(find kobuki_navigation)/launch/velocity_smoother.launch.xml"/>
<include file="$(find kobuki_navigation)/launch/safety_controller.launch.xml"/>
-->
<!-- sensor -->
<node pkg="depthimage_to_laserscan" type="depthimage_to_laserscan" name="kobuki_d2l_node" output="screen">
<remap from="output_frame_id" to="/base_scan"/>
<remap from="image" to="/camera/depth/image_raw" />
</node>
<!-- tf -->
<node pkg="kobuki_tf" type="kobuki_tf" name="kobuki_tf" output="screen">
</node>
<!-- Map server -->
<arg name="map_file" default="$(find kobuki_navigation)/maps/map.yaml"/>
<node name="map_server" pkg="map_server" type="map_server" args="$(arg map_file)">
</node>
<!-- AMCL -->
<include file="$(find kobuki_navigation)/launch/amcl.launch.xml"/>
<!-- move_base -->
<arg name="cmd_vel_topic" default="/mobile_base/commands/velocity" />
<arg name="odom_topic" default="odom" />
<node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
<rosparam file="$(find kobuki_navigation)/param/costmap_common_params.yaml" command="load" ns="global_costmap" />
<rosparam file="$(find kobuki_navigation)/param/costmap_common_params.yaml" command="load" ns="local_costmap" />
<rosparam file="$(find kobuki_navigation)/param/local_costmap_params.yaml" command="load" />
<rosparam file="$(find kobuki_navigation)/param/global_costmap_params.yaml" command="load" />
<rosparam file="$(find kobuki_navigation)/param/base_local_planner_params.yaml" command="load ...