boundingbox_occlusion_rejector_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 
41 
42 namespace jsk_pcl_ros
43 {
45  {
46  DiagnosticNodelet::onInit();
48  pub_ = advertise<jsk_recognition_msgs::BoundingBoxArray>(*pnh_, "output", 1);
49  pub_target_image_ = advertise<sensor_msgs::Image>(*pnh_, "output/target_image", 1);
50  pub_candidate_image_ = advertise<sensor_msgs::Image>(*pnh_, "output/candidate_image", 1);
52  }
53 
55  {
56  sub_camera_info_ = pnh_->subscribe("input/camera_info", 1, &BoundingBoxOcclusionRejector::infoCallback, this);
57  sub_target_boxes_ = pnh_->subscribe("input/target_boxes", 1, &BoundingBoxOcclusionRejector::targetBoxesCallback, this);
58  sub_candidate_boxes_ = pnh_->subscribe("input/candidate_boxes", 1, &BoundingBoxOcclusionRejector::reject, this);
59  }
60 
62  {
66  }
67 
69  const sensor_msgs::CameraInfo::ConstPtr& info_msg)
70  {
71  boost::mutex::scoped_lock lock(mutex_);
72  latest_info_msg_ = info_msg;
73  }
74 
76  const jsk_recognition_msgs::BoundingBoxArray::ConstPtr& target_boxes_msg)
77  {
78  boost::mutex::scoped_lock lock(mutex_);
79  latest_target_boxes_msg_ = target_boxes_msg;
80  }
81 
82 
84  const jsk_recognition_msgs::BoundingBoxArray::ConstPtr& candidate_boxes_msg)
85  {
86  boost::mutex::scoped_lock lock(mutex_);
87 
89  NODELET_ERROR("No camera info or target_boxes is available");
90  return;
91  }
92 
93  // All the header should be same
94  if (latest_info_msg_->header.frame_id != latest_target_boxes_msg_->header.frame_id ||
95  latest_target_boxes_msg_->header.frame_id != candidate_boxes_msg->header.frame_id) {
96  NODELET_ERROR("Different frame_id");
97  return;
98  }
99 
102  cv::Mat image = cv::Mat::zeros(latest_info_msg_->height, latest_info_msg_->width, CV_8UC1);
103  std::vector<std::vector<cv::Point2i> > faces;
104  // Draw target boxes
105  for (size_t i = 0; i < latest_target_boxes_msg_->boxes.size(); i++) {
106  jsk_recognition_msgs::BoundingBox box = latest_target_boxes_msg_->boxes[i];
107  // Get vertices
108  std::vector<cv::Point3d> vertices = getVertices(box);
109  std::vector<cv::Point2i> projected_vertices = projectVertices(vertices, model);
110  std::vector<std::vector<cv::Point2i> > projected_faces = separateIntoFaces(projected_vertices);
111  for (size_t j = 0; j < projected_faces.size(); j++) {
112  faces.push_back(projected_faces[j]);
113  }
114  }
115  for (size_t i = 0; i < faces.size(); i++) {
116  std::vector<std::vector<cv::Point2i> > one_face;
117  one_face.push_back(faces[i]);
118  cv::fillPoly(image, one_face, cv::Scalar(255));
119  }
120 
121  // Publish image
123  cv_bridge::CvImage target_image_bridge(
124  latest_info_msg_->header,
126  image);
127  pub_target_image_.publish(target_image_bridge.toImageMsg());
128  }
129 
130  // Reject
131  std::vector<size_t> candidate_indices;
132  for (size_t i = 0; i < candidate_boxes_msg->boxes.size(); i++) {
133  //cv::Mat copied_image = image.clone();
134  cv::Mat candidate_image = cv::Mat::zeros(latest_info_msg_->height, latest_info_msg_->width, CV_8UC1);
135  jsk_recognition_msgs::BoundingBox box = candidate_boxes_msg->boxes[i];
136  // Get vertices
137  std::vector<cv::Point3d> vertices = getVertices(box);
138  std::vector<cv::Point2i> projected_vertices = projectVertices(vertices, model);
139  std::vector<std::vector<cv::Point2i> > projected_faces = separateIntoFaces(projected_vertices);
140  for (size_t j = 0; j < projected_faces.size(); j++) {
141  std::vector<std::vector<cv::Point2i> > one_face;
142  one_face.push_back(projected_faces[j]);
143  cv::fillPoly(candidate_image, one_face, cv::Scalar(255));
146  candidate_image).toImageMsg());
147  }
148  }
149  cv::bitwise_and(image, candidate_image, candidate_image);
150  if (cv::countNonZero(candidate_image) == 0) {
151  candidate_indices.push_back(i);
152  }
153  }
154  jsk_recognition_msgs::BoundingBoxArray rejected_boxes;
155  rejected_boxes.header = candidate_boxes_msg->header;
156  for (size_t i = 0; i < candidate_indices.size(); i++) {
157  rejected_boxes.boxes.push_back(candidate_boxes_msg->boxes[candidate_indices[i]]);
158  }
159  pub_.publish(rejected_boxes);
160  }
161 
162  std::vector<std::vector<cv::Point2i> > BoundingBoxOcclusionRejector::separateIntoFaces(
163  const std::vector<cv::Point2i>& vertices)
164  {
165  // a, b, c, d, e, f, g, h
166  std::vector<std::vector<cv::Point2i> > ret;
167  std::vector<cv::Point2i> face0, face1, face2, face3, face4, face5;
168  cv::Point2i a = vertices[0];
169  cv::Point2i b = vertices[1];
170  cv::Point2i c = vertices[2];
171  cv::Point2i d = vertices[3];
172  cv::Point2i e = vertices[4];
173  cv::Point2i f = vertices[5];
174  cv::Point2i g = vertices[6];
175  cv::Point2i h = vertices[7];
176  face0.push_back(a); face0.push_back(e); face0.push_back(f); face0.push_back(b);
177  face1.push_back(b); face1.push_back(f); face1.push_back(g); face1.push_back(c);
178  face2.push_back(c); face2.push_back(g); face2.push_back(h); face2.push_back(d);
179  face3.push_back(d); face3.push_back(h); face3.push_back(e); face3.push_back(a);
180  face4.push_back(a); face4.push_back(b); face4.push_back(c); face4.push_back(d);
181  face5.push_back(e); face5.push_back(h); face5.push_back(g); face5.push_back(f);
182 
183  ret.push_back(face0);
184  ret.push_back(face1);
185  ret.push_back(face2);
186  ret.push_back(face3);
187  ret.push_back(face4);
188  ret.push_back(face5);
189  return ret;
190  }
191 
192  std::vector<cv::Point2i> BoundingBoxOcclusionRejector::projectVertices(const std::vector<cv::Point3d>& vertices,
194  {
195  std::vector<cv::Point2i> ret;
196  for (size_t i = 0; i < vertices.size(); i++) {
197  ret.push_back(model.project3dToPixel(vertices[i]));
198  }
199  return ret;
200  }
201 
202  std::vector<cv::Point3d> BoundingBoxOcclusionRejector::getVertices(const jsk_recognition_msgs::BoundingBox& box)
203  {
204  Eigen::Affine3f pose;
205  tf::poseMsgToEigen(box.pose, pose);
206  Eigen::Vector3f local_a(box.dimensions.x / 2, box.dimensions.y / 2, box.dimensions.z / 2);
207  Eigen::Vector3f local_b(-box.dimensions.x / 2, box.dimensions.y / 2, box.dimensions.z / 2);
208  Eigen::Vector3f local_c(-box.dimensions.x / 2, -box.dimensions.y / 2, box.dimensions.z / 2);
209  Eigen::Vector3f local_d(box.dimensions.x / 2, -box.dimensions.y / 2, box.dimensions.z / 2);
210  Eigen::Vector3f local_e(box.dimensions.x / 2, box.dimensions.y / 2, -box.dimensions.z / 2);
211  Eigen::Vector3f local_f(-box.dimensions.x / 2, box.dimensions.y / 2, -box.dimensions.z / 2);
212  Eigen::Vector3f local_g(-box.dimensions.x / 2, -box.dimensions.y / 2, -box.dimensions.z / 2);
213  Eigen::Vector3f local_h(box.dimensions.x / 2, -box.dimensions.y / 2, -box.dimensions.z / 2);
214  Eigen::Vector3f a = pose * local_a;
215  Eigen::Vector3f b = pose * local_b;
216  Eigen::Vector3f c = pose * local_c;
217  Eigen::Vector3f d = pose * local_d;
218  Eigen::Vector3f e = pose * local_e;
219  Eigen::Vector3f f = pose * local_f;
220  Eigen::Vector3f g = pose * local_g;
221  Eigen::Vector3f h = pose * local_h;
222  cv::Point3d cv_a(a[0], a[1], a[2]);
223  cv::Point3d cv_b(b[0], b[1], b[2]);
224  cv::Point3d cv_c(c[0], c[1], c[2]);
225  cv::Point3d cv_d(d[0], d[1], d[2]);
226  cv::Point3d cv_e(e[0], e[1], e[2]);
227  cv::Point3d cv_f(f[0], f[1], f[2]);
228  cv::Point3d cv_g(g[0], g[1], g[2]);
229  cv::Point3d cv_h(h[0], h[1], h[2]);
230  std::vector<cv::Point3d> ret;
231  ret.push_back(cv_a);
232  ret.push_back(cv_b);
233  ret.push_back(cv_c);
234  ret.push_back(cv_d);
235  ret.push_back(cv_e);
236  ret.push_back(cv_f);
237  ret.push_back(cv_g);
238  ret.push_back(cv_h);
239  return ret;
240  }
241 
242 }
243 
d
#define NODELET_ERROR(...)
virtual void infoCallback(const sensor_msgs::CameraInfo::ConstPtr &info_msg)
void publish(const boost::shared_ptr< M > &message) const
void poseMsgToEigen(const geometry_msgs::Pose &m, Eigen::Affine3d &e)
virtual void targetBoxesCallback(const jsk_recognition_msgs::BoundingBoxArray::ConstPtr &target_boxes_msg)
GLint faces[6][4]
jsk_recognition_msgs::BoundingBoxArray::ConstPtr latest_target_boxes_msg_
pose
virtual std::vector< cv::Point2i > projectVertices(const std::vector< cv::Point3d > &vertices, const image_geometry::PinholeCameraModel &model)
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::BoundingBoxOcclusionRejector, nodelet::Nodelet)
bool fromCameraInfo(const sensor_msgs::CameraInfo &msg)
boost::shared_ptr< ros::NodeHandle > pnh_
uint32_t getNumSubscribers() const
virtual void reject(const jsk_recognition_msgs::BoundingBoxArray::ConstPtr &candidate_boxes_msg)
c
cv::Point2d project3dToPixel(const cv::Point3d &xyz) const
static tf::TransformListener * getInstance()
virtual std::vector< cv::Point3d > getVertices(const jsk_recognition_msgs::BoundingBox &box)
virtual std::vector< std::vector< cv::Point2i > > separateIntoFaces(const std::vector< cv::Point2i > &vertices)
sensor_msgs::ImagePtr toImageMsg() const
char a[26]


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Mon May 3 2021 03:03:46