23 #include <sensor_msgs/JointState.h> 36 msg_.name = {
"joint1",
"joint2"};
37 msg_.position = {0.1, -0.11};
48 thread_ = std::thread{ [
this, move]{ this->
start(move); } };
63 sensor_msgs::JointStateConstPtr
msg(
new sensor_msgs::JointState(
msg_));
73 sensor_msgs::JointStateConstPtr
msg(
new sensor_msgs::JointState(
msg_));
78 msg_.position.at(0) = std::min(1000.0,
msg_.position.at(0)+0.1);
81 std::this_thread::sleep_for(std::chrono::milliseconds(10));
~JointStatesPublisherMock()
void publish(const boost::shared_ptr< M > &message) const
void startAsync(bool move=false)
Start a new thread publishing joint states.
void start(bool positions_fixed)
std::atomic_bool terminate_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
sensor_msgs::JointStateConstPtr getNextMessage()
Obtain the message that is published next.
sensor_msgs::JointState msg_
JointStatesPublisherMock()
static const std::string JOINT_STATES_TOPIC_NAME
static constexpr unsigned int JOINT_STATES_TOPIC_QUEUE_SIZE
ros::Publisher joint_states_pub_