Functions | |
rtabmap::CameraModel | cameraModelFromROS (const sensor_msgs::CameraInfo &camInfo, const rtabmap::Transform &localTransform=rtabmap::Transform::getIdentity()) |
void | cameraModelToROS (const rtabmap::CameraModel &model, sensor_msgs::CameraInfo &camInfo) |
cv::Mat | compressedMatFromBytes (const std::vector< unsigned char > &bytes, bool copy=true) |
void | compressedMatToBytes (const cv::Mat &compressed, std::vector< unsigned char > &bytes) |
bool | convertRGBDMsgs (const std::vector< cv_bridge::CvImageConstPtr > &imageMsgs, const std::vector< cv_bridge::CvImageConstPtr > &depthMsgs, const std::vector< sensor_msgs::CameraInfo > &cameraInfoMsgs, const std::vector< sensor_msgs::CameraInfo > &depthCameraInfoMsgs, const std::string &frameId, const std::string &odomFrameId, const ros::Time &odomStamp, cv::Mat &rgb, cv::Mat &depth, std::vector< rtabmap::CameraModel > &cameraModels, std::vector< rtabmap::StereoCameraModel > &stereoCameraModels, tf::TransformListener &listener, double waitForTransform, bool alreadRectifiedImages, const std::vector< std::vector< rtabmap_msgs::KeyPoint > > &localKeyPointsMsgs=std::vector< std::vector< rtabmap_msgs::KeyPoint > >(), const std::vector< std::vector< rtabmap_msgs::Point3f > > &localPoints3dMsgs=std::vector< std::vector< rtabmap_msgs::Point3f > >(), const std::vector< cv::Mat > &localDescriptorsMsgs=std::vector< cv::Mat >(), std::vector< cv::KeyPoint > *localKeyPoints=0, std::vector< cv::Point3f > *localPoints3d=0, cv::Mat *localDescriptors=0) |
bool | convertScan3dMsg (const sensor_msgs::PointCloud2 &scan3dMsg, const std::string &frameId, const std::string &odomFrameId, const ros::Time &odomStamp, rtabmap::LaserScan &scan, tf::TransformListener &listener, double waitForTransform, int maxPoints=0, float maxRange=0.0f, bool is2D=false) |
bool | convertScanMsg (const sensor_msgs::LaserScan &scan2dMsg, const std::string &frameId, const std::string &odomFrameId, const ros::Time &odomStamp, rtabmap::LaserScan &scan, tf::TransformListener &listener, double waitForTransform, bool outputInFrameId=false) |
bool | convertStereoMsg (const cv_bridge::CvImageConstPtr &leftImageMsg, const cv_bridge::CvImageConstPtr &rightImageMsg, const sensor_msgs::CameraInfo &leftCamInfoMsg, const sensor_msgs::CameraInfo &rightCamInfoMsg, const std::string &frameId, const std::string &odomFrameId, const ros::Time &odomStamp, cv::Mat &left, cv::Mat &right, rtabmap::StereoCameraModel &stereoModel, tf::TransformListener &listener, double waitForTransform, bool alreadyRectified) |
bool | deskew (const sensor_msgs::PointCloud2 &input, sensor_msgs::PointCloud2 &output, const std::string &fixedFrameId, tf::TransformListener &listener, double waitForTransform, bool slerp=false) |
bool | deskew (const sensor_msgs::PointCloud2 &input, sensor_msgs::PointCloud2 &output, double previousStamp, const rtabmap::Transform &velocity) |
bool | deskew_impl (const sensor_msgs::PointCloud2 &input, sensor_msgs::PointCloud2 &output, const std::string &fixedFrameId, tf::TransformListener *listener, double waitForTransform, bool slerp, const rtabmap::Transform &velocity, double previousStamp) |
rtabmap::EnvSensor | envSensorFromROS (const rtabmap_msgs::EnvSensor &msg) |
rtabmap::EnvSensors | envSensorsFromROS (const std::vector< rtabmap_msgs::EnvSensor > &msg) |
void | envSensorsToROS (const rtabmap::EnvSensors &sensors, std::vector< rtabmap_msgs::EnvSensor > &msg) |
void | envSensorToROS (const rtabmap::EnvSensor &sensor, rtabmap_msgs::EnvSensor &msg) |
rtabmap::Transform | getMovingTransform (const std::string &movingFrame, const std::string &fixedFrame, const ros::Time &stampFrom, const ros::Time &stampTo, tf::TransformListener &listener, double waitForTransform) |
rtabmap::Transform | getTransform (const std::string &fromFrameId, const std::string &toFrameId, const ros::Time &stamp, tf::TransformListener &listener, double waitForTransform) |
rtabmap::GlobalDescriptor | globalDescriptorFromROS (const rtabmap_msgs::GlobalDescriptor &msg) |
std::vector< rtabmap::GlobalDescriptor > | globalDescriptorsFromROS (const std::vector< rtabmap_msgs::GlobalDescriptor > &msg) |
void | globalDescriptorsToROS (const std::vector< rtabmap::GlobalDescriptor > &desc, std::vector< rtabmap_msgs::GlobalDescriptor > &msg) |
void | globalDescriptorToROS (const rtabmap::GlobalDescriptor &desc, rtabmap_msgs::GlobalDescriptor &msg) |
rtabmap::IMU | imuFromROS (const sensor_msgs::Imu &msg, const rtabmap::Transform &localTransform=rtabmap::Transform::getIdentity()) |
void | imuToROS (const rtabmap::IMU &imu, sensor_msgs::Imu &msg) |
void | infoFromROS (const rtabmap_msgs::Info &info, rtabmap::Statistics &stat) |
void | infoToROS (const rtabmap::Statistics &stats, rtabmap_msgs::Info &info) |
cv::KeyPoint | keypointFromROS (const rtabmap_msgs::KeyPoint &msg) |
std::vector< cv::KeyPoint > | keypointsFromROS (const std::vector< rtabmap_msgs::KeyPoint > &msg) |
void | keypointsFromROS (const std::vector< rtabmap_msgs::KeyPoint > &msg, std::vector< cv::KeyPoint > &kpts, int xShift=0) |
void | keypointsToROS (const std::vector< cv::KeyPoint > &kpts, std::vector< rtabmap_msgs::KeyPoint > &msg) |
void | keypointToROS (const cv::KeyPoint &kpt, rtabmap_msgs::KeyPoint &msg) |
rtabmap::Landmarks | landmarksFromROS (const std::map< int, std::pair< geometry_msgs::PoseWithCovarianceStamped, float > > &tags, const std::string &frameId, const std::string &odomFrameId, const ros::Time &odomStamp, tf::TransformListener &listener, double waitForTransform, double defaultLinVariance, double defaultAngVariance) |
rtabmap::Link | linkFromROS (const rtabmap_msgs::Link &msg) |
void | linkToROS (const rtabmap::Link &link, rtabmap_msgs::Link &msg) |
void | mapDataFromROS (const rtabmap_msgs::MapData &msg, std::map< int, rtabmap::Transform > &poses, std::multimap< int, rtabmap::Link > &links, std::map< int, rtabmap::Signature > &signatures, rtabmap::Transform &mapToOdom) |
void | mapDataToROS (const std::map< int, rtabmap::Transform > &poses, const std::multimap< int, rtabmap::Link > &links, const std::map< int, rtabmap::Signature > &signatures, const rtabmap::Transform &mapToOdom, rtabmap_msgs::MapData &msg) |
void | mapGraphFromROS (const rtabmap_msgs::MapGraph &msg, std::map< int, rtabmap::Transform > &poses, std::multimap< int, rtabmap::Link > &links, rtabmap::Transform &mapToOdom) |
void | mapGraphToROS (const std::map< int, rtabmap::Transform > &poses, const std::multimap< int, rtabmap::Link > &links, const rtabmap::Transform &mapToOdom, rtabmap_msgs::MapGraph &msg) |
rtabmap::Signature | nodeDataFromROS (const rtabmap_msgs::Node &msg) |
void | nodeDataToROS (const rtabmap::Signature &signature, rtabmap_msgs::Node &msg) |
rtabmap::Signature | nodeFromROS (const rtabmap_msgs::Node &msg) |
rtabmap::Signature | nodeInfoFromROS (const rtabmap_msgs::Node &msg) |
void | nodeInfoToROS (const rtabmap::Signature &signature, rtabmap_msgs::Node &msg) |
void | nodeToROS (const rtabmap::Signature &signature, rtabmap_msgs::Node &msg) |
rtabmap::OdometryInfo | odomInfoFromROS (const rtabmap_msgs::OdomInfo &msg, bool ignoreData=false) |
void | odomInfoToROS (const rtabmap::OdometryInfo &info, rtabmap_msgs::OdomInfo &msg, bool ignoreData=false) |
std::map< std::string, float > | odomInfoToStatistics (const rtabmap::OdometryInfo &info) |
cv::Point2f | point2fFromROS (const rtabmap_msgs::Point2f &msg) |
void | point2fToROS (const cv::Point2f &kpt, rtabmap_msgs::Point2f &msg) |
cv::Point3f | point3fFromROS (const rtabmap_msgs::Point3f &msg) |
void | point3fToROS (const cv::Point3f &pt, rtabmap_msgs::Point3f &msg) |
std::vector< cv::Point2f > | points2fFromROS (const std::vector< rtabmap_msgs::Point2f > &msg) |
void | points2fToROS (const std::vector< cv::Point2f > &kpts, std::vector< rtabmap_msgs::Point2f > &msg) |
std::vector< cv::Point3f > | points3fFromROS (const std::vector< rtabmap_msgs::Point3f > &msg, const rtabmap::Transform &transform=rtabmap::Transform()) |
void | points3fFromROS (const std::vector< rtabmap_msgs::Point3f > &msg, std::vector< cv::Point3f > &points3, const rtabmap::Transform &transform=rtabmap::Transform()) |
void | points3fToROS (const std::vector< cv::Point3f > &pts, std::vector< rtabmap_msgs::Point3f > &msg, const rtabmap::Transform &transform=rtabmap::Transform()) |
rtabmap::SensorData | rgbdImageFromROS (const rtabmap_msgs::RGBDImageConstPtr &image) |
void | rgbdImageToROS (const rtabmap::SensorData &data, rtabmap_msgs::RGBDImage &msg, const std::string &sensorFrameId) |
rtabmap::SensorData | sensorDataFromROS (const rtabmap_msgs::SensorData &msg) |
void | sensorDataToROS (const rtabmap::SensorData &signature, rtabmap_msgs::SensorData &msg, const std::string &frameId="base_link", bool copyRawData=false) |
rtabmap::StereoCameraModel | stereoCameraModelFromROS (const sensor_msgs::CameraInfo &leftCamInfo, const sensor_msgs::CameraInfo &rightCamInfo, const rtabmap::Transform &localTransform=rtabmap::Transform::getIdentity(), const rtabmap::Transform &stereoTransform=rtabmap::Transform()) |
rtabmap::StereoCameraModel | stereoCameraModelFromROS (const sensor_msgs::CameraInfo &leftCamInfo, const sensor_msgs::CameraInfo &rightCamInfo, const std::string &frameId, tf::TransformListener &listener, double waitForTransform) |
double | timestampFromROS (const ros::Time &stamp) |
void | toCvCopy (const rtabmap_msgs::RGBDImage &image, cv_bridge::CvImagePtr &rgb, cv_bridge::CvImagePtr &depth) |
void | toCvShare (const rtabmap_msgs::RGBDImage &image, const boost::shared_ptr< void const > &trackedObject, cv_bridge::CvImageConstPtr &rgb, cv_bridge::CvImageConstPtr &depth) |
void | toCvShare (const rtabmap_msgs::RGBDImageConstPtr &image, cv_bridge::CvImageConstPtr &rgb, cv_bridge::CvImageConstPtr &depth) |
rtabmap::Transform | transformFromGeometryMsg (const geometry_msgs::Transform &msg) |
rtabmap::Transform | transformFromPoseMsg (const geometry_msgs::Pose &msg, bool ignoreRotationIfNotSet=false) |
rtabmap::Transform | transformFromTF (const tf::Transform &transform) |
void | transformToGeometryMsg (const rtabmap::Transform &transform, geometry_msgs::Transform &msg) |
void | transformToPoseMsg (const rtabmap::Transform &transform, geometry_msgs::Pose &msg) |
void | transformToTF (const rtabmap::Transform &transform, tf::Transform &tfTransform) |
cv::Mat | userDataFromROS (const rtabmap_msgs::UserData &dataMsg) |
void | userDataToROS (const cv::Mat &data, rtabmap_msgs::UserData &dataMsg, bool compress) |
rtabmap::CameraModel rtabmap_conversions::cameraModelFromROS | ( | const sensor_msgs::CameraInfo & | camInfo, |
const rtabmap::Transform & | localTransform = rtabmap::Transform::getIdentity() |
||
) |
Definition at line 795 of file MsgConversion.cpp.
void rtabmap_conversions::cameraModelToROS | ( | const rtabmap::CameraModel & | model, |
sensor_msgs::CameraInfo & | camInfo | ||
) |
Definition at line 869 of file MsgConversion.cpp.
cv::Mat rtabmap_conversions::compressedMatFromBytes | ( | const std::vector< unsigned char > & | bytes, |
bool | copy = true |
||
) |
Definition at line 444 of file MsgConversion.cpp.
void rtabmap_conversions::compressedMatToBytes | ( | const cv::Mat & | compressed, |
std::vector< unsigned char > & | bytes | ||
) |
Definition at line 433 of file MsgConversion.cpp.
bool rtabmap_conversions::convertRGBDMsgs | ( | const std::vector< cv_bridge::CvImageConstPtr > & | imageMsgs, |
const std::vector< cv_bridge::CvImageConstPtr > & | depthMsgs, | ||
const std::vector< sensor_msgs::CameraInfo > & | cameraInfoMsgs, | ||
const std::vector< sensor_msgs::CameraInfo > & | depthCameraInfoMsgs, | ||
const std::string & | frameId, | ||
const std::string & | odomFrameId, | ||
const ros::Time & | odomStamp, | ||
cv::Mat & | rgb, | ||
cv::Mat & | depth, | ||
std::vector< rtabmap::CameraModel > & | cameraModels, | ||
std::vector< rtabmap::StereoCameraModel > & | stereoCameraModels, | ||
tf::TransformListener & | listener, | ||
double | waitForTransform, | ||
bool | alreadRectifiedImages, | ||
const std::vector< std::vector< rtabmap_msgs::KeyPoint > > & | localKeyPointsMsgs = std::vector<std::vector<rtabmap_msgs::KeyPoint> >() , |
||
const std::vector< std::vector< rtabmap_msgs::Point3f > > & | localPoints3dMsgs = std::vector<std::vector<rtabmap_msgs::Point3f> >() , |
||
const std::vector< cv::Mat > & | localDescriptorsMsgs = std::vector<cv::Mat>() , |
||
std::vector< cv::KeyPoint > * | localKeyPoints = 0 , |
||
std::vector< cv::Point3f > * | localPoints3d = 0 , |
||
cv::Mat * | localDescriptors = 0 |
||
) |
Definition at line 2042 of file MsgConversion.cpp.
bool rtabmap_conversions::convertScan3dMsg | ( | const sensor_msgs::PointCloud2 & | scan3dMsg, |
const std::string & | frameId, | ||
const std::string & | odomFrameId, | ||
const ros::Time & | odomStamp, | ||
rtabmap::LaserScan & | scan, | ||
tf::TransformListener & | listener, | ||
double | waitForTransform, | ||
int | maxPoints = 0 , |
||
float | maxRange = 0.0f , |
||
bool | is2D = false |
||
) |
Definition at line 2751 of file MsgConversion.cpp.
bool rtabmap_conversions::convertScanMsg | ( | const sensor_msgs::LaserScan & | scan2dMsg, |
const std::string & | frameId, | ||
const std::string & | odomFrameId, | ||
const ros::Time & | odomStamp, | ||
rtabmap::LaserScan & | scan, | ||
tf::TransformListener & | listener, | ||
double | waitForTransform, | ||
bool | outputInFrameId = false |
||
) |
Definition at line 2592 of file MsgConversion.cpp.
bool rtabmap_conversions::convertStereoMsg | ( | const cv_bridge::CvImageConstPtr & | leftImageMsg, |
const cv_bridge::CvImageConstPtr & | rightImageMsg, | ||
const sensor_msgs::CameraInfo & | leftCamInfoMsg, | ||
const sensor_msgs::CameraInfo & | rightCamInfoMsg, | ||
const std::string & | frameId, | ||
const std::string & | odomFrameId, | ||
const ros::Time & | odomStamp, | ||
cv::Mat & | left, | ||
cv::Mat & | right, | ||
rtabmap::StereoCameraModel & | stereoModel, | ||
tf::TransformListener & | listener, | ||
double | waitForTransform, | ||
bool | alreadyRectified | ||
) |
Definition at line 2435 of file MsgConversion.cpp.
bool rtabmap_conversions::deskew | ( | const sensor_msgs::PointCloud2 & | input, |
sensor_msgs::PointCloud2 & | output, | ||
const std::string & | fixedFrameId, | ||
tf::TransformListener & | listener, | ||
double | waitForTransform, | ||
bool | slerp = false |
||
) |
Definition at line 3395 of file MsgConversion.cpp.
bool rtabmap_conversions::deskew | ( | const sensor_msgs::PointCloud2 & | input, |
sensor_msgs::PointCloud2 & | output, | ||
double | previousStamp, | ||
const rtabmap::Transform & | velocity | ||
) |
Definition at line 3406 of file MsgConversion.cpp.
bool rtabmap_conversions::deskew_impl | ( | const sensor_msgs::PointCloud2 & | input, |
sensor_msgs::PointCloud2 & | output, | ||
const std::string & | fixedFrameId, | ||
tf::TransformListener * | listener, | ||
double | waitForTransform, | ||
bool | slerp, | ||
const rtabmap::Transform & | velocity, | ||
double | previousStamp | ||
) |
Definition at line 2798 of file MsgConversion.cpp.
rtabmap::EnvSensor rtabmap_conversions::envSensorFromROS | ( | const rtabmap_msgs::EnvSensor & | msg | ) |
Definition at line 665 of file MsgConversion.cpp.
rtabmap::EnvSensors rtabmap_conversions::envSensorsFromROS | ( | const std::vector< rtabmap_msgs::EnvSensor > & | msg | ) |
Definition at line 677 of file MsgConversion.cpp.
void rtabmap_conversions::envSensorsToROS | ( | const rtabmap::EnvSensors & | sensors, |
std::vector< rtabmap_msgs::EnvSensor > & | msg | ||
) |
Definition at line 691 of file MsgConversion.cpp.
void rtabmap_conversions::envSensorToROS | ( | const rtabmap::EnvSensor & | sensor, |
rtabmap_msgs::EnvSensor & | msg | ||
) |
Definition at line 670 of file MsgConversion.cpp.
rtabmap::Transform rtabmap_conversions::getMovingTransform | ( | const std::string & | movingFrame, |
const std::string & | fixedFrame, | ||
const ros::Time & | stampFrom, | ||
const ros::Time & | stampTo, | ||
tf::TransformListener & | listener, | ||
double | waitForTransform | ||
) |
Definition at line 2007 of file MsgConversion.cpp.
rtabmap::Transform rtabmap_conversions::getTransform | ( | const std::string & | fromFrameId, |
const std::string & | toFrameId, | ||
const ros::Time & | stamp, | ||
tf::TransformListener & | listener, | ||
double | waitForTransform | ||
) |
Definition at line 1971 of file MsgConversion.cpp.
rtabmap::GlobalDescriptor rtabmap_conversions::globalDescriptorFromROS | ( | const rtabmap_msgs::GlobalDescriptor & | msg | ) |
Definition at line 626 of file MsgConversion.cpp.
std::vector< rtabmap::GlobalDescriptor > rtabmap_conversions::globalDescriptorsFromROS | ( | const std::vector< rtabmap_msgs::GlobalDescriptor > & | msg | ) |
Definition at line 638 of file MsgConversion.cpp.
void rtabmap_conversions::globalDescriptorsToROS | ( | const std::vector< rtabmap::GlobalDescriptor > & | desc, |
std::vector< rtabmap_msgs::GlobalDescriptor > & | msg | ||
) |
Definition at line 652 of file MsgConversion.cpp.
void rtabmap_conversions::globalDescriptorToROS | ( | const rtabmap::GlobalDescriptor & | desc, |
rtabmap_msgs::GlobalDescriptor & | msg | ||
) |
Definition at line 631 of file MsgConversion.cpp.
rtabmap::IMU rtabmap_conversions::imuFromROS | ( | const sensor_msgs::Imu & | msg, |
const rtabmap::Transform & | localTransform = rtabmap::Transform::getIdentity() |
||
) |
Definition at line 1866 of file MsgConversion.cpp.
void rtabmap_conversions::imuToROS | ( | const rtabmap::IMU & | imu, |
sensor_msgs::Imu & | msg | ||
) |
Definition at line 1877 of file MsgConversion.cpp.
void rtabmap_conversions::infoFromROS | ( | const rtabmap_msgs::Info & | info, |
rtabmap::Statistics & | stat | ||
) |
Definition at line 458 of file MsgConversion.cpp.
void rtabmap_conversions::infoToROS | ( | const rtabmap::Statistics & | stats, |
rtabmap_msgs::Info & | info | ||
) |
Definition at line 526 of file MsgConversion.cpp.
cv::KeyPoint rtabmap_conversions::keypointFromROS | ( | const rtabmap_msgs::KeyPoint & | msg | ) |
Definition at line 580 of file MsgConversion.cpp.
std::vector< cv::KeyPoint > rtabmap_conversions::keypointsFromROS | ( | const std::vector< rtabmap_msgs::KeyPoint > & | msg | ) |
Definition at line 596 of file MsgConversion.cpp.
void rtabmap_conversions::keypointsFromROS | ( | const std::vector< rtabmap_msgs::KeyPoint > & | msg, |
std::vector< cv::KeyPoint > & | kpts, | ||
int | xShift = 0 |
||
) |
Definition at line 606 of file MsgConversion.cpp.
void rtabmap_conversions::keypointsToROS | ( | const std::vector< cv::KeyPoint > & | kpts, |
std::vector< rtabmap_msgs::KeyPoint > & | msg | ||
) |
Definition at line 617 of file MsgConversion.cpp.
void rtabmap_conversions::keypointToROS | ( | const cv::KeyPoint & | kpt, |
rtabmap_msgs::KeyPoint & | msg | ||
) |
Definition at line 585 of file MsgConversion.cpp.
rtabmap::Landmarks rtabmap_conversions::landmarksFromROS | ( | const std::map< int, std::pair< geometry_msgs::PoseWithCovarianceStamped, float > > & | tags, |
const std::string & | frameId, | ||
const std::string & | odomFrameId, | ||
const ros::Time & | odomStamp, | ||
tf::TransformListener & | listener, | ||
double | waitForTransform, | ||
double | defaultLinVariance, | ||
double | defaultAngVariance | ||
) |
Definition at line 1903 of file MsgConversion.cpp.
rtabmap::Link rtabmap_conversions::linkFromROS | ( | const rtabmap_msgs::Link & | msg | ) |
Definition at line 562 of file MsgConversion.cpp.
void rtabmap_conversions::linkToROS | ( | const rtabmap::Link & | link, |
rtabmap_msgs::Link & | msg | ||
) |
Definition at line 568 of file MsgConversion.cpp.
void rtabmap_conversions::mapDataFromROS | ( | const rtabmap_msgs::MapData & | msg, |
std::map< int, rtabmap::Transform > & | poses, | ||
std::multimap< int, rtabmap::Link > & | links, | ||
std::map< int, rtabmap::Signature > & | signatures, | ||
rtabmap::Transform & | mapToOdom | ||
) |
Definition at line 977 of file MsgConversion.cpp.
void rtabmap_conversions::mapDataToROS | ( | const std::map< int, rtabmap::Transform > & | poses, |
const std::multimap< int, rtabmap::Link > & | links, | ||
const std::map< int, rtabmap::Signature > & | signatures, | ||
const rtabmap::Transform & | mapToOdom, | ||
rtabmap_msgs::MapData & | msg | ||
) |
Definition at line 993 of file MsgConversion.cpp.
void rtabmap_conversions::mapGraphFromROS | ( | const rtabmap_msgs::MapGraph & | msg, |
std::map< int, rtabmap::Transform > & | poses, | ||
std::multimap< int, rtabmap::Link > & | links, | ||
rtabmap::Transform & | mapToOdom | ||
) |
Definition at line 1014 of file MsgConversion.cpp.
void rtabmap_conversions::mapGraphToROS | ( | const std::map< int, rtabmap::Transform > & | poses, |
const std::multimap< int, rtabmap::Link > & | links, | ||
const rtabmap::Transform & | mapToOdom, | ||
rtabmap_msgs::MapGraph & | msg | ||
) |
Definition at line 1033 of file MsgConversion.cpp.
rtabmap::Signature rtabmap_conversions::nodeDataFromROS | ( | const rtabmap_msgs::Node & | msg | ) |
Definition at line 1535 of file MsgConversion.cpp.
void rtabmap_conversions::nodeDataToROS | ( | const rtabmap::Signature & | signature, |
rtabmap_msgs::Node & | msg | ||
) |
Definition at line 1539 of file MsgConversion.cpp.
rtabmap::Signature rtabmap_conversions::nodeFromROS | ( | const rtabmap_msgs::Node & | msg | ) |
Definition at line 1399 of file MsgConversion.cpp.
rtabmap::Signature rtabmap_conversions::nodeInfoFromROS | ( | const rtabmap_msgs::Node & | msg | ) |
Definition at line 1544 of file MsgConversion.cpp.
void rtabmap_conversions::nodeInfoToROS | ( | const rtabmap::Signature & | signature, |
rtabmap_msgs::Node & | msg | ||
) |
Definition at line 1556 of file MsgConversion.cpp.
void rtabmap_conversions::nodeToROS | ( | const rtabmap::Signature & | signature, |
rtabmap_msgs::Node & | msg | ||
) |
Definition at line 1463 of file MsgConversion.cpp.
rtabmap::OdometryInfo rtabmap_conversions::odomInfoFromROS | ( | const rtabmap_msgs::OdomInfo & | msg, |
bool | ignoreData = false |
||
) |
Definition at line 1659 of file MsgConversion.cpp.
void rtabmap_conversions::odomInfoToROS | ( | const rtabmap::OdometryInfo & | info, |
rtabmap_msgs::OdomInfo & | msg, | ||
bool | ignoreData = false |
||
) |
Definition at line 1738 of file MsgConversion.cpp.
std::map< std::string, float > rtabmap_conversions::odomInfoToStatistics | ( | const rtabmap::OdometryInfo & | info | ) |
Definition at line 1568 of file MsgConversion.cpp.
cv::Point2f rtabmap_conversions::point2fFromROS | ( | const rtabmap_msgs::Point2f & | msg | ) |
Definition at line 705 of file MsgConversion.cpp.
void rtabmap_conversions::point2fToROS | ( | const cv::Point2f & | kpt, |
rtabmap_msgs::Point2f & | msg | ||
) |
Definition at line 710 of file MsgConversion.cpp.
cv::Point3f rtabmap_conversions::point3fFromROS | ( | const rtabmap_msgs::Point3f & | msg | ) |
Definition at line 735 of file MsgConversion.cpp.
void rtabmap_conversions::point3fToROS | ( | const cv::Point3f & | pt, |
rtabmap_msgs::Point3f & | msg | ||
) |
Definition at line 740 of file MsgConversion.cpp.
std::vector< cv::Point2f > rtabmap_conversions::points2fFromROS | ( | const std::vector< rtabmap_msgs::Point2f > & | msg | ) |
Definition at line 716 of file MsgConversion.cpp.
void rtabmap_conversions::points2fToROS | ( | const std::vector< cv::Point2f > & | kpts, |
std::vector< rtabmap_msgs::Point2f > & | msg | ||
) |
Definition at line 726 of file MsgConversion.cpp.
std::vector< cv::Point3f > rtabmap_conversions::points3fFromROS | ( | const std::vector< rtabmap_msgs::Point3f > & | msg, |
const rtabmap::Transform & | transform = rtabmap::Transform() |
||
) |
Definition at line 747 of file MsgConversion.cpp.
void rtabmap_conversions::points3fFromROS | ( | const std::vector< rtabmap_msgs::Point3f > & | msg, |
std::vector< cv::Point3f > & | points3, | ||
const rtabmap::Transform & | transform = rtabmap::Transform() |
||
) |
Definition at line 762 of file MsgConversion.cpp.
void rtabmap_conversions::points3fToROS | ( | const std::vector< cv::Point3f > & | pts, |
std::vector< rtabmap_msgs::Point3f > & | msg, | ||
const rtabmap::Transform & | transform = rtabmap::Transform() |
||
) |
Definition at line 777 of file MsgConversion.cpp.
rtabmap::SensorData rtabmap_conversions::rgbdImageFromROS | ( | const rtabmap_msgs::RGBDImageConstPtr & | image | ) |
Definition at line 288 of file MsgConversion.cpp.
void rtabmap_conversions::rgbdImageToROS | ( | const rtabmap::SensorData & | data, |
rtabmap_msgs::RGBDImage & | msg, | ||
const std::string & | sensorFrameId | ||
) |
Definition at line 212 of file MsgConversion.cpp.
rtabmap::SensorData rtabmap_conversions::sensorDataFromROS | ( | const rtabmap_msgs::SensorData & | msg | ) |
Definition at line 1064 of file MsgConversion.cpp.
void rtabmap_conversions::sensorDataToROS | ( | const rtabmap::SensorData & | signature, |
rtabmap_msgs::SensorData & | msg, | ||
const std::string & | frameId = "base_link" , |
||
bool | copyRawData = false |
||
) |
Definition at line 1252 of file MsgConversion.cpp.
rtabmap::StereoCameraModel rtabmap_conversions::stereoCameraModelFromROS | ( | const sensor_msgs::CameraInfo & | leftCamInfo, |
const sensor_msgs::CameraInfo & | rightCamInfo, | ||
const rtabmap::Transform & | localTransform = rtabmap::Transform::getIdentity() , |
||
const rtabmap::Transform & | stereoTransform = rtabmap::Transform() |
||
) |
Definition at line 934 of file MsgConversion.cpp.
rtabmap::StereoCameraModel rtabmap_conversions::stereoCameraModelFromROS | ( | const sensor_msgs::CameraInfo & | leftCamInfo, |
const sensor_msgs::CameraInfo & | rightCamInfo, | ||
const std::string & | frameId, | ||
tf::TransformListener & | listener, | ||
double | waitForTransform | ||
) |
Definition at line 946 of file MsgConversion.cpp.
|
inline |
Definition at line 198 of file MsgConversion.h.
void rtabmap_conversions::toCvCopy | ( | const rtabmap_msgs::RGBDImage & | image, |
cv_bridge::CvImagePtr & | rgb, | ||
cv_bridge::CvImagePtr & | depth | ||
) |
Definition at line 136 of file MsgConversion.cpp.
void rtabmap_conversions::toCvShare | ( | const rtabmap_msgs::RGBDImage & | image, |
const boost::shared_ptr< void const > & | trackedObject, | ||
cv_bridge::CvImageConstPtr & | rgb, | ||
cv_bridge::CvImageConstPtr & | depth | ||
) |
Definition at line 171 of file MsgConversion.cpp.
void rtabmap_conversions::toCvShare | ( | const rtabmap_msgs::RGBDImageConstPtr & | image, |
cv_bridge::CvImageConstPtr & | rgb, | ||
cv_bridge::CvImageConstPtr & | depth | ||
) |
Definition at line 166 of file MsgConversion.cpp.
rtabmap::Transform rtabmap_conversions::transformFromGeometryMsg | ( | const geometry_msgs::Transform & | msg | ) |
Definition at line 91 of file MsgConversion.cpp.
rtabmap::Transform rtabmap_conversions::transformFromPoseMsg | ( | const geometry_msgs::Pose & | msg, |
bool | ignoreRotationIfNotSet = false |
||
) |
Definition at line 118 of file MsgConversion.cpp.
rtabmap::Transform rtabmap_conversions::transformFromTF | ( | const tf::Transform & | transform | ) |
Definition at line 64 of file MsgConversion.cpp.
void rtabmap_conversions::transformToGeometryMsg | ( | const rtabmap::Transform & | transform, |
geometry_msgs::Transform & | msg | ||
) |
Definition at line 71 of file MsgConversion.cpp.
void rtabmap_conversions::transformToPoseMsg | ( | const rtabmap::Transform & | transform, |
geometry_msgs::Pose & | msg | ||
) |
Definition at line 106 of file MsgConversion.cpp.
void rtabmap_conversions::transformToTF | ( | const rtabmap::Transform & | transform, |
tf::Transform & | tfTransform | ||
) |
Definition at line 52 of file MsgConversion.cpp.
cv::Mat rtabmap_conversions::userDataFromROS | ( | const rtabmap_msgs::UserData & | dataMsg | ) |
Definition at line 1820 of file MsgConversion.cpp.
void rtabmap_conversions::userDataToROS | ( | const cv::Mat & | data, |
rtabmap_msgs::UserData & | dataMsg, | ||
bool | compress | ||
) |
Definition at line 1844 of file MsgConversion.cpp.