normal_direction_filter_nodelet.cpp
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2014, JSK Lab
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/o2r other materials provided
17  * with the distribution.
18  * * Neither the name of the JSK Lab nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
40 
41 namespace jsk_pcl_ros
42 {
44  {
45  DiagnosticNodelet::onInit();
46  pnh_->param("use_imu", use_imu_, false);
47  if (!use_imu_) {
48  std::vector<double> direction;
49  if (!jsk_topic_tools::readVectorParameter(*pnh_, "direction", direction)) {
50  NODELET_ERROR("You need to specify ~direction");
51  return;
52  }
53  jsk_recognition_utils::pointFromVectorToVector<std::vector<double>, Eigen::Vector3f>(
54  direction, static_direction_);
55  }
56  else {
58  }
59 
60  srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
61  dynamic_reconfigure::Server<Config>::CallbackType f =
62  boost::bind (
64  srv_->setCallback (f);
65  pnh_->param("queue_size", queue_size_, 200);
66  pub_ = advertise<PCLIndicesMsg>(*pnh_, "output", 1);
68  }
69 
70 
71  void NormalDirectionFilter::configCallback(Config &config, uint32_t level)
72  {
73  boost::mutex::scoped_lock lock(mutex_);
74  eps_angle_ = config.eps_angle;
75  angle_offset_ = config.angle_offset;
76  }
77 
79  {
80  if (!use_imu_) {
81  sub_ = pnh_->subscribe("input", 1, &NormalDirectionFilter::filter, this);
82  }
83  else {
84  sub_input_.subscribe(*pnh_, "input", 1);
85  sub_imu_.subscribe(*pnh_, "input_imu", 1);
86  sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(queue_size_);
87  sync_->connectInput(sub_input_, sub_imu_);
88  sync_->registerCallback(boost::bind(&NormalDirectionFilter::filter, this, _1, _2));
89  }
90  }
91 
93  {
94  if (!use_imu_) {
95  sub_.shutdown();
96  }
97  else {
100  }
101  }
102 
104  const pcl::PointCloud<pcl::Normal>::Ptr& normal_cloud,
105  const Eigen::Vector3f& direction,
106  pcl::PointIndices& indices)
107  {
108  for (size_t i = 0; i < normal_cloud->points.size(); i++) {
109  Eigen::Vector3f normal = normal_cloud->points[i].getNormalVector3fMap().normalized();
110  if (!std::isnan(normal[0]) &&
111  !std::isnan(normal[1]) &&
112  !std::isnan(normal[2])) {
113  double dot = std::abs(normal.dot(direction));
114  if (dot < -1.0) {
115  dot = -1.0;
116  }
117  else if (dot > 1.0) {
118  dot = 1.0;
119  }
120  double angle = acos(dot);
121  double angle_diff = std::abs(angle - angle_offset_);
122  if (angle_diff < eps_angle_) {
123  indices.indices.push_back(i);
124  }
125  }
126  }
127  }
128 
130  const sensor_msgs::PointCloud2::ConstPtr& msg,
131  const sensor_msgs::Imu::ConstPtr& imu_msg)
132  {
133  boost::mutex::scoped_lock lock(mutex_);
134  vital_checker_->poke();
135  pcl::PointCloud<pcl::Normal>::Ptr normal(new pcl::PointCloud<pcl::Normal>);
136  pcl::fromROSMsg(*msg, *normal);
137  geometry_msgs::Vector3Stamped stamped_imu, transformed_imu;
138  stamped_imu.header = imu_msg->header;
139  stamped_imu.vector = imu_msg->linear_acceleration;
140  try
141  {
142  tf_listener_->waitForTransform(msg->header.frame_id, imu_msg->header.frame_id, imu_msg->header.stamp,
143  ros::Duration(0.1));
145  msg->header.frame_id, stamped_imu, transformed_imu);
146  Eigen::Vector3d imu_vectord;
147  Eigen::Vector3f imu_vector;
148  tf::vectorMsgToEigen(transformed_imu.vector, imu_vectord);
149  jsk_recognition_utils::pointFromVectorToVector<Eigen::Vector3d, Eigen::Vector3f>(
150  imu_vectord, imu_vector);
151  imu_vector.normalize();
152  pcl::PointIndices indices;
153  filterIndices(normal, imu_vector, indices);
154  pcl_msgs::PointIndices ros_indices;
155  pcl_conversions::fromPCL(indices, ros_indices);
156  ros_indices.header = msg->header;
157  pub_.publish(ros_indices);
158  }
159  catch (tf2::ConnectivityException &e)
160  {
161  NODELET_ERROR("[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
162  }
164  {
165  NODELET_ERROR("[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
166  }
167  catch (tf2::ExtrapolationException &e)
168  {
169  NODELET_ERROR("[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
170  }
171  }
172 
174  const sensor_msgs::PointCloud2::ConstPtr& msg)
175  {
176  boost::mutex::scoped_lock lock(mutex_);
177  vital_checker_->poke();
178  pcl::PointCloud<pcl::Normal>::Ptr normal(new pcl::PointCloud<pcl::Normal>);
179  pcl::fromROSMsg(*msg, *normal);
180 
181  pcl::PointIndices indices;
182  filterIndices(normal, static_direction_, indices);
183  pcl_msgs::PointIndices ros_indices;
184  pcl_conversions::fromPCL(indices, ros_indices);
185  ros_indices.header = msg->header;
186  pub_.publish(ros_indices);
187  }
188 
189 }
190 
virtual void configCallback(Config &config, uint32_t level)
virtual void filterIndices(const pcl::PointCloud< pcl::Normal >::Ptr &normal, const Eigen::Vector3f &direction, pcl::PointIndices &indices)
#define NODELET_ERROR(...)
void publish(const boost::shared_ptr< M > &message) const
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
T dot(T *pf1, T *pf2, int length)
bool readVectorParameter(ros::NodeHandle &nh, const std::string &param_name, std::vector< double > &result)
bool waitForTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration &timeout, const ros::Duration &polling_sleep_duration=ros::Duration(0.01), std::string *error_msg=NULL) const
message_filters::Subscriber< sensor_msgs::Imu > sub_imu_
void vectorMsgToEigen(const geometry_msgs::Vector3 &m, Eigen::Vector3d &e)
GLfloat angle
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_
boost::shared_ptr< ros::NodeHandle > pnh_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::NormalDirectionFilter, nodelet::Nodelet)
jsk_topic_tools::VitalChecker::Ptr vital_checker_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
INLINE Rall1d< T, V, S > acos(const Rall1d< T, V, S > &x)
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)
virtual void filter(const sensor_msgs::PointCloud2::ConstPtr &msg)
static tf::TransformListener * getInstance()
void transformVector(const std::string &target_frame, const geometry_msgs::Vector3Stamped &stamped_in, geometry_msgs::Vector3Stamped &stamped_out) const
std_msgs::Header fromPCL(const pcl::PCLHeader &pcl_header)


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Mon May 3 2021 03:03:47