00001 00046 #ifndef JACO_DRIVER_JACO_COMM_H 00047 #define JACO_DRIVER_JACO_COMM_H 00048 00049 #include <boost/thread/recursive_mutex.hpp> 00050 00051 #include <kinova/KinovaTypes.h> 00052 00053 #include <jaco_driver/jaco_types.h> 00054 #include "jaco_driver/jaco_api.h" 00055 00056 00057 namespace jaco 00058 { 00059 00060 class JacoComm 00061 { 00062 public: 00063 JacoComm(const ros::NodeHandle& node_handle, 00064 boost::recursive_mutex& api_mutex, 00065 const bool is_movement_on_start); 00066 ~JacoComm(); 00067 00068 bool isHomed(void); 00069 void homeArm(void); 00070 void initFingers(void); 00071 void setJointAngles(const JacoAngles &angles, int timeout = 0, bool push = true); 00072 void setCartesianPosition(const JacoPose &position, int timeout = 0, bool push = true); 00073 void setFingerPositions(const FingerAngles &fingers, int timeout = 0, bool push = true); 00074 void setJointVelocities(const AngularInfo& joint_vel); 00075 void setCartesianVelocities(const CartesianInfo &velocities); 00076 void setConfig(const ClientConfigurations &config); 00077 void getJointAngles(JacoAngles &angles); 00078 void getCartesianPosition(JacoPose &position); 00079 void getFingerPositions(FingerAngles &fingers); 00080 void getQuickStatus(QuickStatus &quick_status); 00081 void getConfig(ClientConfigurations &config); 00082 void printAngles(const JacoAngles &angles); 00083 void printPosition(const JacoPose &position); 00084 void printFingers(const FingersPosition &fingers); 00085 void printConfig(const ClientConfigurations &config); 00086 void stopAPI(); 00087 void startAPI(); 00088 bool isStopped(); 00089 int numFingers(); 00090 00091 private: 00092 boost::recursive_mutex& api_mutex_; 00093 jaco::JacoAPI jaco_api_; 00094 bool is_software_stop_; 00095 int num_fingers_; 00096 }; 00097 00098 } // namespace jaco 00099 #endif // JACO_DRIVER_JACO_COMM_H