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/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 
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  onInitPostProcess();
55  }
56 
58  // message_filters::Synchronizer needs to be called reset
59  // before message_filters::Subscriber is freed.
60  // Calling reset fixes the following error on shutdown of the nodelet:
61  // terminate called after throwing an instance of
62  // 'boost::exception_detail::clone_impl<boost::exception_detail::error_info_injector<boost::lock_error> >'
63  // what(): boost: mutex lock failed in pthread_mutex_lock: Invalid argument
64  // Also see https://github.com/ros/ros_comm/issues/720 .
65  sync_.reset();
66  async_.reset();
67  sync_box_.reset();
68  async_box_.reset();
69  }
70 
72  {
73  // camera_info + bounding box array
74  sub_info_.subscribe(*pnh_, "input/info", 1);
75  sub_boxes_.subscribe(*pnh_, "input", 1);
76  if (approximate_sync_) {
77  async_ = boost::make_shared<message_filters::Synchronizer<ApproximateSyncPolicy> >(queue_size_);
78  async_->connectInput(sub_info_, sub_boxes_);
79  async_->registerCallback(boost::bind(&BoundingBoxToRect::inputCallback, this, _1, _2));
80  } else {
81  sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(queue_size_);
82  sync_->connectInput(sub_info_, sub_boxes_);
83  sync_->registerCallback(boost::bind(&BoundingBoxToRect::inputCallback, this, _1, _2));
84  }
85  // camera_info + bounding box
86  sub_box_.subscribe(*pnh_, "input/box", 1);
87  if (approximate_sync_) {
88  async_box_ = boost::make_shared<message_filters::Synchronizer<ApproximateSyncPolicyBox> >(queue_size_);
89  async_box_->connectInput(sub_info_, sub_box_);
90  async_box_->registerCallback(boost::bind(&BoundingBoxToRect::inputBoxCallback, this, _1, _2));
91  } else {
92  sync_box_ = boost::make_shared<message_filters::Synchronizer<SyncPolicyBox> >(queue_size_);
93  sync_box_->connectInput(sub_info_, sub_box_);
94  sync_box_->registerCallback(boost::bind(&BoundingBoxToRect::inputBoxCallback, this, _1, _2));
95  }
96  }
97 
99  {
103  frame_id_ = "";
104  }
105 
106  void BoundingBoxToRect::inputBoxCallback(const sensor_msgs::CameraInfo::ConstPtr& info_msg,
107  const jsk_recognition_msgs::BoundingBox::ConstPtr& box_msg)
108  {
109  jsk_recognition_msgs::BoundingBoxArray::Ptr boxes_msg(
110  new jsk_recognition_msgs::BoundingBoxArray());
111  boxes_msg->header = box_msg->header;
112  boxes_msg->boxes.push_back(*box_msg);
113  inputCallback(info_msg, boxes_msg);
114  }
115 
116  void BoundingBoxToRect::inputCallback(const sensor_msgs::CameraInfo::ConstPtr& info_msg,
117  const jsk_recognition_msgs::BoundingBoxArray::ConstPtr& boxes_msg)
118  {
119  boost::mutex::scoped_lock lock(mutex_);
120  if (frame_id_.empty()) {
121  // setup tf message filters
122  frame_id_ = boxes_msg->header.frame_id;
125  *tf_listener_,
126  frame_id_,
127  tf_queue_size_));
128  tf_filter_->registerCallback(boost::bind(&BoundingBoxToRect::internalCallback, this, _1));
129  }
130  jsk_recognition_msgs::BoundingBoxArrayWithCameraInfo internal_msg;
131  internal_msg.header = boxes_msg->header;
132  internal_msg.boxes = *boxes_msg;
133  internal_msg.camera_info = *info_msg;
134  pub_internal_.publish(internal_msg);
135  }
136 
138  const jsk_recognition_msgs::BoundingBoxArrayWithCameraInfo::ConstPtr& msg)
139  {
140  boost::mutex::scoped_lock lock(mutex_);
142  tf_listener_,
143  msg->boxes.header.frame_id,
144  msg->camera_info.header.frame_id,
145  msg->boxes.header.stamp,
146  ros::Duration(0.0));
147  Eigen::Affine3f box_to_info;
148  tf::transformTFToEigen(box_to_info_tf, box_to_info);
150  model.fromCameraInfo(msg->camera_info);
151  jsk_recognition_msgs::RectArray rect_array;
152  rect_array.header = msg->camera_info.header;
153  for (size_t i = 0; i < msg->boxes.boxes.size(); i++) {
154  jsk_recognition_msgs::BoundingBox box = msg->boxes.boxes[i];
155  jsk_recognition_utils::Cube cube(box);
156  jsk_recognition_utils::Vertices vertices = cube.transformVertices(box_to_info);
157  std::vector<cv::Point> points = jsk_recognition_utils::project3DPointstoPixel(model, vertices);
158  cv::Rect rect = cv::boundingRect(points);
159  jsk_recognition_msgs::Rect ros_rect;
160  ros_rect.x = rect.x;
161  ros_rect.y = rect.y;
162  ros_rect.width = rect.width;
163  ros_rect.height = rect.height;
164  rect_array.rects.push_back(ros_rect);
165  }
166  pub_.publish(rect_array);
167  }
168 }
169 
jsk_perception::BoundingBoxToRect::~BoundingBoxToRect
virtual ~BoundingBoxToRect()
Definition: bounding_box_to_rect.cpp:57
jsk_perception::BoundingBoxToRect::queue_size_
int queue_size_
Definition: bounding_box_to_rect.h:161
jsk_perception::BoundingBoxToRect::sub_boxes_
message_filters::Subscriber< jsk_recognition_msgs::BoundingBoxArray > sub_boxes_
Definition: bounding_box_to_rect.h:152
msg
msg
i
int i
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(jsk_perception::BoundingBoxToRect, nodelet::Nodelet)
sensor_model_utils.h
jsk_perception::BoundingBoxToRect::pub_internal_
ros::Publisher pub_internal_
Definition: bounding_box_to_rect.h:164
_1
boost::arg< 1 > _1
jsk_perception::BoundingBoxToRect::onInit
virtual void onInit()
Definition: bounding_box_to_rect.cpp:44
jsk_perception::BoundingBoxToRect::sub_info_
message_filters::Subscriber< sensor_msgs::CameraInfo > sub_info_
Definition: bounding_box_to_rect.h:150
tf::StampedTransform
jsk_perception::BoundingBoxToRect::inputBoxCallback
virtual void inputBoxCallback(const sensor_msgs::CameraInfo::ConstPtr &info_msg, const jsk_recognition_msgs::BoundingBox::ConstPtr &box_msg)
Definition: bounding_box_to_rect.cpp:106
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
message_filters::Subscriber::unsubscribe
void unsubscribe()
jsk_perception::BoundingBoxToRect::async_
boost::shared_ptr< message_filters::Synchronizer< ApproximateSyncPolicy > > async_
Definition: bounding_box_to_rect.h:155
jsk_perception::BoundingBoxToRect::tf_listener_
tf::TransformListener * tf_listener_
Definition: bounding_box_to_rect.h:158
class_list_macros.h
jsk_perception::BoundingBoxToRect::tf_queue_size_
int tf_queue_size_
Definition: bounding_box_to_rect.h:160
jsk_perception
Definition: add_mask_image.h:48
jsk_perception::BoundingBoxToRect::internalCallback
virtual void internalCallback(const jsk_recognition_msgs::BoundingBoxArrayWithCameraInfo::ConstPtr &msg)
Definition: bounding_box_to_rect.cpp:137
jsk_perception::BoundingBoxToRect::approximate_sync_
bool approximate_sync_
Definition: bounding_box_to_rect.h:159
jsk_perception::BoundingBoxToRect::tf_filter_
boost::shared_ptr< tf::MessageFilter< jsk_recognition_msgs::BoundingBoxArrayWithCameraInfo > > tf_filter_
Definition: bounding_box_to_rect.h:162
tf::transformTFToEigen
void transformTFToEigen(const tf::Transform &t, Eigen::Affine3f &eigen)
jsk_perception::BoundingBoxToRect::sync_box_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicyBox > > sync_box_
Definition: bounding_box_to_rect.h:156
node_scripts.craft.craft.model
model
Definition: craft.py:106
_2
boost::arg< 2 > _2
jsk_perception::BoundingBoxToRect::sub_box_with_info_
message_filters::Subscriber< jsk_recognition_msgs::BoundingBoxArrayWithCameraInfo > sub_box_with_info_
Definition: bounding_box_to_rect.h:153
jsk_perception::BoundingBoxToRect::subscribe
virtual void subscribe()
Definition: bounding_box_to_rect.cpp:71
lock
mutex_t * lock
jsk_perception::BoundingBoxToRect::sync_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
Definition: bounding_box_to_rect.h:154
jsk_perception::BoundingBoxToRect::sub_box_
message_filters::Subscriber< jsk_recognition_msgs::BoundingBox > sub_box_
Definition: bounding_box_to_rect.h:151
jsk_recognition_utils::project3DPointstoPixel
std::vector< cv::Point > project3DPointstoPixel(const image_geometry::PinholeCameraModel &model, const Vertices &vertices)
bounding_box_to_rect.h
message_filters::Subscriber::subscribe
void subscribe()
nodelet::Nodelet
jsk_perception::BoundingBoxToRect::inputCallback
virtual void inputCallback(const sensor_msgs::CameraInfo::ConstPtr &info_msg, const jsk_recognition_msgs::BoundingBoxArray::ConstPtr &boxes_msg)
Definition: bounding_box_to_rect.cpp:116
image_geometry::PinholeCameraModel
jsk_perception::BoundingBoxToRect
Definition: bounding_box_to_rect.h:86
tf::MessageFilter
jsk_recognition_utils::Cube::transformVertices
Vertices transformVertices(const Eigen::Affine3f &pose_offset)
jsk_perception::BoundingBoxToRect::unsubscribe
virtual void unsubscribe()
Definition: bounding_box_to_rect.cpp:98
jsk_recognition_utils::Cube
jsk_recognition_utils::TfListenerSingleton::getInstance
static tf::TransformListener * getInstance()
jsk_perception::BoundingBoxToRect::mutex_
boost::mutex mutex_
Definition: bounding_box_to_rect.h:148
jsk_recognition_utils::lookupTransformWithDuration
tf::StampedTransform lookupTransformWithDuration(tf::TransformListener *listener, const std::string &to_frame, const std::string &from_frame, const ros::Time &stamp, ros::Duration duration)
jsk_perception::BoundingBoxToRect::async_box_
boost::shared_ptr< message_filters::Synchronizer< ApproximateSyncPolicyBox > > async_box_
Definition: bounding_box_to_rect.h:157
ros::Duration
jsk_perception::BoundingBoxToRect::frame_id_
std::string frame_id_
Definition: bounding_box_to_rect.h:149
jsk_perception::BoundingBoxToRect::pub_
ros::Publisher pub_
Definition: bounding_box_to_rect.h:163
info_msg
info_msg
jsk_recognition_utils::Vertices
std::vector< Eigen::Vector3f, Eigen::aligned_allocator< Eigen::Vector3f > > Vertices
cube.h


jsk_perception
Author(s): Manabu Saito, Ryohei Ueda
autogenerated on Fri May 16 2025 03:11:16