ee_cart_imped_arm.hh
Go to the documentation of this file.
00001 #ifndef __EE_CART_IMPED_ARM_HH__
00002 #define __EE_CART_IMPED_ARM_HH__
00003 
00004 #include <ros/ros.h>
00005 #include <ee_cart_imped_msgs/EECartImpedAction.h>
00006 #include <actionlib/client/simple_action_client.h>
00007 
00015 typedef actionlib::SimpleActionClient<ee_cart_imped_msgs::EECartImpedAction>
00016 EECartImpedClient;
00017 
00027 class EECartImpedArm {
00028 private:
00029   
00038   EECartImpedClient *traj_client_;
00039 
00040 public:
00041 
00056   EECartImpedArm(std::string ns);
00057 
00062   ~EECartImpedArm();
00063 
00077   void startTrajectory(ee_cart_imped_msgs::EECartImpedGoal goal,
00078                        bool wait=true);
00079 
00090   void stopTrajectory();
00091 
00128   static void addTrajectoryPoint(ee_cart_imped_msgs::EECartImpedGoal &goal, 
00129                                  double x, double y, double z, double ox, 
00130                                  double oy, double oz, double ow,
00131                                  double fx, double fy, double fz, double tx,
00132                                  double ty, double tz, bool iswfx, bool iswfy,
00133                                  bool iswfz, bool iswtx, bool iswty, bool iswtz,
00134                                  double ts, std::string frame_id);
00135 };
00136 
00137 #endif //ee_cart_imped_arm.hh


ee_cart_imped_action
Author(s): Jenny Barry, Mario Bollini, and Huan Liu
autogenerated on Sun Jan 5 2014 11:14:46