polygon_array_distance_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 
43 namespace jsk_pcl_ros_utils
44 {
46  {
47  DiagnosticNodelet::onInit();
48  if (!pnh_->getParam("target_frame_id", target_frame_id_)) {
49  ROS_ERROR("You need to specify ~target_frame_id");
50  return;
51  }
52  pnh_->param("tf_queue_size", tf_queue_size_, 10);
54  pub_ = advertise<jsk_recognition_msgs::PolygonArray>(*pnh_, "output", 1);
55 
56  onInitPostProcess();
57  }
58 
60  {
61  sub_.subscribe(*pnh_, "input", 10);
63  sub_,
64  *tf_listener_,
67  tf_filter_->registerCallback(
68  boost::bind(&PolygonArrayDistanceLikelihood::likelihood, this, _1));
69  }
70 
72  {
73  sub_.unsubscribe();
74  }
75 
77  const jsk_recognition_msgs::PolygonArray::ConstPtr& msg)
78  {
79  boost::mutex::scoped_lock lock(mutex_);
80  vital_checker_->poke();
81  jsk_recognition_msgs::PolygonArray new_msg(*msg);
82 
83  try
84  {
85  // Resolve tf
86  // ConstPtrmpute position of target_frame_id
87  // respected from msg->header.frame_id
90  msg->header.frame_id, target_frame_id_, msg->header.stamp, transform);
91  Eigen::Affine3f pose;
93  Eigen::Vector3f p(pose.translation());
94 
95  double min_distance = DBL_MAX;
96  double max_distance = - DBL_MAX;
97  std::vector<double> distances;
98  for (size_t i = 0; i < msg->polygons.size(); i++) {
101  double distance;
102  polygon->nearestPoint(p, distance);
103  min_distance = std::min(distance, min_distance);
104  max_distance = std::max(distance, max_distance);
105  distances.push_back(distance);
106  }
107 
108  // Normalization
109  for (size_t i = 0; i < distances.size(); i++) {
110  // double normalized_distance
111  // = (distances[i] - min_distance) / (max_distance - min_distance);
112  double likelihood = 1 / (1 + distances[i] * distances[i]);
113 
114  if (msg->likelihood.size() == 0) {
115  new_msg.likelihood.push_back(likelihood);
116  }
117  else {
118  new_msg.likelihood[i] = new_msg.likelihood[i] * likelihood;
119  }
120  }
121  pub_.publish(new_msg);
122  }
123  catch (...)
124  {
125  NODELET_ERROR("Unknown transform error");
126  }
127 
128  }
129 }
130 
jsk_pcl_ros_utils
Definition: add_point_indices.h:51
NODELET_ERROR
#define NODELET_ERROR(...)
msg
msg
boost::shared_ptr
i
int i
jsk_pcl_ros_utils::PolygonArrayDistanceLikelihood::tf_queue_size_
int tf_queue_size_
Definition: polygon_array_distance_likelihood.h:128
p
p
lock
lock
jsk_pcl_ros_utils::PolygonArrayDistanceLikelihood::subscribe
virtual void subscribe()
Definition: polygon_array_distance_likelihood_nodelet.cpp:59
geo_util.h
jsk_pcl_ros_utils::PolygonArrayDistanceLikelihood::tf_listener_
tf::TransformListener * tf_listener_
Definition: polygon_array_distance_likelihood.h:126
jsk_pcl_ros_utils::PolygonArrayDistanceLikelihood::likelihood
virtual void likelihood(const jsk_recognition_msgs::PolygonArray::ConstPtr &msg)
Definition: polygon_array_distance_likelihood_nodelet.cpp:76
transform
template Halfspace< double > transform(const Halfspace< double > &a, const Transform3< double > &tf)
polygon_array_distance_likelihood.h
tf::StampedTransform
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
message_filters::Subscriber::unsubscribe
void unsubscribe()
jsk_pcl_ros_utils::PolygonArrayDistanceLikelihood::unsubscribe
virtual void unsubscribe()
Definition: polygon_array_distance_likelihood_nodelet.cpp:71
pose
pose
class_list_macros.h
jsk_pcl_ros_utils::PolygonArrayDistanceLikelihood::target_frame_id_
std::string target_frame_id_
Definition: polygon_array_distance_likelihood.h:127
jsk_pcl_ros_utils::PolygonArrayDistanceLikelihood
Definition: polygon_array_distance_likelihood.h:79
tf::transformTFToEigen
void transformTFToEigen(const tf::Transform &t, Eigen::Affine3f &eigen)
ROS_ERROR
#define ROS_ERROR(...)
_1
boost::arg< 1 > _1
pcl_conversion_util.h
jsk_pcl_ros_utils::PolygonArrayDistanceLikelihood::sub_
message_filters::Subscriber< jsk_recognition_msgs::PolygonArray > sub_
Definition: polygon_array_distance_likelihood.h:123
distance
template void distance(DistanceTraversalNodeBase< double > *node, BVHFrontList *front_list, int qsize)
jsk_pcl_ros_utils::PolygonArrayDistanceLikelihood::tf_filter_
boost::shared_ptr< tf::MessageFilter< jsk_recognition_msgs::PolygonArray > > tf_filter_
Definition: polygon_array_distance_likelihood.h:125
message_filters::Subscriber::subscribe
void subscribe()
nodelet::Nodelet
jsk_pcl_ros_utils::PolygonArrayDistanceLikelihood::pub_
ros::Publisher pub_
Definition: polygon_array_distance_likelihood.h:124
jsk_recognition_utils::Polygon::fromROSMsgPtr
static Polygon::Ptr fromROSMsgPtr(const geometry_msgs::Polygon &polygon)
tf::MessageFilter
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros_utils::PolygonArrayDistanceLikelihood, nodelet::Nodelet)
jsk_pcl_ros_utils::PolygonArrayDistanceLikelihood::onInit
virtual void onInit()
Definition: polygon_array_distance_likelihood_nodelet.cpp:45
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::PolygonArrayDistanceLikelihood::mutex_
boost::mutex mutex_
Definition: polygon_array_distance_likelihood.h:129


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