-
Notifications
You must be signed in to change notification settings - Fork 412
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
Don't auto-activate ROS time if clock topic is being published #559
Changes from all commits
ac4132b
9ddb1ae
e2947fc
e34e0d7
73d4a7b
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -34,7 +34,8 @@ namespace rclcpp | |
{ | ||
|
||
TimeSource::TimeSource(std::shared_ptr<rclcpp::Node> node) | ||
: ros_time_active_(false) | ||
: clock_subscription_(nullptr), | ||
ros_time_active_(false) | ||
{ | ||
this->attachNode(node); | ||
} | ||
|
@@ -65,28 +66,6 @@ void TimeSource::attachNode( | |
node_services_ = node_services_interface; | ||
// TODO(tfoote): Update QOS | ||
|
||
const std::string topic_name = "/clock"; | ||
|
||
rclcpp::callback_group::CallbackGroup::SharedPtr group; | ||
using rclcpp::message_memory_strategy::MessageMemoryStrategy; | ||
auto msg_mem_strat = MessageMemoryStrategy<MessageT, Alloc>::create_default(); | ||
auto allocator = std::make_shared<Alloc>(); | ||
|
||
auto cb = std::bind(&TimeSource::clock_cb, this, std::placeholders::_1); | ||
|
||
clock_subscription_ = rclcpp::create_subscription< | ||
MessageT, decltype(cb), Alloc, MessageT, SubscriptionT | ||
>( | ||
node_topics_.get(), | ||
topic_name, | ||
std::move(cb), | ||
rmw_qos_profile_default, | ||
group, | ||
false, | ||
false, | ||
msg_mem_strat, | ||
allocator); | ||
|
||
parameter_client_ = std::make_shared<rclcpp::AsyncParametersClient>( | ||
node_base_, | ||
node_topics_, | ||
|
@@ -163,19 +142,56 @@ void TimeSource::set_clock( | |
|
||
void TimeSource::clock_cb(const rosgraph_msgs::msg::Clock::SharedPtr msg) | ||
{ | ||
if (!this->ros_time_active_) { | ||
if (!this->ros_time_active_ && SET_TRUE == this->parameter_state_) { | ||
enable_ros_time(); | ||
} | ||
// Cache the last message in case a new clock is attached. | ||
last_msg_set_ = msg; | ||
auto time_msg = std::make_shared<builtin_interfaces::msg::Time>(msg->clock); | ||
|
||
std::lock_guard<std::mutex> guard(clock_list_lock_); | ||
for (auto it = associated_clocks_.begin(); it != associated_clocks_.end(); ++it) { | ||
set_clock(time_msg, true, *it); | ||
if (SET_TRUE == this->parameter_state_) { | ||
std::lock_guard<std::mutex> guard(clock_list_lock_); | ||
for (auto it = associated_clocks_.begin(); it != associated_clocks_.end(); ++it) { | ||
set_clock(time_msg, true, *it); | ||
} | ||
} | ||
} | ||
|
||
void TimeSource::create_clock_sub() | ||
{ | ||
std::lock_guard<std::mutex> guard(clock_sub_lock_); | ||
if (clock_subscription_) { | ||
// Subscription already created. | ||
return; | ||
} | ||
const std::string topic_name = "/clock"; | ||
|
||
rclcpp::callback_group::CallbackGroup::SharedPtr group; | ||
using rclcpp::message_memory_strategy::MessageMemoryStrategy; | ||
auto msg_mem_strat = MessageMemoryStrategy<MessageT, Alloc>::create_default(); | ||
auto allocator = std::make_shared<Alloc>(); | ||
auto cb = std::bind(&TimeSource::clock_cb, this, std::placeholders::_1); | ||
|
||
clock_subscription_ = rclcpp::create_subscription< | ||
MessageT, decltype(cb), Alloc, MessageT, SubscriptionT | ||
>( | ||
node_topics_.get(), | ||
topic_name, | ||
std::move(cb), | ||
rmw_qos_profile_default, | ||
group, | ||
false, | ||
false, | ||
msg_mem_strat, | ||
allocator); | ||
} | ||
|
||
void TimeSource::destroy_clock_sub() | ||
{ | ||
std::lock_guard<std::mutex> guard(clock_sub_lock_); | ||
clock_subscription_.reset(); | ||
} | ||
|
||
void TimeSource::on_parameter_event(const rcl_interfaces::msg::ParameterEvent::SharedPtr event) | ||
{ | ||
// Filter for only 'use_sim_time' being added or changed. | ||
|
@@ -190,9 +206,11 @@ void TimeSource::on_parameter_event(const rcl_interfaces::msg::ParameterEvent::S | |
if (it.second->value.bool_value) { | ||
parameter_state_ = SET_TRUE; | ||
enable_ros_time(); | ||
create_clock_sub(); | ||
} else { | ||
parameter_state_ = SET_FALSE; | ||
disable_ros_time(); | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Should the topic be destroyed here explicitly? (opposite of There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. I had reasoned that if the sim param had been set at some point then it wouldn't be so bad to leave the subscription around, but being symmetric might be better hey (so it reflects the same state a node that never had sim time set would have). There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Yeah, I'm not sure it will ever come up, but conversely I don't think it would be wrong to remove the subscription if the parameter were allowed to be changed during runtime (not sure where we landed on that point). There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. yeah, it can be changed at runtime (there are parameter callbacks that will get triggered): 9ddb1ae |
||
destroy_clock_sub(); | ||
} | ||
} | ||
// Handle the case that use_sim_time was deleted. | ||
|
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Is this in danger of being called more than once and therefore recreating the topic?
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
for posterity: 9ddb1ae