Public Member Functions | Private Member Functions | Private Attributes | List of all members
prbt_hardware_support::JointStatesPublisherMock Class Reference

Asynchronously publishes predefined messages on the /joint_states topic with rate ~100Hz. More...

#include <joint_states_publisher_mock.h>

Public Member Functions

sensor_msgs::JointStateConstPtr getNextMessage ()
 Obtain the message that is published next. More...
 
 JointStatesPublisherMock ()
 
void startAsync (bool move=false)
 Start a new thread publishing joint states. More...
 
void terminate ()
 
 ~JointStatesPublisherMock ()
 

Private Member Functions

void start (bool positions_fixed)
 

Private Attributes

ros::Publisher joint_states_pub_
 
sensor_msgs::JointState msg_
 
std::mutex msg_mutex_
 
ros::NodeHandle nh_
 
std::atomic_bool terminate_
 
std::thread thread_
 

Detailed Description

Asynchronously publishes predefined messages on the /joint_states topic with rate ~100Hz.

Definition at line 34 of file joint_states_publisher_mock.h.

Constructor & Destructor Documentation

prbt_hardware_support::JointStatesPublisherMock::JointStatesPublisherMock ( )

Definition at line 33 of file joint_states_publisher_mock.cpp.

prbt_hardware_support::JointStatesPublisherMock::~JointStatesPublisherMock ( )

Definition at line 40 of file joint_states_publisher_mock.cpp.

Member Function Documentation

sensor_msgs::JointStateConstPtr prbt_hardware_support::JointStatesPublisherMock::getNextMessage ( )

Obtain the message that is published next.

Definition at line 60 of file joint_states_publisher_mock.cpp.

void prbt_hardware_support::JointStatesPublisherMock::start ( bool  positions_fixed)
private

Definition at line 67 of file joint_states_publisher_mock.cpp.

void prbt_hardware_support::JointStatesPublisherMock::startAsync ( bool  move = false)

Start a new thread publishing joint states.

Parameters
moveIf true, a movement is simulated, otherwise the positions do not change.

Definition at line 45 of file joint_states_publisher_mock.cpp.

void prbt_hardware_support::JointStatesPublisherMock::terminate ( )

Definition at line 51 of file joint_states_publisher_mock.cpp.

Member Data Documentation

ros::Publisher prbt_hardware_support::JointStatesPublisherMock::joint_states_pub_
private

Definition at line 60 of file joint_states_publisher_mock.h.

sensor_msgs::JointState prbt_hardware_support::JointStatesPublisherMock::msg_
private

Definition at line 64 of file joint_states_publisher_mock.h.

std::mutex prbt_hardware_support::JointStatesPublisherMock::msg_mutex_
private

Definition at line 63 of file joint_states_publisher_mock.h.

ros::NodeHandle prbt_hardware_support::JointStatesPublisherMock::nh_
private

Definition at line 59 of file joint_states_publisher_mock.h.

std::atomic_bool prbt_hardware_support::JointStatesPublisherMock::terminate_
private

Definition at line 62 of file joint_states_publisher_mock.h.

std::thread prbt_hardware_support::JointStatesPublisherMock::thread_
private

Definition at line 61 of file joint_states_publisher_mock.h.


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


prbt_hardware_support
Author(s):
autogenerated on Tue Feb 2 2021 03:50:18