00001 00046 #ifndef _JACO_COMM_H_ 00047 #define _JACO_COMM_H_ 00048 00049 #include <jaco_driver/KinovaTypes.h> 00050 #include <jaco_driver/jaco_types.h> 00051 #include "jaco_driver/jaco_api.h" 00052 #include <boost/thread/recursive_mutex.hpp> 00053 00054 namespace jaco 00055 { 00056 00057 class JacoComm 00058 { 00059 public: 00060 JacoComm(JacoAngles); 00061 ~JacoComm(); 00062 bool HomeState(void); 00063 void HomeArm(void); 00064 void InitializeFingers(void); 00065 void SetAngles(JacoAngles &angles, int timeout = 0, bool push = true); 00066 void SetPosition(JacoPose &position, int timeout = 0, bool push = true); 00067 void SetFingers(FingerAngles &fingers, int timeout = 0, bool push = true); 00068 void SetVelocities(AngularInfo joint_vel); 00069 void SetCartesianVelocities(CartesianInfo velocities); 00070 void SetConfig(ClientConfigurations config); 00071 void GetAngles(JacoAngles &angles); 00072 void GetPosition(JacoPose &position); 00073 void GetFingers(FingerAngles &fingers); 00074 void GetConfig(ClientConfigurations &config); 00075 void PrintAngles(JacoAngles &angles); 00076 void PrintPosition(JacoPose &position); 00077 void PrintFingers(FingersPosition fingers); 00078 void PrintConfig(ClientConfigurations config); 00079 void Stop(); 00080 void Start(); 00081 bool Stopped(); 00082 00083 private: 00084 boost::recursive_mutex api_mutex; 00085 jaco::JacoAPI* API; 00086 bool software_stop; 00087 JacoAngles home_position; 00088 00089 void WaitForHome(int); 00090 }; 00091 00092 } 00093 00094 #endif // _JACO_COMM_H_