Public Member Functions | Private Types | Private Member Functions | Private Attributes | Friends
arm_components_name_manager::ArmJointStateSubscriber Class Reference

#include <ArmJointStateSubscriber.h>

List of all members.

Public Member Functions

std::vector< float > armAngles (bool &valid) const
 ArmJointStateSubscriber (const ArmComponentsNameManager &_manager, ros::NodeHandle &n, const std::string &joint_states_topic)
std::vector< float > gripperAngles (bool &valid) const
bool isActive () const
void setActive (bool flag)
std::string toString () const
bool waitForUpdate (float timeout=-1, float checkStepTime=0.1) const
 ~ArmJointStateSubscriber ()

Private Types

typedef
baselib_binding::unique_lock
< baselib_binding::recursive_mutex >
::type 
unique_lock

Private Member Functions

void callback (const sensor_msgs::JointState &msg)
ros::Time getLastUpdateTime () const

Private Attributes

std::vector< float > arm_angles
std::vector< float > gripper_angles
const ArmComponentsNameManager jointsManager
ros::Time last_update_time
baselib_binding::recursive_mutex mutex
ros::NodeHandle node
ros::Subscriber subscriber
bool subscriberActive
bool valid_arm
bool valid_grippers

Friends

std::ostream & operator<< (std::ostream &o, const ArmJointStateSubscriber &j)

Detailed Description

Helper class which subscribes to sensor_msgs::JointState topic to maintain up-to-date state of the arm. It does the updates only when active, which can be triggered with setActive(true).

Author:
Jennifer Buehler
Date:
March 2016

Definition at line 47 of file ArmJointStateSubscriber.h.


Member Typedef Documentation

typedef baselib_binding::unique_lock<baselib_binding::recursive_mutex>::type arm_components_name_manager::ArmJointStateSubscriber::unique_lock [private]

Definition at line 92 of file ArmJointStateSubscriber.h.


Constructor & Destructor Documentation

ArmJointStateSubscriber::ArmJointStateSubscriber ( const ArmComponentsNameManager _manager,
ros::NodeHandle n,
const std::string &  joint_states_topic 
)

Definition at line 29 of file ArmJointStateSubscriber.cpp.

Definition at line 43 of file ArmJointStateSubscriber.cpp.


Member Function Documentation

std::vector< float > ArmJointStateSubscriber::armAngles ( bool &  valid) const

Definition at line 88 of file ArmJointStateSubscriber.cpp.

void ArmJointStateSubscriber::callback ( const sensor_msgs::JointState &  msg) [private]

Definition at line 116 of file ArmJointStateSubscriber.cpp.

Definition at line 82 of file ArmJointStateSubscriber.cpp.

std::vector< float > ArmJointStateSubscriber::gripperAngles ( bool &  valid) const

Definition at line 96 of file ArmJointStateSubscriber.cpp.

Returns:
true if subscriber is active. See also setActive(bool).

Definition at line 52 of file ArmJointStateSubscriber.cpp.

Activates or deactivates the processing of incoming messages. This can be used to save a bit of processing time when updates are currently not required.

Definition at line 45 of file ArmJointStateSubscriber.cpp.

std::string ArmJointStateSubscriber::toString ( ) const

Definition at line 104 of file ArmJointStateSubscriber.cpp.

bool ArmJointStateSubscriber::waitForUpdate ( float  timeout = -1,
float  checkStepTime = 0.1 
) const

Waits for the next JointState message to arrive. Only succeeds if active (isActive() returns true)

Parameters:
timeoutthe timeout, or negative if no timeout to be used
checkStepTimetime (in seconds) to sleep in-between checks wheter a new joint state has arrived.
Returns:
true if successfully waited until next message or false if timeout reached (or isActive() returned false)

Definition at line 59 of file ArmJointStateSubscriber.cpp.


Friends And Related Function Documentation

std::ostream& operator<< ( std::ostream &  o,
const ArmJointStateSubscriber j 
) [friend]

Definition at line 57 of file ArmJointStateSubscriber.h.


Member Data Documentation

Definition at line 106 of file ArmJointStateSubscriber.h.

Definition at line 107 of file ArmJointStateSubscriber.h.

Definition at line 104 of file ArmJointStateSubscriber.h.

Definition at line 115 of file ArmJointStateSubscriber.h.

baselib_binding::recursive_mutex arm_components_name_manager::ArmJointStateSubscriber::mutex [mutable, private]

Definition at line 101 of file ArmJointStateSubscriber.h.

Definition at line 109 of file ArmJointStateSubscriber.h.

Definition at line 113 of file ArmJointStateSubscriber.h.

Definition at line 114 of file ArmJointStateSubscriber.h.

Definition at line 102 of file ArmJointStateSubscriber.h.

Definition at line 102 of file ArmJointStateSubscriber.h.


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


arm_components_name_manager
Author(s): Jennifer Buehler
autogenerated on Sat Mar 2 2019 03:21:40