Auto navigation example

classic Classic list List threaded Threaded
4 messages Options
Reply | Threaded
Open this post in threaded view
|

Auto navigation example

Jacky Liu
This post was updated on .
Currently I could build up 2D and 3D map by the following command:
1
2
3
4
roslaunch kinect2_bridge kinect2_bridge.launch publish_tf:=true 
roslaunch rtabmap_ros rgbd_mapping.launch rtabmap_args:="--delete_db_on_start" rviz:=true rtabmapviz:=false 
rosrun tf static_transform_publisher 0 0 0 -1.5707963267948966 0 -1.5707963267948966 camera_link kinect2_link 100 
roslaunch rtabmap_ros rgbd_mapping.launch rtabmap_args:="--delete_db_on_start" rgb_topic:=/kinect2/qhd/image_color_rect depth_registered_topic:=/kinect2/qhd/image_depth_rect camera_info_topic:=/kinect2/qhd/camera_info 

However, when I click the "2D Nav Goal" nothing happend(no planning path appear).

Did I missed something?
(My final goal is to use Kinectv2+turtlebot2 to do auto navigation. Right now I can only do SLAM.)
Reply | Threaded
Open this post in threaded view
|

Re: Auto navigation example

matlabbe
Administrator
Hi,

move_base is not started. As you are using a turtlebot, look at this tutorial (you may have to change turtlebot configuration files to use kinectv2 instead of default kinect or XTION):
http://wiki.ros.org/rtabmap_ros/Tutorials/MappingAndNavigationOnTurtlebot

You may also want to try official turtlebot tutorials before trying with rtabmap:
http://wiki.ros.org/turtlebot_navigation/Tutorials/indigo/Build%20a%20map%20with%20SLAM

cheers,
Mathieu
Reply | Threaded
Open this post in threaded view
|

Re: Auto navigation example

Jacky Liu
This post was updated on .
matlabbe Thanks for your reply.

After I started the move_base node by the launch file in turtlebot_navigation,
and the kobuki node nothing change.

1
2
3
4
5
6
7
roslaunch kinect2_bridge kinect2_bridge.launch publish_tf:=true 
roslaunch rtabmap_ros rgbd_mapping.launch rtabmap_args:="--delete_db_on_start" rviz:=true rtabmapviz:=false 
rosrun tf static_transform_publisher 0 0 0 -1.5707963267948966 0 -1.5707963267948966 camera_link kinect2_link 100 
roslaunch rtabmap_ros rgbd_mapping.launch rtabmap_args:="--delete_db_on_start" rgb_topic:=/kinect2/qhd/image_color_rect depth_registered_topic:=/kinect2/qhd/image_depth_rect camera_info_topic:=/kinect2/qhd/camera_info

roslaunch turtlebot_navigation move_base.launch
roslaunch kobuki_node minimal.launch 

/opt/ros/kinetic/share/turtlebot_navigation/launch/includes/move_base.launch.xml

 1
 2
 3
 4
 5
 6
 7
 8
 9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
<launch>
  <include file="$(find turtlebot_navigation)/launch/includes/velocity_smoother.launch.xml"/>
  <include file="$(find turtlebot_navigation)/launch/includes/safety_controller.launch.xml"/>
  
  <arg name="odom_frame_id"   default="odom"/>
  <arg name="base_frame_id"   default="base_footprint"/>
  <arg name="global_frame_id" default="map"/>
  <arg name="odom_topic" default="odom" />
  <arg name="laser_topic" default="scan" />
  <arg name="custom_param_file" default="$(find turtlebot_navigation)/param/dummy.yaml"/>

  <node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
    <rosparam file="$(find turtlebot_navigation)/param/costmap_common_params.yaml" command="load" ns="global_costmap" />
    <rosparam file="$(find turtlebot_navigation)/param/costmap_common_params.yaml" command="load" ns="local_costmap" />   
    <rosparam file="$(find turtlebot_navigation)/param/local_costmap_params.yaml" command="load" />   
    <rosparam file="$(find turtlebot_navigation)/param/global_costmap_params.yaml" command="load" />
    <rosparam file="$(find turtlebot_navigation)/param/dwa_local_planner_params.yaml" command="load" />
    <rosparam file="$(find turtlebot_navigation)/param/move_base_params.yaml" command="load" />
    <rosparam file="$(find turtlebot_navigation)/param/global_planner_params.yaml" command="load" />
    <rosparam file="$(find turtlebot_navigation)/param/navfn_global_planner_params.yaml" command="load" />
    <!-- external params file that could be loaded into the move_base namespace -->
    <rosparam file="$(arg custom_param_file)" command="load" />
    
    <!-- reset frame_id parameters using user input data -->
    <param name="global_costmap/global_frame" value="$(arg global_frame_id)"/>
    <param name="global_costmap/robot_base_frame" value="$(arg base_frame_id)"/>
    <param name="local_costmap/global_frame" value="$(arg odom_frame_id)"/>
    <param name="local_costmap/robot_base_frame" value="$(arg base_frame_id)"/>
    <param name="DWAPlannerROS/global_frame_id" value="$(arg odom_frame_id)"/>

    <remap from="cmd_vel" to="navigation_velocity_smoother/raw_cmd_vel"/>
    <remap from="odom" to="$(arg odom_topic)"/>
    <remap from="scan" to="$(arg laser_topic)"/>
  </node>
</launch>
Reply | Threaded
Open this post in threaded view
|

Re: Auto navigation example

matlabbe
Administrator
Hi,

I am not aware on how exactly all turtlebot launch files are configured, but you would have to remap the /rtabmap/grid_map topic to /map to be connected to move_base (see top schema on this tutorial). The frame_id is not the same between rtabmap and move_base (it should be base_footprint). You should not start rgbd_mapping.launch twice. Here is a combined example:

roslaunch kinect2_bridge kinect2_bridge.launch publish_tf:=true 
# Adjust height of the camera
rosrun tf static_transform_publisher 0 0 0 -1.5707963267948966 0 -1.5707963267948966 base_footprint kinect2_link 100 
roslaunch rtabmap_ros rgbd_mapping.launch rtabmap_args:="--delete_db_on_start" frame_id:=base_footprint rgb_topic:=/kinect2/qhd/image_color_rect depth_registered_topic:=/kinect2/qhd/image_depth_rect camera_info_topic:=/kinect2/qhd/camera_info rviz:=true rtabmapviz:=false 

roslaunch turtlebot_navigation move_base.launch
roslaunch kobuki_node minimal.launch 

<launch>
  <include file="$(find turtlebot_navigation)/launch/includes/velocity_smoother.launch.xml"/>
  <include file="$(find turtlebot_navigation)/launch/includes/safety_controller.launch.xml"/>
  
  <arg name="odom_frame_id"   default="odom"/>
  <arg name="base_frame_id"   default="base_footprint"/>
  <arg name="global_frame_id" default="map"/>
  <arg name="odom_topic" default="odom" />
  <arg name="laser_topic" default="scan" />
  <arg name="custom_param_file" default="$(find turtlebot_navigation)/param/dummy.yaml"/>

  <!-- remap /map to /rtabmap/map -->
  <remap from="map" to="/rtabmap/grid_map"/> 

  <node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
    <rosparam file="$(find turtlebot_navigation)/param/costmap_common_params.yaml" command="load" ns="global_costmap" />
    <rosparam file="$(find turtlebot_navigation)/param/costmap_common_params.yaml" command="load" ns="local_costmap" />   
    <rosparam file="$(find turtlebot_navigation)/param/local_costmap_params.yaml" command="load" />   
    <rosparam file="$(find turtlebot_navigation)/param/global_costmap_params.yaml" command="load" />
    <rosparam file="$(find turtlebot_navigation)/param/dwa_local_planner_params.yaml" command="load" />
    <rosparam file="$(find turtlebot_navigation)/param/move_base_params.yaml" command="load" />
    <rosparam file="$(find turtlebot_navigation)/param/global_planner_params.yaml" command="load" />
    <rosparam file="$(find turtlebot_navigation)/param/navfn_global_planner_params.yaml" command="load" />
    <!-- external params file that could be loaded into the move_base namespace -->
    <rosparam file="$(arg custom_param_file)" command="load" />
    
    <!-- reset frame_id parameters using user input data -->
    <param name="global_costmap/global_frame" value="$(arg global_frame_id)"/>
    <param name="global_costmap/robot_base_frame" value="$(arg base_frame_id)"/>
    <param name="local_costmap/global_frame" value="$(arg odom_frame_id)"/>
    <param name="local_costmap/robot_base_frame" value="$(arg base_frame_id)"/>
    <param name="DWAPlannerROS/global_frame_id" value="$(arg odom_frame_id)"/>

    <remap from="cmd_vel" to="navigation_velocity_smoother/raw_cmd_vel"/>
    <remap from="odom" to="$(arg odom_topic)"/>
    <remap from="scan" to="$(arg laser_topic)"/>
  </node>
</launch>

It is strange that kinect2 topics are not connected to rtabmap in your graph and that rgbd_odometry is missing, make sure you are able to map before trying integrate move_base. Is this basic tutorial working? http://wiki.ros.org/rtabmap_ros/Tutorials/HandHeldMapping

cheers,
Mathieu