PointCloudFilter.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2014-2017, Dataspeed Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Dataspeed Inc. nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 #include "PointCloudFilter.h"
37 
39 {
40 
42 {
43  if (!nh.getParam("width", width_)) {
44  width_ = 0.14 * M_PI;
45  }
46  ros::SubscriberStatusCallback connect_cb = boost::bind(&PointCloudFilter::connectCb, this);
47  pub_ = nh.advertise<sensor_msgs::PointCloud2>("points_filtered", 10, connect_cb, connect_cb);
48 }
49 
51 {
52 }
53 
55 {
56  boost::lock_guard<boost::mutex> lock(connect_mutex_);
57  if (!pub_.getNumSubscribers()) {
58  sub_.shutdown();
59  } else if (!sub_) {
60  sub_ = nh_.subscribe("points", 10, &PointCloudFilter::recvCallback, this);
61  }
62 }
63 
64 static inline float normalizeAnglePositive(float angle)
65 {
66  return fmodf(fmodf(angle, 2.0*M_PI) + 2.0*M_PI, 2.0*M_PI);
67 }
68 
69 void PointCloudFilter::recvCallback(const sensor_msgs::PointCloud2Ptr& msg)
70 {
71 #if 0
73 #endif
74 
75  if (width_ == 0.0) {
76  pub_.publish(msg);
77  return;
78  }
79 
80  const float ANGLE_WIDTH = std::min(fabs(width_), M_PI_4);
81  const float ANGLE_START = M_PI_4;
82  const float ANGLE_INC = M_PI_2;
83 
84  // Remove points in the four blind spots. Assumes x, y, and z are consecutive
85 #if 0 // atan2() is slow
86  for (sensor_msgs::PointCloud2Iterator<float> it(*msg, "x"); it != it.end(); it.operator ++()) {
87  const float angle = normalizeAnglePositive(atan2f(it[1], it[0]));
88  for (unsigned int j = 0; j < 4; j++) {
89  const float a1 = ANGLE_START + (j * ANGLE_INC) - (ANGLE_WIDTH / 2);
90  const float a2 = ANGLE_START + (j * ANGLE_INC) + (ANGLE_WIDTH / 2);
91  if ((a2 > angle) && (angle > a1)) {
92  it[2] = NAN; // z
93  break;
94  }
95  }
96  }
97 #elif 1 // unit vector is ~3x faster
98  const float UNIT_X_LOW = cosf(ANGLE_START + (ANGLE_WIDTH / 2));
99  const float UNIT_X_HI = cosf(ANGLE_START - (ANGLE_WIDTH / 2));
100  for (sensor_msgs::PointCloud2Iterator<float> it(*msg, "x"); it != it.end(); it.operator ++()) {
101  const float x = it[0];
102  const float y = it[1];
103  const float unit_x = fabsf(x / sqrtf(x * x + y * y));
104  if ((UNIT_X_HI > unit_x) && (unit_x > UNIT_X_LOW)) {
105  it[2] = NAN; // z
106  }
107  }
108 #endif
109 
110  pub_.publish(msg);
111 
112 #if 0
114  ROS_INFO("PointCloudFilter completed in %04uus", (unsigned int)((toc - tic).toNSec() / 1000));
115 #endif
116 }
117 
118 } // namespace mobility_base_pointcloud_filter
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
void publish(const boost::shared_ptr< M > &message) const
PointCloudFilter(ros::NodeHandle nh, ros::NodeHandle priv_nh)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void recvCallback(const sensor_msgs::PointCloud2Ptr &msg)
#define ROS_INFO(...)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
uint32_t getNumSubscribers() const
static WallTime now()
bool getParam(const std::string &key, std::string &s) const
static float normalizeAnglePositive(float angle)


mobility_base_pointcloud_filter
Author(s): Dataspeed Inc.
autogenerated on Sun Oct 6 2019 03:40:03