namespace mrpt::ros1bridge
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 ros1bridge { // classes class MapHdl; // global functions bool fromROS(const nav_msgs::OccupancyGrid& src, mrpt::maps::COccupancyGridMap2D& des); bool toROS(const mrpt::maps::COccupancyGridMap2D& src, nav_msgs::OccupancyGrid& msg, const std_msgs::Header& header); bool toROS(const mrpt::maps::COccupancyGridMap2D& src, nav_msgs::OccupancyGrid& msg); bool fromROS(const sensor_msgs::PointCloud& msg, mrpt::maps::CSimplePointsMap& obj); bool toROS( const mrpt::maps::CSimplePointsMap& obj, const std_msgs::Header& msg_header, sensor_msgs::PointCloud& msg ); bool fromROS(const sensor_msgs::PointCloud2& msg, mrpt::maps::CSimplePointsMap& obj); bool fromROS( const sensor_msgs::PointCloud2& msg, mrpt::maps::CPointsMapXYZI& obj ); bool fromROS( const sensor_msgs::PointCloud2& msg, mrpt::maps::CPointsMapXYZIRT& obj ); bool fromROS( const sensor_msgs::PointCloud2& m, mrpt::obs::CObservationRotatingScan& o, const mrpt::poses::CPose3D& sensorPoseOnRobot, unsigned int num_azimuth_divisions = 360 ); std::set<std::string> extractFields(const sensor_msgs::PointCloud2& msg); bool toROS( const mrpt::maps::CSimplePointsMap& obj, const std_msgs::Header& msg_header, sensor_msgs::PointCloud2& msg ); bool toROS( const mrpt::maps::CPointsMapXYZI& obj, const std_msgs::Header& msg_header, sensor_msgs::PointCloud2& msg ); bool fromROS(const sensor_msgs::NavSatFix& msg, mrpt::obs::CObservationGPS& obj); bool toROS( const mrpt::obs::CObservationGPS& obj, const std_msgs::Header& msg_header, sensor_msgs::NavSatFix& msg ); mrpt::img::CImage fromROS(const sensor_msgs::Image& i); sensor_msgs::Image toROS(const mrpt::img::CImage& i, const std_msgs::Header& msg_header); bool fromROS(const sensor_msgs::Imu& msg, mrpt::obs::CObservationIMU& obj); bool toROS(const mrpt::obs::CObservationIMU& obj, const std_msgs::Header& msg_header, sensor_msgs::Imu& msg); bool fromROS(const sensor_msgs::LaserScan& msg, const mrpt::poses::CPose3D& pose, mrpt::obs::CObservation2DRangeScan& obj); bool toROS(const mrpt::obs::CObservation2DRangeScan& obj, sensor_msgs::LaserScan& msg); bool toROS(const mrpt::obs::CObservation2DRangeScan& obj, sensor_msgs::LaserScan& msg, geometry_msgs::Pose& pose); static mrpt::system::VerbosityLevel rosLoggerLvlToMRPTLoggerLvl(log4cxx::LevelPtr lvl); static void mrptToROSLoggerCallback( const std::string& msg, const mrpt::system::VerbosityLevel level, ] const std::string& loggerName, ] const mrpt::system::TTimeStamp timestamp ); tf2::Matrix3x3 toROS(const mrpt::math::CMatrixDouble33& src); tf2::Transform toROS_tfTransform(const mrpt::poses::CPose2D& src); geometry_msgs::Pose toROS_Pose(const mrpt::poses::CPose2D& src); tf2::Transform toROS_tfTransform(const mrpt::math::TPose2D& src); geometry_msgs::Pose toROS_Pose(const mrpt::math::TPose2D& src); tf2::Transform toROS_tfTransform(const mrpt::poses::CPose3D& src); geometry_msgs::Pose toROS_Pose(const mrpt::poses::CPose3D& src); tf2::Transform toROS_tfTransform(const mrpt::math::TPose3D& src); geometry_msgs::Pose toROS_Pose(const mrpt::math::TPose3D& src); geometry_msgs::PoseWithCovariance toROS_Pose(const mrpt::poses::CPose3DPDFGaussian& src); geometry_msgs::PoseWithCovariance toROS(const mrpt::poses::CPose3DPDFGaussianInf& src); geometry_msgs::PoseWithCovariance toROS(const mrpt::poses::CPosePDFGaussian& src); geometry_msgs::PoseWithCovariance toROS(const mrpt::poses::CPosePDFGaussianInf& src); geometry_msgs::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::Pose& src); mrpt::poses::CPose3DPDFGaussian fromROS(const geometry_msgs::PoseWithCovariance& src); mrpt::math::CQuaternionDouble fromROS(const geometry_msgs::Quaternion& src); bool fromROS(const sensor_msgs::Range& msg, mrpt::obs::CObservationRange& obj); bool toROS(const mrpt::obs::CObservationRange& obj, const std_msgs::Header& msg_header, sensor_msgs::Range* msg); bool toROS( const mrpt::obs::CObservationStereoImages& obj, const std_msgs::Header& msg_header, sensor_msgs::Image& left, sensor_msgs::Image& right, stereo_msgs::DisparityImage& disparity ); mrpt::system::TTimeStamp fromROS(const ros::Time& src); ros::Time toROS(const mrpt::system::TTimeStamp& src); } // namespace ros1bridge
Global Functions
static mrpt::system::VerbosityLevel rosLoggerLvlToMRPTLoggerLvl(log4cxx::LevelPtr lvl)
function that converts ROS verbosity level log4cxx::Level to MRPT equivalent MRPT’s VerbosityLevel
static void mrptToROSLoggerCallback( const std::string& msg, const mrpt::system::VerbosityLevel level, ] const std::string& loggerName, ] const mrpt::system::TTimeStamp timestamp )
callback that is called by MRPT mrpt::system::COuputLogger to redirect log messages to ROS logger.
This function has to be inline, otherwise option log4j.logger.ros.package_name will be taken from mrpt_bridge instead of the package from which macro is actually called.