polygon_array_foot_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/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 
36 #define BOOST_PARAMETER_MAX_ARITY 7
37 
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 
67  }
68 
70  {
71  sub_.subscribe(*pnh_, "input", 10);
73  sub_,
74  *tf_listener_,
77  tf_filter_->registerCallback(
78  boost::bind(&PolygonArrayFootAngleLikelihood::likelihood, this, _1));
79  }
80 
82  {
83  sub_.unsubscribe();
84  }
85 
87  const jsk_recognition_msgs::PolygonArray::ConstPtr& msg)
88  {
89  boost::mutex::scoped_lock lock(mutex_);
90  vital_checker_->poke();
91  jsk_recognition_msgs::PolygonArray new_msg(*msg);
92 
93  try
94  {
95  // Resolve tf
96  // ConstPtrmpute position of target_frame_id
97  // respected from msg->header.frame_id
98  tf::StampedTransform transform;
100  target_frame_id_, msg->header.frame_id, msg->header.stamp, transform);
101  Eigen::Affine3f pose;
102  tf::transformTFToEigen(transform, pose);
103 
104  Eigen::Vector3f reference_axis = pose.rotation() * axis_;
105 
106  std::vector<double> distances;
107  for (size_t i = 0; i < msg->polygons.size(); i++) {
109  = jsk_recognition_utils::Polygon::fromROSMsgPtr(msg->polygons[i].polygon);
110  double distance;
111  Eigen::Vector3f foot = polygon->nearestPoint(pose.translation(), distance);
112  Eigen::Vector3f foot_dir = (foot - pose.translation()).normalized();
113  double ang_distance = std::abs(reference_axis.dot(foot_dir));
114  distances.push_back(ang_distance);
115  }
116 
117  // Normalization
118  for (size_t i = 0; i < distances.size(); i++) {
119  // double normalized_distance
120  // = (distances[i] - min_distance) / (max_distance - min_distance);
121  double likelihood = 1 / (1 + (distances[i] - 1) * (distances[i] - 1));
122 
123  if (msg->likelihood.size() == 0) {
124  new_msg.likelihood.push_back(likelihood);
125  }
126  else {
127  new_msg.likelihood[i] = new_msg.likelihood[i] * likelihood;
128  }
129  }
130  pub_.publish(new_msg);
131  }
132  catch (...)
133  {
134  NODELET_ERROR("Unknown transform error");
135  }
136 
137  }
138 }
139 
boost::shared_ptr< tf::MessageFilter< jsk_recognition_msgs::PolygonArray > > tf_filter_
lock
message_filters::Subscriber< jsk_recognition_msgs::PolygonArray > sub_
#define NODELET_ERROR(...)
void publish(const boost::shared_ptr< M > &message) const
void transformTFToEigen(const tf::Transform &t, Eigen::Affine3d &e)
pose
bool readVectorParameter(ros::NodeHandle &nh, const std::string &param_name, std::vector< double > &result)
TFSIMD_FORCE_INLINE Vector3 normalized() const
static Polygon::Ptr fromROSMsgPtr(const geometry_msgs::Polygon &polygon)
virtual void likelihood(const jsk_recognition_msgs::PolygonArray::ConstPtr &msg)
boost::shared_ptr< ros::NodeHandle > pnh_
void lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, StampedTransform &transform) const
jsk_topic_tools::VitalChecker::Ptr vital_checker_
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)
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros_utils::PolygonArrayFootAngleLikelihood, nodelet::Nodelet)
static tf::TransformListener * getInstance()
#define ROS_ERROR(...)
double distance(const urdf::Pose &transform)


jsk_pcl_ros_utils
Author(s): Yohei Kakiuchi
autogenerated on Mon May 3 2021 03:03:15