The grasp model retriever node object. More...
#include <GraspModelRetriever.h>
Public Member Functions | |
GraspModelRetriever () | |
Create a GraspModelRetriever and associated ROS information. | |
bool | okay () const |
A check for a valid GraspModelRetriever. | |
virtual | ~GraspModelRetriever () |
Cleans up a GraspModelRetriever. | |
Private Member Functions | |
void | retrieveGraspModel (const rail_pick_and_place_msgs::RetrieveGraspModelGoalConstPtr &goal) |
Callback for the retrieve grasp model action server. | |
Private Attributes | |
actionlib::SimpleActionServer < rail_pick_and_place_msgs::RetrieveGraspModelAction > | as_ |
graspdb::Client * | graspdb_ |
ros::NodeHandle | node_ |
bool | okay_ |
ros::Publisher | point_cloud_pub_ |
ros::Publisher | poses_pub_ |
ros::NodeHandle | private_node_ |
The grasp model retriever node object.
The grasp model retriever allows for loading stored models from the grasp database training set. An action server is started as the main entry point to grasp retrieval. A latched topic is used to publish the resulting point cloud and pose array.
Definition at line 35 of file GraspModelRetriever.h.
Create a GraspModelRetriever and associated ROS information.
Creates a ROS node handle, creates a client to the grasp database, and starts the action server.
Definition at line 22 of file GraspModelRetriever.cpp.
GraspModelRetriever::~GraspModelRetriever | ( | ) | [virtual] |
Cleans up a GraspModelRetriever.
Cleans up any connections used by the GraspModelRetriever.
Definition at line 57 of file GraspModelRetriever.cpp.
bool GraspModelRetriever::okay | ( | ) | const |
A check for a valid GraspModelRetriever.
This function will return true if the appropriate connections were created successfully during initialization.
Definition at line 65 of file GraspModelRetriever.cpp.
void GraspModelRetriever::retrieveGraspModel | ( | const rail_pick_and_place_msgs::RetrieveGraspModelGoalConstPtr & | goal | ) | [private] |
Callback for the retrieve grasp model action server.
The retrieve grasp model action will attempt to load a stored grasp model from the grasp database.
goal | The goal object specifying the parameters. |
Definition at line 70 of file GraspModelRetriever.cpp.
actionlib::SimpleActionServer<rail_pick_and_place_msgs::RetrieveGraspModelAction> rail::pick_and_place::GraspModelRetriever::as_ [private] |
The main action server.
Definition at line 79 of file GraspModelRetriever.h.
The grasp database connection.
Definition at line 74 of file GraspModelRetriever.h.
The public and private ROS node handles.
Definition at line 77 of file GraspModelRetriever.h.
bool rail::pick_and_place::GraspModelRetriever::okay_ [private] |
The okay check flag.
Definition at line 72 of file GraspModelRetriever.h.
The latched publishers for retrieved data.
Definition at line 81 of file GraspModelRetriever.h.
Definition at line 81 of file GraspModelRetriever.h.
Definition at line 77 of file GraspModelRetriever.h.