30 #ifndef RVIZ_POINT_CLOUD_TRANSFORMER_H 31 #define RVIZ_POINT_CLOUD_TRANSFORMER_H 38 #include <OgreVector3.h> 39 #include <OgreColourValue.h> 77 Support_Color = 1 << 2,
78 Support_Both = Support_XYZ | Support_Color,
85 virtual uint8_t supports(
const sensor_msgs::PointCloud2ConstPtr& cloud) = 0;
94 virtual bool transform(
const sensor_msgs::PointCloud2ConstPtr& cloud,
96 const Ogre::Matrix4& transform,
97 V_PointCloudPoint& out) = 0;
106 virtual uint8_t
score(
const sensor_msgs::PointCloud2ConstPtr& )
124 void needRetransform();
A single element of a property tree, with a name, value, description, and possibly children...
std::vector< PointCloud::Point > V_PointCloudPoint
ROS_DECLARE_MESSAGE(PointCloud2)