collision_map_interface.h
Go to the documentation of this file.
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   ros::ServiceClient cluster_bounding_box_3d_client_;
00089   ros::ServiceClient cluster_bounding_box2_3d_client_;
00090 
00092   ros::ServiceClient get_model_mesh_srv_;
00093 
00095   int collision_object_current_id_;
00096 
00098   bool getMeshFromDatabasePose(const household_objects_database_msgs::DatabaseModelPose &model_pose,
00099                                arm_navigation_msgs::Shape& mesh);
00100 
00102   std::string getNextObjectName();
00103 
00105   bool connectionsPresent();
00106 
00108   void connectServices();
00109 
00111   int point_skip_num_;
00112 
00114   int collision_box_size_;
00115 
00117   double table_thickness_;
00118 
00119  public:
00121   CollisionMapInterface();
00122 
00124 
00126   bool connectionsEstablished(ros::Duration timeout);
00127 
00129   void processCollisionGeometryForTable(const tabletop_object_detector::Table &table,
00130                                         std::string table_collision_name);
00131 
00133   void processCollisionGeometryForObject(const household_objects_database_msgs::DatabaseModelPose &model_pose, 
00134                                          std::string &collision_name);
00135 
00137   void processCollisionGeometryForObjectAsBoundingBox
00138             (const household_objects_database_msgs::DatabaseModelPose &model_pose,
00139              std::string &collision_name);
00140   
00142   void processCollisionGeometryForCluster(const sensor_msgs::PointCloud &cluster, 
00143                                           std::string &collision_name, float collision_size = -1.0);
00144 
00146   void processCollisionGeometryForBoundingBox(const object_manipulation_msgs::ClusterBoundingBox &box, 
00147                                               std::string &collision_name);
00148 
00150   void removeCollisionModel(std::string collision_name);
00151 
00153   void resetCollisionModels();
00154 
00156   void resetAttachedModels();
00157 
00158   void resetCollisionId(int id = 0){collision_object_current_id_ = id;}
00159 
00161   void getClusterBoundingBox(const sensor_msgs::PointCloud &cluster,
00162                              geometry_msgs::PoseStamped &pose_stamped, 
00163                              geometry_msgs::Vector3 &dimensions);
00164 
00166   void getClusterBoundingBox(const sensor_msgs::PointCloud2 &cluster,
00167                              geometry_msgs::PoseStamped &pose_stamped, 
00168                              geometry_msgs::Vector3 &dimensions);
00169 
00171   void getClusterBoundingBox3D(const sensor_msgs::PointCloud &cluster,
00172                              geometry_msgs::PoseStamped &pose_stamped, 
00173                              geometry_msgs::Vector3 &dimensions);
00174 
00176   void getClusterBoundingBox3D(const sensor_msgs::PointCloud2 &cluster,
00177                              geometry_msgs::PoseStamped &pose_stamped, 
00178                              geometry_msgs::Vector3 &dimensions);
00179 
00181   bool extendBoundingBoxZToTable(const tabletop_object_detector::Table &table,
00182                                  geometry_msgs::PoseStamped &pose_stamped, 
00183                                  geometry_msgs::Vector3 &dimensions);
00184 };
00185 
00186 } //namespace tabletop_collision_map_perception
00187 
00188 #endif


tabletop_collision_map_processing
Author(s): Matei Ciocarlie
autogenerated on Fri Jan 3 2014 11:49:29