pcl_ros_util.h
Go to the documentation of this file.
00001 // -*- mode: c++ -*-
00002 /*********************************************************************
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2015, JSK Lab
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/o2r other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of the JSK Lab nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *********************************************************************/
00035 
00036 
00041 #ifndef JSK_RECOGNITION_UTILS_PCL_ROS_UTIL_H_
00042 #define JSK_RECOGNITION_UTILS_PCL_ROS_UTIL_H_
00043 
00044 #include <ros/ros.h>
00045 
00046 #include <std_msgs/Header.h>
00047 #include <pcl_msgs/PointIndices.h>
00048 
00049 #include <jsk_recognition_msgs/BoundingBox.h>
00050 #include <pcl/PointIndices.h>
00051 #include <pcl/filters/crop_box.h>
00052 #include <sensor_msgs/PointCloud2.h>
00053 
00054 #include "jsk_recognition_utils/pcl_conversion_util.h"
00055 
00056 namespace jsk_recognition_utils
00057 {
00063   void publishPointIndices(ros::Publisher& pub,
00064                            const pcl::PointIndices& indices,
00065                            const std_msgs::Header& header);
00066   
00071   bool isSameFrameId(const std::string& a, const std::string& b);
00072 
00077   bool isSameFrameId(const std_msgs::Header& a, const std_msgs::Header& b);
00078 
00083   template<class T1, class T2>
00084   bool isSameFrameId(const T1& a, const T2& b)
00085   {
00086     return isSameFrameId(a.header, b.header);
00087   }
00088   
00093   bool hasField(const std::string& field_name, const sensor_msgs::PointCloud2& msg);
00094 
00099   template<typename PointT>
00100   void
00101   cropPointCloud(const typename pcl::PointCloud<PointT>::Ptr& cloud,
00102                  const jsk_recognition_msgs::BoundingBox& bbox_msg,
00103                  std::vector<int>* indices,
00104                  bool extract_removed_indices=false)
00105   {
00106     if (cloud->header.frame_id != bbox_msg.header.frame_id)
00107     {
00108       fprintf(stderr, "Frame id of input cloud and bounding box must be same. Cloud: %s, BoundingBox: %s.",
00109               cloud->header.frame_id.c_str(), bbox_msg.header.frame_id.c_str());
00110       return;
00111     }
00112     pcl::CropBox<PointT> crop_box(/*extract_removed_indices=*/extract_removed_indices);
00113 
00114     crop_box.setInputCloud(cloud);
00115 
00116     Eigen::Affine3f box_pose;
00117     tf::poseMsgToEigen(bbox_msg.pose, box_pose);
00118     crop_box.setTranslation(box_pose.translation());
00119     float roll, pitch, yaw;
00120     pcl::getEulerAngles(box_pose, roll, pitch, yaw);
00121     crop_box.setRotation(Eigen::Vector3f(roll, pitch, yaw));
00122 
00123     Eigen::Vector4f max_point(bbox_msg.dimensions.x / 2,
00124                               bbox_msg.dimensions.y / 2,
00125                               bbox_msg.dimensions.z / 2,
00126                               0);
00127     Eigen::Vector4f min_point(-bbox_msg.dimensions.x / 2,
00128                               -bbox_msg.dimensions.y / 2,
00129                               -bbox_msg.dimensions.z / 2,
00130                               0);
00131     crop_box.setMax(max_point);
00132     crop_box.setMin(min_point);
00133 
00134     crop_box.filter(*indices);
00135   }
00136 
00137 }  // namespace jsk_recognition_utils
00138 
00139 #endif  // JSK_RECOGNITION_UTILS_PCL_ROS_UTIL_H_


jsk_recognition_utils
Author(s):
autogenerated on Tue Jul 2 2019 19:40:37