Ouster launch failing

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

Ouster launch failing

denzle
Hi,

I've had my outer lidar working for quite some time but had to reboot and install everything recently and i'm now unable to get the lidar working with ROS with Rtab-ROS throwing a range or errors. From simply crashing straight away, sync issues or unable to "guess_frame_id" [ERROR] [1654729342.003748082]: "guess_frame_id" is set, but guess cannot be computed between frames "os_sensor_stabilized" -> "os_sensor". I'm trying various methods to test and fix the problems but nothings worked yet.

The launch file i'm using is almost exactly the same as i have previously used and had everything working along with trying a blank one from the tests folder. Has anyone else come across a sudden change in compatibility with ouster and Rtab-ros?

I've added my launch in case anyone can see any glaring issues and will add more TF and node info in the near future.

any help would be greatly appreciated.

Cheers
Dan


<?xml version="1.0"?>
<launch>
  
    <!-- 
    Hand-held 3D lidar mapping example using only a Ouster GEN2 (no camera).
    Prerequisities: rtabmap should be built with libpointmatcher
    
    Example:
    
      $ roslaunch rtabmap_ros test_ouster_gen2.launch sensor_hostname:=os-XXXXXXXXXXXX.local udp_dest:=192.168.1.XXX
      $ rosrun rviz rviz -f map
      RVIZ: Show TF and /rtabmap/cloud_map topics
    
    ISSUE: You may have to reset odometry after receiving the first cloud if the map looks tilted. The problem seems 
           coming from the first cloud sent by os_cloud_node, which may be poorly synchronized with IMU data.
           
    PTP mode (synchronize timestamp with host computer time)
    
      * Install:
      
        $ sudo apt install linuxptp httpie
        $ printf "[global]\ntx_timestamp_timeout 10\n" >> ~/os.conf
      
      * Running:
     
        (replace "XXXXXXXXXXXX" by your ouster serial, as well as XXX by its IP address)
        (replace "eth0" by the network interface used to communicate with ouster)
       
        $ http PUT http://os-XXXXXXXXXXXX.local/api/v1/time/ptp/profile <<< '"default-relaxed"'
        $ sudo ptp4l -i eth0 -m -f ~/os.conf -S
        $ roslaunch rtabmap_ros test_ouster_gen2.launch sensor_hostname:=os-XXXXXXXXXXXX.local udp_dest:=192.168.1.XXX ptp:=true
       
    -->
    


    <!-- Required: -->
    <arg name="sensor_hostname" default="os-122105000261.local"/>
    <arg name="udp_dest"        default="169.254.255.255"/> 
    <arg name="use_sim_time"  default="false"/>

    <arg name="frame_id"      default="os_sensor"/>
    <arg name="rtabmapviz"    default="true"/>
    <arg name="scan_20_hz"    default="true"/>
    <arg name="voxel_size"    default="0.15"/>           <!-- indoor: 0.1 to 0.3, outdoor: 0.3 to 0.5 --> 
    <arg name="assemble"      default="false"/>
    <arg name="ptp"           default="true"/>          <!-- See comments in header to start before launching the launch -->
    <arg name="distortion_correction"  default="false"/> <!-- Requires this pull request: https://github.com/ouster-lidar/ouster_example/pull/245 -->
    
    <param if="$(arg use_sim_time)" name="use_sim_time" value="true"/>
    

    <!-- IMU orientation estimation and publish tf accordingly to os_sensor frame -->
    <node pkg="nodelet" type="nodelet" name="imu_nodelet_manager" args="manager">
      <remap from="imu/data_raw" to="/os_cloud_node/imu"/>
      <remap from="imu/data" to="/os_cloud_node/imu/data"/>
    </node>
    <node pkg="nodelet" type="nodelet" name="imu_filter" args="load imu_filter_madgwick/ImuFilterNodelet imu_nodelet_manager">
      <param name="use_mag" value="false"/>
      <param name="world_frame" value="enu"/>
      <param name="publish_tf" value="false"/>
    </node>
    <node pkg="nodelet" type="nodelet" name="imu_to_tf" args="load rtabmap_ros/imu_to_tf imu_nodelet_manager">
      <remap from="imu/data" to="/os_cloud_node/imu/data"/>
      <param name="fixed_frame_id" value="$(arg frame_id)_stabilized"/>
      <param name="base_frame_id" value="$(arg frame_id)"/>
    </node> 

    <group ns="rtabmap">
      <node pkg="rtabmap_ros" type="icp_odometry" name="icp_odometry" output="screen">
        <remap from="scan_cloud" to="/os_cloud_node/points"/>
        <remap from="imu"        to="/os_cloud_node/imu/data"/>
        <param name="frame_id"        type="string" value="$(arg frame_id)"/>  
        <param name="odom_frame_id"   type="string" value="odom"/>
        <param     if="$(arg scan_20_hz)" name="expected_update_rate" type="double" value="25"/>
        <param unless="$(arg scan_20_hz)" name="expected_update_rate" type="double" value="15"/>

        <param name="guess_frame_id"   type="string" value="$(arg frame_id)_stabilized"/>
        <param name="wait_imu_to_init" type="bool" value="true"/>
     
        <!-- ICP parameters -->
        <param name="Icp/PointToPlane"        type="string" value="true"/>
        <param name="Icp/Iterations"          type="string" value="20"/>
        <param name="Icp/VoxelSize"           type="string" value="$(arg voxel_size)"/>
        <param name="Icp/DownsamplingStep"    type="string" value="1"/> <!-- cannot be increased with ring-like lidar -->
        <param name="Icp/Epsilon"             type="string" value="0.001"/>
        <param name="Icp/PointToPlaneK"       type="string" value="20"/>
        <param name="Icp/PointToPlaneRadius"  type="string" value="0"/>
        <param name="Icp/MaxTranslation"      type="string" value="2"/>
        <param name="Icp/MaxCorrespondenceDistance" type="string" value="1"/>
        <param name="Icp/PM"                  type="string" value="true"/> 
        <param name="Icp/PMOutlierRatio"      type="string" value="0.1"/>
        <param name="Icp/CorrespondenceRatio" type="string" value="0.01"/>

        <!-- Odom parameters -->       
        <param name="Odom/ScanKeyFrameThr"       type="string" value="0.95"/>
        <param name="Odom/Strategy"              type="string" value="0"/>
        <param name="OdomF2M/ScanSubtractRadius" type="string" value="$(arg voxel_size)"/>
        <param name="OdomF2M/ScanMaxSize"        type="string" value="15000"/>      
      </node>

      <node pkg="rtabmap_ros" type="rtabmap" name="rtabmap" output="screen" args="-d">	  
        <param name="frame_id"             type="string" value="$(arg frame_id)"/>  
        <param name="subscribe_depth"      type="bool" value="false"/>
        <param name="subscribe_rgb"        type="bool" value="false"/>
        <param name="subscribe_scan_cloud" type="bool" value="true"/>
        <param name="approx_sync"          type="bool" value="false"/>
        
        <remap     if="$(arg assemble)" from="scan_cloud" to="assembled_cloud"/>
        <remap unless="$(arg assemble)" from="scan_cloud" to="/os_cloud_node/points"/>
        <remap from="imu"        to="/os_cloud_node/imu/data"/>
     
        <!-- RTAB-Map's parameters -->
        <param     if="$(arg assemble)" name="Rtabmap/DetectionRate" type="string" value="0"/> <!-- already set 1 Hz in point_cloud_assembler -->
        <param unless="$(arg assemble)" name="Rtabmap/DetectionRate" type="string" value="1"/>  
        <param name="RGBD/NeighborLinkRefining"      type="string" value="false"/>
        <param name="RGBD/ProximityBySpace"          type="string" value="true"/>
        <param name="RGBD/ProximityMaxGraphDepth"    type="string" value="0"/>
        <param name="RGBD/ProximityPathMaxNeighbors" type="string" value="1"/>
        <param name="RGBD/LocalRadius"               type="string" value="2"/>
        <param name="RGBD/AngularUpdate"             type="string" value="0.05"/>
        <param name="RGBD/LinearUpdate"              type="string" value="0.05"/>
        <param name="Mem/NotLinkedNodesKept"         type="string" value="false"/>
        <param name="Mem/STMSize"                    type="string" value="30"/>
        <!-- param name="Mem/LaserScanVoxelSize"     type="string" value="0.1"/ -->
        <!-- param name="Mem/LaserScanNormalK"       type="string" value="10"/ -->
        <!-- param name="Mem/LaserScanRadius"        type="string" value="0"/ -->
        
        <param name="Reg/Strategy"                   type="string" value="1"/> 
        <param name="Optimizer/GravitySigma"         type="string" value="0.5"/>
        <param name="Optimizer/Strategy"             type="string" value="1"/> 
        <param name="Grid/CellSize"                  type="string" value="0.1"/>
        <param name="Grid/RangeMax"                  type="string" value="20"/>
        <param name="Grid/ClusterRadius"             type="string" value="1"/>
        <param name="Grid/GroundIsObstacle"          type="string" value="true"/>

        <!-- ICP parameters -->
        <param name="Icp/VoxelSize"                  type="string" value="$(arg voxel_size)"/>
        <param name="Icp/PointToPlaneK"              type="string" value="20"/>
        <param name="Icp/PointToPlaneRadius"         type="string" value="0"/>
        <param name="Icp/PointToPlane"               type="string" value="true"/>
        <param name="Icp/Iterations"                 type="string" value="10"/>
        <param name="Icp/Epsilon"                    type="string" value="0.001"/>
        <param name="Icp/MaxTranslation"             type="string" value="3"/>
        <param name="Icp/MaxCorrespondenceDistance"  type="string" value="1"/>
        <param name="Icp/PM"                         type="string" value="true"/> 
        <param name="Icp/PMOutlierRatio"             type="string" value="0.7"/>
        <param name="Icp/CorrespondenceRatio"        type="string" value="0.2"/>
      </node>
      
      <node if="$(arg assemble)" pkg="rtabmap_ros" type="point_cloud_assembler" name="point_cloud_assembler" output="screen">
        <remap from="cloud"           to="/os_cloud_node/points"/>
        <remap from="odom"            to="odom"/>
        <param name="assembling_time" type="double" value="1" />
        <param name="fixed_frame_id"  type="string" value="" />
      </node>

      <node if="$(arg rtabmapviz)" name="rtabmapviz" pkg="rtabmap_ros" type="rtabmapviz" output="screen">
        <param name="frame_id" type="string" value="$(arg frame_id)"/>
        <param name="odom_frame_id" type="string" value="odom"/>
        <param name="subscribe_odom_info" type="bool" value="true"/>
        <param name="subscribe_scan_cloud" type="bool" value="true"/>
        <param name="approx_sync" type="bool" value="false"/>
        <remap from="scan_cloud" to="/os_cloud_node/points"/>
      </node>
  </group>

</launch>
Reply | Threaded
Open this post in threaded view
|

Re: Ouster launch failing

matlabbe
Administrator
It should still work (we have it working right now with a gen6 ouster lidar). However, we don't use the ouster imu in our setup. Maybe the imu topic name changed. Verify that imu_filter node republishes the imu with quaternion computed (rostopic hz /os_cloud_node/imu/data). Check also your TF tree (rosrun tf2_tools view_frames.py) if there is a missing TF.

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

Re: Ouster launch failing

denzle
 Thanks for your reply Mathieu,

So i have managed to get some connection between the sensor and Rtab-ros. In rtabviz i can see a sparse point cloud but when i come to close the session nothing gets saved. I've tried to rectify any errors that i can find during start up or during the session but it seems as though assembler doesn't want to work now adn i'm recieving a fatal error with message conversion.

Running the rostopic publisher i get no messages returned. I have checked what may have changed but can't seem to find anything.

$rostopic hz /os_cloud_node/imu/data
subscribed to [/os_cloud_node/imu/data]
no new messages
no new messages
no new messages
no new messages

[FATAL] (2022-06-12 17:25:10.054) MsgConversion.cpp:2286::convertScan3dMsg() Condition (scan3dMsg.data.size() == scan3dMsg.row_step*scan3dMsg.height) not met! [data=34603008 row_step=1081344 height=1]
terminate called after throwing an instance of 'UException'
  what():  [FATAL] (2022-06-12 17:25:10.054) MsgConversion.cpp:2286::convertScan3dMsg() Condition (scan3dMsg.data.size() == scan3dMsg.row_step*scan3dMsg.height) not met! [data=34603008 row_step=1081344 height=1]
[ INFO] [1655051110.060511093]: Odom: ratio=0.967202, std dev=0.005441m|0.001720rad, update time=0.009347s
[ INFO] [1655051110.108666188]: Odom: ratio=0.959198, std dev=0.005340m|0.001689rad, update time=0.010132s
[rtabmap/rtabmap-5] process has died [pid 29390, exit code -6, cmd /home/dan/catkin_ws/devel/lib/rtabmap_ros/rtabmap -d scan_cloud:=assembled_cloud imu:=/os_cloud_node/imu/data __name:=rtabmap __log:=/home/dan/.ros/log/2e256bce-ea6c-11ec-90f4-79224fe1d2ac/rtabmap-rtabmap-5.log].
log file: /home/dan/.ros/log/2e256bce-ea6c-11ec-90f4-79224fe1d2ac/rtabmap-rtabmap-5*.log


I've attached the TF tree and RQT Graph




regards
Dan
Reply | Threaded
Open this post in threaded view
|

Re: Ouster launch failing

denzle
With some more playing around i've managed to get it sort of working again although i've had to remove guess_frame_id and any reference to the _stabilized params. One warning i am getting now is that no data is being provided for data_raw and mag. I have checked topic names and everything seems to be the same for both my old launch files and newer ones as well as the ouster launch, so im not sure what i'm missing.

[ INFO] [1655057191.195756317]: Odom: ratio=0.745192, std dev=0.049929m|0.015789rad, update time=0.046110s
[ INFO] [1655057191.251545083]: Odom: ratio=0.734375, std dev=0.048694m|0.015398rad, update time=0.050726s
[ WARN] [1655057191.282711342]: Still waiting for data on topics /imu/data_raw and /imu/mag...
[ INFO] [1655057191.287963803]: rtabmap (116): Rate=1.00s, Limit=0.000s, Conversion=0.0006s, RTAB-Map=0.0893s, Maps update=0.0022s pub=0.0000s (local map=70, WM=70)
[ INFO] [1655057191.319052049]: Odom: ratio=0.718412, std dev=0.048696m|0.015399rad, update time=0.062176s
 
Again any help would be greatly appreciated.
Cheers
Dan
Reply | Threaded
Open this post in threaded view
|

Re: Ouster launch failing

denzle
This post was updated on .
Just in case its any help i've made a short bag file (zipped) at home which i've put in my dropbox (https://www.dropbox.com/sh/z173th1w12nmpzb/AADdVqj8WNDbReNUyQX-l7MVa?dl=0) and added my amended launch file below.

EDIT So from some more tinkering it appears the problem stemmed from having the 'use_mag' set to true and the most recent error appears to have gone.....for now!

Although if you have a moment to have a look over the rosbag to see where i could improve my pointcloud data i would be most grateful. Having mapped woodlands and written up my finding i'm now moving on to bat surveying using LiDAR/RTAB-ros. So one key element is the ability to pick up fast moving bats. Would there be any parameters i could change to increase the detection of small objects flying through the sensors FoV. The sensor will likely be static for the most part. Once i've had chance to get in the field i'll add another rosbag.

Cheers
Dan

<?xml version="1.0"?>
<launch>
  
    <!-- 
    Hand-held 3D lidar mapping example using only a Ouster GEN2 (no camera).
    Prerequisities: rtabmap should be built with libpointmatcher
    
    Example:
    
      $ roslaunch rtabmap_ros test_ouster_gen2.launch sensor_hostname:=os-XXXXXXXXXXXX.local udp_dest:=192.168.1.XXX
      $ rosrun rviz rviz -f map
      RVIZ: Show TF and /rtabmap/cloud_map topics
    
    ISSUE: You may have to reset odometry after receiving the first cloud if the map looks tilted. The problem seems 
           coming from the first cloud sent by os_cloud_node, which may be poorly synchronized with IMU data.
           
    PTP mode (synchronize timestamp with host computer time)
    
      * Install:
      
        $ sudo apt install linuxptp httpie
        $ printf "[global]\ntx_timestamp_timeout 10\n" >> ~/os.conf
      
      * Running:
     
        (replace "XXXXXXXXXXXX" by your ouster serial, as well as XXX by its IP address)
        (replace "eth0" by the network interface used to communicate with ouster)
       
        $ http PUT http://os-XXXXXXXXXXXX.local/api/v1/time/ptp/profile <<< '"default-relaxed"'
        $ sudo ptp4l -i eth0 -m -f ~/os.conf -S
        $ roslaunch rtabmap_ros test_ouster_gen2.launch sensor_hostname:=os-XXXXXXXXXXXX.local udp_dest:=192.168.1.XXX ptp:=true
       
    -->
    


    <!-- Required: -->
    <arg name="sensor_hostname" default="os-122105000261.local"/>
    <arg name="udp_dest"        default="169.254.255.255"/> 
    <arg name="use_sim_time"  default="false"/>

    <arg name="frame_id"      default="os_sensor"/>
    <arg name="rtabmapviz"    default="true"/>
    <arg name="scan_20_hz"    default="true"/>
    <arg name="voxel_size"    default="0.3"/>           <!-- indoor: 0.1 to 0.3, outdoor: 0.3 to 0.5 --> 
    <arg name="assemble"      default="false"/>
    <arg name="ptp"           default="true"/>          <!-- See comments in header to start before launching the launch -->
    <arg name="distortion_correction"  default="false"/> <!-- Requires this pull request: https://github.com/ouster-lidar/ouster_example/pull/245 -->
    
    <param if="$(arg use_sim_time)" name="use_sim_time" value="false"/>
    

    <!-- IMU orientation estimation and publish tf accordingly to os_sensor frame -->
    <node pkg="nodelet" type="nodelet" name="imu_nodelet_manager" args="manager">
      <remap from="imu/data_raw" to="/os_cloud_node/imu"/>
      <remap from="imu/data" to="/os_cloud_node/imu/data"/>
    </node>
    <node pkg="nodelet" type="nodelet" name="imu_filter" args="load imu_filter_madgwick/ImuFilterNodelet imu_nodelet_manager">
      <param name="use_mag" value="true"/>
      <param name="world_frame" value="enu"/>
      <param name="publish_tf" value="false"/>
    </node>
    <node pkg="nodelet" type="nodelet" name="imu_to_tf" args="load rtabmap_ros/imu_to_tf imu_nodelet_manager">
      <remap from="imu/data" to="/os_cloud_node/imu/data"/>
      <param name="fixed_frame_id" value="$(arg frame_id)_stabilized"/>
      <param name="base_frame_id" value="$(arg frame_id)"/>
    </node> 

    <group ns="rtabmap">
      <node pkg="rtabmap_ros" type="icp_odometry" name="icp_odometry" output="screen">
        <remap from="scan_cloud" to="/os_cloud_node/points"/>
        <remap from="imu"        to="/os_cloud_node/imu/data"/>
        <param name="frame_id"        type="string" value="$(arg frame_id)"/>  
        <param name="odom_frame_id"   type="string" value="odom"/>
        <param     if="$(arg scan_20_hz)" name="expected_update_rate" type="double" value="25"/>
        <param unless="$(arg scan_20_hz)" name="expected_update_rate" type="double" value="15"/>

        <param name="wait_imu_to_init" type="bool" value="false"/>
     
        <!-- ICP parameters -->
        <param name="Icp/PointToPlane"        type="string" value="true"/>
        <param name="Icp/Iterations"          type="string" value="30"/>
        <param name="Icp/VoxelSize"           type="string" value="$(arg voxel_size)"/>
        <param name="Icp/DownsamplingStep"    type="string" value="1"/> <!-- cannot be increased with ring-like lidar -->
        <param name="Icp/Epsilon"             type="string" value="0.001"/>
        <param name="Icp/PointToPlaneK"       type="string" value="20"/>
        <param name="Icp/PointToPlaneRadius"  type="string" value="0"/>
        <param name="Icp/MaxTranslation"      type="string" value="0.2"/>
        <param name="Icp/MaxCorrespondenceDistance" type="string" value="1"/>
        <param name="Icp/Strategy"                  type="string" value="true"/> 
        <param name="Icp/PMOutlierRatio"      type="string" value="0.1"/>
        <param name="Icp/CorrespondenceRatio" type="string" value="0.01"/>

        <!-- Odom parameters -->       
        <param name="Odom/ScanKeyFrameThr"       type="string" value="0.95"/>
        <param name="Odom/Strategy"              type="string" value="0"/>
        <param name="OdomF2M/ScanSubtractRadius" type="string" value="$(arg voxel_size)"/>
        <param name="OdomF2M/ScanMaxSize"        type="string" value="15000"/>      
      </node>

      <node pkg="rtabmap_ros" type="rtabmap" name="rtabmap" output="screen" args="-d">	  
        <param name="frame_id"             type="string" value="$(arg frame_id)"/>  
        <param name="subscribe_depth"      type="bool" value="false"/>
        <param name="subscribe_rgb"        type="bool" value="false"/>
        <param name="subscribe_scan_cloud" type="bool" value="true"/>
        <param name="approx_sync"          type="bool" value="false"/>
        <param name="scan_cloud_max_points" value="327680"/> <!-- based on os-1 spec: 327,680 pts/second for 10 Hz -->
        
        <remap     if="$(arg assemble)" from="scan_cloud" to="assembled_cloud"/>
        <remap unless="$(arg assemble)" from="scan_cloud" to="/os_cloud_node/points"/>
        <remap from="imu"        to="/os_cloud_node/imu/data"/>
     
        <!-- RTAB-Map's parameters -->
        <param     if="$(arg assemble)" name="Rtabmap/DetectionRate" type="string" value="0"/> <!-- already set 1 Hz in point_cloud_assembler -->
        <param unless="$(arg assemble)" name="Rtabmap/DetectionRate" type="string" value="1"/>  
        <param name="RGBD/NeighborLinkRefining"      type="string" value="false"/>
        <param name="RGBD/ProximityBySpace"          type="string" value="true"/>
        <param name="RGBD/ProximityMaxGraphDepth"    type="string" value="0"/>
        <param name="RGBD/ProximityPathMaxNeighbors" type="string" value="1"/>
        <param name="RGBD/LocalRadius"               type="string" value="2"/>
        <param name="RGBD/AngularUpdate"             type="string" value="0.05"/>
        <param name="RGBD/LinearUpdate"              type="string" value="0.05"/>
        <param name="Mem/NotLinkedNodesKept"         type="string" value="false"/>
        <param name="Mem/STMSize"                    type="string" value="30"/>
        <!-- param name="Mem/LaserScanVoxelSize"     type="string" value="0.1"/ -->
        <!-- param name="Mem/LaserScanNormalK"       type="string" value="10"/ -->
        <!-- param name="Mem/LaserScanRadius"        type="string" value="0"/ -->
        
        <param name="Reg/Strategy"                   type="string" value="1"/> 
        <param name="Optimizer/GravitySigma"         type="string" value="0.5"/>
        <param name="Optimizer/Strategy"             type="string" value="1"/> 
        <param name="Grid/CellSize"                  type="string" value="0.1"/>
        <param name="Grid/RangeMax"                  type="string" value="20"/>
        <param name="Grid/ClusterRadius"             type="string" value="1"/>
        <param name="Grid/GroundIsObstacle"          type="string" value="true"/>

        <!-- ICP parameters -->
        <param name="Icp/VoxelSize"                  type="string" value="$(arg voxel_size)"/>
        <param name="Icp/PointToPlaneK"              type="string" value="20"/>
        <param name="Icp/PointToPlaneRadius"         type="string" value="0"/>
        <param name="Icp/PointToPlane"               type="string" value="true"/>
        <param name="Icp/Iterations"                 type="string" value="10"/>
        <param name="Icp/Epsilon"                    type="string" value="0.001"/>
        <param name="Icp/MaxTranslation"             type="string" value="3"/>
        <param name="Icp/MaxCorrespondenceDistance"  type="string" value="1"/>
        <param name="Icp/Strategy"                         type="string" value="true"/> 
        <param name="Icp/PMOutlierRatio"             type="string" value="0.7"/>
        <param name="Icp/CorrespondenceRatio"        type="string" value="0.2"/>
      </node>
      
      <node if="$(arg assemble)" pkg="rtabmap_ros" type="point_cloud_assembler" name="point_cloud_assembler" output="screen">
        <remap from="cloud"           to="/os_cloud_node/points"/>
        <remap from="odom"            to="odom"/>
        <param name="assembling_time" type="double" value="1" />
        <param name="fixed_frame_id"  type="string" value="" />
      </node>

      <node if="$(arg rtabmapviz)" name="rtabmapviz" pkg="rtabmap_ros" type="rtabmapviz" output="screen">
        <param name="frame_id" type="string" value="$(arg frame_id)"/>
        <param name="odom_frame_id" type="string" value="odom"/>
        <param name="subscribe_odom_info" type="bool" value="true"/>
        <param name="subscribe_scan_cloud" type="bool" value="true"/>
        <param name="approx_sync" type="bool" value="false"/>
        <remap from="scan_cloud" to="/os_cloud_node/points"/>
      </node>
  </group>

</launch>
Reply | Threaded
Open this post in threaded view
|

Re: Ouster launch failing

matlabbe
Administrator
Hi,

glad that you fixed your problem. The bag seems fine, though for small indoor environment like that, you could decrease voxel_size argument in the launch file (see comment  " indoor: 0.1 to 0.3, outdoor: 0.3 to 0.5 " ).