Provides ROS services to access functionality of package grasp_planning_graspit. More...
#include <GraspItServices.h>
Public Member Functions | |
| GraspItServices () | |
| void | start () |
| ~GraspItServices () | |
Private Member Functions | |
| bool | acceptAddToDB (grasp_planning_graspit_msgs::AddToDatabase::Request &req, grasp_planning_graspit_msgs::AddToDatabase::Response &res) |
| bool | acceptEGPlanning (moveit_msgs::GraspPlanning::Request &req, moveit_msgs::GraspPlanning::Response &res) |
| bool | acceptLoadModel (grasp_planning_graspit_msgs::LoadDatabaseModel::Request &req, grasp_planning_graspit_msgs::LoadDatabaseModel::Response &res) |
| bool | acceptSaveWorld (grasp_planning_graspit_msgs::SaveWorld::Request &req, grasp_planning_graspit_msgs::SaveWorld::Response &res) |
| moveit_msgs::Grasp | getGraspMsg (const EigenGraspResult &r, const std::string &id, const std::vector< std::string > &robotJointNames, const std::string &objectFrame) const |
| GraspItServices (const GraspItServices &o) | |
| void | init () |
| void | readParams () |
Private Attributes | |
| ros::ServiceServer | addGraspitFileSrv |
| std::string | addToDBTopic |
| std::string | dbName |
| bool | defaultFinishWithAutograsp |
| int | defaultMaxPlanningSteps |
| int | defaultNumKeepResults |
| int | defaultNumRepeatPlanning |
| SHARED_PTR < GraspIt::EigenGraspPlanner > | egPlanner |
| std::string | egPlannerName |
| ros::ServiceServer | egPlanningSrv |
| std::string | egPlanningTopic |
| SHARED_PTR< GraspItSceneManager > | graspitMgr |
| float | graspMsgPositionFactor |
| ros::ServiceServer | loadGraspitModelSrv |
| std::string | loadModelTopic |
| SHARED_PTR < GraspItSimpleDBManager > | mgr |
| bool | negateJointDOFs |
| ros::NodeHandle | priv |
| ros::NodeHandle | pub |
| std::string | resultsOutputDirectory |
| bool | saveResultFilesGraspit |
| bool | saveResultFilesInventor |
| ros::ServiceServer | saveWorldSrv |
| std::string | saveWorldTopic |
Provides ROS services to access functionality of package grasp_planning_graspit.
This class maintains a GraspIt::GraspItDatabaseManager object. Services are provided to:
The class GraspIt::EigenGraspPlanner is used for the planning. At this stage, the GraspIt::EigenGraspPlanner implementation supports only simulated annealing.
About the grasp planning request:
About the results of a grasp planning request:
All parameters have to be specified within the node's private namespace. Parmeters are documented in the .yaml config file: ``rosed grasp_planning_graspit_ros GraspItServices.yaml``
Definition at line 80 of file GraspItServices.h.
Definition at line 58 of file GraspItServices.cpp.
Definition at line 68 of file GraspItServices.cpp.
| GraspIt::GraspItServices::GraspItServices | ( | const GraspItServices & | o | ) | [inline, private] |
Definition at line 92 of file GraspItServices.h.
| bool GraspItServices::acceptAddToDB | ( | grasp_planning_graspit_msgs::AddToDatabase::Request & | req, |
| grasp_planning_graspit_msgs::AddToDatabase::Response & | res | ||
| ) | [private] |
callback method for service
Definition at line 128 of file GraspItServices.cpp.
| bool GraspItServices::acceptEGPlanning | ( | moveit_msgs::GraspPlanning::Request & | req, |
| moveit_msgs::GraspPlanning::Response & | res | ||
| ) | [private] |
callback method for service
Definition at line 319 of file GraspItServices.cpp.
| bool GraspItServices::acceptLoadModel | ( | grasp_planning_graspit_msgs::LoadDatabaseModel::Request & | req, |
| grasp_planning_graspit_msgs::LoadDatabaseModel::Response & | res | ||
| ) | [private] |
callback method for service
Definition at line 176 of file GraspItServices.cpp.
| bool GraspItServices::acceptSaveWorld | ( | grasp_planning_graspit_msgs::SaveWorld::Request & | req, |
| grasp_planning_graspit_msgs::SaveWorld::Response & | res | ||
| ) | [private] |
callback method for service
Definition at line 222 of file GraspItServices.cpp.
| moveit_msgs::Grasp GraspItServices::getGraspMsg | ( | const EigenGraspResult & | r, |
| const std::string & | id, | ||
| const std::vector< std::string > & | robotJointNames, | ||
| const std::string & | objectFrame | ||
| ) | const [private] |
Helper method to extract results from an GraspIt::EigenGraspResult object and create a moveit_msgs::Grasp object from it.
| objectFrame | the object's reference frame to use for putting into the resulting moveit_msgs::Grasp (typically the center of the object) |
Definition at line 245 of file GraspItServices.cpp.
| void GraspItServices::init | ( | ) | [private] |
Definition at line 73 of file GraspItServices.cpp.
| void GraspItServices::readParams | ( | ) | [private] |
Definition at line 85 of file GraspItServices.cpp.
| void GraspItServices::start | ( | ) |
Start the services.
Definition at line 118 of file GraspItServices.cpp.
Definition at line 140 of file GraspItServices.h.
std::string GraspIt::GraspItServices::addToDBTopic [private] |
Definition at line 149 of file GraspItServices.h.
std::string GraspIt::GraspItServices::dbName [private] |
Definition at line 147 of file GraspItServices.h.
bool GraspIt::GraspItServices::defaultFinishWithAutograsp [private] |
Definition at line 156 of file GraspItServices.h.
int GraspIt::GraspItServices::defaultMaxPlanningSteps [private] |
Definition at line 153 of file GraspItServices.h.
int GraspIt::GraspItServices::defaultNumKeepResults [private] |
Definition at line 155 of file GraspItServices.h.
int GraspIt::GraspItServices::defaultNumRepeatPlanning [private] |
Definition at line 154 of file GraspItServices.h.
Definition at line 136 of file GraspItServices.h.
std::string GraspIt::GraspItServices::egPlannerName [private] |
Definition at line 148 of file GraspItServices.h.
Definition at line 143 of file GraspItServices.h.
std::string GraspIt::GraspItServices::egPlanningTopic [private] |
Definition at line 152 of file GraspItServices.h.
Definition at line 134 of file GraspItServices.h.
float GraspIt::GraspItServices::graspMsgPositionFactor [private] |
Definition at line 157 of file GraspItServices.h.
Definition at line 141 of file GraspItServices.h.
std::string GraspIt::GraspItServices::loadModelTopic [private] |
Definition at line 150 of file GraspItServices.h.
Definition at line 135 of file GraspItServices.h.
bool GraspIt::GraspItServices::negateJointDOFs [private] |
Definition at line 165 of file GraspItServices.h.
Definition at line 168 of file GraspItServices.h.
ros::NodeHandle GraspIt::GraspItServices::pub [private] |
Definition at line 169 of file GraspItServices.h.
std::string GraspIt::GraspItServices::resultsOutputDirectory [private] |
Definition at line 158 of file GraspItServices.h.
bool GraspIt::GraspItServices::saveResultFilesGraspit [private] |
Definition at line 160 of file GraspItServices.h.
bool GraspIt::GraspItServices::saveResultFilesInventor [private] |
Definition at line 159 of file GraspItServices.h.
Definition at line 142 of file GraspItServices.h.
std::string GraspIt::GraspItServices::saveWorldTopic [private] |
Definition at line 151 of file GraspItServices.h.