namespace mrpt::ros2bridge
Overview
ROS message: http://docs.ros.org/api/sensor_msgs/html/msg/NavSatFix.html MRPT message: https://github.com/MRPT/mrpt/blob/master/libs/obs/include/mrpt/obs/CObservationGPS.h.
ROS message : http://docs.ros.org/api/sensor_msgs/html/msg/Range.html MRPT message: https://github.com/MRPT/mrpt/blob/master/libs/obs/include/mrpt/obs/CObservationRange.h.
ROS message: http://docs.ros.org/api/sensor_msgs/html/msg/Imu.html MRPT message: https://github.com/MRPT/mrpt/blob/master/libs/obs/include/mrpt/obs/CObservationIMU.h.
Conversion functions between ROS 1 <-> MRPT types.
namespace ros2bridge { // classes class MapHdl; // global functions bool fromROS(const nav_msgs::msg::OccupancyGrid& src, mrpt::maps::COccupancyGridMap2D& des); bool toROS( const mrpt::maps::COccupancyGridMap2D& src, nav_msgs::msg::OccupancyGrid& msg, const std_msgs::msg::Header& header ); bool toROS(const mrpt::maps::COccupancyGridMap2D& src, nav_msgs::msg::OccupancyGrid& msg); bool fromROS(const sensor_msgs::msg::PointCloud& msg, mrpt::maps::CSimplePointsMap& obj); bool toROS( const mrpt::maps::CSimplePointsMap& obj, const std_msgs::msg::Header& msg_header, sensor_msgs::msg::PointCloud& msg ); bool fromROS(const sensor_msgs::msg::PointCloud2& msg, mrpt::maps::CSimplePointsMap& obj); bool fromROS( const sensor_msgs::msg::PointCloud2& msg, mrpt::maps::CPointsMapXYZI& obj ); bool fromROS( const sensor_msgs::msg::PointCloud2& msg, mrpt::maps::CPointsMapXYZIRT& obj ); bool 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> extractFields(const sensor_msgs::msg::PointCloud2& msg); bool toROS( const mrpt::maps::CSimplePointsMap& obj, const std_msgs::msg::Header& msg_header, sensor_msgs::msg::PointCloud2& msg ); bool toROS( const mrpt::maps::CPointsMapXYZI& obj, const std_msgs::msg::Header& msg_header, sensor_msgs::msg::PointCloud2& msg ); bool toROS( const mrpt::maps::CPointsMapXYZIRT& obj, const std_msgs::msg::Header& msg_header, sensor_msgs::msg::PointCloud2& msg ); bool fromROS(const sensor_msgs::msg::NavSatFix& msg, mrpt::obs::CObservationGPS& obj); bool toROS( const mrpt::obs::CObservationGPS& obj, const std_msgs::msg::Header& msg_header, sensor_msgs::msg::NavSatFix& msg ); mrpt::img::CImage fromROS(const sensor_msgs::msg::Image& i); sensor_msgs::msg::Image toROS(const mrpt::img::CImage& i, const std_msgs::msg::Header& msg_header); bool fromROS(const sensor_msgs::msg::Imu& msg, mrpt::obs::CObservationIMU& obj); bool toROS( const mrpt::obs::CObservationIMU& obj, const std_msgs::msg::Header& msg_header, sensor_msgs::msg::Imu& msg ); bool fromROS(const sensor_msgs::msg::LaserScan& msg, const mrpt::poses::CPose3D& pose, mrpt::obs::CObservation2DRangeScan& obj); bool toROS(const mrpt::obs::CObservation2DRangeScan& obj, sensor_msgs::msg::LaserScan& msg); bool toROS( const mrpt::obs::CObservation2DRangeScan& obj, sensor_msgs::msg::LaserScan& msg, geometry_msgs::msg::Pose& pose ); tf2::Matrix3x3 toROS(const mrpt::math::CMatrixDouble33& src); tf2::Transform toROS_tfTransform(const mrpt::poses::CPose2D& src); geometry_msgs::msg::Pose toROS_Pose(const mrpt::poses::CPose2D& src); tf2::Transform toROS_tfTransform(const mrpt::math::TPose2D& src); geometry_msgs::msg::Pose toROS_Pose(const mrpt::math::TPose2D& src); tf2::Transform toROS_tfTransform(const mrpt::poses::CPose3D& src); geometry_msgs::msg::Pose toROS_Pose(const mrpt::poses::CPose3D& src); tf2::Transform toROS_tfTransform(const mrpt::math::TPose3D& src); geometry_msgs::msg::Pose toROS_Pose(const mrpt::math::TPose3D& src); geometry_msgs::msg::PoseWithCovariance toROS_Pose(const mrpt::poses::CPose3DPDFGaussian& src); geometry_msgs::msg::PoseWithCovariance toROS(const mrpt::poses::CPose3DPDFGaussianInf& src); geometry_msgs::msg::PoseWithCovariance toROS(const mrpt::poses::CPosePDFGaussian& src); geometry_msgs::msg::PoseWithCovariance toROS(const mrpt::poses::CPosePDFGaussianInf& src); geometry_msgs::msg::Quaternion toROS(const mrpt::math::CQuaternionDouble& src); mrpt::poses::CPose3D fromROS(const tf2::Transform& src); mrpt::math::CMatrixDouble33 fromROS(const tf2::Matrix3x3& src); mrpt::poses::CPose3D fromROS(const geometry_msgs::msg::Pose& src); mrpt::poses::CPose3DPDFGaussian fromROS(const geometry_msgs::msg::PoseWithCovariance& src); mrpt::math::CQuaternionDouble fromROS(const geometry_msgs::msg::Quaternion& src); bool fromROS(const sensor_msgs::msg::Range& msg, mrpt::obs::CObservationRange& obj); bool toROS( const mrpt::obs::CObservationRange& obj, const std_msgs::msg::Header& msg_header, sensor_msgs::msg::Range* msg ); bool 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 fromROS(const rclcpp::Time& src); rclcpp::Time toROS(const mrpt::system::TTimeStamp& src); } // namespace ros2bridge