FreePositioning.h
Go to the documentation of this file.
00001 #ifndef FREE_POSITIONING_H_
00002 #define FREE_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 <interactive_markers/interactive_marker_server.h>
00008 #include <rail_manipulation_msgs/PickupAction.h>
00009 #include <remote_manipulation_markers/Common.h>
00010 #include <remote_manipulation_markers/SpecifiedGraspAction.h>
00011 #include <sensor_msgs/JointState.h>
00012 #include <std_srvs/Empty.h>
00013 #include <tf/transform_listener.h>
00014 
00015 class FreePositioning
00016 {
00017 
00018 public:
00019 
00023   FreePositioning();
00024 
00025   ~FreePositioning();
00026 
00027   void publishMarkerPose();
00028 
00029 private:
00030 
00031   void updateJoints(const sensor_msgs::JointState::ConstPtr& msg);
00032 
00033   bool resetMarkerPoseCallback(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res);
00034 
00035   void executeGraspCallback(const remote_manipulation_markers::SpecifiedGraspGoalConstPtr &goal);
00036 
00037   std::string baseLink;
00038   std::string eefLink;
00039 
00040   ros::NodeHandle n, pnh;
00041 
00042   //messages
00043   ros::Publisher markerPosePublisher;
00044 
00045   //services
00046   ros::ServiceServer resetMarkerPoseServer;
00047 
00048   //actionlib
00049   actionlib::SimpleActionClient<rail_manipulation_msgs::PickupAction> *graspClient;
00050   actionlib::SimpleActionServer<remote_manipulation_markers::SpecifiedGraspAction> specifiedGraspServer;
00051 
00052   boost::shared_ptr<interactive_markers::InteractiveMarkerServer> imServer; 
00053 
00054   tf::TransformListener tfListener;
00055 };
00056 
00057 #endif


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