#include <grasp_retriever.h>
Public Member Functions | |
ClusterPlannerGraspRetriever (ros::NodeHandle &nh, const std::string &cluster_planner_name, const object_manipulation_msgs::GraspableObject &graspable_object, const std::string &arm_name) | |
virtual void | getGrasps (std::vector< GraspWithMetadata > &grasps) |
Protected Member Functions | |
void | appendGraspsFromClusterPlanner (std::vector< GraspWithMetadata > &grasps) |
virtual void | fetchFromPlanner (const object_manipulation_msgs::GraspableObject &graspable_object) |
Private Attributes | |
sensor_msgs::PointCloud | cloud_ |
ros::ServiceClient | cluster_planner_srv_ |
std::vector < object_manipulation_msgs::Grasp > | grasps_from_cluster_planner_ |
tf::TransformBroadcaster | tf_broadcaster |
Definition at line 202 of file grasp_retriever.h.
probabilistic_grasp_planner::ClusterPlannerGraspRetriever::ClusterPlannerGraspRetriever | ( | ros::NodeHandle & | nh, |
const std::string & | cluster_planner_name, | ||
const object_manipulation_msgs::GraspableObject & | graspable_object, | ||
const std::string & | arm_name | ||
) |
Definition at line 357 of file grasp_retriever.cpp.
void probabilistic_grasp_planner::ClusterPlannerGraspRetriever::appendGraspsFromClusterPlanner | ( | std::vector< GraspWithMetadata > & | grasps | ) | [protected] |
The "tool point" is roughly in the middle of the object enclosed by the grasp, so roughly 13cm from wrist
Definition at line 391 of file grasp_retriever.cpp.
void probabilistic_grasp_planner::ClusterPlannerGraspRetriever::fetchFromPlanner | ( | const object_manipulation_msgs::GraspableObject & | graspable_object | ) | [protected, virtual] |
Note that this is leaving several of the grasp planning arguments empty. If the cluster planner changes this will need to change as well.
Definition at line 368 of file grasp_retriever.cpp.
void probabilistic_grasp_planner::ClusterPlannerGraspRetriever::getGrasps | ( | std::vector< GraspWithMetadata > & | grasps | ) | [virtual] |
Gets the grasps from both the underlying GraspRetriever and the cluster planner call
Add the grasps from the cluster planner
Implements probabilistic_grasp_planner::GraspRetriever.
Definition at line 384 of file grasp_retriever.cpp.
Definition at line 208 of file grasp_retriever.h.
ros::ServiceClient probabilistic_grasp_planner::ClusterPlannerGraspRetriever::cluster_planner_srv_ [private] |
Definition at line 206 of file grasp_retriever.h.
std::vector<object_manipulation_msgs::Grasp> probabilistic_grasp_planner::ClusterPlannerGraspRetriever::grasps_from_cluster_planner_ [private] |
Definition at line 207 of file grasp_retriever.h.
tf::TransformBroadcaster probabilistic_grasp_planner::ClusterPlannerGraspRetriever::tf_broadcaster [private] |
Definition at line 205 of file grasp_retriever.h.