$search

graspit_ros_planning::RosGraspitInterface Class Reference

Main class, combining a ROS node with a GraspIt! interface. More...

#include <ros_graspit_interface.h>

List of all members.

Public Member Functions

virtual int init (int argc, char **argv)
 Creates the node handles, advertises services, connects to the database.
virtual int mainLoop ()
 Simply calls ros::spinOnce() to process the ROS event loop.
 RosGraspitInterface ()
 Inits ROS, but (for now) without passing any arguments.
 ~RosGraspitInterface ()
 Deletes the node handle and the db manager.

Private Member Functions

bool clearBodiesCB (graspit_ros_planning_msgs::ClearBodies::Request &request, graspit_ros_planning_msgs::ClearBodies::Response &response)
 Callback for the clear bodies service.
void computeEnergy (Body *object, graspit_ros_planning_msgs::TestGrasp::Response &response)
 Performs the grasp test using the grasp energy function.
bool generateGraspCB (graspit_ros_planning_msgs::GenerateGrasp::Request &request, graspit_ros_planning_msgs::GenerateGrasp::Response &response)
 Callback for the grasp generation service, for PR2 gripper.
GraspitDBModel * getModel (int model_id)
 -------------------------- populating the graspit world ------------------------------
bool graspPlanningCB (object_manipulation_msgs::GraspPlanning::Request &request, object_manipulation_msgs::GraspPlanning::Response &response)
 Callback for the general grasp planning service.
void gripperCollisionCheck (const Body *object, graspit_ros_planning_msgs::TestGrasp::Response &response)
 Checks collisions between the gripper and the environment.
bool loadGripper ()
 Loads the gripper info from its file, if not already loaded.
bool loadModelCB (graspit_ros_planning_msgs::LoadDatabaseModel::Request &request, graspit_ros_planning_msgs::LoadDatabaseModel::Response &response)
 Callback for the load model service.
bool loadObstacleCB (graspit_ros_planning_msgs::LoadObstacle::Request &request, graspit_ros_planning_msgs::LoadObstacle::Response &response)
 Callback for the load obstacle service.
bool simulateScanCB (graspit_ros_planning_msgs::SimulateScan::Request &request, graspit_ros_planning_msgs::SimulateScan::Response &response)
 Callback for the clear bodies service.
bool testGraspCB (graspit_ros_planning_msgs::TestGrasp::Request &request, graspit_ros_planning_msgs::TestGrasp::Response &response)
 Callback for the detailed, graspit-specific test grasp service.
void testGraspCompliant (const object_manipulation_msgs::Grasp &grasp, GraspableBody *object, graspit_ros_planning_msgs::TestGrasp::Response &response)
 Tests a grasp using the compliant method.
void testGraspDirect (const object_manipulation_msgs::Grasp &grasp, GraspableBody *object, graspit_ros_planning_msgs::TestGrasp::Response &response)
 Tests a grasp using the direct method.
void testGraspReactive (const object_manipulation_msgs::Grasp &grasp, GraspableBody *object, graspit_ros_planning_msgs::TestGrasp::Response &response)
 Tests a grasp using the direct method.
void testGraspRobustReactive (const object_manipulation_msgs::Grasp &grasp, GraspableBody *object, graspit_ros_planning_msgs::TestGrasp::Response &response)
 Tests a grasp using the direct method.
bool verifyGraspCB (graspit_ros_planning_msgs::VerifyGrasp::Request &request, graspit_ros_planning_msgs::VerifyGrasp::Response &response)
 Callback for the grasp verifying service, for PR2 gripper.

Private Attributes

ros::ServiceServer clear_bodies_srv_
 Server for the clear bodies service.
db_planner::DatabaseManager * db_mgr_
 A GraspIt database manager used for talking to the database.
double default_energy_threshold_
 Used for converting energy values fo probabilities; soon to be replaced.
int default_grasp_test_type_
 Used for general GrapsPlanning calls; should be a value from graspit_ros_planning_msgs::TestGrasp.
ros::ServiceServer generate_grasp_srv_
 Server for the generate grasp service.
ros::ServiceServer grasp_planning_srv_
 Server for the grasp planning service.
Pr2Gripper2010 * gripper_
 A GraspIt instance of the PR2 gripper.
ros::ServiceServer load_model_srv_
 Server for the load model service.
ros::ServiceServer load_obstacle_srv_
 Server for the load obstacle service.
std::map< int, GraspitDBModel * > models_
 Keeps track of all models already retrieved from the database, mapped by their scaled model id.
ros::NodeHandlepriv_nh_
 Node handle in the private namespace.
ros::NodeHandleroot_nh_
 Node handle in the root namespace.
ros::Publisher scan_publisher_
 Publisher for simulated scans.
ros::ServiceServer simulate_scan_srv_
 Server for the scan simulation service.
ros::ServiceServer test_grasp_srv_
 Server for the test grasp service.
ros::ServiceServer verify_grasp_srv_
 Server for the grasp collision checking service.

Detailed Description

Main class, combining a ROS node with a GraspIt! interface.

Note that this class inherits from GraspIt's Plugin class and implements the necessary functions to serve as a GraspIt plugin. See include/plugin.h in the GraspIt code for the base class.

Provides a number of ROS services that directly operate on the GraspIt world, such as loading objects or obstacles, simulating 3D scans of objects, etc.

In particular, note that this class uses the mainLoop() function to perform the ROS even management calls.

Definition at line 77 of file ros_graspit_interface.h.


Constructor & Destructor Documentation

graspit_ros_planning::RosGraspitInterface::RosGraspitInterface (  ) 

Inits ROS, but (for now) without passing any arguments.

Definition at line 160 of file ros_graspit_interface.cpp.

graspit_ros_planning::RosGraspitInterface::~RosGraspitInterface (  ) 

Deletes the node handle and the db manager.

Definition at line 166 of file ros_graspit_interface.cpp.


Member Function Documentation

bool graspit_ros_planning::RosGraspitInterface::clearBodiesCB ( graspit_ros_planning_msgs::ClearBodies::Request request,
graspit_ros_planning_msgs::ClearBodies::Response response 
) [private]

Callback for the clear bodies service.

Definition at line 343 of file ros_graspit_interface.cpp.

void graspit_ros_planning::RosGraspitInterface::computeEnergy ( Body *  object,
graspit_ros_planning_msgs::TestGrasp::Response response 
) [private]

Performs the grasp test using the grasp energy function.

Definition at line 511 of file ros_graspit_interface.cpp.

bool graspit_ros_planning::RosGraspitInterface::generateGraspCB ( graspit_ros_planning_msgs::GenerateGrasp::Request request,
graspit_ros_planning_msgs::GenerateGrasp::Response response 
) [private]

Callback for the grasp generation service, for PR2 gripper.

Definition at line 685 of file ros_graspit_interface.cpp.

GraspitDBModel * graspit_ros_planning::RosGraspitInterface::getModel ( int  model_id  )  [private]

-------------------------- populating the graspit world ------------------------------

Will load a model, or retrieve it from the map of previously loaded models

If the model has laready been loaded, it will retrieve it from the list of models. If not, it will load it, add it to the list, and return it. Returns NULL only if the model could not be loaded from the database.

Definition at line 250 of file ros_graspit_interface.cpp.

bool graspit_ros_planning::RosGraspitInterface::graspPlanningCB ( object_manipulation_msgs::GraspPlanning::Request request,
object_manipulation_msgs::GraspPlanning::Response response 
) [private]

Callback for the general grasp planning service.

Definition at line 1183 of file ros_graspit_interface.cpp.

void graspit_ros_planning::RosGraspitInterface::gripperCollisionCheck ( const Body *  object,
graspit_ros_planning_msgs::TestGrasp::Response response 
) [private]

Checks collisions between the gripper and the environment.

Definition at line 481 of file ros_graspit_interface.cpp.

int graspit_ros_planning::RosGraspitInterface::init ( int  argc,
char **  argv 
) [virtual]

Creates the node handles, advertises services, connects to the database.

Definition at line 177 of file ros_graspit_interface.cpp.

bool graspit_ros_planning::RosGraspitInterface::loadGripper (  )  [private]

Loads the gripper info from its file, if not already loaded.

Definition at line 268 of file ros_graspit_interface.cpp.

bool graspit_ros_planning::RosGraspitInterface::loadModelCB ( graspit_ros_planning_msgs::LoadDatabaseModel::Request request,
graspit_ros_planning_msgs::LoadDatabaseModel::Response response 
) [private]

Callback for the load model service.

Definition at line 287 of file ros_graspit_interface.cpp.

bool graspit_ros_planning::RosGraspitInterface::loadObstacleCB ( graspit_ros_planning_msgs::LoadObstacle::Request request,
graspit_ros_planning_msgs::LoadObstacle::Response response 
) [private]

Callback for the load obstacle service.

Definition at line 380 of file ros_graspit_interface.cpp.

int graspit_ros_planning::RosGraspitInterface::mainLoop (  )  [virtual]

Simply calls ros::spinOnce() to process the ROS event loop.

Definition at line 240 of file ros_graspit_interface.cpp.

bool graspit_ros_planning::RosGraspitInterface::simulateScanCB ( graspit_ros_planning_msgs::SimulateScan::Request request,
graspit_ros_planning_msgs::SimulateScan::Response response 
) [private]

Callback for the clear bodies service.

Definition at line 399 of file ros_graspit_interface.cpp.

bool graspit_ros_planning::RosGraspitInterface::testGraspCB ( graspit_ros_planning_msgs::TestGrasp::Request request,
graspit_ros_planning_msgs::TestGrasp::Response response 
) [private]

Callback for the detailed, graspit-specific test grasp service.

Definition at line 1135 of file ros_graspit_interface.cpp.

void graspit_ros_planning::RosGraspitInterface::testGraspCompliant ( const object_manipulation_msgs::Grasp grasp,
GraspableBody *  object,
graspit_ros_planning_msgs::TestGrasp::Response response 
) [private]

Tests a grasp using the compliant method.

Definition at line 993 of file ros_graspit_interface.cpp.

void graspit_ros_planning::RosGraspitInterface::testGraspDirect ( const object_manipulation_msgs::Grasp grasp,
GraspableBody *  object,
graspit_ros_planning_msgs::TestGrasp::Response response 
) [private]

Tests a grasp using the direct method.

Definition at line 973 of file ros_graspit_interface.cpp.

void graspit_ros_planning::RosGraspitInterface::testGraspReactive ( const object_manipulation_msgs::Grasp grasp,
GraspableBody *  object,
graspit_ros_planning_msgs::TestGrasp::Response response 
) [private]

Tests a grasp using the direct method.

Definition at line 1014 of file ros_graspit_interface.cpp.

void graspit_ros_planning::RosGraspitInterface::testGraspRobustReactive ( const object_manipulation_msgs::Grasp grasp,
GraspableBody *  object,
graspit_ros_planning_msgs::TestGrasp::Response response 
) [private]

Tests a grasp using the direct method.

Definition at line 1041 of file ros_graspit_interface.cpp.

bool graspit_ros_planning::RosGraspitInterface::verifyGraspCB ( graspit_ros_planning_msgs::VerifyGrasp::Request request,
graspit_ros_planning_msgs::VerifyGrasp::Response response 
) [private]

Callback for the grasp verifying service, for PR2 gripper.

Definition at line 535 of file ros_graspit_interface.cpp.


Member Data Documentation

Server for the clear bodies service.

Definition at line 98 of file ros_graspit_interface.h.

db_planner::DatabaseManager* graspit_ros_planning::RosGraspitInterface::db_mgr_ [private]

A GraspIt database manager used for talking to the database.

An interesting point is that here we also have to option of using a ROS interface to the database; pros and cons should be considered in the future.

Definition at line 89 of file ros_graspit_interface.h.

Used for converting energy values fo probabilities; soon to be replaced.

Definition at line 128 of file ros_graspit_interface.h.

Used for general GrapsPlanning calls; should be a value from graspit_ros_planning_msgs::TestGrasp.

Definition at line 125 of file ros_graspit_interface.h.

Server for the generate grasp service.

Definition at line 110 of file ros_graspit_interface.h.

Server for the grasp planning service.

Definition at line 107 of file ros_graspit_interface.h.

A GraspIt instance of the PR2 gripper.

Definition at line 122 of file ros_graspit_interface.h.

Server for the load model service.

Definition at line 92 of file ros_graspit_interface.h.

Server for the load obstacle service.

Definition at line 95 of file ros_graspit_interface.h.

std::map<int, GraspitDBModel*> graspit_ros_planning::RosGraspitInterface::models_ [private]

Keeps track of all models already retrieved from the database, mapped by their scaled model id.

Definition at line 119 of file ros_graspit_interface.h.

Node handle in the private namespace.

Definition at line 84 of file ros_graspit_interface.h.

Node handle in the root namespace.

Definition at line 81 of file ros_graspit_interface.h.

Publisher for simulated scans.

Definition at line 116 of file ros_graspit_interface.h.

Server for the scan simulation service.

Definition at line 101 of file ros_graspit_interface.h.

Server for the test grasp service.

Definition at line 104 of file ros_graspit_interface.h.

Server for the grasp collision checking service.

Definition at line 113 of file ros_graspit_interface.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


graspit_ros_planning
Author(s): Matei Ciocarlie
autogenerated on Fri Mar 1 16:32:38 2013