pointcloudXYZIRT.cc
Go to the documentation of this file.
1 
2 
3 
5 
6 namespace velodyne_pointcloud
7 {
9  const double max_range, const double min_range,
10  const std::string& target_frame, const std::string& fixed_frame,
11  const unsigned int scans_per_block)
12  : DataContainerBase(
13  max_range, min_range, target_frame, fixed_frame,
14  0, 1, true, scans_per_block, 6,
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  "time", 1, sensor_msgs::PointField::FLOAT32),
21  iter_x(cloud, "x"), iter_y(cloud, "y"), iter_z(cloud, "z"),
22  iter_ring(cloud, "ring"), iter_intensity(cloud, "intensity"), iter_time(cloud, "time")
23  {};
24 
25  void PointcloudXYZIRT::setup(const velodyne_msgs::VelodyneScan::ConstPtr& scan_msg){
26  DataContainerBase::setup(scan_msg);
33  }
34 
36  {}
37 
38  void PointcloudXYZIRT::addPoint(float x, float y, float z, uint16_t ring, uint16_t /*azimuth*/, float distance, float intensity, float time)
39  {
40  if(!pointInRange(distance)) return;
41 
42  // convert polar coordinates to Euclidean XYZ
43 
44  transformPoint(x, y, z);
45 
46  *iter_x = x;
47  *iter_y = y;
48  *iter_z = z;
49  *iter_ring = ring;
50  *iter_intensity = intensity;
51  *iter_time = time;
52 
53  ++cloud.width;
54  ++iter_x;
55  ++iter_y;
56  ++iter_z;
57  ++iter_ring;
59  ++iter_time;
60  }
61 }
62 
velodyne_pointcloud
Definition: calibration.h:40
velodyne_pointcloud::PointcloudXYZIRT::iter_intensity
sensor_msgs::PointCloud2Iterator< float > iter_intensity
Definition: pointcloudXYZIRT.h:54
velodyne_pointcloud::PointcloudXYZIRT::setup
virtual void setup(const velodyne_msgs::VelodyneScan::ConstPtr &scan_msg)
Definition: pointcloudXYZIRT.cc:25
velodyne_rawdata::DataContainerBase::transformPoint
void transformPoint(float &x, float &y, float &z)
Definition: datacontainerbase.h:244
velodyne_pointcloud::PointcloudXYZIRT::addPoint
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)
Definition: pointcloudXYZIRT.cc:38
pointcloudXYZIRT.h
sensor_msgs::PointCloud2Iterator< float >
velodyne_rawdata::DataContainerBase::cloud
sensor_msgs::PointCloud2 cloud
Definition: datacontainerbase.h:185
velodyne_pointcloud::PointcloudXYZIRT::newLine
virtual void newLine()
Definition: pointcloudXYZIRT.cc:35
velodyne_pointcloud::PointcloudXYZIRT::iter_y
sensor_msgs::PointCloud2Iterator< float > iter_y
Definition: pointcloudXYZIRT.h:54
velodyne_rawdata::DataContainerBase::pointInRange
bool pointInRange(float range)
Definition: datacontainerbase.h:260
velodyne_pointcloud::PointcloudXYZIRT::PointcloudXYZIRT
PointcloudXYZIRT(const double max_range, const double min_range, const std::string &target_frame, const std::string &fixed_frame, const unsigned int scans_per_block)
Definition: pointcloudXYZIRT.cc:8
velodyne_pointcloud::PointcloudXYZIRT::iter_ring
sensor_msgs::PointCloud2Iterator< uint16_t > iter_ring
Definition: pointcloudXYZIRT.h:55
velodyne_pointcloud::PointcloudXYZIRT::iter_z
sensor_msgs::PointCloud2Iterator< float > iter_z
Definition: pointcloudXYZIRT.h:54
velodyne_pointcloud::PointcloudXYZIRT::iter_x
sensor_msgs::PointCloud2Iterator< float > iter_x
Definition: pointcloudXYZIRT.h:54
velodyne_pointcloud::PointcloudXYZIRT::iter_time
sensor_msgs::PointCloud2Iterator< float > iter_time
Definition: pointcloudXYZIRT.h:54
sensor_msgs


velodyne_pointcloud
Author(s): Jack O'Quin, Piyush Khandelwal, Jesse Vera, Sebastian Pütz
autogenerated on Sun Jun 2 2024 02:29:13