Namespace mrpt::ros2bridge
Detailed Description
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 Conversion functions between ROS 1 <-> MRPT types.
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
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
Classes
Functions
Function mrpt::ros2bridge::fromROS(const sensor_msgs::msg::NavSatFix&, mrpt::obs::CObservationGPS&)
Function mrpt::ros2bridge::fromROS(const sensor_msgs::msg::Image&)
Function mrpt::ros2bridge::fromROS(const sensor_msgs::msg::Imu&, mrpt::obs::CObservationIMU&)
Function mrpt::ros2bridge::fromROS(const geometry_msgs::msg::Pose&)
Function mrpt::ros2bridge::fromROS(const geometry_msgs::msg::PoseWithCovariance&)
Function mrpt::ros2bridge::fromROS(const geometry_msgs::msg::Quaternion&)
Function mrpt::ros2bridge::fromROS(const sensor_msgs::msg::Range&, mrpt::obs::CObservationRange&)
Function mrpt::ros2bridge::toROS(const mrpt::img::CImage&, const std_msgs::msg::Header&)
Function mrpt::ros2bridge::toROS(const mrpt::math::CMatrixDouble33&)
Function mrpt::ros2bridge::toROS(const mrpt::poses::CPose3DPDFGaussianInf&)
Function mrpt::ros2bridge::toROS(const mrpt::poses::CPosePDFGaussian&)
Function mrpt::ros2bridge::toROS(const mrpt::poses::CPosePDFGaussianInf&)
Function mrpt::ros2bridge::toROS(const mrpt::math::CQuaternionDouble&)
Function mrpt::ros2bridge::toROS(const mrpt::system::TTimeStamp&)
Function mrpt::ros2bridge::toROS_Pose(const mrpt::poses::CPose2D&)
Function mrpt::ros2bridge::toROS_Pose(const mrpt::math::TPose2D&)
Function mrpt::ros2bridge::toROS_Pose(const mrpt::poses::CPose3D&)
Function mrpt::ros2bridge::toROS_Pose(const mrpt::math::TPose3D&)
Function mrpt::ros2bridge::toROS_Pose(const mrpt::poses::CPose3DPDFGaussian&)
Function mrpt::ros2bridge::toROS_tfTransform(const mrpt::poses::CPose2D&)
Function mrpt::ros2bridge::toROS_tfTransform(const mrpt::math::TPose2D&)
Function mrpt::ros2bridge::toROS_tfTransform(const mrpt::poses::CPose3D&)
Function mrpt::ros2bridge::toROS_tfTransform(const mrpt::math::TPose3D&)