Aikido
aikido::control::ros::RosJointStateClient Class Reference

Client that listens for JointState messages for each skeleton joint and provides a method for extracting the most recent position of each joint. More...

#include <aikido/control/ros/RosJointStateClient.hpp>

Classes

struct  JointStateRecord
 

Public Member Functions

 RosJointStateClient (dart::dynamics::SkeletonPtr _skeleton, ::ros::NodeHandle _nodeHandle, const std::string &_topicName, std::size_t _capacity)
 Constructor. More...
 
void spin ()
 Update mBuffer with any JointState messages that have been received. More...
 
Eigen::VectorXd getLatestPosition (const dart::dynamics::MetaSkeleton &_metaSkeleton) const
 Returns the most recent position of each joint in _metaSkeleton. More...
 

Private Member Functions

void jointStateCallback (const sensor_msgs::JointState &_jointState)
 Callback to add a new JointState to mBuffer. More...
 

Private Attributes

std::mutex mMutex
 
dart::dynamics::SkeletonPtr mSkeleton
 
std::unordered_map< std::string, boost::circular_buffer< JointStateRecord > > mBuffer
 
std::size_t mCapacity
 
::ros::CallbackQueue mCallbackQueue
 
::ros::NodeHandle mNodeHandle
 
::ros::Subscriber mSubscriber
 

Detailed Description

Client that listens for JointState messages for each skeleton joint and provides a method for extracting the most recent position of each joint.

Constructor & Destructor Documentation

◆ RosJointStateClient()

aikido::control::ros::RosJointStateClient::RosJointStateClient ( dart::dynamics::SkeletonPtr  _skeleton,
::ros::NodeHandle  _nodeHandle,
const std::string &  _topicName,
std::size_t  _capacity 
)

Constructor.

Parameters
_skeletonSkeleton to read JointState updates for.
_nodeHandleROS node.
_topicNameName of topic to subscribe to for JointState updates.
_capacityNumber of JointStateRecords that are saved per joint.

Member Function Documentation

◆ getLatestPosition()

Eigen::VectorXd aikido::control::ros::RosJointStateClient::getLatestPosition ( const dart::dynamics::MetaSkeleton &  _metaSkeleton) const

Returns the most recent position of each joint in _metaSkeleton.

Parameters
_metaSkeletonSkeleton to read DOFs from.
Returns
vector of positions for each DOF

◆ jointStateCallback()

void aikido::control::ros::RosJointStateClient::jointStateCallback ( const sensor_msgs::JointState &  _jointState)
private

Callback to add a new JointState to mBuffer.

Parameters
_jointStateNew JointState to add to mBuffer

◆ spin()

void aikido::control::ros::RosJointStateClient::spin ( )

Update mBuffer with any JointState messages that have been received.

Member Data Documentation

◆ mBuffer

std::unordered_map<std::string, boost::circular_buffer<JointStateRecord> > aikido::control::ros::RosJointStateClient::mBuffer
private

◆ mCallbackQueue

::ros::CallbackQueue aikido::control::ros::RosJointStateClient::mCallbackQueue
private

◆ mCapacity

std::size_t aikido::control::ros::RosJointStateClient::mCapacity
private

◆ mMutex

std::mutex aikido::control::ros::RosJointStateClient::mMutex
mutableprivate

◆ mNodeHandle

::ros::NodeHandle aikido::control::ros::RosJointStateClient::mNodeHandle
private

◆ mSkeleton

dart::dynamics::SkeletonPtr aikido::control::ros::RosJointStateClient::mSkeleton
private

◆ mSubscriber

::ros::Subscriber aikido::control::ros::RosJointStateClient::mSubscriber
private