common_actions.h
Go to the documentation of this file.
00001 #ifndef COMMON_ACTIONS_H_
00002 #define COMMON_ACTIONS_H_
00003 
00004 #include <ros/ros.h>
00005 #include <actionlib/server/simple_action_server.h>
00006 #include <actionlib/client/simple_action_client.h>
00007 #include <carl_moveit/WipeSurfaceAction.h>
00008 #include <rail_manipulation_msgs/ArmAction.h>
00009 #include <rail_manipulation_msgs/CartesianPath.h>
00010 #include <rail_manipulation_msgs/GripperAction.h>
00011 #include <rail_manipulation_msgs/LiftAction.h>
00012 #include <rail_manipulation_msgs/MoveToJointPoseAction.h>
00013 #include <rail_manipulation_msgs/MoveToPoseAction.h>
00014 #include <rail_manipulation_msgs/PickupAction.h>
00015 #include <rail_manipulation_msgs/StoreAction.h>
00016 #include <std_srvs/Empty.h>
00017 #include <tf/transform_broadcaster.h>
00018 #include <tf/transform_listener.h>
00019 #include <wpi_jaco_msgs/AngularCommand.h>
00020 #include <wpi_jaco_msgs/GetAngularPosition.h>
00021 #include <wpi_jaco_msgs/GetCartesianPosition.h>
00022 
00023 #define NUM_JACO_JOINTS 6
00024 #define MAX_HOME_ATTEMPTS 3
00025 
00026 class CommonActions
00027 {
00028 
00029 public:
00030 
00034   CommonActions();
00035 
00036 private:
00037   ros::NodeHandle n;
00038   ros::Publisher angularCmdPublisher;
00039 
00040   ros::ServiceClient eraseTrajectoriesClient;
00041   ros::ServiceClient cartesianPathClient;
00042   ros::ServiceClient jacoPosClient;
00043   ros::ServiceClient attachClosestObjectClient;
00044   ros::ServiceClient detachObjectsClient;
00045 
00046   actionlib::SimpleActionClient<rail_manipulation_msgs::MoveToJointPoseAction> moveToJointPoseClient;
00047   actionlib::SimpleActionClient<rail_manipulation_msgs::MoveToPoseAction> moveToPoseClient;
00048   actionlib::SimpleActionClient<rail_manipulation_msgs::GripperAction> gripperClient;
00049   actionlib::SimpleActionClient<rail_manipulation_msgs::LiftAction> liftClient;
00050   actionlib::SimpleActionServer<rail_manipulation_msgs::LiftAction> liftServer;
00051   actionlib::SimpleActionServer<rail_manipulation_msgs::ArmAction> armServer;
00052   actionlib::SimpleActionServer<rail_manipulation_msgs::PickupAction> pickupServer;
00053   actionlib::SimpleActionServer<rail_manipulation_msgs::StoreAction> storeServer;
00054   actionlib::SimpleActionServer<carl_moveit::WipeSurfaceAction> wipeSurfaceServer;
00055 
00056   tf::TransformBroadcaster tfBroadcaster;
00057   tf::TransformListener tfListener;
00058 
00059   std::vector<float> homePosition;
00060   std::vector<float> defaultRetractPosition;
00061 
00070   void executeArmAction(const rail_manipulation_msgs::ArmGoalConstPtr &goal);
00071 
00081   void executePickup(const rail_manipulation_msgs::PickupGoalConstPtr &goal);
00082 
00091   void executeStore(const rail_manipulation_msgs::StoreGoalConstPtr &goal);
00092 
00093   void executeWipeSurface(const carl_moveit::WipeSurfaceGoalConstPtr &goal);
00094 
00099   void liftArm(const rail_manipulation_msgs::LiftGoalConstPtr &goal);
00100 
00106   bool isArmRetracted(const std::vector<float> &retractPos);
00107 };
00108 
00109 #endif


carl_moveit
Author(s): David Kent
autogenerated on Thu Jun 6 2019 20:28:44