organized_cloudXYZIR.cc
Go to the documentation of this file.
1 
3 
4 namespace velodyne_pointcloud
5 {
6 
8  const double max_range, const double min_range,
9  const std::string& target_frame, const std::string& fixed_frame,
10  const unsigned int num_lasers, const unsigned int scans_per_block,
12  : DataContainerBase(
13  max_range, min_range, target_frame, fixed_frame,
14  num_lasers, 0, false, scans_per_block, tf_ptr, 5,
15  "x", 1, sensor_msgs::PointField::FLOAT32,
16  "y", 1, sensor_msgs::PointField::FLOAT32,
17  "z", 1, sensor_msgs::PointField::FLOAT32,
18  "intensity", 1, sensor_msgs::PointField::FLOAT32,
19  "ring", 1, sensor_msgs::PointField::UINT16),
20  iter_x(cloud, "x"), iter_y(cloud, "y"), iter_z(cloud, "z"),
21  iter_intensity(cloud, "intensity"), iter_ring(cloud, "ring")
22  {
23  }
24 
26  {
32  ++cloud.height;
33  }
34 
35  void OrganizedCloudXYZIR::setup(const velodyne_msgs::VelodyneScan::ConstPtr& scan_msg){
36  DataContainerBase::setup(scan_msg);
42  }
43 
44 
45  void OrganizedCloudXYZIR::addPoint(float x, float y, float z,
46  const uint16_t ring, const uint16_t /*azimuth*/, const float distance, const float intensity)
47  {
54  if (pointInRange(distance))
55  {
56  if(config_.transform)
57  transformPoint(x, y, z);
58 
59  *(iter_x+ring) = x;
60  *(iter_y+ring) = y;
61  *(iter_z+ring) = z;
62  *(iter_intensity+ring) = intensity;
63  *(iter_ring+ring) = ring;
64  }
65  else
66  {
67  *(iter_x+ring) = nanf("");
68  *(iter_y+ring) = nanf("");
69  *(iter_z+ring) = nanf("");
70  *(iter_intensity+ring) = nanf("");
71  *(iter_ring+ring) = ring;
72  }
73  }
74 }
75 
virtual void addPoint(float x, float y, float z, const uint16_t ring, const uint16_t azimuth, const float distance, const float intensity)
sensor_msgs::PointCloud2Iterator< float > iter_intensity
virtual void setup(const velodyne_msgs::VelodyneScan::ConstPtr &scan_msg)
sensor_msgs::PointCloud2Iterator< float > iter_x
void transformPoint(float &x, float &y, float &z)
sensor_msgs::PointCloud2Iterator< float > iter_z
bool transform
enable / disable transform points
sensor_msgs::PointCloud2Iterator< float > iter_y
sensor_msgs::PointCloud2Iterator< uint16_t > iter_ring
OrganizedCloudXYZIR(const double max_range, const double min_range, const std::string &target_frame, const std::string &fixed_frame, const unsigned int num_lasers, const unsigned int scans_per_block, boost::shared_ptr< tf::TransformListener > tf_ptr=boost::shared_ptr< tf::TransformListener >())


velodyne_pointcloud
Author(s): Jack O'Quin, Piyush Khandelwal, Jesse Vera, Sebastian Pütz
autogenerated on Thu Jul 4 2019 19:09:30