00001 #ifndef ARM_COMPONENTS_NAME_MANAGER_ARMJOINTSTATESUBSCRIBER_H 00002 #define ARM_COMPONENTS_NAME_MANAGER_ARMJOINTSTATESUBSCRIBER_H 00003 00004 #ifdef DOXYGEN_SHOULD_SKIP_THIS 00005 00024 #endif 00025 00026 #include <iostream> 00027 #include <sstream> 00028 00029 #include <ros/ros.h> 00030 #include <sensor_msgs/JointState.h> 00031 #include <arm_components_name_manager/ArmComponentsNameManager.h> 00032 #include <baselib_binding/Thread.h> 00033 00034 // #include <convenience_ros_functions/TypedSubscriber.h> 00035 00036 namespace arm_components_name_manager 00037 { 00038 00047 class ArmJointStateSubscriber 00048 { 00049 public: 00050 ArmJointStateSubscriber( 00051 const ArmComponentsNameManager& _manager, 00052 ros::NodeHandle& n, 00053 const std::string& joint_states_topic); 00054 00055 ~ArmJointStateSubscriber(); 00056 00057 friend std::ostream& operator<<(std::ostream& o, const ArmJointStateSubscriber& j) 00058 { 00059 o << j.toString(); 00060 return o; 00061 } 00062 00068 void setActive(bool flag); 00069 00079 bool waitForUpdate(float timeout=-1, float checkStepTime=0.1) const; 00080 00081 std::vector<float> armAngles(bool& valid) const; 00082 00083 std::vector<float> gripperAngles(bool& valid) const; 00084 00085 std::string toString() const; 00086 00090 bool isActive() const; 00091 private: 00092 typedef baselib_binding::unique_lock<baselib_binding::recursive_mutex>::type unique_lock; 00093 // typedef convenience_ros_functions::TypedSubscriber<sensor_msgs::JointState> JointStateSubscriber; 00094 00095 void callback(const sensor_msgs::JointState& msg); 00096 // void process(const ros::TimerEvent& t); 00097 00098 ros::Time getLastUpdateTime() const; 00099 00100 // protects all fields which need protecting 00101 mutable baselib_binding::recursive_mutex mutex; 00102 bool valid_arm, valid_grippers; 00103 00104 const ArmComponentsNameManager jointsManager; 00105 00106 std::vector<float> arm_angles; 00107 std::vector<float> gripper_angles; 00108 00109 ros::NodeHandle node; 00110 00111 /* JointStateSubscriber subscriber; 00112 ros::Timer update_connection;*/ 00113 ros::Subscriber subscriber; 00114 bool subscriberActive; 00115 ros::Time last_update_time; 00116 }; 00117 } // namespace 00118 #endif // ARM_COMPONENTS_NAME_MANAGER_ARMJOINTSTATESUBSCRIBER_H