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

Conversation

dhood
Copy link
Member

@dhood dhood commented Sep 20, 2018

closes #514 and #515

Previously, the clock subscription was always created. When messages were received on the clock topic, ROS time was set to active (#514), even if use_sim_time was set to false (#515).

Now, ROS time will only be set active if the use_sim_time parameter is explicitly set true. The subscription is only created if the parameter is set (can be set after node startup).

  • Linux Build Status
  • Linux-aarch64 Build Status
  • macOS Build Status
  • Windows Build Status

In progress because CI might uncover things relying on the previous behaviour (the /chatter topic won't appear by default now)

@dhood dhood added the in progress Actively being worked on (Kanban column) label Sep 20, 2018
@dhood dhood self-assigned this Sep 20, 2018
@@ -190,6 +194,7 @@ 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();
Copy link
Member

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?

Copy link
Member Author

Choose a reason for hiding this comment

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

for posterity: 9ddb1ae

@@ -190,6 +194,7 @@ 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();
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

@dhood
Copy link
Member Author

dhood commented Sep 21, 2018

  • Linux Build Status
  • Linux-aarch64 Build Status
  • macOS Build Status
  • Windows Build Status

@dhood
Copy link
Member Author

dhood commented Sep 24, 2018

oops this was sitting in the in-progress column accidentally. Good for review thanks!

@@ -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

// 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

@dhood
Copy link
Member Author

dhood commented Sep 24, 2018

  • Linux Build Status
  • Linux-aarch64 Build Status
  • macOS Build Status
  • Windows Build Status

@dhood dhood added in review Waiting for review (Kanban column) and removed in progress Actively being worked on (Kanban column) labels Sep 24, 2018
@dhood dhood merged commit 6ff3ff4 into master Sep 25, 2018
@dhood dhood deleted the avoid_using_ros_time branch September 25, 2018 15:34
@dhood dhood removed the in review Waiting for review (Kanban column) label Sep 25, 2018
nnmm pushed a commit to ApexAI/rclcpp that referenced this pull request Jul 9, 2022
* fix return type of rcl_publisher_get_subscription_count

* fix it in c file too
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

Nodes default to using ROS time if /clock is published
2 participants