35 #define BOOST_PARAMETER_MAX_ARITY 7
39 #include <opencv2/opencv.hpp>
44 #include <jsk_topic_tools/rosparam_utils.h>
50 #if ( CV_MAJOR_VERSION >= 4)
51 #include <opencv2/imgproc/imgproc_c.h>
58 DiagnosticNodelet::onInit();
60 pnh_->param(
"negative",
negative_,
false);
63 Eigen::Affine3f
pose = Eigen::Affine3f::Identity();
64 std::vector<double> initial_pos;
65 if (jsk_topic_tools::readVectorParameter(*pnh_,
69 pose.translation() = Eigen::Vector3f(initial_pos[0],
74 std::vector<double> initial_rot;
75 if (jsk_topic_tools::readVectorParameter(*pnh_,
80 * Eigen::AngleAxisf(initial_rot[0],
81 Eigen::Vector3f::UnitX())
82 * Eigen::AngleAxisf(initial_rot[1],
83 Eigen::Vector3f::UnitY())
84 * Eigen::AngleAxisf(initial_rot[2],
85 Eigen::Vector3f::UnitZ());
90 double dimension_x, dimension_y, dimension_z;
91 pnh_->param(
"dimension_x", dimension_x, 0.1);
92 pnh_->param(
"dimension_y", dimension_y, 0.1);
93 pnh_->param(
"dimension_z", dimension_z, 0.1);
98 pnh_->param(
"frame_id",
frame_id, std::string(
"base_link"));
105 std::vector<std::vector<double> > initial_pos_list;
106 std::vector<std::vector<double> > initial_rot_list;
107 std::vector<std::vector<double> > dimensions;
108 jsk_topic_tools::readVectorParameter(*pnh_,
"initial_pos_list",
110 jsk_topic_tools::readVectorParameter(*pnh_,
"initial_rot_list",
112 jsk_topic_tools::readVectorParameter(*pnh_,
"dimensions", dimensions);
113 jsk_topic_tools::readVectorParameter(*pnh_,
"prefixes",
prefixes_);
114 if (initial_pos_list.size() != 0) {
116 for (
size_t i = 0;
i < initial_pos_list.size();
i++) {
117 if (initial_pos_list[
i].
size() != 3) {
118 NODELET_FATAL(
"element of ~initial_pos_list should be [x, y, z]");
121 pose_list_[
i].translation() = Eigen::Vector3f(initial_pos_list[
i][0],
122 initial_pos_list[
i][1],
123 initial_pos_list[
i][2]);
128 if (initial_rot_list.size() != 0) {
130 if (initial_pos_list.size() != 0 &&
131 initial_rot_list.size() != initial_pos_list.size()) {
133 "the size of ~initial_pos_list and ~initial_rot_list are different");
136 if (initial_pos_list.size() == 0) {
139 for (
size_t i = 0;
i < initial_rot_list.size();
i++) {
140 if (initial_rot_list[
i].
size() != 3) {
141 NODELET_FATAL(
"element of ~initial_rot_list should be [rx, ry, rz]");
145 * Eigen::AngleAxisf(initial_rot_list[
i][0],
146 Eigen::Vector3f::UnitX())
147 * Eigen::AngleAxisf(initial_rot_list[
i][1],
148 Eigen::Vector3f::UnitY())
149 * Eigen::AngleAxisf(initial_rot_list[
i][2],
150 Eigen::Vector3f::UnitZ());
155 if (dimensions.size() != 0) {
160 "the size of ~dimensions and ~initial_pos_list or ~initial_rot_list are different");
166 for (
size_t i = 0;
i < dimensions.size();
i++) {
177 if (
prefixes_.size() != dimensions.size()) {
179 "the size of ~prefixes and ~dimensions are different");
187 jsk_topic_tools::readVectorParameter(*pnh_,
"frame_id_list",
frame_id_list_);
191 = advertise<jsk_recognition_msgs::BoundingBoxArray>(*pnh_,
"output/box_array", 1);
192 pub_mask_ = advertise<sensor_msgs::Image>(*pnh_,
"output/mask", 1);
193 pub_indices_ = advertise<PCLIndicesMsg>(*pnh_,
"output/point_indices", 1);
194 pub_cluster_indices_ = advertise<jsk_recognition_msgs::ClusterPointIndices>(*pnh_,
"output/cluster_point_indices", 1);
213 sub_pose_ = pnh_->subscribe(
"input/pose",
215 sub_box_ = pnh_->subscribe(
"input/box",
219 sub_pose_ = pnh_->subscribe(
"input/pose_array",
221 sub_box_ = pnh_->subscribe(
"input/box_array",
237 nonoffsetted_vertices.push_back(
238 Eigen::Vector3f(-dimension[0]/2, -dimension[1]/2, -dimension[2]/2));
239 nonoffsetted_vertices.push_back(
240 Eigen::Vector3f(-dimension[0]/2, -dimension[1]/2, dimension[2]/2));
241 nonoffsetted_vertices.push_back(
242 Eigen::Vector3f(-dimension[0]/2, dimension[1]/2, -dimension[2]/2));
243 nonoffsetted_vertices.push_back(
244 Eigen::Vector3f(-dimension[0]/2, dimension[1]/2, dimension[2]/2));
245 nonoffsetted_vertices.push_back(
246 Eigen::Vector3f(dimension[0]/2, -dimension[1]/2, -dimension[2]/2));
247 nonoffsetted_vertices.push_back(
248 Eigen::Vector3f(dimension[0]/2, -dimension[1]/2, dimension[2]/2));
249 nonoffsetted_vertices.push_back(
250 Eigen::Vector3f(dimension[0]/2, dimension[1]/2, -dimension[2]/2));
251 nonoffsetted_vertices.push_back(
252 Eigen::Vector3f(dimension[0]/2, dimension[1]/2, dimension[2]/2));
253 return nonoffsetted_vertices;
258 const geometry_msgs::PoseStamped::ConstPtr& pose)
266 const jsk_recognition_msgs::BoundingBox::ConstPtr&
box)
278 const geometry_msgs::PoseArray::ConstPtr& pose_array)
285 pose_array->header.frame_id);
292 const jsk_recognition_msgs::BoundingBoxArray::ConstPtr& box_array)
301 dimensions_[
i] = Eigen::Vector3f(box_array->boxes[
i].dimensions.x,
302 box_array->boxes[
i].dimensions.y,
303 box_array->boxes[
i].dimensions.z);
308 const std_msgs::Header&
header)
310 jsk_recognition_msgs::BoundingBoxArray box_array;
311 box_array.header.frame_id =
header.frame_id;
312 box_array.header.stamp =
header.stamp;
314 jsk_recognition_msgs::BoundingBox
box;
318 box_array.boxes.push_back(
box);
324 const sensor_msgs::CameraInfo::ConstPtr&
msg,
325 std::vector<cv::Point2d>&
points,
328 double min_u, min_v, max_u, max_v;
332 for (
size_t i = 0;
i <
points.size();
i++) {
341 if (uv.x >
msg->width) {
345 if (uv.y >
msg->height) {
363 cv::Rect raw_roi(min_u, min_v, (max_u - min_u), (max_v - min_v));
364 cv::Rect original(0, 0,
msg->width,
msg->height);
365 cv::Rect roi_region = raw_roi & original;
366 sensor_msgs::CameraInfo roi(*
msg);
367 roi.roi.x_offset = roi_region.x;
368 roi.roi.y_offset = roi_region.y;
369 roi.roi.width = roi_region.width;
370 roi.roi.height = roi_region.height;
371 roi.roi.do_rectify =
true;
374 mask = cv::Mat::zeros(
msg->height,
msg->width, CV_8UC1);
375 cv::Size roi_size(roi_region.width, roi_region.height);
376 cv::Rect roi_rect(cv::Point(roi_region.x, roi_region.y), roi_size);
377 const cv::Scalar
white(255);
378 cv::rectangle(mask, roi_rect,
white, CV_FILLED);
382 #if __cplusplus >= 201103L
383 #define pcl_isfinite(x) std::isfinite(x)
387 const sensor_msgs::PointCloud2::ConstPtr&
msg)
391 vital_checker_->poke();
396 pcl::PointIndices::Ptr all_indices (
new pcl::PointIndices);
397 jsk_recognition_msgs::ClusterPointIndices cluster_indices_msg;
398 std::map<std::string, tf::StampedTransform> transforms;
403 if (transforms.find(
frame_id) == transforms.end()) {
407 msg->header.frame_id,
410 transforms[
frame_id] = new_transform;
415 pcl::PointCloud<pcl::PointXYZ>::Ptr
416 cloud(
new pcl::PointCloud<pcl::PointXYZ>);
422 pcl::PointIndices::Ptr indices (
new pcl::PointIndices);
423 jsk_recognition_msgs::BoundingBox bbox_msg;
424 bbox_msg.header.frame_id =
cloud->header.frame_id;
429 jsk_recognition_utils::cropPointCloud<pcl::PointXYZ>(
cloud, bbox_msg, &(indices->indices));
433 pcl::PointIndices non_nan_indices;
434 for (
size_t j = 0; j < indices->indices.size(); j++) {
435 pcl::PointXYZ
p =
cloud->points[indices->indices[j]];
436 if (pcl_isfinite(
p.x) && pcl_isfinite(
p.y) && pcl_isfinite(
p.z)) {
437 non_nan_indices.indices.push_back(indices->indices[j]);
442 cluster_indices_msg.cluster_indices.push_back(indices_msg);
444 indices_msg.header =
msg->header;
452 pcl::PointIndices::Ptr tmp_indices (
new pcl::PointIndices);
453 std::set<int> positive_indices(all_indices->indices.begin(), all_indices->indices.end());
454 for (
size_t i = 0;
i <
msg->width *
msg->height;
i++) {
455 if (positive_indices.find(
i) == positive_indices.end()) {
456 tmp_indices->indices.push_back(
i);
459 all_indices = tmp_indices;
463 cluster_indices_msg.header = indices_msg.header =
msg->header;
468 catch (std::runtime_error &e) {
469 NODELET_ERROR(
"[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
476 vital_checker_->poke();
480 cv::Mat all_mask_image = cv::Mat::zeros(
msg->height,
msg->width, CV_8UC1);
481 bool model_success_p =
model.fromCameraInfo(
msg);
482 if (!model_success_p) {
483 ROS_ERROR(
"failed to create camera model");
489 msg->header.frame_id,
495 msg->header.stamp)) {
499 Eigen::Affine3f eigen_transform;
503 for (
size_t i = 0;
i < original_vertices.size();
i++) {
504 vertices.push_back(eigen_transform.inverse()
505 * (offset * original_vertices[
i]));
507 std::vector<cv::Point2d> local_points;
508 for (
size_t i = 0;
i < vertices.size();
i++) {
509 cv::Point3d
p(vertices[
i][0], vertices[
i][1], vertices[
i][2]);
510 cv::Point2d uv =
model.project3dToPixel(
p);
511 local_points.push_back(uv);
515 all_mask_image = all_mask_image | mask_image;
525 catch (std::runtime_error &e) {
526 NODELET_ERROR(
"[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());