1 #ifndef _RAPID_ROBOT_JOINT_STATE_READER_H_
2 #define _RAPID_ROBOT_JOINT_STATE_READER_H_
9 #include "sensor_msgs/JointState.h"
45 bool HasJoint(
const std::string& name)
const;
52 double position(
const std::string& name)
const;
55 std::map<std::string, double>
positions()
const;
84 const ros::Duration& timeout)
const;
87 void callback(
const sensor_msgs::JointState& msg);
92 std::map<std::string, double> positions_;
94 bool received_callback_;
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.