38 nh_private_(nh_private)
40 ROS_INFO(
"Starting ScanToCloudConverter");
54 ROS_INFO(
"Destroying ScanToCloudConverter");
59 PointCloudT::Ptr cloud_msg =
62 cloud_msg->points.resize(scan_msg->ranges.size());
64 for (
unsigned int i = 0; i < scan_msg->ranges.size(); ++i)
66 PointT& p = cloud_msg->points[i];
67 float range = scan_msg->ranges[i];
68 if (range > scan_msg->range_min && range < scan_msg->range_max)
70 float angle = scan_msg->angle_min + i*scan_msg->angle_increment;
72 p.x = range * cos(angle);
73 p.y = range * sin(angle);
80 cloud_msg->width = scan_msg->ranges.size();
81 cloud_msg->height = 1;
82 cloud_msg->is_dense =
false;
void publish(const boost::shared_ptr< M > &message) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void toPCL(const ros::Time &stamp, pcl::uint64_t &pcl_stamp)