Skip to content

Commit a7a4fc9

Browse files
authored
Merge pull request #138 from Hugal31/fix/rtt_rosclock_no_rosmaster
Do not use ROS connection with rtt_rosclock::SimClockThread if time source is manual
2 parents 2c599b3 + cc87ef9 commit a7a4fc9

File tree

2 files changed

+3
-3
lines changed

2 files changed

+3
-3
lines changed

rtt_rosclock/include/rtt_rosclock/rtt_rosclock_sim_clock_thread.h

Lines changed: 0 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -126,8 +126,6 @@ namespace rtt_rosclock {
126126
//! Keep running the thread loop if this is set to true
127127
bool process_callbacks_;
128128

129-
//! ROS NodeHandle for communication
130-
ros::NodeHandle nh_;
131129
//! ROS /clock topic subscriber
132130
ros::Subscriber clock_subscriber_;
133131
//! Custom callback queue used in this thread

rtt_rosclock/src/rtt_rosclock_sim_clock_thread.cpp

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -220,6 +220,8 @@ bool SimClockThread::initialize()
220220
{
221221
case SIM_CLOCK_SOURCE_ROS_CLOCK_TOPIC:
222222
{
223+
ros::NodeHandle nh;
224+
223225
// Get /use_sim_time parameter from ROS
224226
bool use_sim_time = false;
225227
ros::param::get("/use_sim_time", use_sim_time);
@@ -239,7 +241,7 @@ bool SimClockThread::initialize()
239241
ros::SubscribeOptions ops = ros::SubscribeOptions::create<rosgraph_msgs::Clock>(
240242
"/clock", 1, boost::bind(&SimClockThread::clockMsgCallback, this, _1),
241243
ros::VoidConstPtr(), &callback_queue_);
242-
clock_subscriber_ = nh_.subscribe(ops);
244+
clock_subscriber_ = nh.subscribe(ops);
243245

244246
// The loop needs to run in order to call the callback queue
245247
process_callbacks_ = true;

0 commit comments

Comments
 (0)