#include <grasp_generator.h>
Public Member Functions | |
void | generateGrasps () |
GraspGeneratorServiceCaller (ros::NodeHandle &nh, const std::string service_name, const object_manipulation_msgs::GraspableObject &graspable_object, const std::string arm_name) | |
Private Member Functions | |
void | appendMetadataToGrasps (std::vector< object_manipulation_msgs::Grasp > &grasp_msgs, std::vector< GraspWM > &grasps) |
Private Attributes | |
const std::string | arm_name_ |
const object_manipulation_msgs::GraspableObject | object_ |
ros::ServiceClient | service_ |
const std::string | service_name_ |
Definition at line 69 of file grasp_generator.h.
bayesian_grasp_planner::GraspGeneratorServiceCaller::GraspGeneratorServiceCaller | ( | ros::NodeHandle & | nh, | |
const std::string | service_name, | |||
const object_manipulation_msgs::GraspableObject & | graspable_object, | |||
const std::string | arm_name | |||
) |
Definition at line 40 of file grasp_generator.cpp.
void bayesian_grasp_planner::GraspGeneratorServiceCaller::appendMetadataToGrasps | ( | std::vector< object_manipulation_msgs::Grasp > & | grasp_msgs, | |
std::vector< GraspWM > & | grasps | |||
) | [private] |
The "tool point" is roughly in the middle of the object enclosed by the grasp, so roughly 13cm from wrist
Definition at line 67 of file grasp_generator.cpp.
void bayesian_grasp_planner::GraspGeneratorServiceCaller::generateGrasps | ( | ) | [virtual] |
Implements bayesian_grasp_planner::GraspGenerator.
Definition at line 48 of file grasp_generator.cpp.
const std::string bayesian_grasp_planner::GraspGeneratorServiceCaller::arm_name_ [private] |
Definition at line 74 of file grasp_generator.h.
const object_manipulation_msgs::GraspableObject bayesian_grasp_planner::GraspGeneratorServiceCaller::object_ [private] |
Definition at line 73 of file grasp_generator.h.
ros::ServiceClient bayesian_grasp_planner::GraspGeneratorServiceCaller::service_ [private] |
Definition at line 72 of file grasp_generator.h.
const std::string bayesian_grasp_planner::GraspGeneratorServiceCaller::service_name_ [private] |
Definition at line 75 of file grasp_generator.h.