rapid
A ROS robotics library.
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Pages
rapid::JointStateReader Class Reference

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...
 

Detailed Description

Tracks the latest joint states.

Currently, we only track joint positions/angles, not velocities or efforts.

Usage:

JointStateReader js_reader;
js_reader.Start();
js_reader.WaitForMessages(ros::Duration(1.0));
if (js_reader.HasJoint("torso_lift_link")) {
double torso_pos = js_reader.position("torso_lift_link");
}
std::map joint_positions = js_reader.positions();

Definition at line 26 of file joint_state_reader.h.

Constructor & Destructor Documentation

rapid::JointStateReader::JointStateReader ( )

Constructor.

rapid::JointStateReader::JointStateReader ( const std::string &  joint_states_topic)

Constructor with a different joint states topic.

Member Function Documentation

bool rapid::JointStateReader::HasJoint ( const std::string &  name) const

Returns true if this reader has a given joint state.

Parameters
[in]nameThe name of the joint to check.
Returns
true if the reader has received at least one value from the joint_states topic for the given joint, false otherwise.
double rapid::JointStateReader::position ( const std::string &  name) const

Returns the position of the given joint.

Parameters
[in]nameThe name of the joint.
Exceptions
std::out_of_rangeif 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.

Parameters
[in]nameThe name of the joint to wait for.
[in]timeoutThe maximum amount of time to wait.
Returns
true if the joint value was available before the timeout, false otherwise.
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.

Parameters
[in]timeoutThe maximum amount of time to wait.
Returns
true if a message was received before the timeout, false otherwise.

The documentation for this class was generated from the following file: