tf_transform_bounding_box_array_nodelet.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2015, JSK Lab
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/o2r other materials provided
16  * with the distribution.
17  * * Neither the name of the JSK Lab 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 #define BOOST_PARAMETER_MAX_ARITY 7
36 
39 
40 namespace jsk_pcl_ros_utils
41 {
42 
44  {
45  DiagnosticNodelet::onInit();
46  if (!pnh_->getParam("target_frame_id", target_frame_id_)) {
47  ROS_FATAL("~target_frame_id is not specified");
48  return;
49  }
50 
51  pnh_->param("use_latest_tf", use_latest_tf_, false);
52  pnh_->param("tf_queue_size", tf_queue_size_, 10);
54  pub_ = advertise<jsk_recognition_msgs::BoundingBoxArray>(*pnh_, "output", 1);
55 
57  }
58 
60  {
61  if (use_latest_tf_) {
62  sub_ = pnh_->subscribe("input", 1, &TfTransformBoundingBoxArray::transform, this);
63  }
64  else {
65  sub_filter_.subscribe(*pnh_, "input", 10);
68  *tf_listener_,
71  tf_filter_->registerCallback(boost::bind(&TfTransformBoundingBoxArray::transform, this, _1));
72  }
73  }
74 
76  {
77  if (use_latest_tf_) {
78  sub_.shutdown();
79  }
80  else {
82  }
83  }
84 
86  const jsk_recognition_msgs::BoundingBoxArray::ConstPtr& msg)
87  {
88  vital_checker_->poke();
89  try
90  {
91  jsk_recognition_msgs::BoundingBoxArray transformed_box;
92  transformed_box.header.stamp = msg->header.stamp;
93  transformed_box.header.frame_id = target_frame_id_;
94  tf::StampedTransform tf_transform;
95  if (use_latest_tf_) {
96  tf_listener_->lookupTransform(target_frame_id_, msg->header.frame_id,
97  ros::Time(0), tf_transform);
98  }
99  else {
100  tf_listener_->lookupTransform(target_frame_id_, msg->header.frame_id,
101  msg->header.stamp, tf_transform);
102  }
103 
104  Eigen::Affine3f transform;
105  tf::transformTFToEigen(tf_transform, transform);
106  for (size_t i = 0; i < msg->boxes.size(); i++) {
107  jsk_recognition_msgs::BoundingBox box = jsk_recognition_msgs::BoundingBox(msg->boxes[i]);
108  Eigen::Affine3f pose;
109  tf::poseMsgToEigen(box.pose, pose);
110  Eigen::Affine3f new_pose = transform * pose;
111  tf::poseEigenToMsg(new_pose, box.pose);
112  box.header.frame_id = target_frame_id_;
113  transformed_box.boxes.push_back(box);
114  }
115  pub_.publish(transformed_box);
116  }
117  catch (tf2::ConnectivityException &e)
118  {
119  NODELET_ERROR("Transform error: %s", e.what());
120  }
122  {
123  NODELET_ERROR("Transform error: %s", e.what());
124  }
125  catch (...)
126  {
127  NODELET_ERROR("Unknown transform error");
128  }
129  }
130 
131 }
#define ROS_FATAL(...)
#define NODELET_ERROR(...)
void publish(const boost::shared_ptr< M > &message) const
void transformTFToEigen(const tf::Transform &t, Eigen::Affine3d &e)
void poseEigenToMsg(const Eigen::Affine3d &e, geometry_msgs::Pose &m)
void poseMsgToEigen(const geometry_msgs::Pose &m, Eigen::Affine3d &e)
boost::shared_ptr< tf::MessageFilter< jsk_recognition_msgs::BoundingBoxArray > > tf_filter_
pose
message_filters::Subscriber< jsk_recognition_msgs::BoundingBoxArray > sub_filter_
virtual void transform(const jsk_recognition_msgs::BoundingBoxArray::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_
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros_utils::TfTransformBoundingBoxArray, nodelet::Nodelet)
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)
static tf::TransformListener * getInstance()


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