Namespaces | Classes | Functions
mrpt_bridge Namespace Reference

Namespaces

namespace  point_cloud

Classes

class  MapHdl
 the map class is implemented as singeleton use map::instance ()->ros2mrpt ... More...

Functions

bool check_field (const sensor_msgs::PointField &input_field, std::string check_name, const sensor_msgs::PointField **output)
void convert (const ros::Time &src, mrpt::system::TTimeStamp &des)
void convert (const mrpt::system::TTimeStamp &src, ros::Time &des)
bool convert (const sensor_msgs::LaserScan &_msg, const mrpt::poses::CPose3D &_pose, mrpt::slam::CObservation2DRangeScan &_obj)
mrpt::math::CMatrixDouble33convert (const tf::Matrix3x3 &_src, mrpt::math::CMatrixDouble33 &_des)
bool convert (const mrpt::slam::CObservation2DRangeScan &_obj, sensor_msgs::LaserScan &_msg)
tf::Matrix3x3convert (const mrpt::math::CMatrixDouble33 &_src, tf::Matrix3x3 &_des)
tf::Transformconvert (const mrpt::poses::CPose3D &_src, tf::Transform &_des)
bool convert (const mrpt::slam::CObservation2DRangeScan &_obj, sensor_msgs::LaserScan &_msg, geometry_msgs::Pose &_pose)
mrpt::poses::CPose3D & convert (const tf::Transform &_src, mrpt::poses::CPose3D &_des)
geometry_msgs::Poseconvert (const mrpt::poses::CPose3D &_src, geometry_msgs::Pose &_des)
geometry_msgs::Poseconvert (const mrpt::poses::CPose2D &_src, geometry_msgs::Pose &_des)
geometry_msgs::PoseWithCovarianceconvert (const mrpt::poses::CPose3DPDFGaussian &_src, geometry_msgs::PoseWithCovariance &_des)
tf::Transformconvert (const mrpt::poses::CPose3DPDFGaussian &_src, tf::Transform &)
geometry_msgs::PoseWithCovarianceconvert (const mrpt::poses::CPosePDFGaussian &_src, geometry_msgs::PoseWithCovariance &_des)
geometry_msgs::Quaternionconvert (const mrpt::poses::CQuaternionDouble &_src, geometry_msgs::Quaternion &_des)
mrpt::poses::CPose2D & convert (const geometry_msgs::Pose &_src, mrpt::poses::CPose2D &_des)
mrpt::poses::CPose3D & convert (const geometry_msgs::Pose &_src, mrpt::poses::CPose3D &_des)
mrpt::poses::CPose3DPDFGaussian & convert (const geometry_msgs::PoseWithCovariance &_src, mrpt::poses::CPose3DPDFGaussian &_des)
mrpt::poses::CPosePDFGaussian & convert (const geometry_msgs::PoseWithCovariance &_src, mrpt::poses::CPosePDFGaussian &_des)
mrpt::poses::CQuaternionDoubleconvert (const geometry_msgs::Quaternion &_src, mrpt::poses::CQuaternionDouble &_des)
bool convert (const nav_msgs::OccupancyGrid &src, mrpt::slam::COccupancyGridMap2D &des)
bool convert (const mrpt::slam::COccupancyGridMap2D &src, nav_msgs::OccupancyGrid &msg, const std_msgs::Header &header)
bool convert (const mrpt::slam::COccupancyGridMap2D &src, nav_msgs::OccupancyGrid &msg)
bool copy (const sensor_msgs::PointCloud2 &msg, mrpt::slam::CSimplePointsMap &obj)
bool copy (const mrpt::slam::CSimplePointsMap &obj, const std_msgs::Header &msg_header, sensor_msgs::PointCloud2 &msg)
void get_float_from_field (const sensor_msgs::PointField *field, const unsigned char *data, float &output)

Function Documentation

bool mrpt_bridge::check_field ( const sensor_msgs::PointField &  input_field,
std::string  check_name,
const sensor_msgs::PointField **  output 
) [inline]

Definition at line 11 of file point_cloud2.cpp.

void mrpt_bridge::convert ( const ros::Time src,
mrpt::system::TTimeStamp &  des 
) [inline]

converts ros time to mrpt time

Parameters:
srcros time
desmrpt time

Definition at line 14 of file time.h.

void mrpt_bridge::convert ( const mrpt::system::TTimeStamp &  src,
ros::Time des 
) [inline]

converts mrpt time to ros time

Parameters:
srcros time
desmrpt time

Definition at line 25 of file time.h.

bool mrpt_bridge::convert ( const sensor_msgs::LaserScan &  _msg,
const mrpt::poses::CPose3D &  _pose,
mrpt::slam::CObservation2DRangeScan &  _obj 
)
Returns:
true on sucessful conversion, false on any error.
See also:
mrpt2ros

Definition at line 11 of file laser_scan.cpp.

Convert: ROS's Matrix -> MRPT's Matrix

Definition at line 24 of file pose.cpp.

bool mrpt_bridge::convert ( const mrpt::slam::CObservation2DRangeScan &  _obj,
sensor_msgs::LaserScan &  _msg 
)
Returns:
true on sucessful conversion, false on any error.
See also:
ros2mrpt

Definition at line 34 of file laser_scan.cpp.

Convert: MRPT's Matrix -> Matrix

Definition at line 32 of file pose.cpp.

tf::Transform & mrpt_bridge::convert ( const mrpt::poses::CPose3D &  _src,
tf::Transform _des 
)

Convert: MRPT's CPose3D -> ROS's Transform

Definition at line 64 of file pose.cpp.

bool mrpt_bridge::convert ( const mrpt::slam::CObservation2DRangeScan &  _obj,
sensor_msgs::LaserScan &  _msg,
geometry_msgs::Pose _pose 
)
Returns:
true on sucessful conversion, false on any error.
See also:
ros2mrpt

Definition at line 62 of file laser_scan.cpp.

mrpt::poses::CPose3D & mrpt_bridge::convert ( const tf::Transform _src,
mrpt::poses::CPose3D &  _des 
)

Convert: ROS's CPose3D -> MRPT's Transform

Definition at line 73 of file pose.cpp.

geometry_msgs::Pose & mrpt_bridge::convert ( const mrpt::poses::CPose3D &  _src,
geometry_msgs::Pose _des 
)

Convert: MRPT's CPose3D -> ROS's Pose

Definition at line 83 of file pose.cpp.

geometry_msgs::Pose & mrpt_bridge::convert ( const mrpt::poses::CPose2D &  _src,
geometry_msgs::Pose _des 
)

Convert: MRPT's CPose2D (x,y,yaw) -> ROS's Pose

Definition at line 100 of file pose.cpp.

geometry_msgs::PoseWithCovariance & mrpt_bridge::convert ( const mrpt::poses::CPose3DPDFGaussian &  _src,
geometry_msgs::PoseWithCovariance _des 
)

Convert: MRPT's CPose3DPDFGaussian -> ROS's PoseWithCovariance

Definition at line 44 of file pose.cpp.

tf::Transform & mrpt_bridge::convert ( const mrpt::poses::CPose3DPDFGaussian &  _src,
tf::Transform _des 
)

Convert: MRPT's CPose3DPDFGaussian -> ROS's Transform

Definition at line 40 of file pose.cpp.

geometry_msgs::PoseWithCovariance & mrpt_bridge::convert ( const mrpt::poses::CPosePDFGaussian &  _src,
geometry_msgs::PoseWithCovariance _des 
)

Convert: MRPT's CPosePDFGaussian (x,y,yaw) -> ROS's PoseWithCovariance

Definition at line 142 of file pose.cpp.

Convert: MRPT's CQuaternionDouble -> ROS's Quaternion

Definition at line 203 of file pose.cpp.

mrpt::poses::CPose2D & mrpt_bridge::convert ( const geometry_msgs::Pose _src,
mrpt::poses::CPose2D &  _des 
)

Convert: ROS's Pose -> MRPT's CPose2D

Definition at line 126 of file pose.cpp.

mrpt::poses::CPose3D & mrpt_bridge::convert ( const geometry_msgs::Pose _src,
mrpt::poses::CPose3D &  _des 
)

Convert: ROS's Pose -> MRPT's CPose3D

Definition at line 212 of file pose.cpp.

mrpt::poses::CPose3DPDFGaussian & mrpt_bridge::convert ( const geometry_msgs::PoseWithCovariance _src,
mrpt::poses::CPose3DPDFGaussian &  _des 
)

Convert: ROS's PoseWithCovariance -> MRPT's CPose3DPDFGaussian

Definition at line 168 of file pose.cpp.

mrpt::poses::CPosePDFGaussian & mrpt_bridge::convert ( const geometry_msgs::PoseWithCovariance _src,
mrpt::poses::CPosePDFGaussian &  _des 
)

Convert: ROS's PoseWithCovariance -> MRPT's CPosePDFGaussian (x,y,yaw)

Definition at line 180 of file pose.cpp.

Convert: ROS's Quaternion -> MRPT's CQuaternionDouble

Definition at line 194 of file pose.cpp.

bool mrpt_bridge::convert ( const nav_msgs::OccupancyGrid src,
mrpt::slam::COccupancyGridMap2D &  des 
)

converts ros msg to mrpt object

Returns:
true on sucessful conversion, false on any error.
Parameters:
src
des

I hope the data is allways aligned

I hope the data is allways aligned

Definition at line 57 of file map.cpp.

bool mrpt_bridge::convert ( const mrpt::slam::COccupancyGridMap2D &  src,
nav_msgs::OccupancyGrid msg,
const std_msgs::Header &  header 
)

converts mrpt object to ros msg and updates the msg header

Returns:
true on sucessful conversion, false on any error.
Parameters:
src
des
header

Definition at line 86 of file map.cpp.

bool mrpt_bridge::convert ( const mrpt::slam::COccupancyGridMap2D &  src,
nav_msgs::OccupancyGrid msg 
)

converts mrpt object to ros msg

Returns:
true on sucessful conversion, false on any error.
Parameters:
src
des
header

I hope the data is allways aligned

I hope the data is allways aligned

Definition at line 93 of file map.cpp.

bool mrpt_bridge::copy ( const sensor_msgs::PointCloud2 &  msg,
mrpt::slam::CSimplePointsMap &  obj 
)

Convert sensor_msgs/PointCloud2 -> mrpt::slam::CSimplePointsMap CSimplePointsMap only contains (x,y,z) data, so sensor_msgs::PointCloud2::channels are ignored.

Returns:
true on sucessful conversion, false on any error.
See also:
mrpt2ros

Convert sensor_msgs/PointCloud2 -> mrpt::slam::CSimplePointsMap

Returns:
true on sucessful conversion, false on any error.

Definition at line 49 of file point_cloud2.cpp.

bool mrpt_bridge::copy ( const mrpt::slam::CSimplePointsMap &  obj,
const std_msgs::Header &  msg_header,
sensor_msgs::PointCloud2 &  msg 
)

Convert mrpt::slam::CSimplePointsMap -> sensor_msgs/PointCloud2 The user must supply the "msg_header" field to be copied into the output message object, since that part does not appear in MRPT classes.

Since CSimplePointsMap only contains (x,y,z) data, sensor_msgs::PointCloud2::channels will be empty.

Returns:
true on sucessful conversion, false on any error.
See also:
ros2mrpt

Convert mrpt::slam::CSimplePointsMap -> sensor_msgs/PointCloud2 The user must supply the "msg_header" field to be copied into the output message object, since that part does not appear in MRPT classes.

Since CSimplePointsMap only contains (x,y,z) data, sensor_msgs::PointCloud2::channels will be empty.

Returns:
true on sucessful conversion, false on any error.

Definition at line 94 of file point_cloud2.cpp.

void mrpt_bridge::get_float_from_field ( const sensor_msgs::PointField *  field,
const unsigned char *  data,
float &  output 
) [inline]

Definition at line 31 of file point_cloud2.cpp.



mrpt_bridge
Author(s):
autogenerated on Tue Aug 5 2014 10:58:06