organized_cloudXYZIRT.cc
Go to the documentation of this file.
1 
3 
4 namespace velodyne_pointcloud
5 {
7  const double max_range, const double min_range,
8  const std::string& target_frame, const std::string& fixed_frame,
9  const unsigned int num_lasers, const unsigned int scans_per_block)
10  : DataContainerBase(
11  max_range, min_range, target_frame, fixed_frame,
12  num_lasers, 0, false, scans_per_block, 6,
13  "x", 1, sensor_msgs::PointField::FLOAT32,
14  "y", 1, sensor_msgs::PointField::FLOAT32,
15  "z", 1, sensor_msgs::PointField::FLOAT32,
16  "intensity", 1, sensor_msgs::PointField::FLOAT32,
17  "ring", 1, sensor_msgs::PointField::UINT16,
18  "time", 1, sensor_msgs::PointField::FLOAT32),
19  iter_x(cloud, "x"), iter_y(cloud, "y"), iter_z(cloud, "z"),
20  iter_intensity(cloud, "intensity"), iter_ring(cloud, "ring"), iter_time(cloud, "time")
21  {
22  }
23 
25  {
32  ++cloud.height;
33  }
34 
35  void OrganizedCloudXYZIRT::setup(const velodyne_msgs::VelodyneScan::ConstPtr& scan_msg){
36  DataContainerBase::setup(scan_msg);
43  }
44 
45 
46  void OrganizedCloudXYZIRT::addPoint(float x, float y, float z,
47  const uint16_t ring, const uint16_t /*azimuth*/, const float distance, const float intensity, const float time)
48  {
55  if (pointInRange(distance))
56  {
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  *(iter_time+ring) = time;
65  }
66  else
67  {
68  *(iter_x+ring) = nanf("");
69  *(iter_y+ring) = nanf("");
70  *(iter_z+ring) = nanf("");
71  *(iter_intensity+ring) = nanf("");
72  *(iter_ring+ring) = ring;
73  *(iter_time+ring) = time;
74  }
75  }
76 }
77 
velodyne_pointcloud
Definition: calibration.h:40
velodyne_pointcloud::OrganizedCloudXYZIRT::iter_intensity
sensor_msgs::PointCloud2Iterator< float > iter_intensity
Definition: organized_cloudXYZIRT.h:57
velodyne_rawdata::DataContainerBase::transformPoint
void transformPoint(float &x, float &y, float &z)
Definition: datacontainerbase.h:244
organized_cloudXYZIRT.h
sensor_msgs::PointCloud2Iterator< float >
velodyne_rawdata::DataContainerBase::cloud
sensor_msgs::PointCloud2 cloud
Definition: datacontainerbase.h:185
velodyne_pointcloud::OrganizedCloudXYZIRT::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: organized_cloudXYZIRT.cc:46
velodyne_pointcloud::OrganizedCloudXYZIRT::OrganizedCloudXYZIRT
OrganizedCloudXYZIRT(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)
Definition: organized_cloudXYZIRT.cc:6
velodyne_rawdata::DataContainerBase::pointInRange
bool pointInRange(float range)
Definition: datacontainerbase.h:260
velodyne_pointcloud::OrganizedCloudXYZIRT::iter_time
sensor_msgs::PointCloud2Iterator< float > iter_time
Definition: organized_cloudXYZIRT.h:57
velodyne_rawdata::DataContainerBase::Config::init_width
unsigned int init_width
Definition: datacontainerbase.h:79
velodyne_pointcloud::OrganizedCloudXYZIRT::setup
virtual void setup(const velodyne_msgs::VelodyneScan::ConstPtr &scan_msg)
Definition: organized_cloudXYZIRT.cc:35
velodyne_rawdata::DataContainerBase::config_
Config config_
Definition: datacontainerbase.h:266
velodyne_pointcloud::OrganizedCloudXYZIRT::iter_ring
sensor_msgs::PointCloud2Iterator< uint16_t > iter_ring
Definition: organized_cloudXYZIRT.h:58
velodyne_pointcloud::OrganizedCloudXYZIRT::iter_z
sensor_msgs::PointCloud2Iterator< float > iter_z
Definition: organized_cloudXYZIRT.h:57
sensor_msgs
velodyne_pointcloud::OrganizedCloudXYZIRT::newLine
virtual void newLine()
Definition: organized_cloudXYZIRT.cc:24
velodyne_pointcloud::OrganizedCloudXYZIRT::iter_x
sensor_msgs::PointCloud2Iterator< float > iter_x
Definition: organized_cloudXYZIRT.h:57
velodyne_pointcloud::OrganizedCloudXYZIRT::iter_y
sensor_msgs::PointCloud2Iterator< float > iter_y
Definition: organized_cloudXYZIRT.h:57


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