#include <OverheadGraspPlanner.h>

Classes | |
| struct | ParameterVals |
Public Member Functions | |
| void | fetchParameters (bool useNodeNamespace) |
| void | generateGraspPoses (const geometry_msgs::Pose &pose, int numCandidates, std::vector< geometry_msgs::Pose > &poses) |
| std::string | getPlannerName () |
| OverheadGraspPlanner () | |
| bool | planGrasp (object_manipulation_msgs::GraspPlanning::Request &req, object_manipulation_msgs::GraspPlanning::Response &res) |
| virtual | ~OverheadGraspPlanner () |
Protected Attributes | |
| ParameterVals | _ParamVals |
| tf::TransformListener | _tfListener |
| bool | _UsingDefaultApproachVector |
| std::string | _WorldFrameId |
Static Protected Attributes | |
| static const std::string | _GraspPlannerName = GRASP_PLANNER_NAME |
Definition at line 43 of file OverheadGraspPlanner.h.
Definition at line 28 of file OverheadGraspPlanner.cpp.
| OverheadGraspPlanner::~OverheadGraspPlanner | ( | ) | [virtual] |
Definition at line 38 of file OverheadGraspPlanner.cpp.
| void OverheadGraspPlanner::fetchParameters | ( | bool | useNodeNamespace | ) | [virtual] |
Implements GraspPlannerInterface.
Definition at line 42 of file OverheadGraspPlanner.cpp.
| void OverheadGraspPlanner::generateGraspPoses | ( | const geometry_msgs::Pose & | pose, |
| int | numCandidates, | ||
| std::vector< geometry_msgs::Pose > & | poses | ||
| ) |
Definition at line 418 of file OverheadGraspPlanner.cpp.
| std::string OverheadGraspPlanner::getPlannerName | ( | ) | [virtual] |
Implements GraspPlannerInterface.
Definition at line 90 of file OverheadGraspPlanner.cpp.
| bool OverheadGraspPlanner::planGrasp | ( | object_manipulation_msgs::GraspPlanning::Request & | req, |
| object_manipulation_msgs::GraspPlanning::Response & | res | ||
| ) | [virtual] |
Implements GraspPlannerInterface.
Definition at line 95 of file OverheadGraspPlanner.cpp.
const std::string OverheadGraspPlanner::_GraspPlannerName = GRASP_PLANNER_NAME [static, protected] |
Definition at line 70 of file OverheadGraspPlanner.h.
ParameterVals OverheadGraspPlanner::_ParamVals [protected] |
Definition at line 72 of file OverheadGraspPlanner.h.
Definition at line 73 of file OverheadGraspPlanner.h.
bool OverheadGraspPlanner::_UsingDefaultApproachVector [protected] |
Definition at line 76 of file OverheadGraspPlanner.h.
std::string OverheadGraspPlanner::_WorldFrameId [protected] |
Definition at line 71 of file OverheadGraspPlanner.h.