ConstrainedPositioning.h
Go to the documentation of this file.
00001 #ifndef CONSTRAINED_POSITIONING_H_
00002 #define CONSTRAINED_POSITIONING_H_
00003 
00004 #include <ros/ros.h>
00005 #include <actionlib/client/simple_action_client.h>
00006 #include <actionlib/server/simple_action_server.h>
00007 #include <boost/thread/recursive_mutex.hpp>
00008 #include <interactive_markers/interactive_marker_server.h>
00009 #include <remote_manipulation_markers/Common.h>
00010 #include <remote_manipulation_markers/CreateSphere.h>
00011 #include <remote_manipulation_markers/SpecifiedGraspAction.h>
00012 #include <rail_manipulation_msgs/PickupAction.h>
00013 #include <std_srvs/Empty.h>
00014 #include <tf/transform_datatypes.h>
00015 
00016 class ConstrainedPositioning
00017 {
00018 
00019 public:
00020 
00024   ConstrainedPositioning();
00025 
00026   ~ConstrainedPositioning();
00027 
00028   void publishMarkerPose();
00029 
00030 private:
00031 
00032   bool clearGripperMarkerCallback(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res);
00033 
00034   bool clearFullMarkerCallback(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res);
00035 
00036   bool createSphereMarkerCallback(remote_manipulation_markers::CreateSphere::Request &req, remote_manipulation_markers::CreateSphere::Response &res);
00037 
00038   void processMarkerFeedback(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback);
00039 
00040   void executeGraspCallback(const remote_manipulation_markers::SpecifiedGraspGoalConstPtr &goal);
00041 
00042   ros::NodeHandle n, pnh;
00043 
00044   //publishers
00045   ros::Publisher markerPosePublisher;
00046 
00047   //services
00048   ros::ServiceServer clearGripperMarkerServer;
00049   ros::ServiceServer clearFullMarkerServer;
00050   ros::ServiceServer createSphereServer;
00051 
00052   //actionlib
00053   actionlib::SimpleActionClient<rail_manipulation_msgs::PickupAction> *graspClient;
00054   actionlib::SimpleActionServer<remote_manipulation_markers::SpecifiedGraspAction> specifiedGraspServer;
00055 
00056   boost::shared_ptr<interactive_markers::InteractiveMarkerServer> imServer; 
00057 
00058   boost::recursive_mutex graspMutex;
00059 };
00060 
00061 #endif


remote_manipulation_markers
Author(s): David Kent
autogenerated on Thu Jun 6 2019 22:05:39