[mrpt-ros2bridge]
Conversion between MRPT and ROS2 types.
Library mrpt-ros2bridge
This C++ library is part of MRPT and can be installed in Debian-based systems with:
sudo apt install libmrpt-ros2bridge-dev
Read also how to import MRPT into your CMake scripts.
Library contents
// classes class mrpt::ros2bridge::MapHdl; // global functions bool mrpt::ros2bridge::fromROS(const nav_msgs::msg::OccupancyGrid& src, mrpt::maps::COccupancyGridMap2D& des); bool mrpt::ros2bridge::toROS( const mrpt::maps::COccupancyGridMap2D& src, nav_msgs::msg::OccupancyGrid& msg, const std_msgs::msg::Header& header ); bool mrpt::ros2bridge::toROS(const mrpt::maps::COccupancyGridMap2D& src, nav_msgs::msg::OccupancyGrid& msg); bool mrpt::ros2bridge::fromROS(const sensor_msgs::msg::PointCloud& msg, mrpt::maps::CSimplePointsMap& obj); bool mrpt::ros2bridge::toROS( const mrpt::maps::CSimplePointsMap& obj, const std_msgs::msg::Header& msg_header, sensor_msgs::msg::PointCloud& msg ); bool mrpt::ros2bridge::fromROS(const sensor_msgs::msg::PointCloud2& msg, mrpt::maps::CSimplePointsMap& obj); bool mrpt::ros2bridge::fromROS( const sensor_msgs::msg::PointCloud2& msg, mrpt::maps::CPointsMapXYZI& obj ); bool mrpt::ros2bridge::fromROS( const sensor_msgs::msg::PointCloud2& m, mrpt::obs::CObservationRotatingScan& o, const mrpt::poses::CPose3D& sensorPoseOnRobot, unsigned int num_azimuth_divisions = 0, float max_intensity = 1000.0f ); std::set<std::string> mrpt::ros2bridge::extractFields(const sensor_msgs::msg::PointCloud2& msg); bool mrpt::ros2bridge::toROS( const mrpt::maps::CSimplePointsMap& obj, const std_msgs::msg::Header& msg_header, sensor_msgs::msg::PointCloud2& msg ); bool mrpt::ros2bridge::toROS( const mrpt::maps::CPointsMapXYZI& obj, const std_msgs::msg::Header& msg_header, sensor_msgs::msg::PointCloud2& msg ); bool mrpt::ros2bridge::fromROS(const sensor_msgs::msg::NavSatFix& msg, mrpt::obs::CObservationGPS& obj); bool mrpt::ros2bridge::toROS( const mrpt::obs::CObservationGPS& obj, const std_msgs::msg::Header& msg_header, sensor_msgs::msg::NavSatFix& msg ); mrpt::img::CImage mrpt::ros2bridge::fromROS(const sensor_msgs::msg::Image& i); sensor_msgs::msg::Image mrpt::ros2bridge::toROS(const mrpt::img::CImage& i, const std_msgs::msg::Header& msg_header); bool mrpt::ros2bridge::fromROS(const sensor_msgs::msg::Imu& msg, mrpt::obs::CObservationIMU& obj); bool mrpt::ros2bridge::toROS( const mrpt::obs::CObservationIMU& obj, const std_msgs::msg::Header& msg_header, sensor_msgs::msg::Imu& msg ); bool mrpt::ros2bridge::fromROS(const sensor_msgs::msg::LaserScan& msg, const mrpt::poses::CPose3D& pose, mrpt::obs::CObservation2DRangeScan& obj); bool mrpt::ros2bridge::toROS(const mrpt::obs::CObservation2DRangeScan& obj, sensor_msgs::msg::LaserScan& msg); bool mrpt::ros2bridge::toROS( const mrpt::obs::CObservation2DRangeScan& obj, sensor_msgs::msg::LaserScan& msg, geometry_msgs::msg::Pose& pose ); tf2::Matrix3x3 mrpt::ros2bridge::toROS(const mrpt::math::CMatrixDouble33& src); tf2::Transform mrpt::ros2bridge::toROS_tfTransform(const mrpt::poses::CPose2D& src); geometry_msgs::msg::Pose mrpt::ros2bridge::toROS_Pose(const mrpt::poses::CPose2D& src); tf2::Transform mrpt::ros2bridge::toROS_tfTransform(const mrpt::math::TPose2D& src); geometry_msgs::msg::Pose mrpt::ros2bridge::toROS_Pose(const mrpt::math::TPose2D& src); tf2::Transform mrpt::ros2bridge::toROS_tfTransform(const mrpt::poses::CPose3D& src); geometry_msgs::msg::Pose mrpt::ros2bridge::toROS_Pose(const mrpt::poses::CPose3D& src); tf2::Transform mrpt::ros2bridge::toROS_tfTransform(const mrpt::math::TPose3D& src); geometry_msgs::msg::Pose mrpt::ros2bridge::toROS_Pose(const mrpt::math::TPose3D& src); geometry_msgs::msg::PoseWithCovariance mrpt::ros2bridge::toROS_Pose(const mrpt::poses::CPose3DPDFGaussian& src); geometry_msgs::msg::PoseWithCovariance mrpt::ros2bridge::toROS(const mrpt::poses::CPose3DPDFGaussianInf& src); geometry_msgs::msg::PoseWithCovariance mrpt::ros2bridge::toROS(const mrpt::poses::CPosePDFGaussian& src); geometry_msgs::msg::PoseWithCovariance mrpt::ros2bridge::toROS(const mrpt::poses::CPosePDFGaussianInf& src); geometry_msgs::msg::Quaternion mrpt::ros2bridge::toROS(const mrpt::math::CQuaternionDouble& src); mrpt::poses::CPose3D mrpt::ros2bridge::fromROS(const tf2::Transform& src); mrpt::math::CMatrixDouble33 mrpt::ros2bridge::fromROS(const tf2::Matrix3x3& src); mrpt::poses::CPose3D mrpt::ros2bridge::fromROS(const geometry_msgs::msg::Pose& src); mrpt::poses::CPose3DPDFGaussian mrpt::ros2bridge::fromROS(const geometry_msgs::msg::PoseWithCovariance& src); mrpt::math::CQuaternionDouble mrpt::ros2bridge::fromROS(const geometry_msgs::msg::Quaternion& src); bool mrpt::ros2bridge::fromROS(const sensor_msgs::msg::Range& msg, mrpt::obs::CObservationRange& obj); bool mrpt::ros2bridge::toROS( const mrpt::obs::CObservationRange& obj, const std_msgs::msg::Header& msg_header, sensor_msgs::msg::Range* msg ); bool mrpt::ros2bridge::toROS( const mrpt::obs::CObservationStereoImages& obj, const std_msgs::msg::Header& msg_header, sensor_msgs::msg::Image& left, sensor_msgs::msg::Image& right, stereo_msgs::msg::DisparityImage& disparity ); mrpt::system::TTimeStamp mrpt::ros2bridge::fromROS(const rclcpp::Time& src); rclcpp::Time mrpt::ros2bridge::toROS(const mrpt::system::TTimeStamp& src);
Global Functions
bool mrpt::ros2bridge::fromROS(const nav_msgs::msg::OccupancyGrid& src, mrpt::maps::COccupancyGridMap2D& des)
converts ros msg to mrpt object
Parameters:
src |
|
des |
Returns:
true on sucessful conversion, false on any error.
bool mrpt::ros2bridge::toROS( const mrpt::maps::COccupancyGridMap2D& src, nav_msgs::msg::OccupancyGrid& msg, const std_msgs::msg::Header& header )
converts mrpt object to ros msg and updates the msg header
Parameters:
src |
|
header |
Returns:
true on sucessful conversion, false on any error.
bool mrpt::ros2bridge::toROS(const mrpt::maps::COccupancyGridMap2D& src, nav_msgs::msg::OccupancyGrid& msg)
converts mrpt object to ros msg
Returns:
true on sucessful conversion, false on any error.
bool mrpt::ros2bridge::fromROS(const sensor_msgs::msg::PointCloud& msg, mrpt::maps::CSimplePointsMap& obj)
Convert sensor_msgs/PointCloud -> mrpt::maps::CSimplePointsMap CSimplePointsMap only contains (x,y,z) data, so sensor_msgs::PointCloud::channels are ignored.
Returns:
true on sucessful conversion, false on any error.
See also:
bool mrpt::ros2bridge::toROS( const mrpt::maps::CSimplePointsMap& obj, const std_msgs::msg::Header& msg_header, sensor_msgs::msg::PointCloud& msg )
Convert mrpt::maps::CSimplePointsMap -> sensor_msgs/PointCloud 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::PointCloud::channels will be empty.
Returns:
true on sucessful conversion, false on any error.
See also:
bool mrpt::ros2bridge::fromROS(const sensor_msgs::msg::PointCloud2& msg, mrpt::maps::CSimplePointsMap& obj)
Convert sensor_msgs/PointCloud2 -> mrpt::slam::CSimplePointsMap Only (x,y,z) data is converted.
Convert sensor_msgs/PointCloud2 -> mrpt::slam::CSimplePointsMap.
To use the intensity channel, see the alternative signature for CPointsMapXYZI. Requires point cloud fields: x,y,z.
Returns:
true on sucessful conversion, false on any error.
true on sucessful conversion, false on any error.
See also:
bool mrpt::ros2bridge::fromROS( const sensor_msgs::msg::PointCloud2& m, mrpt::obs::CObservationRotatingScan& o, const mrpt::poses::CPose3D& sensorPoseOnRobot, unsigned int num_azimuth_divisions = 0, float max_intensity = 1000.0f )
Convert sensor_msgs/PointCloud2 -> mrpt::obs::CObservationRotatingScan.
Requires point cloud fields: x,y,z,ring[,intensity][,time]
If num_azimuth_divisions=0, it will be taken from the point cloud “width” field.
Points are supposed to be given in the sensor frame of reference.
std::set<std::string> mrpt::ros2bridge::extractFields(const sensor_msgs::msg::PointCloud2& msg)
Extract a list of fields found in the point cloud.
Typically: {“x”,”y”,”z”,”intensity”}
bool mrpt::ros2bridge::toROS( const mrpt::maps::CSimplePointsMap& obj, const std_msgs::msg::Header& msg_header, sensor_msgs::msg::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.
Generated sensor_msgs::PointCloud2::channels: x
, y
, z
.
Returns:
true on sucessful conversion, false on any error.
See also:
bool mrpt::ros2bridge::toROS( const mrpt::maps::CPointsMapXYZI& obj, const std_msgs::msg::Header& msg_header, sensor_msgs::msg::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.
Generated sensor_msgs::PointCloud2::channels: x
, y
, z
, intensity
Returns:
true on sucessful conversion, false on any error.
See also:
bool mrpt::ros2bridge::fromROS(const sensor_msgs::msg::NavSatFix& msg, mrpt::obs::CObservationGPS& obj)
Convert sensor_msgs/NavSatFix -> mrpt::obs::CObservationGPS.
Returns:
true on sucessful conversion, false on any error.
bool mrpt::ros2bridge::toROS( const mrpt::obs::CObservationGPS& obj, const std_msgs::msg::Header& msg_header, sensor_msgs::msg::NavSatFix& msg )
Convert mrpt::obs::CObservationGPS -> sensor_msgs/NavSatFix 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 COnservationGPS does not contain “position_covariance” and “position_covariance_type” sensor_msgs::NavSatFix::position_covariance_type and sensor_msgs::NavSatFix::position_covariance will be empty.
Returns:
true on sucessful conversion, false on any error.
mrpt::img::CImage mrpt::ros2bridge::fromROS(const sensor_msgs::msg::Image& i)
Makes a deep copy of the image data.
sensor_msgs::msg::Image mrpt::ros2bridge::toROS( const mrpt::img::CImage& i, const std_msgs::msg::Header& msg_header )
Makes a deep copy of the image data.
bool mrpt::ros2bridge::fromROS(const sensor_msgs::msg::Imu& msg, mrpt::obs::CObservationIMU& obj)
Convert sensor_msgs/Imu -> mrpt::obs::CObservationIMU // STILL NEED TO WRITE CODE FOR COVARIANCE.
Returns:
true on sucessful conversion, false on any error.
bool mrpt::ros2bridge::toROS( const mrpt::obs::CObservationIMU& obj, const std_msgs::msg::Header& msg_header, sensor_msgs::msg::Imu& msg )
Convert mrpt::obs::CObservationIMU -> sensor_msgs/Imu 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 COnservationIMU does not contain covariance terms NEED TO fix those.
Returns:
true on sucessful conversion, false on any error.
bool mrpt::ros2bridge::fromROS( const sensor_msgs::msg::LaserScan& msg, const mrpt::poses::CPose3D& pose, mrpt::obs::CObservation2DRangeScan& obj )
ROS->MRPT: Takes a sensor_msgs::msg::LaserScan and the relative pose of the laser wrt base_link and builds a CObservation2DRangeScan.
Returns:
true on sucessful conversion, false on any error.
See also:
bool mrpt::ros2bridge::toROS(const mrpt::obs::CObservation2DRangeScan& obj, sensor_msgs::msg::LaserScan& msg)
MRPT->ROS: Takes a CObservation2DRangeScan and outputs range data in sensor_msgs::msg::LaserScan.
Returns:
true on sucessful conversion, false on any error.
See also:
bool mrpt::ros2bridge::toROS( const mrpt::obs::CObservation2DRangeScan& obj, sensor_msgs::msg::LaserScan& msg, geometry_msgs::msg::Pose& pose )
MRPT->ROS: Takes a CObservation2DRangeScan and outputs range data in sensor_msgs::msg::LaserScan + the relative pose of the laser wrt base_link.
Returns:
true on sucessful conversion, false on any error.
See also:
bool mrpt::ros2bridge::fromROS(const sensor_msgs::msg::Range& msg, mrpt::obs::CObservationRange& obj)
Convert sensor_msgs/Range -> mrpt::obs::CObservationRange.
Returns:
true on sucessful conversion, false on any error.
bool mrpt::ros2bridge::toROS( const mrpt::obs::CObservationRange& obj, const std_msgs::msg::Header& msg_header, sensor_msgs::msg::Range* msg )
Convert mrpt::obs::CObservationRange -> sensor_msgs/Range 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 COnservation does not contain “radiation_type”, sensor_msgs::msg::Range::radiation_type will be empty.
Returns:
true on sucessful conversion, false on any error.
mrpt::system::TTimeStamp mrpt::ros2bridge::fromROS(const rclcpp::Time& src)
converts ros time to mrpt time
Parameters:
src |
ros time |
des |
mrpt time |
rclcpp::Time mrpt::ros2bridge::toROS(const mrpt::system::TTimeStamp& src)
converts mrpt time to ros time
Parameters:
src |
ros time |
des |
mrpt time |