Skip to content
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

Merged
merged 5 commits into from
Sep 25, 2018
Merged
Show file tree
Hide file tree
Changes from 1 commit
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 4 additions & 0 deletions rclcpp/include/rclcpp/time_source.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -80,13 +80,17 @@ class TimeSource
using Alloc = std::allocator<void>;
using SubscriptionT = rclcpp::Subscription<MessageT, Alloc>;
std::shared_ptr<SubscriptionT> clock_subscription_;
std::mutex clock_sub_lock_;

// The clock callback itself
void clock_cb(const rosgraph_msgs::msg::Clock::SharedPtr msg);

// Create the subscription for the clock topic
void create_clock_sub();

// Destroy the subscription for the clock topic
void destroy_clock_sub();

// Parameter Client pointer
std::shared_ptr<rclcpp::AsyncParametersClient> parameter_client_;

Expand Down
17 changes: 17 additions & 0 deletions rclcpp/src/rclcpp/time_source.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,7 @@ TimeSource::TimeSource(std::shared_ptr<rclcpp::Node> node)
: ros_time_active_(false)
{
this->attachNode(node);
clock_subscription_.reset();
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Is there a reason this has to go after this->attachNode(node);? It would be better (in my opinion) to do this in the member initialization section of the constructor as clock_subscription_(nullptr).

Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

nah, there wasn't a reason: 73d4a7b

}

TimeSource::TimeSource()
Expand Down Expand Up @@ -158,6 +159,11 @@ void TimeSource::clock_cb(const rosgraph_msgs::msg::Clock::SharedPtr msg)

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;
Expand All @@ -180,6 +186,16 @@ void TimeSource::create_clock_sub()
allocator);
}

void TimeSource::destroy_clock_sub()
{
std::lock_guard<std::mutex> guard(clock_sub_lock_);
if (!clock_subscription_) {
// Subscription already destroyed/never created.
return;
}
clock_subscription_.reset();
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This call is always safe, so you can do it ever if !clock_subscription_.

Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Updated in e34e0d7

}

void TimeSource::on_parameter_event(const rcl_interfaces::msg::ParameterEvent::SharedPtr event)
{
// Filter for only 'use_sim_time' being added or changed.
Expand All @@ -198,6 +214,7 @@ void TimeSource::on_parameter_event(const rcl_interfaces::msg::ParameterEvent::S
} else {
parameter_state_ = SET_FALSE;
disable_ros_time();
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Should the topic be destroyed here explicitly? (opposite of create_clock_sub())

Copy link
Member Author

Choose a reason for hiding this comment

The 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).

Copy link
Member

Choose a reason for hiding this comment

The 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).

Copy link
Member Author

Choose a reason for hiding this comment

The 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.
Expand Down