16 #include <sensor_msgs/PointCloud2.h> 50 unsigned int num_azimuth_divisions = 360);
55 std::set<std::string>
extractFields(
const sensor_msgs::PointCloud2& msg);
68 sensor_msgs::PointCloud2& msg);
A cloud of points in 2D or 3D, which can be built from a sequence of laser scans. ...
std::set< std::string > extractFields(const sensor_msgs::PointCloud2 &msg)
Extract a list of fields found in the point cloud.
A map of 3D points with reflectance/intensity (float).
bool toROS(const mrpt::obs::CObservationGPS &obj, const std_msgs::Header &msg_header, sensor_msgs::NavSatFix &msg)
Convert mrpt::obs::CObservationGPS -> sensor_msgs/NavSatFix The user must supply the "msg_header" fie...
ROS message: http://docs.ros.org/api/sensor_msgs/html/msg/NavSatFix.html MRPT message: https://github...
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
bool fromROS(const sensor_msgs::NavSatFix &msg, mrpt::obs::CObservationGPS &obj)
Convert sensor_msgs/NavSatFix -> mrpt::obs::CObservationGPS.
A CObservation-derived class for raw range data from a 2D or 3D rotating scanner. ...