GraspPlannerServer.h
Go to the documentation of this file.
00001 /*
00002  * GraspPlannerServer.h
00003  *
00004  *  Created on: Aug 9, 2012
00005  *      Author: jnicho
00006  */
00007 
00008 #ifndef GRASPPLANNERSERVER_H_
00009 #define GRASPPLANNERSERVER_H_
00010 
00011 #include <ros/ros.h>
00012 #include <object_manipulator/object_manipulator.h>
00013 #include <object_manipulation_msgs/GraspPlanning.h>
00014 #include <ros/package.h>
00015 #include <object_manipulation_tools/grasp_planners/OverheadGraspPlanner.h>
00016 #include <geometry_msgs/Polygon.h>
00017 #include <geometry_msgs/PolygonStamped.h>
00018 #include <boost/shared_ptr.hpp>
00019 
00020 const std::string SERVICE_NAME = "plan_point_cluster_grasp";
00021 const std::string POSE_PUBLISH_TOPIC_NAME = "grasp_poses";
00022 const std::string PLANE_PUBLISH_TOPIC_NAME = "contact_plane";
00023 const std::string PARAM_NAME_PUBLISH_RESULTS = "publish_results";
00024 
00025 class GraspPlannerServer {
00026 public:
00027         GraspPlannerServer(boost::shared_ptr<GraspPlannerInterface> &plannerPtr);
00028         virtual ~GraspPlannerServer();
00029         void init();
00030         void finish();
00031         bool serviceCallback(object_manipulation_msgs::GraspPlanning::Request &request,
00032                         object_manipulation_msgs::GraspPlanning::Response &response);
00033 
00034         void timerCallback(const ros::TimerEvent &evnt);
00035 
00036         static geometry_msgs::Polygon createPlanePolygon(const tf::Transform &transform,
00037                         tfScalar width = 0.1, tfScalar length = 0.1);
00038 
00039 protected:
00040 
00041         boost::shared_ptr<GraspPlannerInterface> _GraspPlanner;
00042         ros::ServiceServer _ServiceServer;
00043         ros::Publisher _PosePublisher;
00044         ros::Publisher _PlanePublisher;
00045         ros::Timer _PublishTimer;
00046         double _PublishInterval;
00047 
00048         std::string _PosePubTopic;
00049         std::string _PlanePubTopic;
00050         std::string _ServiceName;
00051 
00052         // from ros parameter server
00053         bool _PublishResults;
00054 
00055         // last set of valid messages
00056         bool _ResultsSet;
00057         geometry_msgs::PolygonStamped _LastValidTablePolygonMsg;
00058         geometry_msgs::PoseStamped _LastValidGraspPoseMsg;
00059 };
00060 
00061 #endif /* GRASPPLANNERSERVER_H_ */


object_manipulation_tools
Author(s): Jnicho
autogenerated on Mon Oct 6 2014 00:56:17