Public Member Functions | Private Member Functions | Private Attributes
grasp_planning_graspit_ros::EigenGraspPlannerClient Class Reference

Uses the GraspIt! services to add and load robot and objects and do the planning. This class can be used as a helper. More...

#include <EigenGraspPlannerClient.h>

List of all members.

Public Member Functions

int addObject (const std::string &modelName, const std::string filename, bool objectGraspable)
int addRobot (const std::string &modelName, const std::string filename, const std::vector< std::string > &jointNames)
 EigenGraspPlannerClient ()
bool isOK ()
int loadModel (const int modelID, bool clearWorld, const geometry_msgs::Pose &modelPose)
int plan (const std::string robotModelName, const int objectID, const geometry_msgs::Pose *newObjectPose, const std::string &resultsOutputDirectory, std::vector< moveit_msgs::Grasp > &results)
 ~EigenGraspPlannerClient ()

Private Member Functions

void init ()

Private Attributes

ros::ServiceClient add_to_db_client
std::string addToDBService
ros::ServiceClient eg_planner_client
std::string egPlanningService
bool initialized
ros::ServiceClient load_model_client
std::string loadModelService
ros::NodeHandle node
std::string saveWorldService

Detailed Description

Uses the GraspIt! services to add and load robot and objects and do the planning. This class can be used as a helper.

Reads parameters from ROS parameter service as specified and documented in ``rosed grasp_planning_graspit_ros EigenGraspPlannerClient.yaml``

Author:
Jennifer Buehler
Date:
March 2016

Definition at line 23 of file EigenGraspPlannerClient.h.


Constructor & Destructor Documentation

Definition at line 14 of file EigenGraspPlannerClient.cpp.

Definition at line 19 of file EigenGraspPlannerClient.cpp.


Member Function Documentation

int EigenGraspPlannerClient::addObject ( const std::string &  modelName,
const std::string  filename,
bool  objectGraspable 
)

Adds an object to the database

Parameters:
filenamethe file with the GraspIt! object definition
objectGraspableset to true is object is graspable
Returns:
>=0 ID of object loaded
Return values:
-1could not call service
-2could not add object to database
-3client not initialized. Have the ROS parameters been set for the service names?

Definition at line 87 of file EigenGraspPlannerClient.cpp.

int EigenGraspPlannerClient::addRobot ( const std::string &  modelName,
const std::string  filename,
const std::vector< std::string > &  jointNames 
)

Adds a robot to the database

Parameters:
filenamethe file with the GraspIt! robot definition
jointNamesthe names of the URDF joint names in the order they are specified in the graspit file.
Returns:
>=0 ID of robot loaded
Return values:
-1could not call service
-2could not add robot to database
-3client not initialized. Have the ROS parameters been set for the service names?

Definition at line 56 of file EigenGraspPlannerClient.cpp.

void EigenGraspPlannerClient::init ( ) [private]

Definition at line 29 of file EigenGraspPlannerClient.cpp.

Returns:
true if client configured properly and should be working.

Definition at line 21 of file EigenGraspPlannerClient.cpp.

int EigenGraspPlannerClient::loadModel ( const int  modelID,
bool  clearWorld,
const geometry_msgs::Pose &  modelPose 
)

Loads a model from the database to the GraspIt! world

Parameters:
modelIDID as returned from addRobot() or addObject()
clearWorldclear other models before loading this one
modelPosethe pose where to load the model.
Return values:
0success
-1failed to call service
-2could not load model, is it not in the database?
-3client not initialized. Have the ROS parameters been set for the service names?

Definition at line 117 of file EigenGraspPlannerClient.cpp.

int EigenGraspPlannerClient::plan ( const std::string  robotModelName,
const int  objectID,
const geometry_msgs::Pose *  newObjectPose,
const std::string &  resultsOutputDirectory,
std::vector< moveit_msgs::Grasp > &  results 
)

Does the planning for the given robotModelName and objectID. Both models have to be loaded in the GraspIt! world (by function loadModel()).

Parameters:
objectIDID as returned from addRobot() or addObject()
newObjectPosethis is optional and can be set to NULL to disable. Set a different pose to put the object at in the current graspit world. Has to be in the global frame of the graspit world. If NULL, the current pose in the GraspIt! pose will be used.
resultsOutputDirectorythe directory where the Grasp messages will be saved. This does not need to be the same directory at which the GraspIt! service stores its grasp results. Set to empty string if results should not be saved to file but only returned in results
Return values:
0planning successfully done, results written to output directory
-1could not create results directory (only tried if resultsOutputDirectory non-empty)
-2could not call planning service
-3planning failed
-4client not initialized. Have the ROS parameters been set for the service names?

Definition at line 148 of file EigenGraspPlannerClient.cpp.


Member Data Documentation

Definition at line 100 of file EigenGraspPlannerClient.h.

Definition at line 94 of file EigenGraspPlannerClient.h.

Definition at line 100 of file EigenGraspPlannerClient.h.

Definition at line 97 of file EigenGraspPlannerClient.h.

Definition at line 93 of file EigenGraspPlannerClient.h.

Definition at line 100 of file EigenGraspPlannerClient.h.

Definition at line 95 of file EigenGraspPlannerClient.h.

Definition at line 99 of file EigenGraspPlannerClient.h.

Definition at line 96 of file EigenGraspPlannerClient.h.


The documentation for this class was generated from the following files:


grasp_planning_graspit_ros
Author(s): Jennifer Buehler
autogenerated on Wed May 8 2019 02:53:42