00001 00002 00003 /* 00004 * Copyright (c) 2011, Thomas Ruehr <ruehr@cs.tum.edu> 00005 * All rights reserved. 00006 * 00007 * Redistribution and use in source and binary forms, with or without 00008 * modification, are permitted provided that the following conditions are met: 00009 * 00010 * * Redistributions of source code must retain the above copyright 00011 * notice, this list of conditions and the following disclaimer. 00012 * * Redistributions in binary form must reproduce the above copyright 00013 * notice, this list of conditions and the following disclaimer in the 00014 * documentation and/or other materials provided with the distribution. 00015 * * Neither the name of Willow Garage, Inc. nor the names of its 00016 * contributors may be used to endorse or promote products derived from 00017 * this software without specific prior written permission. 00018 * 00019 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00020 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00021 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00022 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00023 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00024 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00025 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00026 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00027 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00028 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00029 * POSSIBILITY OF SUCH DAMAGE. 00030 */ 00031 00032 00033 #ifndef __Perception3d_H__ 00034 #define __Perception3d_H__ 00035 00036 #include <ros/ros.h> 00037 00038 #include <pcl/point_types.h> 00039 #include <pcl/io/pcd_io.h> 00040 #include "pcl/common/common.h" 00041 00042 #include <boost/thread.hpp> 00043 #include <tf/transform_listener.h> 00044 00045 #define ROSCPP_DEPRECATED 00046 00047 #include <ias_table_msgs/TableCluster.h> 00048 00049 00050 typedef pcl::PointCloud<pcl::PointXYZ> PointCloudT; 00051 00052 class Perception3d{ 00053 00054 public: 00055 00056 static boost::mutex handle_cloud_mutex; 00057 static boost::mutex handle_mutex; 00058 static boost::mutex plane_mutex; 00059 static PointCloudT lastCloud; 00060 static btVector3 handleHint; 00061 static btVector3 handleResult; 00062 static ros::Time cloud_time; 00063 static ros::Time query_time; 00064 static double handleMinDist; 00065 static std::vector<tf::Stamped<tf::Pose> *> handlePoses; 00066 static std::vector<tf::Stamped<tf::Pose> *> planePoses; 00067 00068 //get handles by pose 00069 static void handleCallback(const geometry_msgs::PoseStamped::ConstPtr& msg); 00070 00071 static tf::Stamped<tf::Pose> getHandlePoseFromLaser(int pos); 00072 00073 //get inslied cloud of handles 00074 static void handleCloudCallback(const sensor_msgs::PointCloud2::ConstPtr& msg); 00075 00076 static tf::Stamped<tf::Pose> getHandlePoseFromLaser(tf::Stamped<tf::Pose> hint, double wait = -1); 00077 00078 //get plane center inside fridge 00079 static void fridgePlaneCloudCallback(const sensor_msgs::PointCloud2::ConstPtr& msg); 00080 00081 static tf::Stamped<tf::Pose> getFridgePlaneCenterPose(); 00082 00083 // get bottle 00084 static void bottleCallback(const ias_table_msgs::TableCluster::ConstPtr& msg); 00085 00086 static tf::Stamped<tf::Pose> getBottlePose(); 00087 00088 }; 00089 00090 00091 00092 #endif