Simply calls the grasp planning service with a given name. More...
#include <grasp_success_probability_computer.h>

| Public Member Functions | |
| virtual void | getProbabilities (const std::vector< GraspWithMetadata > &grasps, std::vector< double > &probabilities) | 
| Calls the grasp planning service for all grasps at the same time. | |
| virtual double | getProbability (const GraspWithMetadata &grasp) | 
| Simply calls the grasp planning service. | |
| GSPCServiceCaller (std::string service_name, const object_manipulation_msgs::GraspableObject &target) | |
| Initializes service client and waits for it to become available. | |
| Private Attributes | |
| ServiceWrapper < object_manipulation_msgs::GraspPlanning > | client_ | 
| The service client used to answer calls. | |
| ros::NodeHandle | priv_nh_ | 
| Node handle in the private namespace. | |
| ros::NodeHandle | root_nh_ | 
| Node handle in the root namespace. | |
| std::string | service_name_ | 
| Remembers the name of the service. | |
| object_manipulation_msgs::GraspableObject | target_ | 
| The object that success is computed on. | |
Simply calls the grasp planning service with a given name.
Definition at line 100 of file grasp_success_probability_computer.h.
| probabilistic_grasp_planner::GSPCServiceCaller::GSPCServiceCaller | ( | std::string | service_name, | 
| const object_manipulation_msgs::GraspableObject & | target | ||
| ) | 
Initializes service client and waits for it to become available.
Definition at line 63 of file grasp_success_probability_computer.cpp.
| void probabilistic_grasp_planner::GSPCServiceCaller::getProbabilities | ( | const std::vector< GraspWithMetadata > & | grasps, | 
| std::vector< double > & | probabilities | ||
| ) |  [virtual] | 
Calls the grasp planning service for all grasps at the same time.
Reimplemented from probabilistic_grasp_planner::GraspSuccessProbabilityComputer.
Definition at line 87 of file grasp_success_probability_computer.cpp.
| double probabilistic_grasp_planner::GSPCServiceCaller::getProbability | ( | const GraspWithMetadata & | grasp | ) |  [virtual] | 
Simply calls the grasp planning service.
Implements probabilistic_grasp_planner::GraspSuccessProbabilityComputer.
Definition at line 73 of file grasp_success_probability_computer.cpp.
| ServiceWrapper<object_manipulation_msgs::GraspPlanning> probabilistic_grasp_planner::GSPCServiceCaller::client_  [private] | 
The service client used to answer calls.
Definition at line 107 of file grasp_success_probability_computer.h.
Node handle in the private namespace.
Definition at line 113 of file grasp_success_probability_computer.h.
Node handle in the root namespace.
Definition at line 116 of file grasp_success_probability_computer.h.
| std::string probabilistic_grasp_planner::GSPCServiceCaller::service_name_  [private] | 
Remembers the name of the service.
Definition at line 104 of file grasp_success_probability_computer.h.
| object_manipulation_msgs::GraspableObject probabilistic_grasp_planner::GSPCServiceCaller::target_  [private] | 
The object that success is computed on.
Definition at line 110 of file grasp_success_probability_computer.h.