Remap camera_depth_frame to xtion_depth_frame.

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

Remap camera_depth_frame to xtion_depth_frame.

job28
rtabmap_no_laser.launch
Hi team,

I am trying to map with rtabmap with Tiago simulation in Gazebo. Everything set up as per this. But get the error

[ WARN] [1528439154.574399840, 1043.382000000]: Could not get transform from base_link to camera_depth_frame after 0.200000 seconds (for stamp=1043.153000)! Error="canTransform: source_frame camera_depth_frame does not exist.. canTransform returned after 0.2 timeout was 0.2.".
[ERROR] [1528439154.574530127, 1043.382000000]: Could not convert laser scan msg! Aborting rtabmap update...

I can't find a way to remap the camera_depth_frame to xtion_depth_frame. My launch file looks like this.

<launch>
    <node pkg="depthimage_to_laserscan" type="depthimage_to_laserscan" name="depthimage_to_laserscan">
      <remap from="image" to="/xtion/depth_registered/image_raw"/>
      <remap from="camera_info" to="/xtion/depth_registered/camera_info"/>
      <remap from="scan" to="/rtabmap/xtion_scan"/>
     
    </node>
  <group ns="rtabmap">
    <node name="rtabmap" pkg="rtabmap_ros" type="rtabmap" output="screen" args="--delete_db_on_start">
         
         
         
          <remap from="odom" to="/mobile_base_controller/odom"/>
          <remap from="scan" to="xtion_scan"/>
          <remap from="rgb/image" to="/xtion/rgb/image_rect_color"/>
          <remap from="depth/image" to="/xtion/depth_registered/image_raw"/>
          <remap from="rgb/camera_info" to="/xtion/rgb/camera_info"/>
         
         
         
         
         
         
           
         
         
         
         
         
         
         
    </node>
  </group>
</launch>

i would really appreciate some help!

EDIT: UPLOADED THE LAUNCH FILE AS 'PARAM' TAGS WERE NOT SHOWING UP.
Reply | Threaded
Open this post in threaded view
|

Re: Remap camera_depth_frame to xtion_depth_frame.

kolohe113
Have you fix the issue? I am having a similar problem.
Reply | Threaded
Open this post in threaded view
|

Re: Remap camera_depth_frame to xtion_depth_frame.

job28
No. Still waiting for a reply. Could anyone pls point me in the right direction
Reply | Threaded
Open this post in threaded view
|

Re: Remap camera_depth_frame to xtion_depth_frame.

matlabbe
Administrator
Hi,

for
I can't find a way to remap the camera_depth_frame to xtion_depth_frame.
camera_depth_frame is the frame in image topic messages (sensor_msgs:Image/header/frame_id). What your TF tree looks like?
$ rosrun tf view_frames
$ evince frames.pdf
Is there a missing static_transform_publisher to link your camera frames to robot base frame (base_link)?

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

Re: Remap camera_depth_frame to xtion_depth_frame.

job28
Thanks for the reply, This is what i get when i
$ rostopic echo /xtion/rgb/image_raw
header: 
  seq: 6407
  stamp: 
    secs: 215
    nsecs: 883000000
  frame_id: "xtion_rgb_optical_frame"
height: 480
width: 640
encoding: "bgr8"
is_bigendian: 0
step: 1920
data: [......]
I dont think there is a missing transform, its just that the frame has a different name not `camera_depth_frame` and I dont know how to remap. Frames.pdf attached. frames.pdf Thanks.
Reply | Threaded
Open this post in threaded view
|

Re: Remap camera_depth_frame to xtion_depth_frame.

matlabbe
Administrator
camera_depth_frame should be set in one header of these topics:

<remap from="rgb/image" to="/xtion/rgb/image_rect_color"/>
<remap from="depth/image" to="/xtion/depth_registered/image_raw"/>
<remap from="rgb/camera_info" to="/xtion/rgb/camera_info"/>

Reply | Threaded
Open this post in threaded view
|

Re: Remap camera_depth_frame to xtion_depth_frame.

job28
Hi,
All those topics have `frame_id: "xtion_rgb_optical_frame"`. Should I launch a static_transform_publisher from base link to camera_depth_frame keeping the values same as base link to xtion_rgb_optical_frame (or tf_remap)?

Thanks.
Reply | Threaded
Open this post in threaded view
|

Re: Remap camera_depth_frame to xtion_depth_frame.

matlabbe
Administrator
camera_depth_frame is not hard coded, it is coming from one of the topic. Can you use rqt_console to track down which node is logging the warning message?
Reply | Threaded
Open this post in threaded view
|

Re: Remap camera_depth_frame to xtion_depth_frame.

matlabbe
Administrator
Just found where that frame is coming from: http://wiki.ros.org/depthimage_to_laserscan

Set explicitly output_frame_id to same frame of the input image topic.
Reply | Threaded
Open this post in threaded view
|

Re: Remap camera_depth_frame to xtion_depth_frame.

job28
Oh cool. That solved it! Thanks a bunch. Will report back after further tests.
Reply | Threaded
Open this post in threaded view
|

Re: Remap camera_depth_frame to xtion_depth_frame.

job28
In reply to this post by matlabbe
Mapped successfully! Leaving my launch file for future reference. Thanks @matlabbe

<div style="background: #ffffff; overflow:auto;width:auto;border:solid gray;border-width:.1em .1em .1em .8em;padding:.2em .6em;"><pre style="margin: 0; line-height: 125%"><launch>
  <arg name="database_path"     default="~/.ros/rtabmap.db"/>
  <arg name="rtabmapviz"        default="false"/>
  <arg name="rviz"              default="false"/>
  <arg name="localization"      default="false"/>
  <arg if="$(arg localization)" name="args"  default=""/>
  <arg unless="$(arg localization)" name="args"  default="--delete_db_on_start"/>
  <arg name="wait_for_transform"  default="0.2"/>

  <arg name="rgb_topic"   default="/xtion/rgb/image_rect_color"/>
  <arg name="depth_topic" default="/xtion/depth_registered/image_raw"/>
  <arg name="camera_info_topic" default="/xtion/rgb/camera_info"/>
  <arg name="depth_camera_info_topic" default="/xtion/depth_registered/camera_info"/>
  <arg name="scan_topic" default="/xtion_scan"/>
  <arg name="odom_topic" default="/mobile_base_controller/odom"/>
  <arg name="fixed_frame" default="base_link"/>

  <!-- xtion cloud to laser scan -->
  <node pkg="depthimage_to_laserscan" type="depthimage_to_laserscan" name="depthimage_to_laserscan">
    <remap from="image" to="$(arg depth_topic)"/>
    <remap from="camera_info" to="$(arg depth_camera_info_topic)"/>
    <remap from="scan" to="$(arg scan_topic)"/>
    <param name="range_max" type="double" value="4"/>
    <param name="output_frame_id" type="str" value="xtion_rgb_frame"/>
  </node>

  <!-- SLAM -->
  <group ns="rtabmap">
    <node name="rtabmap" pkg="rtabmap_ros" type="rtabmap" output="screen" args="$(arg args)">
        <remap from="odom" to="$(arg odom_topic)"/>
        <remap from="scan" to="$(arg scan_topic)"/>
        <remap from="rgb/image" to="$(arg rgb_topic)"/>
        <remap from="depth/image" to="$(arg depth_topic)"/>
        <remap from="rgb/camera_info" to="$(arg camera_info_topic)"/>
        <remap from="grid_map" to="/map"/>

        <!-- RTAB-Map's parameters -->
        <param name="queue_size" type="int" value="10"/>
        <param name="database_path"                 type="string" value="$(arg database_path)"/>
        <param name="wait_for_transform"            type="bool" value="true"/>
        <param name="wait_for_transform_duration"   type="double"   value="$(arg wait_for_transform)"/>
        <param name="frame_id"                      type="string" value="$(arg fixed_frame)"/>
        <param name="subscribe_depth"               type="bool" value="true"/>
        <param name="subscribe_scan"                type="bool" value="true"/>

        <!-- RTAB-Map's parameters: do "rosrun rtabmap rtabmap (double-dash)params" to see the list of available parameters. -->
        <param name="RGBD/NeighborLinkRefining" type="string" value="true"/>  <!-- Do odometry correction with consecutive laser scans -->
        <param name="RGBD/ProximityBySpace"     type="string" value="true"/>  <!-- Local loop closure detection (using estimated position) with locations in WM -->
        <param name="RGBD/ProximityByTime"      type="string" value="false"/> <!-- Local loop closure detection with locations in STM -->
        <param name="RGBD/ProximityPathMaxNeighbors" type="string" value="10"/> <!-- Do also proximity detection by space by merging close scans together. -->
        <param name="Reg/Strategy"              type="string" value="1"/>     <!-- 0=Visual, 1=ICP, 2=Visual+ICP -->
        <param name="Vis/InlierDistance"        type="string" value="0.1"/>   <!-- 3D visual words correspondence distance -->
        <param name="RGBD/OptimizeFromGraphEnd" type="string" value="false"/> <!-- Optimize graph from initial node so /map -> /odom transform will be generated -->
        <param name="RGBD/OptimizeMaxError"     type="string" value="2.0"/>        <!-- Reject any loop closure causing large errors (>2x link's covariance) in the map -->
        <param name="Reg/Force3DoF"             type="string" value="true"/>  <!-- 2D SLAM -->
        <param name="Grid/FromDepth"            type="string" value="false"/> <!-- Create 2D occupancy grid from laser scan -->
        <param name="Mem/STMSize"               type="string" value="30"/>    <!-- increased to 30 to avoid adding too many loop closures on just seen locations -->
        <param name="RGBD/LocalRadius"          type="string" value="5"/>     <!-- limit length of proximity detections -->
        <!-- localization mode -->
        <param if="$(arg localization)" name="Mem/IncrementalMemory" type="string" value="false"/>
        <param unless="$(arg localization)" name="Mem/IncrementalMemory" type="string" value="true"/>
        <param name="Mem/InitWMWithAllNodes" type="string" value="$(arg localization)"/>
    </node>
  </group>
</launch>
</pre></div>