ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

rtabmap_ros with Stereo Camera launch file and build a map, not working?

asked 2018-08-03 04:36:17 -0600

Astronaut gravatar image

updated 2018-08-15 04:07:15 -0600

Hi

Im using two point Grey Chameleon3 mono camera set up as Master Salve and synchronized so can work as stereo camera. I have a installed ROS driver and able to publish the camera topics . Im using this ROS driver https://github.com/KumarRobotics/flea3. And

roslaunch flea3 stereo_node.launch left:=13344889 right:=14472242 for stereo camera/

then with

ROS_NAMESPACE=stereo rosrun stereo_image_proc stereo_image_proc

can rectify the stereo image , and can be seen with

rosrun image_view stereo_view stereo:=/stereo image:=image_rect_color

Then tried to use this rtabmap_ros launch file.

<launch>
  <!-- Run the ROS package stereo_image_proc for image rectification and disparity computation -->
  <group ns="stereo">
    <node pkg="stereo_image_proc" type="stereo_image_proc" name="stereo_image_proc"/>

    <!-- Disparity to depth -->
    <node pkg="nodelet" type="nodelet" name="disparity2depth" args="standalone rtabmap_ros/disparity_to_depth"/>
  </group>

 <!-- Rotate the camera frame. -->
  <arg name="pi/2" value="1.5707963267948966" />
  <arg name="optical_rotate" value="0 0 0 -$(arg pi/2) 0 -$(arg pi/2)" />
  <node pkg="tf" type="static_transform_publisher" name="camera_base_link"
  args="$(arg optical_rotate) base_link stereo_camera 100" />  

  <group ns="rtabmap">
    <!-- Visual SLAM -->
    <node name="rtabmap" pkg="rtabmap_ros" type="rtabmap" output="screen" args="--delete_db_on_start">
      <param name="subscribe_depth" type="bool" value="true"/>
      <param name="subscribe_laserScan" type="bool" value="false"/>

      <remap from="rgb/image"       to="/stereo/left/image_rect"/>
      <remap from="rgb/camera_info" to="/stereo/left/camera_info"/>
      <remap from="depth/image"     to="/stereo/depth"/>

      <remap from="odom" to="/stereo_odometer/odometry"/>

      <param name="frame_id" type="string" value="/base_link"/>
      <param name="queue_size" type="int" value="30"/>

      <param name="Rtabmap/TimeThr" type="string" value="700"/>
      <param name="SURF/HessianThreshold" type="string" value="600"/>
      <param name="Vis/MaxDepth" type="string" value="12"/>
      <param name="Vis/MinInliers" type="string" value="10"/>
      <param name="Vis/InlierDistance" type="string" value="0.05"/>
    </node>
  </group>
</launch>

i can not see any map. I got this warnings

[ WARN] [1533288718.609296364]: /rtabmap/rtabmap: Did not receive data since 5 seconds! Make sure the input topics are published ("$ rostopic hz my_topic") and the timestamps in their header are set. If topics are coming from different computers, make sure the clocks of the computers are synchronized ("ntpdate"). If topics are not published at the same rate, you could increase "queue_size" parameter (current=30).
/rtabmap/rtabmap subscribed to (approx sync):
   /stereo_odometer/odometry,
   /stereo/left/image_rect,
   /stereo/depth,
   /stereo/left/camera_info

So, when rostopic hz to each topic rtabmap is subscribed to I got these:

rostopic hz /stereo_camera/right/image_rect
subscribed to [/stereo_camera/right/image_rect]
average rate: 7.658
    min: 0.118s max: 0.156s std dev: 0.01260s window: 7

.......

 rostopic hz  /rtabmap/odom_info
    subscribed to [/rtabmap/odom_info]
    no new messages
    no new messages

.......

rostopic hz  /odom
subscribed to [/odom]
no new messages
no new messages
no new messages

Also I got this warnings now after change the camera name in my ROS driver. It was camera and now is stereo_camera.

[ WARN] [1533529654.855086737]: odometry: Could not get transform from base_link to /stereo_camera/left (stamp=1533529651.500643) after 3.200000 seconds ("wait_for_transform_duration"=3.200000)! Error="canTransform: source_frame stereo_camera/left does not exist.. canTransform returned after 3.21201 timeout was 3 ...
(more)
edit retag flag offensive close merge delete

Comments

Can you do rostopic hz on each topic that rtabmap is subscribed to? You may also want to set approx_sync to false if left, depth and odometry messages have exactly the same stamps (to avoid synchronization issues).

matlabbe gravatar image matlabbe  ( 2018-08-03 15:14:37 -0600 )edit

I edit the comments. Now got different warnings. Is it synchronization problem or? So basically no odometry topic is subscribed. Why?But still no map can show. Im holding the cameras so there is no robot. I just would like to have the map first , so which parameter need to set?

Astronaut gravatar image Astronaut  ( 2018-08-05 23:21:16 -0600 )edit

Show TF tree: $ rosrun tf view_frames. rtabmap won't start if odometry cannot be computed. In your case, odometry is failing because there is a missing TF.

matlabbe gravatar image matlabbe  ( 2018-08-06 15:54:42 -0600 )edit

I run $ rosrun tf view_frames. I edit the comments is missing map->odom->base_link->camera. Is missing map->odom->. Any help?

Astronaut gravatar image Astronaut  ( 2018-08-07 04:42:47 -0600 )edit

Where does camera_link -> base_link coming from? base_link should be the root of the robot, as frame_id is set to it. Your left image topic is publishing under /stereo_camera/left frame, which doesn't exist. For the camera_base_link, you may set base_link /stereo_camera/left instead

matlabbe gravatar image matlabbe  ( 2018-08-07 12:52:56 -0600 )edit

Your launch file <remap from="odom" to="/stereo_odometer/odometry"/>. Are you starting stereo_odometry node from outside this launch file? Check if odom source is publishing correctly.

And as @matlabbe mentioned, camera_link->base_link tf sounds bit confusing. Please check your tf tree is clean.

vinaykumarhs2020 gravatar image vinaykumarhs2020  ( 2018-08-07 14:00:11 -0600 )edit

ok . I change it and edit the comments, The TF tree looks clean now. But I have thee problem still building the map. As I said I dont have the robot , just holding the cameras and would like to build the map while walking with the cameras in my hand

Astronaut gravatar image Astronaut  ( 2018-08-08 03:55:00 -0600 )edit

This tutorial is about hand-held stereo mapping.

matlabbe gravatar image matlabbe  ( 2018-08-08 15:26:40 -0600 )edit

2 Answers

Sort by ยป oldest newest most voted
0

answered 2018-08-15 15:54:52 -0600

matlabbe gravatar image

There is a problem about stereo calibration. Based on the rosbag of the outdoor stereo demo here, the rectified images and disparity images (outputs of stereo_image_proc) should look more like this:

$ rosrun image_view stereo_view stereo:=stereo_camera image:=image_rect_color

image description

Look how dense is the disparity image. The following are the raw images (there are some distortions: lines are not straight like the rectified above) and camera_info used as inputs to stereo_image_proc:

image description

Left camera_info:

header: 
  seq: 844
  stamp: 
    secs: 1415737755
    nsecs: 627326965
  frame_id: stereo_camera
height: 480
width: 640
distortion_model: plumb_bob
D: [-0.344858300062205, 0.131731614744127, -0.00032220157418798, -0.000178643627395838, 0.0]
K: [520.84106910681, 0.0, 320.207922533597, 0.0, 520.652683004955, 251.69140630101, 0.0, 0.0, 1.0]
R: [0.999977409119708, -0.00542294021453702, -0.00397151981806852, 0.00542696944573559, 0.999984769417176, 0.00100445821860056, 0.00396601221263954, -0.00102598884371095, 0.999991609011807]
P: [487.608731712861, 0.0, 318.1162109375, 0.0, 0.0, 487.608731712861, 249.44425201416, 0.0, 0.0, 0.0, 1.0, 0.0]
binning_x: 1
binning_y: 1
roi: 
  x_offset: 0
  y_offset: 0
  height: 480
  width: 640
  do_rectify: False

Right camera_info:

header: 
  seq: 844
  stamp: 
    secs: 1415737755
    nsecs: 627326965
  frame_id: stereo_camera
height: 480
width: 640
distortion_model: plumb_bob
D: [-0.350198880846778, 0.143262162037345, -0.000540958577710845, -0.000386869942974346, 0.0]
K: [525.042672813, 0.0, 315.778978739153, 0.0, 524.605377865008, 246.116481979902, 0.0, 0.0, 1.0]
R: [0.999991166299663, -0.00384047779504094, 0.00170823094047773, 0.00384221006573169, 0.999992106658553, -0.00101194980141688, -0.0017043310860856, 0.0010185042442697, 0.999998028950384]
P: [487.608731712861, 0.0, 318.1162109375, -58.3626989865376, 0.0, 487.608731712861, 249.44425201416, 0.0, 0.0, 0.0, 1.0, 0.0]
binning_x: 1
binning_y: 1
roi: 
  x_offset: 0
  y_offset: 0
  height: 480
  width: 640
  do_rectify: False

I thus recommend to carefully follow the stereo calibration tutorial to get similar results like above with a dense disparity image. Make sure your camera driver publishes the camera_info created from the stereo calibration so that stereo_img_proc can correctly rectify the raw images. Without that dense disparity image, you won't be able to create a 3D map as rtabmap is using the same algorithm (cv::StereoBM) than stereo_img_proc to create the disparity image used to create the clouds.

edit flag offensive delete link more
0

answered 2018-08-07 13:54:02 -0600

vinaykumarhs2020 gravatar image

I have never used Grey Chameleon3 cameras, but I assume that you are using it as a stereo camera. Make sure you check Rtabmap setup for stereo camera for details on how you should setup your nodes. You can either use Stereo-A/Stereo-B methods depending on which works best for your case.

I would follow these steps to debug:

  1. Check for stereo camera output; make sure your camera node is publishing the frames
  2. Ensure that camera frame to base link transform is being published. Make sure the camera topic headers have same frame names.
  3. Check your odometry (stereo/wheel/lidar/fused) output and make sure the rtabmap is subscribing to that topic.

Once the rtabmap ros node is connected to correct camera topics and finds the right transforms, it should start building map (in mapping mode) and publish map->odom transform. You can use rosrun rqt_graph rqt_graph to view your connected topics and rorun tf view_frames to view frames.

edit flag offensive delete link more

Comments

Im using two Grey Chameleon3 monocular Cameras as Master Slave set up so basically its like a stereo camera. Ok will check up set up for stereo camera and how to set up nodes. And Im holding the cameras with my hand while walking around. I edit all changes, But still map is now showing

Astronaut gravatar image Astronaut  ( 2018-08-07 19:52:08 -0600 )edit

Still my map can not be shown. Im not clear how to set up the launch file. The map turn red. is loosing the odometry

Astronaut gravatar image Astronaut  ( 2018-08-13 02:50:44 -0600 )edit

Question Tools

1 follower

Stats

Asked: 2018-08-03 04:36:17 -0600

Seen: 955 times

Last updated: Aug 15 '18