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>
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 |
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``
Definition at line 23 of file EigenGraspPlannerClient.h.
Definition at line 14 of file EigenGraspPlannerClient.cpp.
Definition at line 19 of file EigenGraspPlannerClient.cpp.
int EigenGraspPlannerClient::addObject | ( | const std::string & | modelName, |
const std::string | filename, | ||
bool | objectGraspable | ||
) |
Adds an object to the database
filename | the file with the GraspIt! object definition |
objectGraspable | set to true is object is graspable |
-1 | could not call service |
-2 | could not add object to database |
-3 | client 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
filename | the file with the GraspIt! robot definition |
jointNames | the names of the URDF joint names in the order they are specified in the graspit file. |
-1 | could not call service |
-2 | could not add robot to database |
-3 | client 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.
bool EigenGraspPlannerClient::isOK | ( | ) |
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
modelID | ID as returned from addRobot() or addObject() |
clearWorld | clear other models before loading this one |
modelPose | the pose where to load the model. |
0 | success |
-1 | failed to call service |
-2 | could not load model, is it not in the database? |
-3 | client 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()).
objectID | ID as returned from addRobot() or addObject() |
newObjectPose | this 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. |
resultsOutputDirectory | the 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 |
0 | planning successfully done, results written to output directory |
-1 | could not create results directory (only tried if resultsOutputDirectory non-empty) |
-2 | could not call planning service |
-3 | planning failed |
-4 | client not initialized. Have the ROS parameters been set for the service names? |
Definition at line 148 of file EigenGraspPlannerClient.cpp.
Definition at line 100 of file EigenGraspPlannerClient.h.
std::string grasp_planning_graspit_ros::EigenGraspPlannerClient::addToDBService [private] |
Definition at line 94 of file EigenGraspPlannerClient.h.
Definition at line 100 of file EigenGraspPlannerClient.h.
std::string grasp_planning_graspit_ros::EigenGraspPlannerClient::egPlanningService [private] |
Definition at line 97 of file EigenGraspPlannerClient.h.
Definition at line 93 of file EigenGraspPlannerClient.h.
Definition at line 100 of file EigenGraspPlannerClient.h.
std::string grasp_planning_graspit_ros::EigenGraspPlannerClient::loadModelService [private] |
Definition at line 95 of file EigenGraspPlannerClient.h.
Definition at line 99 of file EigenGraspPlannerClient.h.
std::string grasp_planning_graspit_ros::EigenGraspPlannerClient::saveWorldService [private] |
Definition at line 96 of file EigenGraspPlannerClient.h.