bounding_box_to_rect.cpp
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2016, 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 
41 
42 namespace jsk_perception
43 {
45  {
46  DiagnosticNodelet::onInit();
48  pnh_->param("queue_size", queue_size_, 100);
49  pnh_->param("approximate_sync", approximate_sync_, false);
50  pnh_->param("tf_queue_size", tf_queue_size_, 10);
51  pub_ = advertise<jsk_recognition_msgs::RectArray>(*pnh_, "output", 1);
52  pub_internal_ = pnh_->advertise<jsk_recognition_msgs::BoundingBoxArrayWithCameraInfo>("internal", 1);
53  sub_box_with_info_.subscribe(*pnh_, "internal", 1);
54  //onInitPosrPocess();
55  }
56 
58  {
59  // camera_info + bounding box array
60  sub_info_.subscribe(*pnh_, "input/info", 1);
61  sub_boxes_.subscribe(*pnh_, "input", 1);
62  if (approximate_sync_) {
63  async_ = boost::make_shared<message_filters::Synchronizer<ApproximateSyncPolicy> >(queue_size_);
64  async_->connectInput(sub_info_, sub_boxes_);
65  async_->registerCallback(boost::bind(&BoundingBoxToRect::inputCallback, this, _1, _2));
66  } else {
67  sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(queue_size_);
68  sync_->connectInput(sub_info_, sub_boxes_);
69  sync_->registerCallback(boost::bind(&BoundingBoxToRect::inputCallback, this, _1, _2));
70  }
71  // camera_info + bounding box
72  sub_box_.subscribe(*pnh_, "input/box", 1);
73  if (approximate_sync_) {
74  async_box_ = boost::make_shared<message_filters::Synchronizer<ApproximateSyncPolicyBox> >(queue_size_);
75  async_box_->connectInput(sub_info_, sub_box_);
76  async_box_->registerCallback(boost::bind(&BoundingBoxToRect::inputBoxCallback, this, _1, _2));
77  } else {
78  sync_box_ = boost::make_shared<message_filters::Synchronizer<SyncPolicyBox> >(queue_size_);
79  sync_box_->connectInput(sub_info_, sub_box_);
80  sync_box_->registerCallback(boost::bind(&BoundingBoxToRect::inputBoxCallback, this, _1, _2));
81  }
82  }
83 
85  {
89  frame_id_ = "";
90  }
91 
92  void BoundingBoxToRect::inputBoxCallback(const sensor_msgs::CameraInfo::ConstPtr& info_msg,
93  const jsk_recognition_msgs::BoundingBox::ConstPtr& box_msg)
94  {
95  jsk_recognition_msgs::BoundingBoxArray::Ptr boxes_msg(
96  new jsk_recognition_msgs::BoundingBoxArray());
97  boxes_msg->header = box_msg->header;
98  boxes_msg->boxes.push_back(*box_msg);
99  inputCallback(info_msg, boxes_msg);
100  }
101 
102  void BoundingBoxToRect::inputCallback(const sensor_msgs::CameraInfo::ConstPtr& info_msg,
103  const jsk_recognition_msgs::BoundingBoxArray::ConstPtr& boxes_msg)
104  {
105  boost::mutex::scoped_lock lock(mutex_);
106  if (frame_id_.empty()) {
107  // setup tf message filters
108  frame_id_ = boxes_msg->header.frame_id;
111  *tf_listener_,
112  frame_id_,
113  tf_queue_size_));
114  tf_filter_->registerCallback(boost::bind(&BoundingBoxToRect::internalCallback, this, _1));
115  }
116  jsk_recognition_msgs::BoundingBoxArrayWithCameraInfo internal_msg;
117  internal_msg.header = boxes_msg->header;
118  internal_msg.boxes = *boxes_msg;
119  internal_msg.camera_info = *info_msg;
120  pub_internal_.publish(internal_msg);
121  }
122 
124  const jsk_recognition_msgs::BoundingBoxArrayWithCameraInfo::ConstPtr& msg)
125  {
126  boost::mutex::scoped_lock lock(mutex_);
128  tf_listener_,
129  msg->boxes.header.frame_id,
130  msg->camera_info.header.frame_id,
131  msg->boxes.header.stamp,
132  ros::Duration(0.0));
133  Eigen::Affine3f box_to_info;
134  tf::transformTFToEigen(box_to_info_tf, box_to_info);
136  model.fromCameraInfo(msg->camera_info);
137  jsk_recognition_msgs::RectArray rect_array;
138  rect_array.header = msg->camera_info.header;
139  for (size_t i = 0; i < msg->boxes.boxes.size(); i++) {
140  jsk_recognition_msgs::BoundingBox box = msg->boxes.boxes[i];
141  jsk_recognition_utils::Cube cube(box);
142  jsk_recognition_utils::Vertices vertices = cube.transformVertices(box_to_info);
143  std::vector<cv::Point> points = jsk_recognition_utils::project3DPointstoPixel(model, vertices);
144  cv::Rect rect = cv::boundingRect(points);
145  jsk_recognition_msgs::Rect ros_rect;
146  ros_rect.x = rect.x;
147  ros_rect.y = rect.y;
148  ros_rect.width = rect.width;
149  ros_rect.height = rect.height;
150  rect_array.rects.push_back(ros_rect);
151  }
152  pub_.publish(rect_array);
153  }
154 }
155 
virtual void inputBoxCallback(const sensor_msgs::CameraInfo::ConstPtr &info_msg, const jsk_recognition_msgs::BoundingBox::ConstPtr &box_msg)
virtual void inputCallback(const sensor_msgs::CameraInfo::ConstPtr &info_msg, const jsk_recognition_msgs::BoundingBoxArray::ConstPtr &boxes_msg)
boost::shared_ptr< message_filters::Synchronizer< SyncPolicyBox > > sync_box_
Vertices transformVertices(const Eigen::Affine3f &pose_offset)
void publish(const boost::shared_ptr< M > &message) const
void transformTFToEigen(const tf::Transform &t, Eigen::Affine3d &e)
tf::StampedTransform lookupTransformWithDuration(tf::TransformListener *listener, const std::string &to_frame, const std::string &from_frame, const ros::Time &stamp, ros::Duration duration)
message_filters::Subscriber< jsk_recognition_msgs::BoundingBoxArray > sub_boxes_
boost::shared_ptr< message_filters::Synchronizer< ApproximateSyncPolicy > > async_
boost::shared_ptr< message_filters::Synchronizer< ApproximateSyncPolicyBox > > async_box_
message_filters::Subscriber< sensor_msgs::CameraInfo > sub_info_
message_filters::Subscriber< jsk_recognition_msgs::BoundingBoxArrayWithCameraInfo > sub_box_with_info_
bool fromCameraInfo(const sensor_msgs::CameraInfo &msg)
boost::shared_ptr< ros::NodeHandle > pnh_
boost::shared_ptr< tf::MessageFilter< jsk_recognition_msgs::BoundingBoxArrayWithCameraInfo > > tf_filter_
std::vector< Eigen::Vector3f, Eigen::aligned_allocator< Eigen::Vector3f > > Vertices
mutex_t * lock
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)
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
static tf::TransformListener * getInstance()
message_filters::Subscriber< jsk_recognition_msgs::BoundingBox > sub_box_
std::vector< cv::Point > project3DPointstoPixel(const image_geometry::PinholeCameraModel &model, const Vertices &vertices)
PLUGINLIB_EXPORT_CLASS(jsk_perception::BoundingBoxToRect, nodelet::Nodelet)
tf::TransformListener * tf_listener_
virtual void internalCallback(const jsk_recognition_msgs::BoundingBoxArrayWithCameraInfo::ConstPtr &msg)


jsk_perception
Author(s): Manabu Saito, Ryohei Ueda
autogenerated on Mon May 3 2021 03:03:27