rapid
A ROS robotics library.
|
Tracks the latest joint states. More...
#include <joint_state_reader.h>
Public Member Functions | |
JointStateReader () | |
Constructor. More... | |
JointStateReader (const std::string &joint_states_topic) | |
Constructor with a different joint states topic. More... | |
void | Start () |
Starts subscribing to the joint states. More... | |
bool | HasJoint (const std::string &name) const |
Returns true if this reader has a given joint state. More... | |
double | position (const std::string &name) const |
Returns the position of the given joint. More... | |
std::map< std::string, double > | positions () const |
Returns all the joint positions so far. More... | |
bool | WaitForMessages (const ros::Duration &timeout) const |
Wait for at least one JointState message. More... | |
bool | WaitForJoint (const std::string &name, const ros::Duration &timeout) const |
Wait until a joint value is available. More... | |
Tracks the latest joint states.
Currently, we only track joint positions/angles, not velocities or efforts.
Usage:
Definition at line 26 of file joint_state_reader.h.
rapid::JointStateReader::JointStateReader | ( | ) |
Constructor.
rapid::JointStateReader::JointStateReader | ( | const std::string & | joint_states_topic | ) |
Constructor with a different joint states topic.
bool rapid::JointStateReader::HasJoint | ( | const std::string & | name | ) | const |
Returns true if this reader has a given joint state.
[in] | name | The name of the joint to check. |
double rapid::JointStateReader::position | ( | const std::string & | name | ) | const |
Returns the position of the given joint.
[in] | name | The name of the joint. |
std::out_of_range | if the joint does not exist. |
std::map<std::string, double> rapid::JointStateReader::positions | ( | ) | const |
Returns all the joint positions so far.
void rapid::JointStateReader::Start | ( | ) |
Starts subscribing to the joint states.
The JointStateReader will not work until you call Start().
bool rapid::JointStateReader::WaitForJoint | ( | const std::string & | name, |
const ros::Duration & | timeout | ||
) | const |
Wait until a joint value is available.
Blocks until the given joint value has been recorded at least once or the timeout is reached. Usually, calling WaitForMessages will be sufficient, but sometimes different controllers publish different subsets of the robot joint states, and the first message might not contain the joint you are looking for.
[in] | name | The name of the joint to wait for. |
[in] | timeout | The maximum amount of time to wait. |
bool rapid::JointStateReader::WaitForMessages | ( | const ros::Duration & | timeout | ) | const |
Wait for at least one JointState message.
Blocks until a message is received on the joint_states topic or the timeout is reached. This is useful when you want to read a joint value shortly after calling Start(), and ROS has not had time to process callbacks yet.
[in] | timeout | The maximum amount of time to wait. |