introlab / rtabmap_ros

RTAB-Map's ROS package.
http://wiki.ros.org/rtabmap_ros
BSD 3-Clause "New" or "Revised" License
932 stars 551 forks source link

Not able to launch L515 ICP odometry example on Nvidia AGX #962

Open araujokth opened 1 year ago

araujokth commented 1 year ago

Hi, I am trying to run rtabmap on an NVIDIA AGX with L515 and have a problem when running the tutorial "For RealSense L515: ICP odometry example(ref)." in http://wiki.ros.org/rtabmap_ros/Tutorials/HandHeldMapping. I can run the example for D435i/L515.

When I try to run "rosrun nodelet nodelet standalone rtabmap_util/point_cloud_xyz _approx_sync:=false /depth/image:=/camera/depth/image_rect_raw /depth/camera_info:=/camera/depth/camera_info _decimation:=4" I get the following error:

[ERROR] [1683202698.946983100]: Failed to load nodelet [/rtabmap_util_point_cloud_xyz] of type [rtabmap_util/point_cloud_xyz] even after refreshing the cache: According to the loaded plugin descriptions the class rtabmap_util/point_cloud_xyz with base class type nodelet::Nodelet does not exist. Declared types are RobotLocalization/EkfNodelet RobotLocalization/NavSatTransformNodelet RobotLocalization/UkfNodelet apriltag_ros/ContinuousDetector depth_image_proc/convert_metric depth_image_proc/crop_foremost depth_image_proc/disparity depth_image_proc/point_cloud_xyz depth_image_proc/point_cloud_xyz_radial depth_image_proc/point_cloud_xyzi depth_image_proc/point_cloud_xyzi_radial depth_image_proc/point_cloud_xyzrgb depth_image_proc/register image_proc/crop_decimate image_proc/crop_nonZero image_proc/crop_non_zero image_proc/debayer image_proc/rectify image_proc/resize image_publisher/image_publisher image_rotate/image_rotate image_view/disparity image_view/image imu_filter_madgwick/ImuFilterNodelet laser_filters/scan_to_cloud_filter_chain nodelet_tutorial_math/Plus pcl/BAGReader pcl/BoundaryEstimation pcl/ConvexHull2D pcl/CropBox pcl/EuclideanClusterExtraction pcl/ExtractIndices pcl/ExtractPolygonalPrismData pcl/FPFHEstimation pcl/FPFHEstimationOMP pcl/MomentInvariantsEstimation pcl/MovingLeastSquares pcl/NodeletDEMUX pcl/NodeletMUX pcl/NormalEstimation pcl/NormalEstimationOMP pcl/NormalEstimationTBB pcl/PCDReader pcl/PCDWriter pcl/PFHEstimation pcl/PassThrough pcl/PointCloudConcatenateDataSynchronizer pcl/PointCloudConcatenateFieldsSynchronizer pcl/PrincipalCurvaturesEstimation pcl/ProjectInliers pcl/RadiusOutlierRemoval pcl/SACSegmentation pcl/SACSegmentationFromNormals pcl/SHOTEstimation pcl/SHOTEstimationOMP pcl/SegmentDifferences pcl/StatisticalOutlierRemoval pcl/VFHEstimation pcl/VoxelGrid rtabmap_ros/data_odom_sync rtabmap_ros/data_throttle rtabmap_ros/disparity_to_depth rtabmap_ros/icp_odometry rtabmap_ros/imu_to_tf rtabmap_ros/lidar_deskewing rtabmap_ros/obstacles_detection rtabmap_ros/obstacles_detection_old rtabmap_ros/point_cloud_aggregator rtabmap_ros/point_cloud_assembler rtabmap_ros/point_cloud_xyz rtabmap_ros/point_cloud_xyzrgb rtabmap_ros/pointcloud_to_depthimage rtabmap_ros/rgb_sync rtabmap_ros/rgbd_odometry rtabmap_ros/rgbd_relay rtabmap_ros/rgbd_split rtabmap_ros/rgbd_sync rtabmap_ros/rgbdicp_odometry rtabmap_ros/rgbdx_sync rtabmap_ros/rtabmap rtabmap_ros/stereo_odometry rtabmap_ros/stereo_sync rtabmap_ros/stereo_throttle rtabmap_ros/undistort_depth stereo_image_proc/disparity stereo_image_proc/point_cloud2 tf2_server/nodelet

[ERROR] [1683202698.955357405]: The error before refreshing the cache was: According to the loaded plugin descriptions the class rtabmap_util/point_cloud_xyz with base class type nodelet::Nodelet does not exist. Declared types are RobotLocalization/EkfNodelet RobotLocalization/NavSatTransformNodelet RobotLocalization/UkfNodelet apriltag_ros/ContinuousDetector depth_image_proc/convert_metric depth_image_proc/crop_foremost depth_image_proc/disparity depth_image_proc/point_cloud_xyz depth_image_proc/point_cloud_xyz_radial depth_image_proc/point_cloud_xyzi depth_image_proc/point_cloud_xyzi_radial depth_image_proc/point_cloud_xyzrgb depth_image_proc/register image_proc/crop_decimate image_proc/crop_nonZero image_proc/crop_non_zero image_proc/debayer image_proc/rectify image_proc/resize image_publisher/image_publisher image_rotate/image_rotate image_view/disparity image_view/image imu_filter_madgwick/ImuFilterNodelet laser_filters/scan_to_cloud_filter_chain nodelet_tutorial_math/Plus pcl/BAGReader pcl/BoundaryEstimation pcl/ConvexHull2D pcl/CropBox pcl/EuclideanClusterExtraction pcl/ExtractIndices pcl/ExtractPolygonalPrismData pcl/FPFHEstimation pcl/FPFHEstimationOMP pcl/MomentInvariantsEstimation pcl/MovingLeastSquares pcl/NodeletDEMUX pcl/NodeletMUX pcl/NormalEstimation pcl/NormalEstimationOMP pcl/NormalEstimationTBB pcl/PCDReader pcl/PCDWriter pcl/PFHEstimation pcl/PassThrough pcl/PointCloudConcatenateDataSynchronizer pcl/PointCloudConcatenateFieldsSynchronizer pcl/PrincipalCurvaturesEstimation pcl/ProjectInliers pcl/RadiusOutlierRemoval pcl/SACSegmentation pcl/SACSegmentationFromNormals pcl/SHOTEstimation pcl/SHOTEstimationOMP pcl/SegmentDifferences pcl/StatisticalOutlierRemoval pcl/VFHEstimation pcl/VoxelGrid rtabmap_ros/data_odom_sync rtabmap_ros/data_throttle rtabmap_ros/disparity_to_depth rtabmap_ros/icp_odometry rtabmap_ros/imu_to_tf rtabmap_ros/lidar_deskewing rtabmap_ros/obstacles_detection rtabmap_ros/obstacles_detection_old rtabmap_ros/point_cloud_aggregator rtabmap_ros/point_cloud_assembler rtabmap_ros/point_cloud_xyz rtabmap_ros/point_cloud_xyzrgb rtabmap_ros/pointcloud_to_depthimage rtabmap_ros/rgb_sync rtabmap_ros/rgbd_odometry rtabmap_ros/rgbd_relay rtabmap_ros/rgbd_split rtabmap_ros/rgbd_sync rtabmap_ros/rgbdicp_odometry rtabmap_ros/rgbdx_sync rtabmap_ros/rtabmap rtabmap_ros/stereo_odometry rtabmap_ros/stereo_sync rtabmap_ros/stereo_throttle rtabmap_ros/undistort_depth stereo_image_proc/disparity stereo_image_proc/point_cloud2 tf2_server/nodelet

Any suggestions what the problem could be? Thank you!

matlabbe commented 1 year ago

It seems you are still using old rtabmap_ros interface. The corresponding tutorial is here: http://wiki.ros.org/rtabmap_ros/TutorialsOldInterface/HandHeldMapping

$ rosrun nodelet nodelet standalone rtabmap_ros/point_cloud_xyz \
    _approx_sync:=false  \
    /depth/image:=/camera/depth/image_rect_raw \
    /depth/camera_info:=/camera/depth/camera_info \
    _decimation:=4