rtabmap_ros/OdomInfo Message

File: rtabmap_ros/OdomInfo.msg

Raw Message Definition


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 words;
#    std::vector wordMatches;
#    std::vector wordInliers;
#
#    // Optical Flow odometry
#    std::vector refCorners;
#    std::vector newCorners;
#    std::vector cornerInliers;
#}

bool lost
int32 matches
int32 inliers
float32 variance
int32 features
int32 localMapSize
float32 time

int32 type

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

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


Compact Message Definition

std_msgs/Header header
bool lost
int32 matches
int32 inliers
float32 variance
int32 features
int32 localMapSize
float32 time
int32 type
int32[] wordsKeys
rtabmap_ros/KeyPoint[] wordsValues
int32[] wordMatches
int32[] wordInliers
rtabmap_ros/Point2f[] refCorners
rtabmap_ros/Point2f[] newCorners
int32[] cornerInliers