Go to the documentation of this file.
   30 #ifndef POINT_CLOUD_TRANSFORMERS_H 
   31 #define POINT_CLOUD_TRANSFORMERS_H 
   33 #include <sensor_msgs/PointCloud2.h> 
   41 class EditableEnumProperty;
 
   45 typedef std::vector<std::string> 
V_string;
 
   47 inline int32_t 
findChannelIndex(
const sensor_msgs::PointCloud2ConstPtr& cloud, 
const std::string& channel)
 
   49   for (
size_t i = 0; i < cloud->fields.size(); ++i)
 
   51     if (cloud->fields[i].name == channel)
 
   67   const uint8_t* data = &cloud->data[(point_step * index) + offset];
 
   72   case sensor_msgs::PointField::INT8:
 
   73   case sensor_msgs::PointField::UINT8:
 
   75     uint8_t val = *
reinterpret_cast<const uint8_t*
>(data);
 
   76     ret = 
static_cast<T
>(val);
 
   80   case sensor_msgs::PointField::INT16:
 
   81   case sensor_msgs::PointField::UINT16:
 
   83     uint16_t val = *
reinterpret_cast<const uint16_t*
>(data);
 
   84     ret = 
static_cast<T
>(val);
 
   88   case sensor_msgs::PointField::INT32:
 
   89   case sensor_msgs::PointField::UINT32:
 
   91     uint32_t val = *
reinterpret_cast<const uint32_t*
>(data);
 
   92     ret = 
static_cast<T
>(val);
 
   96   case sensor_msgs::PointField::FLOAT32:
 
   98     float val = *
reinterpret_cast<const float*
>(data);
 
   99     ret = 
static_cast<T
>(val);
 
  103   case sensor_msgs::PointField::FLOAT64:
 
  105     double val = *
reinterpret_cast<const double*
>(data);
 
  106     ret = 
static_cast<T
>(val);
 
  120   uint8_t 
supports(
const sensor_msgs::PointCloud2ConstPtr& cloud) 
override;
 
  121   bool transform(
const sensor_msgs::PointCloud2ConstPtr& cloud,
 
  125   uint8_t 
score(
const sensor_msgs::PointCloud2ConstPtr& cloud) 
override;
 
  127   void updateChannels(
const sensor_msgs::PointCloud2ConstPtr& cloud);
 
  150   uint8_t 
supports(
const sensor_msgs::PointCloud2ConstPtr& cloud) 
override;
 
  151   bool transform(
const sensor_msgs::PointCloud2ConstPtr& cloud,
 
  162   uint8_t 
supports(
const sensor_msgs::PointCloud2ConstPtr& cloud) 
override;
 
  163   bool transform(
const sensor_msgs::PointCloud2ConstPtr& cloud,
 
  174   bool transform(
const sensor_msgs::PointCloud2ConstPtr& cloud,
 
  185   uint8_t 
supports(
const sensor_msgs::PointCloud2ConstPtr& cloud) 
override;
 
  186   bool transform(
const sensor_msgs::PointCloud2ConstPtr& cloud,
 
  197   uint8_t 
supports(
const sensor_msgs::PointCloud2ConstPtr& cloud) 
override;
 
  198   bool transform(
const sensor_msgs::PointCloud2ConstPtr& cloud,
 
  203   uint8_t 
score(
const sensor_msgs::PointCloud2ConstPtr& cloud) 
override;
 
  213   uint8_t 
supports(
const sensor_msgs::PointCloud2ConstPtr& cloud) 
override;
 
  214   bool transform(
const sensor_msgs::PointCloud2ConstPtr& cloud,
 
  219   uint8_t 
score(
const sensor_msgs::PointCloud2ConstPtr& cloud) 
override;
 
  241 #endif // POINT_CLOUD_TRANSFORMERS_H 
  
int32_t findChannelIndex(const sensor_msgs::PointCloud2ConstPtr &cloud, const std::string &channel)
Property specialized to provide getter for booleans.
std::vector< PointCloud::Point > V_PointCloudPoint
T valueFromCloud(const sensor_msgs::PointCloud2ConstPtr &cloud, uint32_t offset, uint8_t type, uint32_t point_step, uint32_t index)
Property specialized to enforce floating point max/min.
A single element of a property tree, with a name, value, description, and possibly children.
std::vector< std::string > V_string
rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust, William Woodall 
autogenerated on Sun May 4 2025 02:31:26