Provides the collision map related services needed by object grasping. More...
#include <collision_map_interface.h>
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::PointCloud &cluster, geometry_msgs::PoseStamped &pose_stamped, geometry_msgs::Vector3 &dimensions) |
Computes the outlier-resistant bounding box for a cluster (PointCloud), z-axis fixed. | |
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), z-axis fixed. | |
void | getClusterBoundingBox3D (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 | getClusterBoundingBox3D (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 | 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_3d_client_ |
ros::ServiceClient | cluster_bounding_box2_client_ |
ros::ServiceClient | cluster_bounding_box_3d_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. |
Provides the collision map related services needed by object grasping.
Definition at line 69 of file collision_map_interface.h.
Connects and waits for all needed services and action servers.
Definition at line 60 of file collision_map_interface.cpp.
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 92 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 85 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 70 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 490 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), z-axis fixed.
Definition at line 408 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), z-axis fixed.
void tabletop_collision_map_processing::CollisionMapInterface::getClusterBoundingBox3D | ( | 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 448 of file collision_map_interface.cpp.
void tabletop_collision_map_processing::CollisionMapInterface::getClusterBoundingBox3D | ( | const sensor_msgs::PointCloud2 & | cluster, |
geometry_msgs::PoseStamped & | pose_stamped, | ||
geometry_msgs::Vector3 & | dimensions | ||
) |
Computes the outlier-resistant bounding box for a cluster (PointCloud2)
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 363 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 146 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 295 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 322 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 219 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 242 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 154 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 110 of file collision_map_interface.cpp.
Removes all the models attached to the robot in the collision map.
Definition at line 131 of file collision_map_interface.cpp.
void tabletop_collision_map_processing::CollisionMapInterface::resetCollisionId | ( | int | id = 0 | ) | [inline] |
Definition at line 160 of file collision_map_interface.h.
Removes all collision models from the map.
Definition at line 120 of file collision_map_interface.cpp.
ros::Publisher tabletop_collision_map_processing::CollisionMapInterface::attached_object_pub_ [private] |
Publisher for attached objects.
Definition at line 85 of file collision_map_interface.h.
ros::ServiceClient tabletop_collision_map_processing::CollisionMapInterface::cluster_bounding_box2_3d_client_ [private] |
Definition at line 91 of file collision_map_interface.h.
ros::ServiceClient tabletop_collision_map_processing::CollisionMapInterface::cluster_bounding_box2_client_ [private] |
Definition at line 89 of file collision_map_interface.h.
ros::ServiceClient tabletop_collision_map_processing::CollisionMapInterface::cluster_bounding_box_3d_client_ [private] |
Definition at line 90 of file collision_map_interface.h.
ros::ServiceClient tabletop_collision_map_processing::CollisionMapInterface::cluster_bounding_box_client_ [private] |
Client for computing the outlier-resistant bounding box of a cluster.
Definition at line 88 of file collision_map_interface.h.
Default box size for points when adding a point cloud collision object.
Definition at line 116 of file collision_map_interface.h.
int tabletop_collision_map_processing::CollisionMapInterface::collision_object_current_id_ [private] |
Counts the number of objects added to the map since the last reset.
Definition at line 97 of file collision_map_interface.h.
ros::Publisher tabletop_collision_map_processing::CollisionMapInterface::collision_object_pub_ [private] |
Publisher for objects in map.
Definition at line 82 of file collision_map_interface.h.
Flag that shows if all the needed service and action servers have been found.
Definition at line 79 of file collision_map_interface.h.
ros::ServiceClient tabletop_collision_map_processing::CollisionMapInterface::get_model_mesh_srv_ [private] |
Client for getting the mesh for a database object.
Definition at line 94 of file collision_map_interface.h.
Only keep every point_skip_num_ points when adding a point cloud collision object.
Definition at line 113 of file collision_map_interface.h.
The private node handle.
Definition at line 76 of file collision_map_interface.h.
The root node handle.
Definition at line 73 of file collision_map_interface.h.
Thickness of the table when added to the collision environment.
Definition at line 119 of file collision_map_interface.h.