00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036 #define BOOST_PARAMETER_MAX_ARITY 7
00037
00038 #include "jsk_pcl_ros/boundingbox_occlusion_rejector.h"
00039 #include "jsk_pcl_ros/pcl_conversion_util.h"
00040 #include <sensor_msgs/image_encodings.h>
00041
00042 namespace jsk_pcl_ros
00043 {
00044 void BoundingBoxOcclusionRejector::onInit()
00045 {
00046 DiagnosticNodelet::onInit();
00047 tf_listener_ = TfListenerSingleton::getInstance();
00048 pub_ = advertise<jsk_recognition_msgs::BoundingBoxArray>(*pnh_, "output", 1);
00049 pub_target_image_ = advertise<sensor_msgs::Image>(*pnh_, "output/target_image", 1);
00050 pub_candidate_image_ = advertise<sensor_msgs::Image>(*pnh_, "output/candidate_image", 1);
00051 }
00052
00053 void BoundingBoxOcclusionRejector::subscribe()
00054 {
00055 sub_camera_info_ = pnh_->subscribe("input/camera_info", 1, &BoundingBoxOcclusionRejector::infoCallback, this);
00056 sub_target_boxes_ = pnh_->subscribe("input/target_boxes", 1, &BoundingBoxOcclusionRejector::targetBoxesCallback, this);
00057 sub_candidate_boxes_ = pnh_->subscribe("input/candidate_boxes", 1, &BoundingBoxOcclusionRejector::reject, this);
00058 }
00059
00060 void BoundingBoxOcclusionRejector::unsubscribe()
00061 {
00062 sub_camera_info_.shutdown();
00063 sub_target_boxes_.shutdown();
00064 sub_candidate_boxes_.shutdown();
00065 }
00066
00067 void BoundingBoxOcclusionRejector::infoCallback(
00068 const sensor_msgs::CameraInfo::ConstPtr& info_msg)
00069 {
00070 boost::mutex::scoped_lock lock(mutex_);
00071 latest_info_msg_ = info_msg;
00072 }
00073
00074 void BoundingBoxOcclusionRejector::targetBoxesCallback(
00075 const jsk_recognition_msgs::BoundingBoxArray::ConstPtr& target_boxes_msg)
00076 {
00077 boost::mutex::scoped_lock lock(mutex_);
00078 latest_target_boxes_msg_ = target_boxes_msg;
00079 }
00080
00081
00082 void BoundingBoxOcclusionRejector::reject(
00083 const jsk_recognition_msgs::BoundingBoxArray::ConstPtr& candidate_boxes_msg)
00084 {
00085 boost::mutex::scoped_lock lock(mutex_);
00086
00087 if (!latest_info_msg_ || !latest_target_boxes_msg_) {
00088 NODELET_ERROR("No camera info or target_boxes is available");
00089 return;
00090 }
00091
00092
00093 if (latest_info_msg_->header.frame_id != latest_target_boxes_msg_->header.frame_id ||
00094 latest_target_boxes_msg_->header.frame_id != candidate_boxes_msg->header.frame_id) {
00095 NODELET_ERROR("Different frame_id");
00096 return;
00097 }
00098
00099 image_geometry::PinholeCameraModel model;
00100 model.fromCameraInfo(*latest_info_msg_);
00101 cv::Mat image = cv::Mat::zeros(latest_info_msg_->height, latest_info_msg_->width, CV_8UC1);
00102 std::vector<std::vector<cv::Point2i> > faces;
00103
00104 for (size_t i = 0; i < latest_target_boxes_msg_->boxes.size(); i++) {
00105 jsk_recognition_msgs::BoundingBox box = latest_target_boxes_msg_->boxes[i];
00106
00107 std::vector<cv::Point3d> vertices = getVertices(box);
00108 std::vector<cv::Point2i> projected_vertices = projectVertices(vertices, model);
00109 std::vector<std::vector<cv::Point2i> > projected_faces = separateIntoFaces(projected_vertices);
00110 for (size_t j = 0; j < projected_faces.size(); j++) {
00111 faces.push_back(projected_faces[j]);
00112 }
00113 }
00114 for (size_t i = 0; i < faces.size(); i++) {
00115 std::vector<std::vector<cv::Point2i> > one_face;
00116 one_face.push_back(faces[i]);
00117 cv::fillPoly(image, one_face, cv::Scalar(255));
00118 }
00119
00120
00121 if (pub_target_image_.getNumSubscribers() > 0) {
00122 cv_bridge::CvImage target_image_bridge(
00123 latest_info_msg_->header,
00124 sensor_msgs::image_encodings::MONO8,
00125 image);
00126 pub_target_image_.publish(target_image_bridge.toImageMsg());
00127 }
00128
00129
00130 std::vector<size_t> candidate_indices;
00131 for (size_t i = 0; i < candidate_boxes_msg->boxes.size(); i++) {
00132
00133 cv::Mat candidate_image = cv::Mat::zeros(latest_info_msg_->height, latest_info_msg_->width, CV_8UC1);
00134 jsk_recognition_msgs::BoundingBox box = candidate_boxes_msg->boxes[i];
00135
00136 std::vector<cv::Point3d> vertices = getVertices(box);
00137 std::vector<cv::Point2i> projected_vertices = projectVertices(vertices, model);
00138 std::vector<std::vector<cv::Point2i> > projected_faces = separateIntoFaces(projected_vertices);
00139 for (size_t j = 0; j < projected_faces.size(); j++) {
00140 std::vector<std::vector<cv::Point2i> > one_face;
00141 one_face.push_back(projected_faces[j]);
00142 cv::fillPoly(candidate_image, one_face, cv::Scalar(255));
00143 if (pub_candidate_image_.getNumSubscribers() > 0) {
00144 pub_candidate_image_.publish(cv_bridge::CvImage(latest_info_msg_->header, sensor_msgs::image_encodings::MONO8,
00145 candidate_image).toImageMsg());
00146 }
00147 }
00148 cv::bitwise_and(image, candidate_image, candidate_image);
00149 if (cv::countNonZero(candidate_image) == 0) {
00150 candidate_indices.push_back(i);
00151 }
00152 }
00153 jsk_recognition_msgs::BoundingBoxArray rejected_boxes;
00154 rejected_boxes.header = candidate_boxes_msg->header;
00155 for (size_t i = 0; i < candidate_indices.size(); i++) {
00156 rejected_boxes.boxes.push_back(candidate_boxes_msg->boxes[candidate_indices[i]]);
00157 }
00158 pub_.publish(rejected_boxes);
00159 }
00160
00161 std::vector<std::vector<cv::Point2i> > BoundingBoxOcclusionRejector::separateIntoFaces(
00162 const std::vector<cv::Point2i>& vertices)
00163 {
00164
00165 std::vector<std::vector<cv::Point2i> > ret;
00166 std::vector<cv::Point2i> face0, face1, face2, face3, face4, face5;
00167 cv::Point2i a = vertices[0];
00168 cv::Point2i b = vertices[1];
00169 cv::Point2i c = vertices[2];
00170 cv::Point2i d = vertices[3];
00171 cv::Point2i e = vertices[4];
00172 cv::Point2i f = vertices[5];
00173 cv::Point2i g = vertices[6];
00174 cv::Point2i h = vertices[7];
00175 face0.push_back(a); face0.push_back(e); face0.push_back(f); face0.push_back(b);
00176 face1.push_back(b); face1.push_back(f); face1.push_back(g); face1.push_back(c);
00177 face2.push_back(c); face2.push_back(g); face2.push_back(h); face2.push_back(d);
00178 face3.push_back(d); face3.push_back(h); face3.push_back(e); face3.push_back(a);
00179 face4.push_back(a); face4.push_back(b); face4.push_back(c); face4.push_back(d);
00180 face5.push_back(e); face5.push_back(h); face5.push_back(g); face5.push_back(f);
00181
00182 ret.push_back(face0);
00183 ret.push_back(face1);
00184 ret.push_back(face2);
00185 ret.push_back(face3);
00186 ret.push_back(face4);
00187 ret.push_back(face5);
00188 return ret;
00189 }
00190
00191 std::vector<cv::Point2i> BoundingBoxOcclusionRejector::projectVertices(const std::vector<cv::Point3d>& vertices,
00192 const image_geometry::PinholeCameraModel& model)
00193 {
00194 std::vector<cv::Point2i> ret;
00195 for (size_t i = 0; i < vertices.size(); i++) {
00196 ret.push_back(model.project3dToPixel(vertices[i]));
00197 }
00198 return ret;
00199 }
00200
00201 std::vector<cv::Point3d> BoundingBoxOcclusionRejector::getVertices(const jsk_recognition_msgs::BoundingBox& box)
00202 {
00203 Eigen::Affine3f pose;
00204 tf::poseMsgToEigen(box.pose, pose);
00205 Eigen::Vector3f local_a(box.dimensions.x / 2, box.dimensions.y / 2, box.dimensions.z / 2);
00206 Eigen::Vector3f local_b(-box.dimensions.x / 2, box.dimensions.y / 2, box.dimensions.z / 2);
00207 Eigen::Vector3f local_c(-box.dimensions.x / 2, -box.dimensions.y / 2, box.dimensions.z / 2);
00208 Eigen::Vector3f local_d(box.dimensions.x / 2, -box.dimensions.y / 2, box.dimensions.z / 2);
00209 Eigen::Vector3f local_e(box.dimensions.x / 2, box.dimensions.y / 2, -box.dimensions.z / 2);
00210 Eigen::Vector3f local_f(-box.dimensions.x / 2, box.dimensions.y / 2, -box.dimensions.z / 2);
00211 Eigen::Vector3f local_g(-box.dimensions.x / 2, -box.dimensions.y / 2, -box.dimensions.z / 2);
00212 Eigen::Vector3f local_h(box.dimensions.x / 2, -box.dimensions.y / 2, -box.dimensions.z / 2);
00213 Eigen::Vector3f a = pose * local_a;
00214 Eigen::Vector3f b = pose * local_b;
00215 Eigen::Vector3f c = pose * local_c;
00216 Eigen::Vector3f d = pose * local_d;
00217 Eigen::Vector3f e = pose * local_e;
00218 Eigen::Vector3f f = pose * local_f;
00219 Eigen::Vector3f g = pose * local_g;
00220 Eigen::Vector3f h = pose * local_h;
00221 cv::Point3d cv_a(a[0], a[1], a[2]);
00222 cv::Point3d cv_b(b[0], b[1], b[2]);
00223 cv::Point3d cv_c(c[0], c[1], c[2]);
00224 cv::Point3d cv_d(d[0], d[1], d[2]);
00225 cv::Point3d cv_e(e[0], e[1], e[2]);
00226 cv::Point3d cv_f(f[0], f[1], f[2]);
00227 cv::Point3d cv_g(g[0], g[1], g[2]);
00228 cv::Point3d cv_h(h[0], h[1], h[2]);
00229 std::vector<cv::Point3d> ret;
00230 ret.push_back(cv_a);
00231 ret.push_back(cv_b);
00232 ret.push_back(cv_c);
00233 ret.push_back(cv_d);
00234 ret.push_back(cv_e);
00235 ret.push_back(cv_f);
00236 ret.push_back(cv_g);
00237 ret.push_back(cv_h);
00238 return ret;
00239 }
00240
00241 }
00242
00243 #include <pluginlib/class_list_macros.h>
00244 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::BoundingBoxOcclusionRejector, nodelet::Nodelet);