PointAndClick.h
Go to the documentation of this file.
00001 #ifndef POINT_AND_CLICK_H_
00002 #define POINT_AND_CLICK_H_
00003 
00004 //ROS
00005 #include <ros/ros.h>
00006 #include <actionlib/client/simple_action_client.h>
00007 #include <actionlib/server/simple_action_server.h>
00008 #include <boost/thread/recursive_mutex.hpp>
00009 #include <geometry_msgs/PoseArray.h>
00010 #include <interactive_markers/interactive_marker_server.h>
00011 #include <rail_manipulation_msgs/PickupAction.h>
00012 #include <remote_manipulation_markers/Common.h>
00013 #include <remote_manipulation_markers/CycleGrasps.h>
00014 #include <remote_manipulation_markers/SpecifiedGraspAction.h>
00015 #include <tf/transform_broadcaster.h>
00016 #include <tf/transform_listener.h>
00017 
00018 class PointAndClick
00019 {
00020 
00021 public:
00022 
00026   PointAndClick();
00027 
00028   ~PointAndClick();
00029 
00030 private:
00031   void graspsCallback(const geometry_msgs::PoseArray &grasps);
00032 
00033   void updateMarker();
00034 
00035   bool cycleGraspsCallback(remote_manipulation_markers::CycleGrasps::Request &req, remote_manipulation_markers::CycleGrasps::Response &res);
00036 
00037   void executeGraspCallback(const remote_manipulation_markers::SpecifiedGraspGoalConstPtr &goal);
00038 
00039   void cycleGraspsForward();
00040 
00041   void cycleGraspsBackward();
00042 
00043   ros::NodeHandle n;
00044   ros::NodeHandle pnh;
00045 
00046   //actionlib
00047   actionlib::SimpleActionClient<rail_manipulation_msgs::PickupAction> *graspClient;
00048   actionlib::SimpleActionServer<remote_manipulation_markers::SpecifiedGraspAction> specifiedGraspServer;
00049 
00050   //topics
00051   ros::Subscriber graspsSubscriber;
00052 
00053   //services
00054   ros::ServiceServer cycleGraspsServer;
00055   ros::ServiceServer executeGraspServer;
00056 
00057   boost::recursive_mutex graspsMutex;
00058   boost::shared_ptr<interactive_markers::InteractiveMarkerServer> imServer;
00059   visualization_msgs::InteractiveMarker graspSelectorMarker;
00060   visualization_msgs::Marker graspMarker;
00061   visualization_msgs::InteractiveMarkerControl graspMarkerControl;
00062 
00063   geometry_msgs::PoseArray graspList;
00064 
00065   tf::TransformBroadcaster tfBroadcaster;
00066   tf::TransformListener tfListener;
00067 
00068   bool graspsReceived;
00069   int graspIndex;
00070 };
00071 
00072 #endif


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