$search

tabletop_collision_map_processing::CollisionMapInterface Class Reference

Provides the collision map related services needed by object grasping. More...

#include <collision_map_interface.h>

List of all members.

Public Member Functions

 CollisionMapInterface ()
 Connects and waits for all needed services and action servers.
bool connectionsEstablished (ros::Duration timeout)
 Waits until all needed services and action servers are available, then connects all appropriate services.
bool extendBoundingBoxZToTable (const tabletop_object_detector::Table &table, geometry_msgs::PoseStamped &pose_stamped, geometry_msgs::Vector3 &dimensions)
 Extends a bounding box along its Z dimension until it touches the table.
void getClusterBoundingBox (const sensor_msgs::PointCloud2 &cluster, geometry_msgs::PoseStamped &pose_stamped, geometry_msgs::Vector3 &dimensions)
 Computes the outlier-resistant bounding box for a cluster (PointCloud2).
void getClusterBoundingBox (const sensor_msgs::PointCloud &cluster, geometry_msgs::PoseStamped &pose_stamped, geometry_msgs::Vector3 &dimensions)
 Computes the outlier-resistant bounding box for a cluster (PointCloud).
void processCollisionGeometryForBoundingBox (const object_manipulation_msgs::ClusterBoundingBox &box, std::string &collision_name)
 Sends collision geometry for a bounding box into the collision map.
void processCollisionGeometryForCluster (const sensor_msgs::PointCloud &cluster, std::string &collision_name, float collision_size=-1.0)
 Sends collision geometry for a point cloud into the collision map.
void processCollisionGeometryForObject (const household_objects_database_msgs::DatabaseModelPose &model_pose, std::string &collision_name)
 Sends collision geometry for object into the collision map.
void processCollisionGeometryForObjectAsBoundingBox (const household_objects_database_msgs::DatabaseModelPose &model_pose, std::string &collision_name)
 Sends collision geometry for bounding box of object vertices into the collision map.
void processCollisionGeometryForTable (const tabletop_object_detector::Table &table, std::string table_collision_name)
 Sends table info into the collision map.
void removeCollisionModel (std::string collision_name)
 Removes the given collision model from the collision environment.
void resetAttachedModels ()
 Removes all the models attached to the robot in the collision map.
void resetCollisionId (int id=0)
void resetCollisionModels ()
 Removes all collision models from the map.

Private Member Functions

bool connectionsPresent ()
 Returns true if all needed services and action servers are available.
void connectServices ()
 Connects all the services that it uses to their appropriate service names.
bool getMeshFromDatabasePose (const household_objects_database_msgs::DatabaseModelPose &model_pose, arm_navigation_msgs::Shape &mesh)
 Produces an object mesh from a database object.
std::string getNextObjectName ()
 Creates a name for an object based on collision_object_current_id_, which is then incremented.

Private Attributes

ros::Publisher attached_object_pub_
 Publisher for attached objects.
ros::ServiceClient cluster_bounding_box2_client_
ros::ServiceClient cluster_bounding_box_client_
 Client for computing the outlier-resistant bounding box of a cluster.
int collision_box_size_
 Default box size for points when adding a point cloud collision object.
int collision_object_current_id_
 Counts the number of objects added to the map since the last reset.
ros::Publisher collision_object_pub_
 Publisher for objects in map.
bool connections_established_
 Flag that shows if all the needed service and action servers have been found.
ros::ServiceClient get_model_mesh_srv_
 Client for getting the mesh for a database object.
int point_skip_num_
 Only keep every point_skip_num_ points when adding a point cloud collision object.
ros::NodeHandle priv_nh_
 The private node handle.
ros::NodeHandle root_nh_
 The root node handle.
double table_thickness_
 Thickness of the table when added to the collision environment.

Detailed Description

Provides the collision map related services needed by object grasping.

Definition at line 67 of file collision_map_interface.h.


Constructor & Destructor Documentation

tabletop_collision_map_processing::CollisionMapInterface::CollisionMapInterface (  ) 

Connects and waits for all needed services and action servers.

Definition at line 58 of file collision_map_interface.cpp.


Member Function Documentation

bool tabletop_collision_map_processing::CollisionMapInterface::connectionsEstablished ( ros::Duration  timeout  ) 

Waits until all needed services and action servers are available, then connects all appropriate services.

Will wait at most timeout for the connections, then return false if the connections are not present. If all connections are found, future calls no longer check them and return true immediately.

Definition at line 86 of file collision_map_interface.cpp.

bool tabletop_collision_map_processing::CollisionMapInterface::connectionsPresent (  )  [private]

Returns true if all needed services and action servers are available.

Definition at line 79 of file collision_map_interface.cpp.

void tabletop_collision_map_processing::CollisionMapInterface::connectServices (  )  [private]

Connects all the services that it uses to their appropriate service names.

Definition at line 68 of file collision_map_interface.cpp.

bool tabletop_collision_map_processing::CollisionMapInterface::extendBoundingBoxZToTable ( const tabletop_object_detector::Table table,
geometry_msgs::PoseStamped pose_stamped,
geometry_msgs::Vector3 dimensions 
)

Extends a bounding box along its Z dimension until it touches the table.

Assumes the bounding box is in the same frame as the table

Definition at line 427 of file collision_map_interface.cpp.

void tabletop_collision_map_processing::CollisionMapInterface::getClusterBoundingBox ( const sensor_msgs::PointCloud2 cluster,
geometry_msgs::PoseStamped pose_stamped,
geometry_msgs::Vector3 dimensions 
)

Computes the outlier-resistant bounding box for a cluster (PointCloud2).

Definition at line 405 of file collision_map_interface.cpp.

void tabletop_collision_map_processing::CollisionMapInterface::getClusterBoundingBox ( const sensor_msgs::PointCloud cluster,
geometry_msgs::PoseStamped pose_stamped,
geometry_msgs::Vector3 dimensions 
)

Computes the outlier-resistant bounding box for a cluster (PointCloud).

Definition at line 385 of file collision_map_interface.cpp.

bool tabletop_collision_map_processing::CollisionMapInterface::getMeshFromDatabasePose ( const household_objects_database_msgs::DatabaseModelPose model_pose,
arm_navigation_msgs::Shape mesh 
) [private]

Produces an object mesh from a database object.

Definition at line 348 of file collision_map_interface.cpp.

std::string tabletop_collision_map_processing::CollisionMapInterface::getNextObjectName (  )  [private]

Creates a name for an object based on collision_object_current_id_, which is then incremented.

Definition at line 140 of file collision_map_interface.cpp.

void tabletop_collision_map_processing::CollisionMapInterface::processCollisionGeometryForBoundingBox ( const object_manipulation_msgs::ClusterBoundingBox box,
std::string &  collision_name 
)

Sends collision geometry for a bounding box into the collision map.

Definition at line 280 of file collision_map_interface.cpp.

void tabletop_collision_map_processing::CollisionMapInterface::processCollisionGeometryForCluster ( const sensor_msgs::PointCloud cluster,
std::string &  collision_name,
float  collision_size = -1.0 
)

Sends collision geometry for a point cloud into the collision map.

Definition at line 307 of file collision_map_interface.cpp.

void tabletop_collision_map_processing::CollisionMapInterface::processCollisionGeometryForObject ( const household_objects_database_msgs::DatabaseModelPose model_pose,
std::string &  collision_name 
)

Sends collision geometry for object into the collision map.

Definition at line 204 of file collision_map_interface.cpp.

void tabletop_collision_map_processing::CollisionMapInterface::processCollisionGeometryForObjectAsBoundingBox ( const household_objects_database_msgs::DatabaseModelPose model_pose,
std::string &  collision_name 
)

Sends collision geometry for bounding box of object vertices into the collision map.

Definition at line 227 of file collision_map_interface.cpp.

void tabletop_collision_map_processing::CollisionMapInterface::processCollisionGeometryForTable ( const tabletop_object_detector::Table table,
std::string  table_collision_name 
)

Sends table info into the collision map.

Definition at line 148 of file collision_map_interface.cpp.

void tabletop_collision_map_processing::CollisionMapInterface::removeCollisionModel ( std::string  collision_name  ) 

Removes the given collision model from the collision environment.

Definition at line 104 of file collision_map_interface.cpp.

void tabletop_collision_map_processing::CollisionMapInterface::resetAttachedModels (  ) 

Removes all the models attached to the robot in the collision map.

Definition at line 125 of file collision_map_interface.cpp.

void tabletop_collision_map_processing::CollisionMapInterface::resetCollisionId ( int  id = 0  )  [inline]

Definition at line 156 of file collision_map_interface.h.

void tabletop_collision_map_processing::CollisionMapInterface::resetCollisionModels (  ) 

Removes all collision models from the map.

Definition at line 114 of file collision_map_interface.cpp.


Member Data Documentation

Publisher for attached objects.

Definition at line 83 of file collision_map_interface.h.

Definition at line 87 of file collision_map_interface.h.

Client for computing the outlier-resistant bounding box of a cluster.

Definition at line 86 of file collision_map_interface.h.

Default box size for points when adding a point cloud collision object.

Definition at line 112 of file collision_map_interface.h.

Counts the number of objects added to the map since the last reset.

Definition at line 93 of file collision_map_interface.h.

Publisher for objects in map.

Definition at line 80 of file collision_map_interface.h.

Flag that shows if all the needed service and action servers have been found.

Definition at line 77 of file collision_map_interface.h.

Client for getting the mesh for a database object.

Definition at line 90 of file collision_map_interface.h.

Only keep every point_skip_num_ points when adding a point cloud collision object.

Definition at line 109 of file collision_map_interface.h.

The private node handle.

Definition at line 74 of file collision_map_interface.h.

The root node handle.

Definition at line 71 of file collision_map_interface.h.

Thickness of the table when added to the collision environment.

Definition at line 115 of file collision_map_interface.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


tabletop_collision_map_processing
Author(s): Matei Ciocarlie
autogenerated on Tue Mar 5 12:32:50 2013