File includes methods for converting CNetworkOfPoses*DInf <=> NetworkOfPoses message types.
More...
|
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 marker_msgs::MarkerDetection &_msg, const mrpt::poses::CPose3D &_pose, mrpt::obs::CObservationBearingRange &_obj) |
|
bool | convert (const marker_msgs::MarkerDetection &_msg, const mrpt::poses::CPose3D &_pose, mrpt::obs::CObservationBeaconRanges &_obj) |
|
void | convert (mrpt_msgs::NetworkOfPoses &ros_graph, const mrpt::graphs::CNetworkOfPoses3DInf_NA &mrpt_graph) |
|
void | get_float_from_field (const sensor_msgs::PointField *field, const unsigned char *data, float &output) |
|
void | mrptToROSLoggerCallback (const std::string &msg, const VerbosityLevel level, const std::string &loggerName, const mrpt::system::TTimeStamp timestamp) |
| callback that is called by MRPT mrpt::utils::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. More...
|
|
void | mrptToROSLoggerCallback_mrpt_15 (const std::string &msg, const VerbosityLevel level, const std::string &loggerName, const mrpt::system::TTimeStamp timestamp, void *userParam) |
|
mrpt::math::TPose3D | p2t (const mrpt::poses::CPose3D &p) |
|
VerbosityLevel | rosLoggerLvlToMRPTLoggerLvl (log4cxx::LevelPtr lvl) |
| function that converts ROS verbosity level log4cxx::Level to MRPT equivalent MRPT's VerbosityLevel More...
|
|
|
bool | convert (const mrpt_msgs::ObservationRangeBeacon &_msg, const mrpt::poses::CPose3D &_pose, mrpt::obs::CObservationBeaconRanges &_obj) |
|
bool | convert (const mrpt::obs::CObservationBeaconRanges &_obj, mrpt_msgs::ObservationRangeBeacon &_msg) |
|
bool | convert (const mrpt::obs::CObservationBeaconRanges &_obj, mrpt_msgs::ObservationRangeBeacon &_msg, geometry_msgs::Pose &_pose) |
|
bool | convert (const mrpt_msgs::ObservationRangeBeacon &_msg, const mrpt::poses::CPose3D &_pose, mrpt::slam::CObservationBeaconRanges &_obj) |
|
bool | convert (const mrpt::slam::CObservationBeaconRanges &_obj, mrpt_msgs::ObservationRangeBeacon &_msg) |
|
bool | convert (const mrpt::slam::CObservationBeaconRanges &_obj, mrpt_msgs::ObservationRangeBeacon &_msg, geometry_msgs::Pose &_pose) |
|
|
bool | convert (const mrpt_msgs::ObservationRangeBearing &_msg, const mrpt::poses::CPose3D &_pose, mrpt::obs::CObservationBearingRange &_obj) |
|
bool | convert (const mrpt::obs::CObservationBearingRange &_obj, mrpt_msgs::ObservationRangeBearing &_msg) |
|
bool | convert (const mrpt::obs::CObservationBearingRange &_obj, mrpt_msgs::ObservationRangeBearing &_msg, geometry_msgs::Pose &_pose) |
|
bool | convert (const sensor_msgs::LaserScan &_msg, const mrpt::poses::CPose3D &_pose, mrpt::obs::CObservation2DRangeScan &_obj) |
|
bool | convert (const mrpt::obs::CObservation2DRangeScan &_obj, sensor_msgs::LaserScan &_msg) |
|
bool | convert (const mrpt::obs::CObservation2DRangeScan &_obj, sensor_msgs::LaserScan &_msg, geometry_msgs::Pose &_pose) |
|
|
bool | convert (const nav_msgs::OccupancyGrid &src, COccupancyGridMap2D &des) |
|
bool | convert (const COccupancyGridMap2D &src, nav_msgs::OccupancyGrid &msg, const std_msgs::Header &header) |
|
bool | convert (const COccupancyGridMap2D &src, nav_msgs::OccupancyGrid &msg) |
|
|
void | convert (const mrpt::graphs::CNetworkOfPoses2D &mrpt_graph, mrpt_msgs::NetworkOfPoses &ros_graph) |
| Convert [MRPT] CNetworkOfPoses*D [ROS] NetworkOfPoses. More...
|
|
void | convert (const mrpt_msgs::NetworkOfPoses &ros_graph, mrpt::graphs::CNetworkOfPoses2DInf &mrpt_graph) |
|
mrpt::poses::CPose3D & | convert (const tf::Transform &_src, mrpt::poses::CPose3D &_des) |
|
mrpt::math::CMatrixDouble33 & | convert (const tf::Matrix3x3 &_src, mrpt::math::CMatrixDouble33 &_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::CPose3DPDFGaussianInf & | convert (const geometry_msgs::PoseWithCovariance &_src, mrpt::poses::CPose3DPDFGaussianInf &_des) |
|
mrpt::poses::CPosePDFGaussian & | convert (const geometry_msgs::PoseWithCovariance &_src, mrpt::poses::CPosePDFGaussian &_des) |
|
mrpt::poses::CPosePDFGaussianInf & | convert (const geometry_msgs::PoseWithCovariance &_src, mrpt::poses::CPosePDFGaussianInf &_des) |
|
mrpt::poses::CQuaternionDouble & | convert (const geometry_msgs::Quaternion &_src, mrpt::poses::CQuaternionDouble &_des) |
|
|
bool | copy (const sensor_msgs::PointCloud2 &msg, mrpt::maps::CSimplePointsMap &obj) |
|
bool | copy (const mrpt::maps::CSimplePointsMap &obj, const std_msgs::Header &msg_header, sensor_msgs::PointCloud2 &msg) |
|
|
tf::Matrix3x3 & | convert (const mrpt::math::CMatrixDouble33 &_src, tf::Matrix3x3 &_des) |
|
tf::Transform & | convert (const mrpt::poses::CPose3D &_src, tf::Transform &_des) |
|
tf::Transform & | convert (const mrpt::math::TPose3D &_src, tf::Transform &_des) |
|
tf::Transform & | convert (const mrpt::poses::CPose2D &_src, tf::Transform &_des) |
|
tf::Transform & | convert (const mrpt::math::TPose2D &_src, tf::Transform &_des) |
|
geometry_msgs::Pose & | convert (const mrpt::poses::CPose3D &_src, geometry_msgs::Pose &_des) |
|
geometry_msgs::Pose & | convert (const mrpt::math::TPose2D &_src, geometry_msgs::Pose &_des) |
|
geometry_msgs::Pose & | convert (const mrpt::poses::CPose2D &_src, geometry_msgs::Pose &_des) |
|
geometry_msgs::PoseWithCovariance & | convert (const mrpt::poses::CPose3DPDFGaussian &_src, geometry_msgs::PoseWithCovariance &_des) |
|
geometry_msgs::PoseWithCovariance & | convert (const mrpt::poses::CPose3DPDFGaussianInf &_src, geometry_msgs::PoseWithCovariance &_des) |
|
tf::Transform & | convert (const mrpt::poses::CPose3DPDFGaussian &_src, tf::Transform &_des) |
|
geometry_msgs::PoseWithCovariance & | convert (const mrpt::poses::CPosePDFGaussian &_src, geometry_msgs::PoseWithCovariance &_des) |
|
geometry_msgs::PoseWithCovariance & | convert (const mrpt::poses::CPosePDFGaussianInf &_src, geometry_msgs::PoseWithCovariance &_des) |
|
geometry_msgs::Quaternion & | convert (const mrpt::poses::CQuaternionDouble &_src, geometry_msgs::Quaternion &_des) |
|
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 113 of file point_cloud2.cpp.