rtabmap_ros

Summary

rtabmap_ros
Version:

0.10.4

Description:

RTAB-Map’s ros-pkg. RTAB-Map is a RGB-D SLAM approach with real-time constraints.

Maintainers:
  • Mathieu Labbe <matlabbe AT gmail DOT com>
Licenses:
  • BSD
Urls:
Authors:
  • Mathieu Labbe
BuildDepends:
BuildtoolDepends:
 
BuildExportDepends:
 
ExecDepends:
Exports:
  • <nodelet plugin=”${prefix}/nodelet_plugins.xml”/>
  • <rviz plugin=”${prefix}/plugin_description.xml”/>
  • <costmap_2d plugin=”${prefix}/costmap_plugins.xml”/>

Types

Message types

rtabmap_ros/KeyPoint
Field:
  • pt (rtabmap_ros/Point2f) –
  • size (float32) –
  • angle (float32) –
  • response (float32) –
  • octave (int32) –
  • class_id (int32) –

class cv::KeyPoint {

Point2f pt; float size; float angle; float response; int octave; int class_id;

}

#class cv::KeyPoint
#{
#    Point2f pt;
#    float size;
#    float angle;
#    float response;
#    int octave;
#    int class_id;
#}

Point2f pt
float32 size
float32 angle
float32 response
int32 octave
int32 class_id
Field:
  • fromId (int32) –
  • toId (int32) –
  • type (int32) –
  • transform (geometry_msgs/Transform) –
  • rotVariance (float32) –
  • transVariance (float32) –

class rtabmap::Link {

int from; int to; Type type; Transform transform; float variance;

}

#class rtabmap::Link
#{
#   int from;
#   int to;
#   Type type;
#   Transform transform;
#   float variance;
#}

int32 fromId
int32 toId
int32 type
geometry_msgs/Transform transform
float32 rotVariance
float32 transVariance
rtabmap_ros/OdomInfo
Field:
  • header (std_msgs/Header) –
  • lost (bool) –
  • matches (int32) –
  • inliers (int32) –
  • variance (float32) –
  • features (int32) –
  • localMapSize (int32) –
  • timeEstimation (float32) –
  • timeParticleFiltering (float32) –
  • stamp (float32) –
  • interval (float32) –
  • distanceTravelled (float32) –
  • type (int32) –
  • wordsKeys[] (int32) –
  • wordsValues[] (rtabmap_ros/KeyPoint) –
  • wordMatches[] (int32) –
  • wordInliers[] (int32) –
  • refCorners[] (rtabmap_ros/Point2f) –
  • newCorners[] (rtabmap_ros/Point2f) –
  • cornerInliers[] (int32) –
  • transform (geometry_msgs/Transform) –
  • transformFiltered (geometry_msgs/Transform) –
Header header

#class rtabmap::OdometryInfo
#{
#    bool lost;
#    int matches;
#    int inliers;
#    float variance;
#    int features;
#    int localMapSize;
#    float time;
#
#    int type; // 0=BOW, 1=Optical Flow, 2=ICP
#
#    // BOW odometry
#    std::multimap<int, cv::KeyPoint> words;
#    std::vector<int> wordMatches;
#    std::vector<int> wordInliers;
#
#    // Optical Flow odometry
#    std::vector<cv::Point2f> refCorners;
#    std::vector<cv::Point2f> newCorners;
#    std::vector<int> cornerInliers;
#}

bool lost
int32 matches
int32 inliers
float32 variance
int32 features
int32 localMapSize
float32 timeEstimation
float32 timeParticleFiltering
float32 stamp
float32 interval
float32 distanceTravelled

int32 type

int32[] wordsKeys
KeyPoint[] wordsValues
int32[] wordMatches
int32[] wordInliers

Point2f[] refCorners
Point2f[] newCorners
int32[] cornerInliers

geometry_msgs/Transform transform
geometry_msgs/Transform transformFiltered
rtabmap_ros/NodeData
Field:
  • id (int32) –
  • mapId (int32) –
  • weight (int32) –
  • stamp (float64) –
  • label (string) –
  • pose (geometry_msgs/Pose) –
  • image[] (uint8) –
  • depth[] (uint8) –
  • fx[] (float32) –
  • fy[] (float32) –
  • cx[] (float32) –
  • cy[] (float32) –
  • baseline (float32) –
  • localTransform[] (geometry_msgs/Transform) –
  • laserScan[] (uint8) –
  • laserScanMaxPts (int32) –
  • userData[] (uint8) –
  • wordIds[] (int32) –
  • wordKpts[] (rtabmap_ros/KeyPoint) –
  • wordPts (sensor_msgs/PointCloud2) –
int32 id
int32 mapId
int32 weight
float64 stamp
string label

# Pose from odometry not corrected
geometry_msgs/Pose pose

# compressed image in /camera_link frame
# use rtabmap::util3d::uncompressImage() from "rtabmap/core/util3d.h"
uint8[] image

# compressed depth image in /camera_link frame
# use rtabmap::util3d::uncompressImage() from "rtabmap/core/util3d.h"
uint8[] depth

# Camera models
float32[] fx
float32[] fy
float32[] cx
float32[] cy
float32 baseline
# local transform (/base_link -> /camera_link)
geometry_msgs/Transform[] localTransform

# compressed 2D laser scan in /base_link frame
# use rtabmap::util3d::uncompressData() from "rtabmap/core/util3d.h"
uint8[] laserScan
int32 laserScanMaxPts

# compressed user data
# use rtabmap::util3d::uncompressData() from "rtabmap/core/util3d.h"
uint8[] userData

# std::multimap<wordId, cv::Keypoint>
# std::multimap<wordId, pcl::PointXYZ>
int32[] wordIds
KeyPoint[] wordKpts
sensor_msgs/PointCloud2 wordPts
rtabmap_ros/Info
Field:
  • header (std_msgs/Header) –
  • refId (int32) –
  • loopClosureId (int32) –
  • localLoopClosureId (int32) –
  • loopClosureTransform (geometry_msgs/Transform) –
  • posteriorKeys[] (int32) –
  • posteriorValues[] (float32) –
  • likelihoodKeys[] (int32) –
  • likelihoodValues[] (float32) –
  • rawLikelihoodKeys[] (int32) –
  • rawLikelihoodValues[] (float32) –
  • weightsKeys[] (int32) –
  • weightsValues[] (int32) –
  • statsKeys[] (string) –
  • statsValues[] (float32) –
  • localPath[] (int32) –
RTAB-Map info with statistics
########################################
# RTAB-Map info with statistics 
########################################

Header header

int32 refId
int32 loopClosureId
int32 localLoopClosureId

geometry_msgs/Transform loopClosureTransform

####
# For statistics...
####
# std::map<int, float> posterior;
int32[] posteriorKeys
float32[] posteriorValues

# std::map<int, float> likelihood;
int32[] likelihoodKeys
float32[] likelihoodValues

# std::map<int, float> rawLikelihood;
int32[] rawLikelihoodKeys
float32[] rawLikelihoodValues

# std::map<int, int> weights;
int32[] weightsKeys
int32[] weightsValues

# std::map<std::string, float> stats
string[] statsKeys
float32[] statsValues

# std::vector<int> localPath
int32[] localPath
rtabmap_ros/MapData
Field:
Header header

##################
# Optimized graph
##################
##
# /map to /odom transform
# Always identity when the graph is optimized from the latest pose.
##
geometry_msgs/Transform mapToOdom

# The poses
int32[] posesId
geometry_msgs/Pose[] poses

# The links
Link[] links

##################
# Graph data
##################
NodeData[] nodes
rtabmap_ros/Point2f
Field:
  • x (float32) –
  • y (float32) –

class cv::Point2f {

float x; float y;

}

#class cv::Point2f
#{
#    float x;
#    float y;
#}

float32 x
float32 y

Service types

rtabmap_ros/GetMap
Field (Request):
 
  • global (bool) –
  • optimized (bool) –
  • graphOnly (bool) –
Field (Response):
 

request

#request
bool global
bool optimized
bool graphOnly
---
#response
MapData data
rtabmap_ros/SetGoal
Field (Request):
 
  • node_id (int32) –
  • node_label (string) –
request
Set either node_id or node_label
#request
# Set either node_id or node_label
int32 node_id
string node_label
---
#response 
rtabmap_ros/ResetPose
Field (Request):
 
  • x (float32) –
  • y (float32) –
  • z (float32) –
  • roll (float32) –
  • pitch (float32) –
  • yaw (float32) –

request

#request
float32 x
float32 y
float32 z
float32 roll
float32 pitch
float32 yaw
---
#response
rtabmap_ros/SetLabel
Field (Request):
 
  • node_id (int32) –
  • node_label (string) –
request
Set node_id = 0 to set label to last node
#request
# Set node_id = 0 to set label to last node
int32 node_id
string node_label
---
#response 
rtabmap_ros/PublishMap
Field (Request):
 
  • global (bool) –
  • optimized (bool) –
  • graphOnly (bool) –

request

#request
bool global
bool optimized
bool graphOnly
---
#response
rtabmap_ros/ListLabels
Field (Response):
 
  • labels[] (string) –
#request
---
#response 
string[] labels