Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Value of queue_size in L515 + T265 #570

Closed
sumitsarkar1 opened this issue Apr 13, 2021 · 16 comments
Closed

Value of queue_size in L515 + T265 #570

sumitsarkar1 opened this issue Apr 13, 2021 · 16 comments

Comments

@sumitsarkar1
Copy link

sumitsarkar1 commented Apr 13, 2021

  1. Ubuntu 18 with ROS Melodic
  2. librealsense and rtabmap and rtabmap_ros build from source
  3. Using T265 with L515 rtabmap_ros stops abruptly after some time
  4. When queue_size is 10 (default value) it stops early..like after 30 seconds to 40 seconds...for larger values like 200 it continues (I did not check how long it continues)..however in that case pause button does not stop the streaming which I guess is not the live streaming but the already recorded data due to large buffer (I may be wrong in this assumption)
  5. Is this T265 +L515 dependent on queue_size which is little difficult to believe because with stand alone RTabMap L515 and T265 works flawlessly for long hours
  6. I followed RTABMAP stopping with L515 and T265 #555 , #574 and #1078
  7. The rtabmap_ros gets abruptly paused...no new map is build in the gui and in the terminal its just some update info lines shows up and then suddenly no update info line starts appearing
    [ INFO] [1618329073.723286023]: rtabmap (27): Rate=1.00s, Limit=0.000s, Conversion=0.0009s, RTAB-Map=0.0878s, Maps update=0.0015s pub=0.0000s (local map=21, WM=21)
  8. The topics are still alive . I have checked it with rviz and rostopic hz and have constant update rates ...the same when the L515 and T265 are launched
  9. L515 alone works fine with visual odometry from its RGB cam. It doesnt hang up due to some queue_size issue
  10. Again , with stand alone RTabMap T265 + L515 works flawless. I just have a remote application to implement for which I need to stream the topics over wireless and do the mapping at a remote compute centre
  11. Following are my launch files . Please suggest if I am missing something

L515 + T265

<launch>
  <arg name="device_type_t265"    		default="t265"/>
  <arg name="device_type_l515"    		default="l515"/>
  <arg name="device_type_d435"    		default="d4.5"/>
  
  <arg name="serial_no_t265"    			default="2322110234"/>
  <arg name="serial_no_l515"    			default="f0231832"/>
  <arg name="serial_no_d435"    			default=""/>
  
  <arg name="t265_ns"              			default="t265"/>
  <arg name="l515_ns"              			default="l515"/>
  <arg name="d435_ns"              			default="d435"/>

  <arg name="tf_prefix_t265"         default="$(arg t265_ns)"/>
  <arg name="tf_prefix_l515"         default="$(arg l515_ns)"/>
  <arg name="tf_prefix_d435"         default="$(arg d435_ns)"/>

  <arg name="initial_reset"             default="false"/>
  <arg name="enable_fisheye"            default="false"/>

  <arg name="color_width"               default="960"/>
  <arg name="color_height"              default="540"/>
  <arg name="depth_width"               default="640"/>
  <arg name="depth_height"              default="480"/>
  <arg name="ordered_pc"                default="false"/>
  <arg name="clip_distance"             default="-2"/>
  <arg name="topic_odom_in"             default="odom_in"/>
  <arg name="calib_odom_file"           default=""/>


  <param name="/t265/realsense2_camera/frames_queue_size" type="int" value="30"/>
  <param name="/t265/realsense2_camera/enable_relocalization" type="bool" value="false"/>
  <group ns="$(arg t265_ns)">
    <include file="$(find realsense2_camera)/launch/includes/nodelet.launch.xml">
      <arg name="device_type"           value="$(arg device_type_t265)"/>
      <arg name="serial_no"             value="$(arg serial_no_t265)"/>
      <arg name="tf_prefix"         	  value="$(arg tf_prefix_t265)"/>
      <arg name="initial_reset"         value="$(arg initial_reset)"/>
      <arg name="enable_fisheye1"       value="$(arg enable_fisheye)"/>
      <arg name="enable_fisheye2"       value="$(arg enable_fisheye)"/>
      <arg name="topic_odom_in"         value="$(arg topic_odom_in)"/>
      <arg name="calib_odom_file"       value="$(arg calib_odom_file)"/>
      <arg name="enable_pose"           value="true"/>
      <arg name="unite_imu_method"	value="linear_interpolation"/>
	
      <!-- <arg name="ordered_pc"            value="$(arg ordered_pc)"/> -->
    </include>
  </group>
  
  <!-- Launch L515 through nodeler -->
  <group ns="$(arg l515_ns)">
    <include file="$(find realsense2_camera)/launch/includes/nodelet.launch.xml">
      <arg name="device_type"           value="$(arg device_type_l515)"/>
      <arg name="serial_no"             value="$(arg serial_no_l515)"/>
      <arg name="tf_prefix"		          value="$(arg tf_prefix_l515)"/>
      <arg name="initial_reset"         value="$(arg initial_reset)"/>
      <arg name="align_depth"           value="true"/>
      <arg name="filters"               value="pointcloud"/>
      <arg name="color_width"           value="$(arg color_width)"/>
      <arg name="color_height"          value="$(arg color_height)"/>
      <arg name="depth_width"           value="$(arg depth_width)"/>
      <arg name="depth_height"          value="$(arg depth_height)"/>
      <arg name="clip_distance"         value="$(arg clip_distance)"/>
      <arg name="ordered_pc"            value="$(arg ordered_pc)"/>
    </include>
  </group>
      <!-- <arg name="enable_infra"          default="true"/> -->

  <!-- <group ns="$(arg d435_ns)">
    <include file="$(find realsense2_camera)/launch/includes/nodelet.launch.xml">
      <arg name="device_type"           value="$(arg device_type_d435)"/>
      <arg name="serial_no"             value="$(arg serial_no_d435)"/>
      <arg name="tf_prefix"		          value="$(arg tf_prefix_d435)"/>
      <arg name="initial_reset"         value="$(arg initial_reset)"/>
      <arg name="align_depth"           value="true"/>
      <arg name="filters"               value="pointcloud"/>
      <arg name="color_width"           value="$(arg color_width)"/>
      <arg name="color_height"          value="$(arg color_height)"/>
      <arg name="depth_width"           value="$(arg depth_width)"/>
      <arg name="depth_height"          value="$(arg depth_height)"/>
      <arg name="clip_distance"         value="$(arg clip_distance)"/>
      <arg name="ordered_pc"            value="$(arg ordered_pc)"/>
    </include>
  </group> -->

  <!-- CAMERA ALIGNMENT -->
  <node pkg="tf" type="static_transform_publisher" name="t265_to_d435" args="0.009 -0.02 0.030 0 0 0 /$(arg tf_prefix_t265)_link /$(arg tf_prefix_d435)_link 100"/>
  <node pkg="tf" type="static_transform_publisher" name="t265_to_l515" args="0 0.085 0.015 0 0 0 /t265_link /l515_link 100"/>
</launch>

For RTabMap_ros

<!-- -->
<launch>
  <!-- Convenience launch file to launch odometry, rtabmap and rtabmapviz nodes at once -->

  <!-- For stereo:=false
        Your RGB-D sensor should be already started with "depth_registration:=true".
        Examples:
           $ roslaunch freenect_launch freenect.launch depth_registration:=true 
           $ roslaunch openni2_launch openni2.launch depth_registration:=true -->
           
  <!-- For stereo:=true
        Your camera should be calibrated and publishing rectified left and right 
        images + corresponding camera_info msgs. You can use stereo_image_proc for image rectification.
        Example:
           $ roslaunch rtabmap_ros bumblebee.launch -->
     
  <!-- Choose between depth and stereo, set both to false to do only scan -->      
  <arg name="stereo"                    default="false"/>
  <arg     if="$(arg stereo)" name="depth"  default="false"/>
  <arg unless="$(arg stereo)" name="depth"  default="true"/>
 
  <!-- Choose visualization -->
  <arg name="rtabmapviz"              default="true" /> 
  <arg name="rviz"                    default="false" />
  
  <!-- Localization-only mode -->
  <arg name="localization"            default="false"/>
  
  <!-- sim time for convenience, if playing a rosbag -->
  <arg name="use_sim_time"            default="false"/>
  <param if="$(arg use_sim_time)" name="use_sim_time" value="true"/>
  
  <!-- Corresponding config files -->
  <arg name="cfg"                     default="" /> <!-- To change RTAB-Map's parameters, set the path of config file (*.ini) generated by the standalone app -->
  <arg name="gui_cfg"                 default="~/.ros/rtabmap_gui.ini" />
  <arg name="rviz_cfg"                default="$(find rtabmap_ros)/launch/config/rgbd.rviz" />
  
  <arg name="frame_id"                default="camera_link"/>     <!-- Fixed frame id, you may set "base_link" or "base_footprint" if they are published -->
  <arg name="odom_frame_id"           default=""/>                <!-- If set, TF is used to get odometry instead of the topic -->
  <arg name="map_frame_id"            default="map"/>
  <arg name="ground_truth_frame_id"   default=""/>     <!-- e.g., "world" -->
  <arg name="ground_truth_base_frame_id" default=""/>  <!-- e.g., "tracker", a fake frame matching the frame "frame_id" (but on different TF tree) -->
  <arg name="namespace"               default="rtabmap"/>
  <arg name="database_path"           default="~/.ros/rtabmap.db"/>
  <arg name="queue_size"              default="10"/>
  <arg name="wait_for_transform"      default="0.2"/>
  <arg name="args"                    default=""/>              <!-- delete_db_on_start, udebug -->
  <arg name="rtabmap_args"            default="$(arg args)"/>   <!-- deprecated, use "args" argument -->
  <arg name="gdb"                     default="false"/>         <!-- Launch nodes in gdb for debugging (apt install xterm gdb) -->
  <arg     if="$(arg gdb)" name="launch_prefix" default="xterm -e gdb -q -ex run --args"/>
  <arg unless="$(arg gdb)" name="launch_prefix" default=""/>
  <arg name="output"                  default="screen"/>        <!-- Control node output (screen or log) -->
  <arg name="publish_tf_map"          default="true"/>

  <!-- if timestamps of the input topics are synchronized using approximate or exact time policy-->
  <arg     if="$(arg stereo)" name="approx_sync"  default="false"/>
  <arg unless="$(arg stereo)" name="approx_sync"  default="$(arg depth)"/>         
   
  <!-- RGB-D related topics -->
  <arg name="rgb_topic"               default="/camera/rgb/image_rect_color" />
  <arg name="depth_topic"             default="/camera/depth_registered/image_raw" />
  <arg name="camera_info_topic"       default="/camera/rgb/camera_info" />
  <arg name="depth_camera_info_topic" default="$(arg camera_info_topic)" />
  
  <!-- stereo related topics -->
  <arg name="stereo_namespace"        default="/stereo_camera"/>
  <arg name="left_image_topic"        default="$(arg stereo_namespace)/left/image_rect_color" />
  <arg name="right_image_topic"       default="$(arg stereo_namespace)/right/image_rect" />      <!-- using grayscale image for efficiency -->
  <arg name="left_camera_info_topic"  default="$(arg stereo_namespace)/left/camera_info" />
  <arg name="right_camera_info_topic" default="$(arg stereo_namespace)/right/camera_info" />
  
  <!-- Already synchronized RGB-D related topic, with rtabmap_ros/rgbd_sync nodelet -->
  <arg name="rgbd_sync"               default="false"/>         <!-- pre-sync rgb_topic, depth_topic, camera_info_topic -->
  <arg name="approx_rgbd_sync"        default="true"/>          <!-- false=exact synchronization -->
  <arg name="subscribe_rgbd"          default="$(arg rgbd_sync)"/>
  <arg name="rgbd_topic"              default="rgbd_image" />
  <arg name="depth_scale"             default="1.0" />         <!-- Deprecated, use rgbd_depth_scale instead -->
  <arg name="rgbd_depth_scale"        default="$(arg depth_scale)" />
  <arg name="rgbd_decimation"         default="1" />
  
  <arg name="compressed"              default="false"/>         <!-- If you want to subscribe to compressed image topics -->
  <arg name="rgb_image_transport"     default="compressed"/>    <!-- Common types: compressed, theora (see "rosrun image_transport list_transports") -->
  <arg name="depth_image_transport"   default="compressedDepth"/>  <!-- Depth compatible types: compressedDepth (see "rosrun image_transport list_transports") -->
   
  <arg name="subscribe_scan"          default="false"/>
  <arg name="scan_topic"              default="/scan"/>
  <arg name="subscribe_scan_cloud"    default="false"/>
  <arg name="scan_cloud_topic"        default="/scan_cloud"/>
  <arg name="subscribe_scan_descriptor" default="false"/>
  <arg name="scan_descriptor_topic"   default="/scan_descriptor"/>
  <arg name="scan_cloud_max_points"   default="0"/>
  <arg name="scan_cloud_filtered"     default="false"/> <!-- use filtered cloud from icp_odometry for mapping -->
  <arg name="gen_scan"                default="false"/> <!-- only works with depth image and if not subscribing to scan topic-->
   
  <arg name="visual_odometry"          default="true"/>          <!-- Launch rtabmap visual odometry node -->
  <arg name="icp_odometry"             default="false"/>         <!-- Launch rtabmap icp odometry node -->
  <arg name="odom_topic"               default="odom"/>          <!-- Odometry topic name -->
  <arg name="vo_frame_id"              default="$(arg odom_topic)"/> <!-- Visual/Icp odometry frame ID for TF -->
  <arg name="publish_tf_odom"          default="true"/>
  <arg name="odom_tf_angular_variance" default="1"/>             <!-- If TF is used to get odometry, this is the default angular variance -->
  <arg name="odom_tf_linear_variance"  default="1"/>             <!-- If TF is used to get odometry, this is the default linear variance -->
  <arg name="odom_args"                default=""/>              <!-- More arguments for odometry (overwrite same parameters in rtabmap_args) -->
  <arg name="odom_sensor_sync"         default="false"/>
  <arg name="odom_guess_frame_id"        default=""/>
  <arg name="odom_guess_min_translation" default="0"/>
  <arg name="odom_guess_min_rotation"    default="0"/>
  <arg name="odom_max_rate"            default="0"/>
  <arg name="odom_expected_rate"       default="0"/>
  <arg name="imu_topic"                default="/imu/data"/>          <!-- only used with VIO approaches -->
  <arg name="wait_imu_to_init"         default="false"/>
  <arg name="use_odom_features"        default="false"/>
  
  <arg name="scan_cloud_assembling"              default="false"/>
  <arg name="scan_cloud_assembling_time"         default="1"/>
  <arg name="scan_cloud_assembling_fixed_frame"  default=""/>
  <arg name="scan_cloud_assembling_voxel_size"   default="0.05"/>
  <arg name="scan_cloud_assembling_noise_radius"   default="0.0"/>    <!-- 0=disabled -->
  <arg name="scan_cloud_assembling_noise_min_neighbors"   default="5"/>
  
  <arg name="subscribe_user_data"      default="false"/>             <!-- user data synchronized subscription -->
  <arg name="user_data_topic"          default="/user_data"/>
  <arg name="user_data_async_topic"    default="/user_data_async" /> <!-- user data async subscription (rate should be lower than map update rate) -->
  
  <arg name="gps_topic"                default="/gps/fix" />         <!-- gps async subscription -->
  
  <arg name="tag_topic"                default="/tag_detections" />  <!-- apriltags async subscription -->
  <arg name="tag_linear_variance"      default="0.0001" />
  <arg name="tag_angular_variance"     default="9999" />             <!-- >=9999 means ignore rotation in optimization, when rotation estimation of the tag is not reliable -->
  
  <!-- These arguments should not be modified directly, see referred topics without "_relay" suffix above -->
  <arg if="$(arg compressed)"     name="rgb_topic_relay"           default="$(arg rgb_topic)_relay"/>
  <arg unless="$(arg compressed)" name="rgb_topic_relay"           default="$(arg rgb_topic)"/>
  <arg if="$(arg compressed)"     name="depth_topic_relay"         default="$(arg depth_topic)_relay"/>
  <arg unless="$(arg compressed)" name="depth_topic_relay"         default="$(arg depth_topic)"/>
  <arg if="$(arg compressed)"     name="left_image_topic_relay"    default="$(arg left_image_topic)_relay"/>
  <arg unless="$(arg compressed)" name="left_image_topic_relay"    default="$(arg left_image_topic)"/>
  <arg if="$(arg compressed)"     name="right_image_topic_relay"   default="$(arg right_image_topic)_relay"/>
  <arg unless="$(arg compressed)" name="right_image_topic_relay"   default="$(arg right_image_topic)"/>
  <arg if="$(arg rgbd_sync)"      name="rgbd_topic_relay"          default="$(arg rgbd_topic)"/>
  <arg unless="$(arg rgbd_sync)"  name="rgbd_topic_relay"          default="$(arg rgbd_topic)_relay"/>

  <!-- Nodes -->
  <group ns="$(arg namespace)">
     
    <!-- relays -->
    <group if="$(arg depth)">
      <group unless="$(arg subscribe_rgbd)">
        <node if="$(arg compressed)" name="republish_rgb" type="republish" pkg="image_transport" args="$(arg rgb_image_transport) in:=$(arg rgb_topic) raw out:=$(arg rgb_topic_relay)" />
        <node if="$(arg compressed)" name="republish_depth" type="republish" pkg="image_transport" args="$(arg depth_image_transport) in:=$(arg depth_topic) raw out:=$(arg depth_topic_relay)" />
      </group>
      <group if="$(arg rgbd_sync)">
        <node if="$(arg compressed)" name="republish_rgb" type="republish" pkg="image_transport" args="$(arg rgb_image_transport) in:=$(arg rgb_topic) raw out:=$(arg rgb_topic_relay)" />
        <node if="$(arg compressed)" name="republish_depth" type="republish" pkg="image_transport" args="$(arg depth_image_transport) in:=$(arg depth_topic) raw out:=$(arg depth_topic_relay)" />
        <node pkg="nodelet" type="nodelet" name="rgbd_sync" args="standalone rtabmap_ros/rgbd_sync" output="$(arg output)">
          <remap from="rgb/image"       to="$(arg rgb_topic_relay)"/>
          <remap from="depth/image"     to="$(arg depth_topic_relay)"/>
          <remap from="rgb/camera_info" to="$(arg camera_info_topic)"/>
          <remap from="rgbd_image"      to="$(arg rgbd_topic_relay)"/>
          <param name="approx_sync"     type="bool"   value="$(arg approx_rgbd_sync)"/>
          <param name="queue_size"      type="int"    value="$(arg queue_size)"/>
          <param name="depth_scale"     type="double" value="$(arg rgbd_depth_scale)"/>
          <param name="decimation"     type="double" value="$(arg rgbd_decimation)"/>
        </node>
      </group>
    </group>
    <group if="$(arg stereo)">
      <group unless="$(arg subscribe_rgbd)">
        <node if="$(arg compressed)" name="republish_left"  type="republish" pkg="image_transport" args="$(arg rgb_image_transport) in:=$(arg left_image_topic) raw out:=$(arg left_image_topic_relay)" />
        <node if="$(arg compressed)" name="republish_right" type="republish" pkg="image_transport" args="$(arg rgb_image_transport) in:=$(arg right_image_topic) raw out:=$(arg right_image_topic_relay)" />
      </group>
      <group if="$(arg rgbd_sync)">
        <node if="$(arg compressed)" name="republish_left"  type="republish" pkg="image_transport" args="$(arg rgb_image_transport) in:=$(arg left_image_topic) raw out:=$(arg left_image_topic_relay)" />
        <node if="$(arg compressed)" name="republish_right" type="republish" pkg="image_transport" args="$(arg rgb_image_transport) in:=$(arg right_image_topic) raw out:=$(arg right_image_topic_relay)" />
        <node pkg="nodelet" type="nodelet" name="stereo_sync" args="standalone rtabmap_ros/stereo_sync" output="$(arg output)">
          <remap from="left/image_rect"   to="$(arg left_image_topic_relay)"/>
          <remap from="right/image_rect"  to="$(arg right_image_topic_relay)"/>
          <remap from="left/camera_info"  to="$(arg left_camera_info_topic)"/>
          <remap from="right/camera_info" to="$(arg right_camera_info_topic)"/>
          <remap from="rgbd_image"      to="$(arg rgbd_topic_relay)"/>
          <param name="approx_sync"     type="bool"   value="$(arg approx_rgbd_sync)"/>
          <param name="queue_size"      type="int"    value="$(arg queue_size)"/>
        </node>
      </group>
    </group>
    
    <group unless="$(arg rgbd_sync)">
       <group if="$(arg subscribe_rgbd)">
         <node name="republish_rgbd_image"  type="rgbd_relay" pkg="rtabmap_ros">
           <remap     if="$(arg compressed)" from="rgbd_image" to="$(arg rgbd_topic)/compressed"/>
           <remap     if="$(arg compressed)" from="$(arg rgbd_topic)/compressed_relay" to="$(arg rgbd_topic_relay)"/>
           <remap unless="$(arg compressed)" from="rgbd_image" to="$(arg rgbd_topic)"/>
           <param if="$(arg compressed)" name="uncompress" value="true"/>
         </node>
      </group>
    </group>

    <!-- Visual odometry -->
    <group unless="$(arg icp_odometry)">
      <group if="$(arg visual_odometry)">
      
        <!-- RGB-D Odometry -->
        <node unless="$(arg stereo)" pkg="rtabmap_ros" type="rgbd_odometry" name="rgbd_odometry" output="$(arg output)" args="$(arg rtabmap_args) $(arg odom_args)" launch-prefix="$(arg launch_prefix)">
          <remap from="rgb/image"       to="$(arg rgb_topic_relay)"/>
          <remap from="depth/image"     to="$(arg depth_topic_relay)"/>
          <remap from="rgb/camera_info" to="$(arg camera_info_topic)"/>
          <remap from="rgbd_image"      to="$(arg rgbd_topic_relay)"/>
          <remap from="odom"            to="$(arg odom_topic)"/>
          <remap from="imu"             to="$(arg imu_topic)"/>
      
          <param name="frame_id"                    type="string" value="$(arg frame_id)"/>
          <param name="odom_frame_id"               type="string" value="$(arg vo_frame_id)"/>
          <param name="publish_tf"                  type="bool"   value="$(arg publish_tf_odom)"/>
          <param name="ground_truth_frame_id"       type="string" value="$(arg ground_truth_frame_id)"/>
          <param name="ground_truth_base_frame_id"  type="string" value="$(arg ground_truth_base_frame_id)"/>
          <param name="wait_for_transform_duration" type="double" value="$(arg wait_for_transform)"/>
          <param name="wait_imu_to_init"            type="bool"   value="$(arg wait_imu_to_init)"/>
          <param name="approx_sync"                 type="bool"   value="$(arg approx_sync)"/>
          <param name="config_path"                 type="string" value="$(arg cfg)"/>
          <param name="queue_size"                  type="int"    value="$(arg queue_size)"/>
          <param name="subscribe_rgbd"              type="bool"   value="$(arg subscribe_rgbd)"/>
          <param name="guess_frame_id"              type="string" value="$(arg odom_guess_frame_id)"/>
          <param name="guess_min_translation"       type="double" value="$(arg odom_guess_min_translation)"/>
          <param name="guess_min_rotation"          type="double" value="$(arg odom_guess_min_rotation)"/>
          <param name="expected_update_rate"        type="double" value="$(arg odom_expected_rate)"/>
          <param name="max_update_rate"             type="double" value="$(arg odom_max_rate)"/>
          <param name="keep_color"                  type="bool"   value="$(arg use_odom_features)"/>
        </node>

        <!-- Stereo Odometry -->
        <node if="$(arg stereo)" pkg="rtabmap_ros" type="stereo_odometry" name="stereo_odometry" output="$(arg output)" args="$(arg rtabmap_args) $(arg odom_args)" launch-prefix="$(arg launch_prefix)">
          <remap from="left/image_rect"        to="$(arg left_image_topic_relay)"/>
          <remap from="right/image_rect"       to="$(arg right_image_topic_relay)"/>
          <remap from="left/camera_info"       to="$(arg left_camera_info_topic)"/>
          <remap from="right/camera_info"      to="$(arg right_camera_info_topic)"/>
          <remap from="rgbd_image"             to="$(arg rgbd_topic_relay)"/>
          <remap from="odom"                   to="$(arg odom_topic)"/>
          <remap from="imu"                    to="$(arg imu_topic)"/>
      
          <param name="frame_id"                    type="string" value="$(arg frame_id)"/>
          <param name="odom_frame_id"               type="string" value="$(arg vo_frame_id)"/>
          <param name="publish_tf"                  type="bool"   value="$(arg publish_tf_odom)"/>
          <param name="ground_truth_frame_id"       type="string" value="$(arg ground_truth_frame_id)"/>
          <param name="ground_truth_base_frame_id"  type="string" value="$(arg ground_truth_base_frame_id)"/>
          <param name="wait_for_transform_duration" type="double" value="$(arg wait_for_transform)"/>
          <param name="wait_imu_to_init"            type="bool"   value="$(arg wait_imu_to_init)"/>
          <param name="approx_sync"                 type="bool"   value="$(arg approx_sync)"/>
          <param name="config_path"                 type="string" value="$(arg cfg)"/>
          <param name="queue_size"                  type="int"    value="$(arg queue_size)"/>
          <param name="subscribe_rgbd"              type="bool"   value="$(arg subscribe_rgbd)"/>
          <param name="guess_frame_id"              type="string" value="$(arg odom_guess_frame_id)"/>
          <param name="guess_min_translation"       type="double" value="$(arg odom_guess_min_translation)"/>
          <param name="guess_min_rotation"          type="double" value="$(arg odom_guess_min_rotation)"/>
          <param name="expected_update_rate"        type="double" value="$(arg odom_expected_rate)"/>
          <param name="max_update_rate"             type="double" value="$(arg odom_max_rate)"/>
          <param name="keep_color"                  type="bool"   value="$(arg use_odom_features)"/>
        </node>
      </group>
    </group>
    
    <!-- ICP Odometry -->
    <node if="$(arg icp_odometry)" pkg="rtabmap_ros" type="icp_odometry" name="icp_odometry" output="$(arg output)" args="$(arg rtabmap_args) $(arg odom_args)" launch-prefix="$(arg launch_prefix)">
      <remap from="scan"                   to="$(arg scan_topic)"/>
      <remap from="scan_cloud"             to="$(arg scan_cloud_topic)"/>
      <remap from="odom"                   to="$(arg odom_topic)"/>
      <remap from="imu"                    to="$(arg imu_topic)"/>
      
      <param name="frame_id"                    type="string" value="$(arg frame_id)"/>
      <param name="odom_frame_id"               type="string" value="$(arg vo_frame_id)"/>
      <param name="publish_tf"                  type="bool"   value="$(arg publish_tf_odom)"/>
      <param name="ground_truth_frame_id"       type="string" value="$(arg ground_truth_frame_id)"/>
      <param name="ground_truth_base_frame_id"  type="string" value="$(arg ground_truth_base_frame_id)"/>
      <param name="wait_for_transform_duration" type="double" value="$(arg wait_for_transform)"/>
      <param name="wait_imu_to_init"            type="bool"   value="$(arg wait_imu_to_init)"/>
      <param name="config_path"                 type="string" value="$(arg cfg)"/>
      <param name="queue_size"                  type="int"    value="$(arg queue_size)"/>
      <param name="guess_frame_id"              type="string" value="$(arg odom_guess_frame_id)"/>
      <param name="guess_min_translation"       type="double" value="$(arg odom_guess_min_translation)"/>
      <param name="guess_min_rotation"          type="double" value="$(arg odom_guess_min_rotation)"/>
      <param name="scan_cloud_max_points"       type="int"    value="$(arg scan_cloud_max_points)"/>
      <param name="expected_update_rate"        type="double" value="$(arg odom_expected_rate)"/>
      <param name="max_update_rate"             type="double" value="$(arg odom_max_rate)"/>
    </node>
    
    <node if="$(arg scan_cloud_assembling)" pkg="rtabmap_ros" type="point_cloud_assembler" name="point_cloud_assembler" output="screen">
      <remap     if="$(arg scan_cloud_filtered)" from="cloud" to="odom_filtered_input_scan"/>
      <remap unless="$(arg scan_cloud_filtered)" from="cloud" to="$(arg scan_cloud_topic)"/>

      <remap from="odom"            to="$(arg odom_topic)"/>
      <param name="assembling_time" type="double" value="$(arg scan_cloud_assembling_time)"/>
      <param name="fixed_frame_id"  type="string" value="$(arg scan_cloud_assembling_fixed_frame)"/>
      <param name="voxel_size"      type="double" value="$(arg scan_cloud_assembling_voxel_size)"/>
      <param name="noise_radius"        type="double" value="$(arg scan_cloud_assembling_noise_radius)"/>
      <param name="noise_min_neighbors" type="int"    value="$(arg scan_cloud_assembling_noise_min_neighbors)"/>
    </node>
  
    <!-- Visual SLAM (robot side) -->
    <!-- args: "delete_db_on_start" and "udebug" -->
    <node name="rtabmap" pkg="rtabmap_ros" type="rtabmap" output="$(arg output)" args="$(arg rtabmap_args)" launch-prefix="$(arg launch_prefix)">
      <param     if="$(arg stereo)" name="subscribe_depth"  type="bool" value="false"/>
      <param unless="$(arg stereo)" name="subscribe_depth"  type="bool" value="$(arg depth)"/>
      <param name="subscribe_rgb"        type="bool"   value="$(arg depth)"/>
      <param name="subscribe_rgbd"       type="bool"   value="$(eval subscribe_rgbd or use_odom_features)"/>
      <param name="subscribe_stereo"     type="bool"   value="$(arg stereo)"/>
      <param name="subscribe_scan"       type="bool"   value="$(arg subscribe_scan)"/>
      <param name="subscribe_scan_cloud" type="bool"   value="$(arg subscribe_scan_cloud)"/>
      <param name="subscribe_scan_descriptor" type="bool" value="$(arg subscribe_scan_descriptor)"/>
      <param name="subscribe_user_data"  type="bool"   value="$(arg subscribe_user_data)"/>
      <param if="$(arg visual_odometry)" name="subscribe_odom_info" type="bool" value="false"/>
      <param if="$(arg icp_odometry)"    name="subscribe_odom_info" type="bool" value="false"/>
      <param name="frame_id"             type="string" value="$(arg frame_id)"/>
      <param name="map_frame_id"         type="string" value="$(arg map_frame_id)"/>
      <param name="odom_frame_id"        type="string" value="$(arg odom_frame_id)"/>
      <param name="publish_tf"           type="bool"   value="$(arg publish_tf_map)"/>
      <param name="gen_scan"             type="bool"   value="$(arg gen_scan)"/>
      <param name="ground_truth_frame_id"       type="string" value="$(arg ground_truth_frame_id)"/>
      <param name="ground_truth_base_frame_id"  type="string" value="$(arg ground_truth_base_frame_id)"/>
      <param name="odom_tf_angular_variance" type="double" value="$(arg odom_tf_angular_variance)"/>
      <param name="odom_tf_linear_variance"  type="double" value="$(arg odom_tf_linear_variance)"/>
      <param name="odom_sensor_sync"         type="bool"   value="$(arg odom_sensor_sync)"/>
      <param name="wait_for_transform_duration"  type="double"   value="$(arg wait_for_transform)"/>
      <param name="database_path"        type="string" value="$(arg database_path)"/>
      <param name="approx_sync"          type="bool"   value="$(eval approx_sync and not use_odom_features)"/>
      <param name="config_path"          type="string" value="$(arg cfg)"/>
      <param name="queue_size"           type="int" value="$(arg queue_size)"/>
      <param name="scan_cloud_max_points"     type="int" value="$(arg scan_cloud_max_points)"/>
      <param name="landmark_linear_variance"   type="double" value="$(arg tag_linear_variance)"/>
      <param name="landmark_angular_variance"  type="double" value="$(arg tag_angular_variance)"/>      
      
      <remap from="rgb/image"       to="$(arg rgb_topic_relay)"/>
      <remap from="depth/image"     to="$(arg depth_topic_relay)"/>
      <remap from="rgb/camera_info" to="$(arg camera_info_topic)"/>
      
      <remap     if="$(arg use_odom_features)" from="rgbd_image" to="odom_rgbd_image"/>
      <remap unless="$(arg use_odom_features)" from="rgbd_image" to="$(arg rgbd_topic_relay)"/>
	
      <remap from="left/image_rect"        to="$(arg left_image_topic_relay)"/>
      <remap from="right/image_rect"       to="$(arg right_image_topic_relay)"/>
      <remap from="left/camera_info"       to="$(arg left_camera_info_topic)"/>
      <remap from="right/camera_info"      to="$(arg right_camera_info_topic)"/>
      
      <remap from="scan"                   to="$(arg scan_topic)"/>
      <remap if="$(eval scan_cloud_assembling)" from="scan_cloud" to="assembled_cloud"/>
      <remap if="$(eval scan_cloud_filtered and not scan_cloud_assembling)" from="scan_cloud" to="odom_filtered_input_scan"/>
      <remap if="$(eval not scan_cloud_filtered and not scan_cloud_assembling)" from="scan_cloud" to="$(arg scan_cloud_topic)"/>
      <remap from="scan_descriptor"        to="$(arg scan_descriptor_topic)"/>
      <remap from="user_data"              to="$(arg user_data_topic)"/>
      <remap from="user_data_async"        to="$(arg user_data_async_topic)"/>
      <remap from="gps/fix"                to="$(arg gps_topic)"/>
      <remap from="tag_detections"         to="$(arg tag_topic)"/>
      <remap from="odom"                   to="$(arg odom_topic)"/>
      <remap from="imu"                    to="$(arg imu_topic)"/>
      
      <!-- 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>
  
    <!-- Visualisation RTAB-Map -->
    <node if="$(arg rtabmapviz)" pkg="rtabmap_ros" type="rtabmapviz" name="rtabmapviz" args="-d $(arg gui_cfg)" output="$(arg output)" launch-prefix="$(arg launch_prefix)">
      <param     if="$(arg stereo)" name="subscribe_depth"  type="bool" value="false"/>
      <param unless="$(arg stereo)" name="subscribe_depth"  type="bool" value="$(arg depth)"/>
      <param name="subscribe_rgbd"       type="bool"   value="$(eval subscribe_rgbd or use_odom_features)"/>
      <param name="subscribe_stereo"     type="bool"   value="$(arg stereo)"/>
      <param unless="$(arg icp_odometry)" name="subscribe_scan"       type="bool"   value="$(arg subscribe_scan)"/>
      <param     if="$(arg icp_odometry)" name="subscribe_scan_cloud" type="bool"   value="$(eval subscribe_scan or subscribe_scan_cloud)"/>
      <param unless="$(arg icp_odometry)" name="subscribe_scan_cloud" type="bool"   value="$(arg subscribe_scan_cloud)"/>
      <param name="subscribe_scan_descriptor" type="bool" value="$(arg subscribe_scan_descriptor)"/>
      <param if="$(arg visual_odometry)" name="subscribe_odom_info" type="bool" value="false"/>
      <param if="$(arg icp_odometry)"    name="subscribe_odom_info" type="bool" value="false"/>
      <param name="frame_id"             type="string" value="$(arg frame_id)"/>
      <param name="odom_frame_id"        type="string" value="$(arg odom_frame_id)"/>
      <param name="wait_for_transform_duration" type="double"   value="$(arg wait_for_transform)"/>
      <param name="queue_size"           type="int"    value="$(arg queue_size)"/>
      <param name="approx_sync"          type="bool"   value="$(eval approx_sync and not use_odom_features)"/>

      <remap from="rgb/image"       to="$(arg rgb_topic_relay)"/>
      <remap from="depth/image"     to="$(arg depth_topic_relay)"/>
      <remap from="rgb/camera_info" to="$(arg camera_info_topic)"/>
      
      <remap     if="$(arg use_odom_features)" from="rgbd_image" to="odom_rgbd_image"/>
      <remap unless="$(arg use_odom_features)" from="rgbd_image" to="$(arg rgbd_topic_relay)"/>
      
      <remap from="left/image_rect"        to="$(arg left_image_topic_relay)"/>
      <remap from="right/image_rect"       to="$(arg right_image_topic_relay)"/>
      <remap from="left/camera_info"       to="$(arg left_camera_info_topic)"/>
      <remap from="right/camera_info"      to="$(arg right_camera_info_topic)"/>
      
      <remap unless="$(arg icp_odometry)" from="scan" to="$(arg scan_topic)"/>
      <remap     if="$(arg icp_odometry)" from="scan_cloud" to="odom_filtered_input_scan"/>
      <remap unless="$(arg icp_odometry)" from="scan_cloud" to="$(arg scan_cloud_topic)"/>
      <remap from="scan_descriptor"        to="$(arg scan_descriptor_topic)"/>
      <remap from="odom"                   to="$(arg odom_topic)"/>
    </node>
  
  </group>
  
  <!-- Visualization RVIZ -->
  <node if="$(arg rviz)" pkg="rviz" type="rviz" name="rviz" args="-d $(arg rviz_cfg)"/>
  <node if="$(arg rviz)" pkg="nodelet" type="nodelet" name="points_xyzrgb" args="standalone rtabmap_ros/point_cloud_xyzrgb" output="$(arg output)">
    <remap if="$(arg stereo)" from="left/image"        to="$(arg left_image_topic_relay)"/>
    <remap if="$(arg stereo)" from="right/image"       to="$(arg right_image_topic_relay)"/>
    <remap if="$(arg stereo)" from="left/camera_info"  to="$(arg left_camera_info_topic)"/>
    <remap if="$(arg stereo)" from="right/camera_info" to="$(arg right_camera_info_topic)"/>
    <remap unless="$(arg subscribe_rgbd)" from="rgb/image"         to="$(arg rgb_topic_relay)"/>
    <remap unless="$(arg subscribe_rgbd)" from="depth/image"       to="$(arg depth_topic_relay)"/>
    <remap unless="$(arg subscribe_rgbd)" from="rgb/camera_info"   to="$(arg camera_info_topic)"/>
    <remap from="rgbd_image"        to="$(arg rgbd_topic_relay)"/>
    <remap from="cloud"             to="voxel_cloud" />

    <param name="decimation"  type="double" value="4"/>
    <param name="voxel_size"  type="double" value="0.0"/>
    <param name="approx_sync" type="bool"   value="$(arg approx_sync)"/>
  </node>

</launch>

Following is the launch command of rtabmap_ros

roslaunch rtabmap_ros rtabmap.launch rtabmap_args:="-d --Mem/UseOdomGravity true --Optimizer/GravitySigma 0.3 --delete_db_on_start" odom_topic:=/t265/odom/sample frame_id:=t265_link rgbd_sync:=true depth_topic:=/l515/aligned_depth_to_color/image_raw rgb_topic:=/l515/color/image_raw camera_info_topic:=/l515/color/camera_info approx_rgbd_sync:=false visual_odometry:=false queue_size:=200

@matlabbe
Copy link
Member

matlabbe commented May 4, 2021

If there is no error, it may means that rtabmap is not able to synchronize topics from T265 and L515 after some time. Maybe the timestamp set in odometry topic drifts in comparison to timsestamp set in L515 topics.

You may compare /rtabmap/rgbd_image/header/stamp with /t265/odom/sample/header/stamp if they are always in sync. This may be why increasing queue_size helps to get data synchronized a little longer but will eventually fail.

With the standalone, we restamp pose and image topics from both camera at the time of receiving them on the computer. Check if there are parameters to chose computer time instead of camera time for realsense cameras. There is a realsense parameter called RS2_OPTION_GLOBAL_TIME_ENABLED that may be related.

@gongyue666
Copy link

I face the same problem, the parameter "RS2_OPTION_GLOBAL_TIME_ENABLED" should be set in rs_l515_and_t265.launch?

@sumitsarkar1
Copy link
Author

@gongyue666 any luck in setting that flag

@gongyue666
Copy link

the warnings are disappeared, but the final result is not very good in my case

@sumitsarkar1
Copy link
Author

final result as in the 3D map or still the streaming cannot be stopped?

@gongyue666
Copy link

final result as in the 3D map performed badly, easily lost~

@shubhamwagh
Copy link

@gongyue666 How do you set RS2_OPTION_GLOBAL_TIME_ENABLED in the launch file?

@shubhamwagh
Copy link

shubhamwagh commented Dec 1, 2021

rtabmap stand-alone application works flawlessly for long hours with L515 + T265. But rtabmap-ros struggles to run the same configuration and for some reason, it is dependent on queue_size value. I did try to put a very high value of queue size but the final map quality is not great as compared to running rtabmap standalone application.

@gongyue666
Copy link

even D435+T265 is better than L515+T265

@shubhamwagh
Copy link

shubhamwagh commented Dec 7, 2021

Yes. But L515 + T265 for indoors gives the best quality map. And I want to get the map somehow from the robot. I am currently running a standalone application via forwarding X (Display) over SSH. @sumitsarkar1 you can run standalone rtabmap application via ssh display forward. Works great for now. Note: the master and client are connected via ethernet cable.

However, it will be great if we can get rtabmap-ros wrapper properly working for L515 + T265 @matlabbe.

@sumitsarkar1
Copy link
Author

sumitsarkar1 commented Dec 7, 2021

@shubhamwagh were you able to run standalone RTabmap via ssh? Like the onboard compute (on the robot) runs SLAM using RTabMap and you can start and stop the mapping using RTabmap GUI from a remote computer. Did you try over wireless... And ya L515 maps are more "crisp" (like walls at a distance more than 5 mtrs) than depth camera maps

@shubhamwagh
Copy link

shubhamwagh commented Dec 7, 2021

@sumitsarkar1 , yes I am able to run standalone RTAB map via ssh display forward. You can check the gist I have created to forward display over ssh. You can follow the steps to forward the display to the client.

The setup of my system is as follows:

Robot (Server):
Single Board computer (Latte Panda Alpha)
L515 + T265 connected to Panda.
Install rtabmap and other third party libraries here.

Laptop (Client):
ssh robot and run rtabmap. Rtabmap GUI opens on client side. I was able to run even realsense-viewer as well.

Robot and Laptop are wired connected via router.

I haven't tried wireless yet, but I believe there will be latency issues with that.

@sumitsarkar1
Copy link
Author

@shubhamwagh thanx a lot...I had some success using ssh and Nautilus...however over wireless there is latency ...but thanx for the forward display suggestions..I will try them

@shubhamwagh
Copy link

shubhamwagh commented Jan 14, 2022

@sumitsarkar1 , I got RTAB-MAP for L515 + T265 working with ROS now.

Looks like by default global_time_sync for L515 is set to false. Add the following rosparams before launching l515. Then it works fine without any issues 😃 .

  <param name="/camera/motion_module/global_time_enabled" type="bool" value="true"/>
  <param name="/camera/l500_depth_sensor/global_time_enabled" type="bool" value="true"/>
  <param name="/camera/rgb_camera/global_time_enabled" type="bool" value="true"/>

Here is my complete launch file for sensor launch

<launch>
  <arg name="device_type_t265"    		default="t265"/>
  <arg name="device_type_l515"    		default="l515"/>
  
  <arg name="serial_no_t265"    			default=""/>
  <arg name="serial_no_l515"    			default=""/>
  
  <arg name="t265_ns"              			default="t265"/>
  <arg name="l515_ns"              			default="l515"/>

  <arg name="tf_prefix_t265"         default="$(arg t265_ns)"/>
  <arg name="tf_prefix_l515"         default="$(arg l515_ns)"/>

  <arg name="initial_reset"             default="false"/>
  <arg name="enable_fisheye"            default="false"/>

  <arg name="color_width"               default="1280"/>
  <arg name="color_height"              default="720"/>
  <arg name="depth_width"               default="640"/>
  <arg name="depth_height"              default="480"/>
  <arg name="ordered_pc"                default="false"/>
  <arg name="clip_distance"             default="-2"/>
  <arg name="topic_odom_in"             default=""/>
  <arg name="calib_odom_file"           default=""/>

  
  <param name="/$(arg t265_ns)/tracking_module/frames_queue_size" type="int" value="16"/>
  <param name="/$(arg t265_ns)/realsense2_camera/enable_relocalization" type="bool" value="false"/>
  
  <param name="/$(arg l515_ns)/motion_module/global_time_enabled" type="bool" value="true"/>
  <param name="/$(arg l515_ns)/l500_depth_sensor/global_time_enabled" type="bool" value="true"/>
  <param name="/$(arg l515_ns)/rgb_camera/global_time_enabled" type="bool" value="true"/>
  
  <!--remap from="/$(arg tf_prefix_t265)/odom/sample" to="/odom" /-->

  <group ns="$(arg t265_ns)">
    <include file="$(find realsense2_camera)/launch/includes/nodelet.launch.xml">
      <arg name="device_type"           value="$(arg device_type_t265)"/>
      <arg name="serial_no"             value="$(arg serial_no_t265)"/>
      <arg name="tf_prefix"         	  value="$(arg tf_prefix_t265)"/>
      <arg name="initial_reset"         value="$(arg initial_reset)"/>
      <arg name="enable_fisheye1"       value="$(arg enable_fisheye)"/>
      <arg name="enable_fisheye2"       value="$(arg enable_fisheye)"/>
      <arg name="topic_odom_in"         value="$(arg topic_odom_in)"/>
      <arg name="calib_odom_file"       value="$(arg calib_odom_file)"/>
      <arg name="gyro_fps"            value="-1"/>
      <arg name="accel_fps"           value="-1"/>
      <arg name="enable_gyro"         value="true"/>
      <arg name="enable_accel"        value="true"/>
      <arg name="enable_pose"         value="true"/>
      <arg name="enable_sync"           value="true"/>

      <!-- <arg name="ordered_pc"            value="$(arg ordered_pc)"/> -->
    </include>
  </group>
  	      <!-- <arg name="enable_infra"          default="true"/> -->
  
  <!-- Launch L515 through nodeler -->
  <group ns="$(arg l515_ns)">
    <include file="$(find realsense2_camera)/launch/includes/nodelet.launch.xml">
      <arg name="device_type"           value="$(arg device_type_l515)"/>
      <arg name="serial_no"             value="$(arg serial_no_l515)"/>
      <arg name="tf_prefix"		          value="$(arg tf_prefix_l515)"/>
      <arg name="initial_reset"         value="$(arg initial_reset)"/>
      <arg name="align_depth"           value="true"/>
      <arg name="filters"               value="pointcloud"/>
      <arg name="color_width"           value="$(arg color_width)"/>
      <arg name="color_height"          value="$(arg color_height)"/>
      <arg name="depth_width"           value="$(arg depth_width)"/>
      <arg name="depth_height"          value="$(arg depth_height)"/>
      <arg name="clip_distance"         value="$(arg clip_distance)"/>
      <arg name="ordered_pc"            value="$(arg ordered_pc)"/>
      <arg name="enable_sync"           value="true"/>
    </include>
  </group>

  <!-- CAMERA ALIGNMENT -->
  <node pkg="tf" type="static_transform_publisher" name="t265_to_l515" args="0.00305 -0.0003 -0.04305 0.0 0.0 1.57 /$(arg tf_prefix_t265)_link /$(arg tf_prefix_l515)_link 100"/>
  

</launch>

Here is how I launch rtabmap:

<launch>

    <arg name="device_type_t265"             default="t265"/>
    <arg name="device_type_l515"             default="l515"/>        <!-- Note: using regular expression. match D435, D435i, D415... -->
    <arg name="serial_no_t265"                       default=""/>
    <arg name="serial_no_l515"                       default=""/>
    <arg name="camera1"                                 default="t265"/>                <!-- Note: Replace with camera name -->
    <arg name="camera2"                                 default="l515"/>                <!-- Note: Replace with camera name -->
    <arg name="clip_distance"             default="-2"/>
    <arg name="debug"                     default="false"/>
    <arg name="use_rviz"                  default="false"/>
    <arg name="use_rtabmapviz"            default="true"/>

    
    <include file="$(find growbot_launch)/auto_launch/rs_t265_and_l515.launch">
            <arg name="device_type_t265"             value="$(arg device_type_t265)"/>
            <arg name="device_type_l515"             value="$(arg device_type_l515)"/>
            <arg name="serial_no_t265"               value="$(arg serial_no_t265)"/>
            <arg name="serial_no_l515"               value="$(arg serial_no_l515)"/>
            <arg name="t265_ns"                         value="$(arg camera1)"/>
            <arg name="l515_ns"                         value="$(arg camera2)"/>
            <arg name="clip_distance"                   value="$(arg clip_distance)"/>

    </include>
    
    <include file="$(find rtabmap_ros)/launch/rtabmap.launch">
            <arg name="rtabmap_args"       value="--delete_db_on_start"/>
            <arg name="cfg"                value="$(find growbot_launch)/config/config.ini"/>
            <arg name="gdb"                value="$(arg debug)"/>
            <arg name="depth_topic"        value="/$(arg camera2)/aligned_depth_to_color/image_raw"/>
            <arg name="frame_id"           value="$(arg camera1)_link"/>
            <arg name="visual_odometry"    value="false"/>
            <arg name="odom_topic"         value="/$(arg camera1)/odom/sample"/>
            <arg name="rgb_topic"          value="/$(arg camera2)/color/image_raw"/>
            <arg name="rgbd_sync"          value="true"/>
            <arg name="approx_rgbd_sync"    value="false"/>
            <arg name="camera_info_topic"  value="/$(arg camera2)/color/camera_info"/>
            <arg name="queue_size"         value="10"/>
            <arg name="rviz"               value="$(arg use_rviz)"/>
            <arg name="rtabmapviz"         value="$(arg use_rtabmapviz)"/>
    </include>
</launch>

@shubhamwagh
Copy link

Following are the issues I referred to, to solve this problem:

  1. L515: frame's time domain is HARDWARE_CLOCK. Timestamps may reset periodically IntelRealSense/realsense-ros#2127
  2. L515 IMU Timestamp Disorder IntelRealSense/realsense-ros#1607 (comment)

Hope this helps someone who wants to work with L515 + T265 sensor configuration using rtabmap_ros

@sumitsarkar1
Copy link
Author

sumitsarkar1 commented Jan 4, 2023

@shubhamwagh what was your launching command? I am using the following

roslaunch rtabmap_ros rtabmap.launch rtabmap_args:="-d --Mem/UseOdomGravity true --Optimizer/GravitySigma 0.3 --delete_db_on_start" odom_topic:=/t265/odom/sample frame_id:=t265_link rgbd_sync:=true depth_topic:=/l515/aligned_depth_to_color/image_raw rgb_topic:=/l515/color/image_raw camera_info_topic:=/l515/color/camera_info approx_rgbd_sync:=true visual_odometry:=false queue_size:=200

I am getting lags in the 3D map rendering

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

4 participants