pointcloudXYZIR.cc
Go to the documentation of this file.
1 
2 
3 
5 
6 namespace velodyne_pointcloud
7 {
8 
10  const double max_range, const double min_range,
11  const std::string& target_frame, const std::string& fixed_frame,
12  const unsigned int scans_per_block, boost::shared_ptr<tf::TransformListener> tf_ptr)
13  : DataContainerBase(
14  max_range, min_range, target_frame, fixed_frame,
15  0, 1, true, scans_per_block, tf_ptr, 6,
16  "x", 1, sensor_msgs::PointField::FLOAT32,
17  "y", 1, sensor_msgs::PointField::FLOAT32,
18  "z", 1, sensor_msgs::PointField::FLOAT32,
19  "intensity", 1, sensor_msgs::PointField::FLOAT32,
20  "ring", 1, sensor_msgs::PointField::UINT16,
21  "time", 1, sensor_msgs::PointField::FLOAT32),
22  iter_x(cloud, "x"), iter_y(cloud, "y"), iter_z(cloud, "z"),
23  iter_ring(cloud, "ring"), iter_intensity(cloud, "intensity"), iter_time(cloud, "time")
24  {};
25 
26  void PointcloudXYZIR::setup(const velodyne_msgs::VelodyneScan::ConstPtr& scan_msg){
27  DataContainerBase::setup(scan_msg);
34  }
35 
37  {}
38 
39  void PointcloudXYZIR::addPoint(float x, float y, float z, uint16_t ring, uint16_t /*azimuth*/, float distance, float intensity, float time)
40  {
41  if(!pointInRange(distance)) return;
42 
43  // convert polar coordinates to Euclidean XYZ
44 
45  if(config_.transform)
46  transformPoint(x, y, z);
47 
48  *iter_x = x;
49  *iter_y = y;
50  *iter_z = z;
51  *iter_ring = ring;
52  *iter_intensity = intensity;
53  *iter_time = time;
54 
55  ++cloud.width;
56  ++iter_x;
57  ++iter_y;
58  ++iter_z;
59  ++iter_ring;
61  ++iter_time;
62  }
63 }
64 
sensor_msgs::PointCloud2Iterator< float > iter_z
sensor_msgs::PointCloud2Iterator< float > iter_y
sensor_msgs::PointCloud2Iterator< uint16_t > iter_ring
sensor_msgs::PointCloud2Iterator< float > iter_time
virtual void addPoint(float x, float y, float z, const uint16_t ring, const uint16_t azimuth, const float distance, const float intensity, const float time)
sensor_msgs::PointCloud2Iterator< float > iter_x
virtual void setup(const velodyne_msgs::VelodyneScan::ConstPtr &scan_msg)
void transformPoint(float &x, float &y, float &z)
bool transform
enable / disable transform points
PointcloudXYZIR(const double max_range, const double min_range, const std::string &target_frame, const std::string &fixed_frame, const unsigned int scans_per_block, boost::shared_ptr< tf::TransformListener > tf_ptr=boost::shared_ptr< tf::TransformListener >())
sensor_msgs::PointCloud2Iterator< float > iter_intensity


velodyne_pointcloud
Author(s): Jack O'Quin, Piyush Khandelwal, Jesse Vera, Sebastian Pütz
autogenerated on Sun Sep 6 2020 03:25:30