42 #include <sensor_msgs/LaserScan.h>    69     int concurrency_level;
    74     if (concurrency_level == 1)
    84     if (concurrency_level > 0)
    94     if (!target_frame_.empty())
   117       NODELET_INFO(
"Got a subscriber to scan, starting subscriber to pointcloud");
   127       NODELET_INFO(
"No subscibers to scan, shutting down subscriber to pointcloud");
   143     sensor_msgs::LaserScan output;
   144     output.header = cloud_msg->header;
   153     output.time_increment = 0.0;
   159     uint32_t ranges_size = std::ceil((output.angle_max - output.angle_min) / output.angle_increment);
   164       output.ranges.assign(ranges_size, std::numeric_limits<double>::infinity());
   168       output.ranges.assign(ranges_size, output.range_max + 1.0);
   171     sensor_msgs::PointCloud2ConstPtr cloud_out;
   172     sensor_msgs::PointCloud2Ptr cloud;
   175     if (!(output.header.frame_id == cloud_msg->header.frame_id))
   179         cloud.reset(
new sensor_msgs::PointCloud2);
   191       cloud_out = cloud_msg;
   196               iter_x(*cloud_out, 
"x"), iter_y(*cloud_out, 
"y"), iter_z(*cloud_out, 
"z");
   197               iter_x != iter_x.end();
   198               ++iter_x, ++iter_y, ++iter_z)
   201       if (std::isnan(*iter_x) || std::isnan(*iter_y) || std::isnan(*iter_z))
   203         NODELET_DEBUG(
"rejected for nan in point(%f, %f, %f)\n", *iter_x, *iter_y, *iter_z);
   213       double range = 
hypot(*iter_x, *iter_y);
   216         NODELET_DEBUG(
"rejected for range %f below minimum value %f. Point: (%f, %f, %f)", range, 
range_min_, *iter_x, *iter_y,
   222       if (angle < output.angle_min || angle > output.angle_max)
   224         NODELET_DEBUG(
"rejected for angle %f not in range (%f, %f)\n", angle, output.angle_min, output.angle_max);
   229       int index = (angle - output.angle_min) / output.angle_increment;
   230       if (range < output.ranges[index])
   232         output.ranges[index] = range;
 
#define NODELET_WARN_STREAM_THROTTLE(rate,...)
void publish(const boost::shared_ptr< M > &message) const 
TF2SIMD_FORCE_INLINE tf2Scalar angle(const Quaternion &q1, const Quaternion &q2)
boost::shared_ptr< tf2_ros::Buffer > tf2_
ros::NodeHandle & getMTNodeHandle() const 
INLINE Rall1d< T, V, S > hypot(const Rall1d< T, V, S > &y, const Rall1d< T, V, S > &x)
const ros::Subscriber & getSubscriber() const 
ros::NodeHandle & getPrivateNodeHandle() const 
void failureCb(const sensor_msgs::PointCloud2ConstPtr &cloud_msg, tf2_ros::filter_failure_reasons::FilterFailureReason reason)
#define NODELET_ERROR_STREAM(...)
tf2_ros::MessageFilter< sensor_msgs::PointCloud2 > MessageFilter
boost::shared_ptr< MessageFilter > message_filter_
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const 
uint32_t getNumPublishers() const 
PointCloudToLaserScanNodelet()
unsigned int input_queue_size_
ros::NodeHandle private_nh_
std::string target_frame_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::NodeHandle & getNodeHandle() const 
#define NODELET_INFO(...)
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_
uint32_t getNumSubscribers() const 
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
void cloudCb(const sensor_msgs::PointCloud2ConstPtr &cloud_msg)
INLINE Rall1d< T, V, S > atan2(const Rall1d< T, V, S > &y, const Rall1d< T, V, S > &x)
PLUGINLIB_DECLARE_CLASS(pointcloud_to_laserscan, PointCloudToLaserScanNodelet, pointcloud_to_laserscan::PointCloudToLaserScanNodelet, nodelet::Nodelet)
boost::shared_ptr< tf2_ros::TransformListener > tf2_listener_
boost::mutex connect_mutex_
#define NODELET_DEBUG(...)
Connection registerCallback(const C &callback)