rapid
A ROS robotics library.
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Pages
joint_state_reader.h
Go to the documentation of this file.
1 #ifndef _RAPID_ROBOT_JOINT_STATE_READER_H_
2 #define _RAPID_ROBOT_JOINT_STATE_READER_H_
3 
4 #include <map>
5 #include <string>
6 #include <vector>
7 
8 #include "ros/ros.h"
9 #include "sensor_msgs/JointState.h"
10 
11 namespace rapid {
27  public:
30 
32  JointStateReader(const std::string& joint_states_topic);
33 
37  void Start();
38 
45  bool HasJoint(const std::string& name) const;
46 
52  double position(const std::string& name) const;
53 
55  std::map<std::string, double> positions() const;
56 
68  bool WaitForMessages(const ros::Duration& timeout) const;
69 
83  bool WaitForJoint(const std::string& name,
84  const ros::Duration& timeout) const;
85 
86  private:
87  void callback(const sensor_msgs::JointState& msg);
88 
89  ros::NodeHandle nh_;
90  ros::Subscriber sub_;
91  std::string topic_;
92  std::map<std::string, double> positions_;
93 
94  bool received_callback_;
95 };
96 } // namespace rapid
97 
98 #endif // _RAPID_ROBOT_JOINT_STATE_READER_H_
bool WaitForJoint(const std::string &name, const ros::Duration &timeout) const
Wait until a joint value is available.
void Start()
Starts subscribing to the joint states.
std::map< std::string, double > positions() const
Returns all the joint positions so far.
bool HasJoint(const std::string &name) const
Returns true if this reader has a given joint state.
bool WaitForMessages(const ros::Duration &timeout) const
Wait for at least one JointState message.
JointStateReader()
Constructor.
double position(const std::string &name) const
Returns the position of the given joint.
Tracks the latest joint states.