polygon_array_angle_likelihood_nodelet.cpp
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2015, 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/or 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 
36 #define BOOST_PARAMETER_MAX_ARITY 7
37 
42 #include <jsk_topic_tools/rosparam_utils.h>
43 
44 namespace jsk_pcl_ros_utils
45 {
47  {
48  DiagnosticNodelet::onInit();
49  if (!pnh_->getParam("target_frame_id", target_frame_id_)) {
50  ROS_ERROR("You need to specify ~target_frame_id");
51  return;
52  }
53  pnh_->param("tf_queue_size", tf_queue_size_, 10);
54  std::vector<double> axis(3);
55  if (!jsk_topic_tools::readVectorParameter(*pnh_, "axis", axis)) {
56  axis[0] = 1;
57  axis[1] = 0;
58  axis[2] = 0;
59  }
60  axis_[0] = axis[0];
61  axis_[1] = axis[1];
62  axis_[2] = axis[2];
64  pub_ = advertise<jsk_recognition_msgs::PolygonArray>(*pnh_, "output", 1);
65  onInitPostProcess();
66  }
67 
69  {
70  sub_.subscribe(*pnh_, "input", 10);
72  sub_,
73  *tf_listener_,
76  tf_filter_->registerCallback(
77  boost::bind(&PolygonArrayAngleLikelihood::likelihood, this, _1));
78  }
79 
81  {
82  sub_.unsubscribe();
83  }
84 
86  const jsk_recognition_msgs::PolygonArray::ConstPtr& msg)
87  {
88  boost::mutex::scoped_lock lock(mutex_);
89  vital_checker_->poke();
90  jsk_recognition_msgs::PolygonArray new_msg(*msg);
91 
92  try
93  {
94  // Resolve tf
95  // ConstPtrmpute position of target_frame_id
96  // respected from msg->header.frame_id
99  target_frame_id_, msg->header.frame_id, msg->header.stamp, transform);
100  Eigen::Affine3f pose;
102 
103  // Use x
104  Eigen::Vector3f reference_axis = pose.rotation() * axis_;
105 
106  double min_distance = DBL_MAX;
107  double max_distance = - DBL_MAX;
108  std::vector<double> distances;
109  for (size_t i = 0; i < msg->polygons.size(); i++) {
112  Eigen::Vector3f n = polygon->getNormal();
113  double distance = std::abs(reference_axis.dot(n));
114  min_distance = std::min(distance, min_distance);
115  max_distance = std::max(distance, max_distance);
116  distances.push_back(distance);
117  }
118 
119  // Normalization
120  for (size_t i = 0; i < distances.size(); i++) {
121  // double normalized_distance
122  // = (distances[i] - min_distance) / (max_distance - min_distance);
123  double likelihood = 1 / (1 + (distances[i] - 1) * (distances[i] - 1));
124 
125  if (msg->likelihood.size() == 0) {
126  new_msg.likelihood.push_back(likelihood);
127  }
128  else {
129  new_msg.likelihood[i] = new_msg.likelihood[i] * likelihood;
130  }
131  }
132  pub_.publish(new_msg);
133  }
134  catch (...)
135  {
136  NODELET_ERROR("Unknown transform error");
137  }
138 
139  }
140 }
141 
jsk_pcl_ros_utils
Definition: add_point_indices.h:51
NODELET_ERROR
#define NODELET_ERROR(...)
msg
msg
jsk_pcl_ros_utils::PolygonArrayAngleLikelihood::pub_
ros::Publisher pub_
Definition: polygon_array_angle_likelihood.h:125
boost::shared_ptr
i
int i
jsk_pcl_ros_utils::PolygonArrayAngleLikelihood::unsubscribe
virtual void unsubscribe()
Definition: polygon_array_angle_likelihood_nodelet.cpp:80
lock
lock
geo_util.h
jsk_pcl_ros_utils::PolygonArrayAngleLikelihood::mutex_
boost::mutex mutex_
Definition: polygon_array_angle_likelihood.h:130
transform
template Halfspace< double > transform(const Halfspace< double > &a, const Transform3< double > &tf)
tf::StampedTransform
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
jsk_pcl_ros_utils::PolygonArrayAngleLikelihood
Definition: polygon_array_angle_likelihood.h:80
message_filters::Subscriber::unsubscribe
void unsubscribe()
pose
pose
polygon_array_angle_likelihood.h
class_list_macros.h
jsk_pcl_ros_utils::PolygonArrayAngleLikelihood::tf_filter_
boost::shared_ptr< tf::MessageFilter< jsk_recognition_msgs::PolygonArray > > tf_filter_
Definition: polygon_array_angle_likelihood.h:126
jsk_pcl_ros_utils::PolygonArrayAngleLikelihood::tf_queue_size_
int tf_queue_size_
Definition: polygon_array_angle_likelihood.h:129
tf::transformTFToEigen
void transformTFToEigen(const tf::Transform &t, Eigen::Affine3f &eigen)
ROS_ERROR
#define ROS_ERROR(...)
_1
boost::arg< 1 > _1
jsk_pcl_ros_utils::PolygonArrayAngleLikelihood::target_frame_id_
std::string target_frame_id_
Definition: polygon_array_angle_likelihood.h:128
jsk_pcl_ros_utils::PolygonArrayAngleLikelihood::tf_listener_
tf::TransformListener * tf_listener_
Definition: polygon_array_angle_likelihood.h:127
pcl_conversion_util.h
distance
template void distance(DistanceTraversalNodeBase< double > *node, BVHFrontList *front_list, int qsize)
jsk_pcl_ros_utils::PolygonArrayAngleLikelihood::likelihood
virtual void likelihood(const jsk_recognition_msgs::PolygonArray::ConstPtr &msg)
Definition: polygon_array_angle_likelihood_nodelet.cpp:85
message_filters::Subscriber::subscribe
void subscribe()
nodelet::Nodelet
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros_utils::PolygonArrayAngleLikelihood, nodelet::Nodelet)
jsk_recognition_utils::Polygon::fromROSMsgPtr
static Polygon::Ptr fromROSMsgPtr(const geometry_msgs::Polygon &polygon)
tf::MessageFilter
jsk_pcl_ros_utils::PolygonArrayAngleLikelihood::axis_
Eigen::Vector3f axis_
Definition: polygon_array_angle_likelihood.h:131
jsk_pcl_ros_utils::PolygonArrayAngleLikelihood::subscribe
virtual void subscribe()
Definition: polygon_array_angle_likelihood_nodelet.cpp:68
jsk_pcl_ros_utils::PolygonArrayAngleLikelihood::onInit
virtual void onInit()
Definition: polygon_array_angle_likelihood_nodelet.cpp:46
jsk_recognition_utils::TfListenerSingleton::getInstance
static tf::TransformListener * getInstance()
tf_listener_singleton.h
tf::Transformer::lookupTransform
void lookupTransform(const std::string &target_frame, const ros::Time &target_time, const std::string &source_frame, const ros::Time &source_time, const std::string &fixed_frame, StampedTransform &transform) const
jsk_pcl_ros_utils::PolygonArrayAngleLikelihood::sub_
message_filters::Subscriber< jsk_recognition_msgs::PolygonArray > sub_
Definition: polygon_array_angle_likelihood.h:124


jsk_pcl_ros_utils
Author(s): Yohei Kakiuchi
autogenerated on Fri May 16 2025 03:11:43