36 #define BOOST_PARAMETER_MAX_ARITY 7 46 DiagnosticNodelet::onInit();
48 pub_ = advertise<jsk_recognition_msgs::BoundingBoxArray>(*
pnh_,
"output", 1);
69 const sensor_msgs::CameraInfo::ConstPtr& info_msg)
76 const jsk_recognition_msgs::BoundingBoxArray::ConstPtr& target_boxes_msg)
84 const jsk_recognition_msgs::BoundingBoxArray::ConstPtr& candidate_boxes_msg)
103 std::vector<std::vector<cv::Point2i> >
faces;
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]);
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));
131 std::vector<size_t> candidate_indices;
132 for (
size_t i = 0; i < candidate_boxes_msg->boxes.size(); i++) {
135 jsk_recognition_msgs::BoundingBox
box = candidate_boxes_msg->boxes[i];
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));
149 cv::bitwise_and(image, candidate_image, candidate_image);
150 if (cv::countNonZero(candidate_image) == 0) {
151 candidate_indices.push_back(i);
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]]);
163 const std::vector<cv::Point2i>& vertices)
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);
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);
195 std::vector<cv::Point2i> ret;
196 for (
size_t i = 0; i < vertices.size(); i++) {
204 Eigen::Affine3f
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;
ros::Publisher pub_target_image_
#define NODELET_ERROR(...)
virtual void infoCallback(const sensor_msgs::CameraInfo::ConstPtr &info_msg)
void publish(const boost::shared_ptr< M > &message) const
virtual void unsubscribe()
ros::Subscriber sub_camera_info_
void poseMsgToEigen(const geometry_msgs::Pose &m, Eigen::Affine3d &e)
virtual void targetBoxesCallback(const jsk_recognition_msgs::BoundingBoxArray::ConstPtr &target_boxes_msg)
ros::Subscriber sub_target_boxes_
tf::TransformListener * tf_listener_
jsk_recognition_msgs::BoundingBoxArray::ConstPtr latest_target_boxes_msg_
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)
uint32_t getNumSubscribers() const
virtual void reject(const jsk_recognition_msgs::BoundingBoxArray::ConstPtr &candidate_boxes_msg)
sensor_msgs::CameraInfo::ConstPtr latest_info_msg_
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
ros::Publisher pub_candidate_image_
ros::Subscriber sub_candidate_boxes_