Public Member Functions | Private Types | Private Member Functions | Private Attributes | List of all members
pilz_testutils::JointStatePublisherMock Class Reference

Mocks the joint_states interface. Can simulate robot movement by changing the position of the first joint in controller_joint_names. More...

#include <joint_state_publisher_mock.h>

Public Member Functions

JointStateConstPtr getNextMessage ()
 Return the message which will be published next. More...
 
void goHome ()
 Go back to home position (position=velocity=0.0). More...
 
 JointStatePublisherMock ()
 
 JointStatePublisherMock (const JointStatePublisherMock &other)=delete
 
JointStatePublisherMockoperator= (const JointStatePublisherMock &other)=delete
 
void setJoint1Velocity (const double &vel)
 
void startPublishingAsync (const double &joint1_start_position=0.0)
 
void stopPublishing ()
 
 ~JointStatePublisherMock ()
 

Private Types

typedef sensor_msgs::JointState JointState
 
typedef sensor_msgs::JointStateConstPtr JointStateConstPtr
 

Private Member Functions

void createNextMessage ()
 
void publish ()
 
void run ()
 
void updateJoint1Position ()
 
void updateNextMessage ()
 

Private Attributes

std::atomic_bool go_home_flag_
 
double joint1_position_ { 0.0 }
 
double joint1_velocity_ { 0.0 }
 
std::vector< std::string > joint_names_
 
JointState next_msg_
 
std::mutex next_msg_mutex_
 
ros::Time next_time_stamp_
 
ros::NodeHandle nh_
 
ros::Publisher pub_
 
std::thread publisher_thread_
 
std::atomic_bool stop_flag_
 

Detailed Description

Mocks the joint_states interface. Can simulate robot movement by changing the position of the first joint in controller_joint_names.

Definition at line 38 of file joint_state_publisher_mock.h.

Member Typedef Documentation

◆ JointState

typedef sensor_msgs::JointState pilz_testutils::JointStatePublisherMock::JointState
private

Definition at line 40 of file joint_state_publisher_mock.h.

◆ JointStateConstPtr

typedef sensor_msgs::JointStateConstPtr pilz_testutils::JointStatePublisherMock::JointStateConstPtr
private

Definition at line 41 of file joint_state_publisher_mock.h.

Constructor & Destructor Documentation

◆ JointStatePublisherMock() [1/2]

pilz_testutils::JointStatePublisherMock::JointStatePublisherMock ( )

Definition at line 37 of file joint_state_publisher_mock.cpp.

◆ ~JointStatePublisherMock()

pilz_testutils::JointStatePublisherMock::~JointStatePublisherMock ( )

Definition at line 45 of file joint_state_publisher_mock.cpp.

◆ JointStatePublisherMock() [2/2]

pilz_testutils::JointStatePublisherMock::JointStatePublisherMock ( const JointStatePublisherMock other)
delete

Member Function Documentation

◆ createNextMessage()

void pilz_testutils::JointStatePublisherMock::createNextMessage ( )
private

Definition at line 104 of file joint_state_publisher_mock.cpp.

◆ getNextMessage()

sensor_msgs::JointStateConstPtr pilz_testutils::JointStatePublisherMock::getNextMessage ( )

Return the message which will be published next.

Definition at line 78 of file joint_state_publisher_mock.cpp.

◆ goHome()

void pilz_testutils::JointStatePublisherMock::goHome ( )

Go back to home position (position=velocity=0.0).

This is needed in order to ensure a clean tear-down. The current velocity is maintained until the home position is reached.

Definition at line 64 of file joint_state_publisher_mock.cpp.

◆ operator=()

JointStatePublisherMock& pilz_testutils::JointStatePublisherMock::operator= ( const JointStatePublisherMock other)
delete

◆ publish()

void pilz_testutils::JointStatePublisherMock::publish ( )
private

Definition at line 115 of file joint_state_publisher_mock.cpp.

◆ run()

void pilz_testutils::JointStatePublisherMock::run ( )
private

Definition at line 84 of file joint_state_publisher_mock.cpp.

◆ setJoint1Velocity()

void pilz_testutils::JointStatePublisherMock::setJoint1Velocity ( const double &  vel)

Definition at line 57 of file joint_state_publisher_mock.cpp.

◆ startPublishingAsync()

void pilz_testutils::JointStatePublisherMock::startPublishingAsync ( const double &  joint1_start_position = 0.0)

Definition at line 50 of file joint_state_publisher_mock.cpp.

◆ stopPublishing()

void pilz_testutils::JointStatePublisherMock::stopPublishing ( )

Definition at line 69 of file joint_state_publisher_mock.cpp.

◆ updateJoint1Position()

void pilz_testutils::JointStatePublisherMock::updateJoint1Position ( )
private

Definition at line 126 of file joint_state_publisher_mock.cpp.

◆ updateNextMessage()

void pilz_testutils::JointStatePublisherMock::updateNextMessage ( )
private

Definition at line 120 of file joint_state_publisher_mock.cpp.

Member Data Documentation

◆ go_home_flag_

std::atomic_bool pilz_testutils::JointStatePublisherMock::go_home_flag_
private

Definition at line 82 of file joint_state_publisher_mock.h.

◆ joint1_position_

double pilz_testutils::JointStatePublisherMock::joint1_position_ { 0.0 }
private

Definition at line 84 of file joint_state_publisher_mock.h.

◆ joint1_velocity_

double pilz_testutils::JointStatePublisherMock::joint1_velocity_ { 0.0 }
private

Definition at line 85 of file joint_state_publisher_mock.h.

◆ joint_names_

std::vector<std::string> pilz_testutils::JointStatePublisherMock::joint_names_
private

Definition at line 80 of file joint_state_publisher_mock.h.

◆ next_msg_

JointState pilz_testutils::JointStatePublisherMock::next_msg_
private

Definition at line 87 of file joint_state_publisher_mock.h.

◆ next_msg_mutex_

std::mutex pilz_testutils::JointStatePublisherMock::next_msg_mutex_
private

Definition at line 88 of file joint_state_publisher_mock.h.

◆ next_time_stamp_

ros::Time pilz_testutils::JointStatePublisherMock::next_time_stamp_
private

Definition at line 86 of file joint_state_publisher_mock.h.

◆ nh_

ros::NodeHandle pilz_testutils::JointStatePublisherMock::nh_
private

Definition at line 78 of file joint_state_publisher_mock.h.

◆ pub_

ros::Publisher pilz_testutils::JointStatePublisherMock::pub_
private

Definition at line 79 of file joint_state_publisher_mock.h.

◆ publisher_thread_

std::thread pilz_testutils::JointStatePublisherMock::publisher_thread_
private

Definition at line 83 of file joint_state_publisher_mock.h.

◆ stop_flag_

std::atomic_bool pilz_testutils::JointStatePublisherMock::stop_flag_
private

Definition at line 81 of file joint_state_publisher_mock.h.


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


pilz_testutils
Author(s):
autogenerated on Sat Nov 25 2023 03:16:57