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

Fix use_sim_time issue on LifeCycleNode (#651) #1

Merged
merged 1 commit into from
Mar 27, 2019
Merged
Show file tree
Hide file tree
Changes from all commits
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
7 changes: 7 additions & 0 deletions rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,7 @@
#include "rclcpp/node_interfaces/node_logging_interface.hpp"
#include "rclcpp/node_interfaces/node_parameters_interface.hpp"
#include "rclcpp/node_interfaces/node_services_interface.hpp"
#include "rclcpp/node_interfaces/node_time_source_interface.hpp"
#include "rclcpp/node_interfaces/node_timers_interface.hpp"
#include "rclcpp/node_interfaces/node_topics_interface.hpp"
#include "rclcpp/node_interfaces/node_waitables_interface.hpp"
Expand Down Expand Up @@ -383,6 +384,11 @@ class LifecycleNode : public node_interfaces::LifecycleNodeInterface,
rclcpp::node_interfaces::NodeParametersInterface::SharedPtr
get_node_parameters_interface();

/// Return the Node's internal NodeParametersInterface implementation.
RCLCPP_LIFECYCLE_PUBLIC
rclcpp::node_interfaces::NodeTimeSourceInterface::SharedPtr
get_node_time_source_interface();

/// Return the Node's internal NodeWaitablesInterface implementation.
RCLCPP_LIFECYCLE_PUBLIC
rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr
Expand Down Expand Up @@ -513,6 +519,7 @@ class LifecycleNode : public node_interfaces::LifecycleNodeInterface,
rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services_;
rclcpp::node_interfaces::NodeClockInterface::SharedPtr node_clock_;
rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_parameters_;
rclcpp::node_interfaces::NodeTimeSourceInterface::SharedPtr node_time_source_;
rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr node_waitables_;

bool use_intra_process_comms_;
Expand Down
16 changes: 16 additions & 0 deletions rclcpp_lifecycle/src/lifecycle_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,7 @@
#include "rclcpp/node_interfaces/node_logging.hpp"
#include "rclcpp/node_interfaces/node_parameters.hpp"
#include "rclcpp/node_interfaces/node_services.hpp"
#include "rclcpp/node_interfaces/node_time_source.hpp"
#include "rclcpp/node_interfaces/node_timers.hpp"
#include "rclcpp/node_interfaces/node_topics.hpp"
#include "rclcpp/node_interfaces/node_waitables.hpp"
Expand Down Expand Up @@ -81,6 +82,15 @@ LifecycleNode::LifecycleNode(
options.start_parameter_event_publisher(),
options.parameter_event_qos_profile()
)),
node_time_source_(new rclcpp::node_interfaces::NodeTimeSource(
node_base_,
node_topics_,
node_graph_,
node_services_,
node_logging_,
node_clock_,
node_parameters_
)),
node_waitables_(new rclcpp::node_interfaces::NodeWaitables(node_base_.get())),
use_intra_process_comms_(options.use_intra_process_comms()),
impl_(new LifecycleNodeInterfaceImpl(node_base_, node_services_))
Expand Down Expand Up @@ -274,6 +284,12 @@ LifecycleNode::get_node_logging_interface()
return node_logging_;
}

rclcpp::node_interfaces::NodeTimeSourceInterface::SharedPtr
LifecycleNode::get_node_time_source_interface()
{
return node_time_source_;
}

rclcpp::node_interfaces::NodeTimersInterface::SharedPtr
LifecycleNode::get_node_timers_interface()
{
Expand Down