35 #define BOOST_PARAMETER_MAX_ARITY 7 39 #include <opencv2/opencv.hpp> 50 #if ( CV_MAJOR_VERSION >= 4) 51 #include <opencv2/imgproc/imgproc_c.h> 58 DiagnosticNodelet::onInit();
63 Eigen::Affine3f
pose = Eigen::Affine3f::Identity();
64 std::vector<double> initial_pos;
69 pose.translation() = Eigen::Vector3f(initial_pos[0],
74 std::vector<double> initial_rot;
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;
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++) {
167 dimensions_.push_back(Eigen::Vector3f(dimensions[i][0],
177 if (
prefixes_.size() != dimensions.size()) {
179 "the size of ~prefixes and ~dimensions are different");
182 for(
int i = 0; i <
prefixes_.size(); i++){
191 = advertise<jsk_recognition_msgs::BoundingBoxArray>(*
pnh_,
"output/box_array", 1);
192 pub_mask_ = advertise<sensor_msgs::Image>(*
pnh_,
"output/mask", 1);
194 pub_cluster_indices_ = advertise<jsk_recognition_msgs::ClusterPointIndices>(*
pnh_,
"output/cluster_point_indices", 1);
202 for (
size_t i = 0; i <
pose_list_.size(); i++) {
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);
286 for (
size_t i = 0; i <
pose_list_.size(); i++) {
292 const jsk_recognition_msgs::BoundingBoxArray::ConstPtr& box_array)
298 for (
size_t i = 0; i <
pose_list_.size(); i++) {
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;
313 for (
size_t i = 0; i <
pose_list_.size(); i++) {
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++) {
333 cv::Point2d uv(points[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 const sensor_msgs::PointCloud2::ConstPtr&
msg)
391 pcl::PointIndices::Ptr all_indices (
new pcl::PointIndices);
392 jsk_recognition_msgs::ClusterPointIndices cluster_indices_msg;
393 std::map<std::string, tf::StampedTransform> transforms;
395 for (
size_t i = 0; i <
pose_list_.size(); i++) {
398 if (transforms.find(frame_id) == transforms.end()) {
402 msg->header.frame_id,
405 transforms[
frame_id] = new_transform;
408 Eigen::Affine3f transform;
410 pcl::PointCloud<pcl::PointXYZ>::Ptr
411 cloud(
new pcl::PointCloud<pcl::PointXYZ>);
414 Eigen::Affine3f transformed_box_pose = transform *
pose_list_[i];
417 pcl::PointIndices::Ptr indices (
new pcl::PointIndices);
418 jsk_recognition_msgs::BoundingBox bbox_msg;
419 bbox_msg.header.frame_id = cloud->header.frame_id;
424 jsk_recognition_utils::cropPointCloud<pcl::PointXYZ>(cloud, bbox_msg, &(indices->indices));
428 pcl::PointIndices non_nan_indices;
429 for (
size_t j = 0; j < indices->indices.size(); j++) {
430 pcl::PointXYZ
p = cloud->points[indices->indices[j]];
431 if (pcl_isfinite(p.x) && pcl_isfinite(p.y) && pcl_isfinite(p.z)) {
432 non_nan_indices.indices.push_back(indices->indices[j]);
437 cluster_indices_msg.cluster_indices.push_back(indices_msg);
439 indices_msg.header = msg->header;
447 pcl::PointIndices::Ptr tmp_indices (
new pcl::PointIndices);
448 std::set<int> positive_indices(all_indices->indices.begin(), all_indices->indices.end());
449 for (
size_t i = 0; i < msg->width * msg->height; i++) {
450 if (positive_indices.find(i) == positive_indices.end()) {
451 tmp_indices->indices.push_back(i);
454 all_indices = tmp_indices;
458 cluster_indices_msg.header = indices_msg.header = msg->header;
463 catch (std::runtime_error &e) {
464 NODELET_ERROR(
"[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
475 cv::Mat all_mask_image = cv::Mat::zeros(msg->height, msg->width, CV_8UC1);
477 if (!model_success_p) {
478 ROS_ERROR(
"failed to create camera model");
481 for (
size_t i = 0; i <
pose_list_.size(); i++) {
484 msg->header.frame_id,
490 msg->header.stamp)) {
493 msg->header.stamp, transform);
494 Eigen::Affine3f eigen_transform;
498 for (
size_t i = 0; i < original_vertices.size(); i++) {
499 vertices.push_back(eigen_transform.inverse()
500 * (offset * original_vertices[i]));
502 std::vector<cv::Point2d> local_points;
503 for (
size_t i = 0; i < vertices.size(); i++) {
504 cv::Point3d
p(vertices[i][0], vertices[i][1], vertices[i][2]);
506 local_points.push_back(uv);
510 all_mask_image = all_mask_image | mask_image;
520 catch (std::runtime_error &e) {
521 NODELET_ERROR(
"[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
virtual void boxArrayCallback(const jsk_recognition_msgs::BoundingBoxArray::ConstPtr &box)
virtual jsk_recognition_utils::Vertices cubeVertices(Eigen::Vector3f &dimension)
std::vector< Eigen::Affine3f > pose_list_
std::vector< ros::Publisher > multiple_pub_indices_
#define NODELET_ERROR(...)
void publish(const boost::shared_ptr< M > &message) const
virtual void poseCallback(const geometry_msgs::PoseStamped::ConstPtr &pose)
void pointFromVectorToXYZ(const FromT &p, ToT &msg)
void transformTFToEigen(const tf::Transform &t, Eigen::Affine3d &e)
bool use_multiple_attention_
void poseEigenToMsg(const Eigen::Affine3d &e, geometry_msgs::Pose &m)
void poseMsgToEigen(const geometry_msgs::Pose &m, Eigen::Affine3d &e)
tf::StampedTransform lookupTransformWithDuration(tf::TransformListener *listener, const std::string &to_frame, const std::string &from_frame, const ros::Time &stamp, ros::Duration duration)
ros::Subscriber sub_points_
virtual void clipPointcloud(const sensor_msgs::PointCloud2::ConstPtr &msg)
ros::Publisher pub_bounding_box_array_
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
virtual void publishBoundingBox(const std_msgs::Header &header)
virtual void boxCallback(const jsk_recognition_msgs::BoundingBox::ConstPtr &box)
virtual void computeROI(const sensor_msgs::CameraInfo::ConstPtr &msg, std::vector< cv::Point2d > &points, cv::Mat &mask)
ros::Subscriber sub_pose_
virtual void poseArrayCallback(const geometry_msgs::PoseArray::ConstPtr &pose)
std::vector< std::string > frame_id_list_
ros::Publisher pub_camera_info_
bool fromCameraInfo(const sensor_msgs::CameraInfo &msg)
virtual void unsubscribe()
virtual void initializePoseList(size_t num)
std::vector< int > addIndices(const std::vector< int > &a, const std::vector< int > &b)
tf::TransformListener * tf_listener_
std::vector< Eigen::Affine3f > transformed_pose_list_
jsk_recognition_utils::Vertices dimensions_
virtual void clip(const sensor_msgs::CameraInfo::ConstPtr &msg)
std::vector< Eigen::Vector3f, Eigen::aligned_allocator< Eigen::Vector3f > > Vertices
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::AttentionClipper, nodelet::Nodelet)
ros::Publisher pub_cluster_indices_
cv::Point2d project3dToPixel(const cv::Point3d &xyz) const
static tf::TransformListener * getInstance()
#define NODELET_FATAL(...)
pcl::PointIndices PCLIndicesMsg
std::vector< std::string > prefixes_
#define NODELET_DEBUG(...)
sensor_msgs::ImagePtr toImageMsg() const
std_msgs::Header fromPCL(const pcl::PCLHeader &pcl_header)
ros::Publisher pub_indices_