#include <GraspPlannerServer.h>
Public Member Functions | |
void | finish () |
GraspPlannerServer (boost::shared_ptr< GraspPlannerInterface > &plannerPtr) | |
void | init () |
bool | serviceCallback (object_manipulation_msgs::GraspPlanning::Request &request, object_manipulation_msgs::GraspPlanning::Response &response) |
void | timerCallback (const ros::TimerEvent &evnt) |
virtual | ~GraspPlannerServer () |
Static Public Member Functions | |
static geometry_msgs::Polygon | createPlanePolygon (const tf::Transform &transform, tfScalar width=0.1, tfScalar length=0.1) |
Protected Attributes | |
boost::shared_ptr < GraspPlannerInterface > | _GraspPlanner |
geometry_msgs::PoseStamped | _LastValidGraspPoseMsg |
geometry_msgs::PolygonStamped | _LastValidTablePolygonMsg |
ros::Publisher | _PlanePublisher |
std::string | _PlanePubTopic |
ros::Publisher | _PosePublisher |
std::string | _PosePubTopic |
double | _PublishInterval |
bool | _PublishResults |
ros::Timer | _PublishTimer |
bool | _ResultsSet |
std::string | _ServiceName |
ros::ServiceServer | _ServiceServer |
Definition at line 25 of file GraspPlannerServer.h.
GraspPlannerServer::GraspPlannerServer | ( | boost::shared_ptr< GraspPlannerInterface > & | plannerPtr | ) |
Definition at line 14 of file GraspPlannerServer.cpp.
GraspPlannerServer::~GraspPlannerServer | ( | ) | [virtual] |
Definition at line 26 of file GraspPlannerServer.cpp.
geometry_msgs::Polygon GraspPlannerServer::createPlanePolygon | ( | const tf::Transform & | transform, |
tfScalar | width = 0.1 , |
||
tfScalar | length = 0.1 |
||
) | [static] |
Definition at line 123 of file GraspPlannerServer.cpp.
void GraspPlannerServer::finish | ( | ) |
Definition at line 60 of file GraspPlannerServer.cpp.
void GraspPlannerServer::init | ( | ) |
Definition at line 31 of file GraspPlannerServer.cpp.
bool GraspPlannerServer::serviceCallback | ( | object_manipulation_msgs::GraspPlanning::Request & | request, |
object_manipulation_msgs::GraspPlanning::Response & | response | ||
) |
Definition at line 69 of file GraspPlannerServer.cpp.
void GraspPlannerServer::timerCallback | ( | const ros::TimerEvent & | evnt | ) |
Definition at line 106 of file GraspPlannerServer.cpp.
boost::shared_ptr<GraspPlannerInterface> GraspPlannerServer::_GraspPlanner [protected] |
Definition at line 41 of file GraspPlannerServer.h.
geometry_msgs::PoseStamped GraspPlannerServer::_LastValidGraspPoseMsg [protected] |
Definition at line 58 of file GraspPlannerServer.h.
geometry_msgs::PolygonStamped GraspPlannerServer::_LastValidTablePolygonMsg [protected] |
Definition at line 57 of file GraspPlannerServer.h.
ros::Publisher GraspPlannerServer::_PlanePublisher [protected] |
Definition at line 44 of file GraspPlannerServer.h.
std::string GraspPlannerServer::_PlanePubTopic [protected] |
Definition at line 49 of file GraspPlannerServer.h.
ros::Publisher GraspPlannerServer::_PosePublisher [protected] |
Definition at line 43 of file GraspPlannerServer.h.
std::string GraspPlannerServer::_PosePubTopic [protected] |
Definition at line 48 of file GraspPlannerServer.h.
double GraspPlannerServer::_PublishInterval [protected] |
Definition at line 46 of file GraspPlannerServer.h.
bool GraspPlannerServer::_PublishResults [protected] |
Definition at line 53 of file GraspPlannerServer.h.
ros::Timer GraspPlannerServer::_PublishTimer [protected] |
Definition at line 45 of file GraspPlannerServer.h.
bool GraspPlannerServer::_ResultsSet [protected] |
Definition at line 56 of file GraspPlannerServer.h.
std::string GraspPlannerServer::_ServiceName [protected] |
Definition at line 50 of file GraspPlannerServer.h.
ros::ServiceServer GraspPlannerServer::_ServiceServer [protected] |
Definition at line 42 of file GraspPlannerServer.h.