$search
00001 /********************************************************************* 00002 * 00003 * Copyright (c) 2009, Willow Garage, Inc. 00004 * All rights reserved. 00005 * 00006 * Redistribution and use in source and binary forms, with or without 00007 * modification, are permitted provided that the following conditions 00008 * 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 00013 * copyright notice, this list of conditions and the following 00014 * disclaimer in the documentation and/or other materials provided 00015 * with the distribution. 00016 * * Neither the name of the Willow Garage nor the names of its 00017 * contributors may be used to endorse or promote products derived 00018 * from this software without specific prior written permission. 00019 * 00020 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00021 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00022 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00023 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00024 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00025 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00026 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00027 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00028 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00029 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00030 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00031 * POSSIBILITY OF SUCH DAMAGE. 00032 *********************************************************************/ 00033 00034 // Author(s): Gil Jones and Matei Ciocarlie 00035 00036 #ifndef _COLLISION_MAP_INTERFACE_H_ 00037 #define _COLLISION_MAP_INTERFACE_H_ 00038 00039 #include <stdexcept> 00040 00041 #include <ros/ros.h> 00042 00043 #include <actionlib/client/simple_action_client.h> 00044 00045 #include <household_objects_database_msgs/DatabaseModelPose.h> 00046 00047 #include <sensor_msgs/PointCloud.h> 00048 00049 #include <arm_navigation_msgs/Shape.h> 00050 00051 #include <tabletop_object_detector/Table.h> 00052 #include <tabletop_object_detector/TabletopDetectionResult.h> 00053 00054 #include <object_manipulation_msgs/GraspableObject.h> 00055 #include <object_manipulation_msgs/ClusterBoundingBox.h> 00056 00057 namespace tabletop_collision_map_processing { 00058 00060 class CollisionMapException : public std::runtime_error 00061 { 00062 public: 00063 CollisionMapException(const std::string error) : std::runtime_error("collision map: "+error) {}; 00064 }; 00065 00067 class CollisionMapInterface 00068 { 00069 private: 00071 ros::NodeHandle root_nh_; 00072 00074 ros::NodeHandle priv_nh_; 00075 00077 bool connections_established_; 00078 00080 ros::Publisher collision_object_pub_; 00081 00083 ros::Publisher attached_object_pub_; 00084 00086 ros::ServiceClient cluster_bounding_box_client_; 00087 ros::ServiceClient cluster_bounding_box2_client_; 00088 00090 ros::ServiceClient get_model_mesh_srv_; 00091 00093 int collision_object_current_id_; 00094 00096 bool getMeshFromDatabasePose(const household_objects_database_msgs::DatabaseModelPose &model_pose, 00097 arm_navigation_msgs::Shape& mesh); 00098 00100 std::string getNextObjectName(); 00101 00103 bool connectionsPresent(); 00104 00106 void connectServices(); 00107 00109 int point_skip_num_; 00110 00112 int collision_box_size_; 00113 00115 double table_thickness_; 00116 00117 public: 00119 CollisionMapInterface(); 00120 00122 00124 bool connectionsEstablished(ros::Duration timeout); 00125 00127 void processCollisionGeometryForTable(const tabletop_object_detector::Table &table, 00128 std::string table_collision_name); 00129 00131 void processCollisionGeometryForObject(const household_objects_database_msgs::DatabaseModelPose &model_pose, 00132 std::string &collision_name); 00133 00135 void processCollisionGeometryForObjectAsBoundingBox 00136 (const household_objects_database_msgs::DatabaseModelPose &model_pose, 00137 std::string &collision_name); 00138 00140 void processCollisionGeometryForCluster(const sensor_msgs::PointCloud &cluster, 00141 std::string &collision_name, float collision_size = -1.0); 00142 00144 void processCollisionGeometryForBoundingBox(const object_manipulation_msgs::ClusterBoundingBox &box, 00145 std::string &collision_name); 00146 00148 void removeCollisionModel(std::string collision_name); 00149 00151 void resetCollisionModels(); 00152 00154 void resetAttachedModels(); 00155 00156 void resetCollisionId(int id = 0){collision_object_current_id_ = id;} 00157 00159 void getClusterBoundingBox(const sensor_msgs::PointCloud &cluster, 00160 geometry_msgs::PoseStamped &pose_stamped, 00161 geometry_msgs::Vector3 &dimensions); 00162 00164 void getClusterBoundingBox(const sensor_msgs::PointCloud2 &cluster, 00165 geometry_msgs::PoseStamped &pose_stamped, 00166 geometry_msgs::Vector3 &dimensions); 00167 00169 bool extendBoundingBoxZToTable(const tabletop_object_detector::Table &table, 00170 geometry_msgs::PoseStamped &pose_stamped, 00171 geometry_msgs::Vector3 &dimensions); 00172 }; 00173 00174 } //namespace tabletop_collision_map_perception 00175 00176 #endif