2016-12-14 09:29:27 -08:00
|
|
|
// Copyright 2016 Open Source Robotics Foundation, Inc.
|
|
|
|
//
|
|
|
|
// Licensed under the Apache License, Version 2.0 (the "License");
|
|
|
|
// you may not use this file except in compliance with the License.
|
|
|
|
// You may obtain a copy of the License at
|
|
|
|
//
|
|
|
|
// http://www.apache.org/licenses/LICENSE-2.0
|
|
|
|
//
|
|
|
|
// Unless required by applicable law or agreed to in writing, software
|
|
|
|
// distributed under the License is distributed on an "AS IS" BASIS,
|
|
|
|
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
|
|
|
// See the License for the specific language governing permissions and
|
|
|
|
// limitations under the License.
|
|
|
|
|
|
|
|
#include "rclcpp_lifecycle/lifecycle_node.hpp"
|
|
|
|
|
|
|
|
#include <string>
|
|
|
|
#include <map>
|
|
|
|
#include <memory>
|
|
|
|
#include <vector>
|
|
|
|
#include <utility>
|
|
|
|
|
|
|
|
#include "lifecycle_msgs/msg/state.hpp"
|
|
|
|
#include "lifecycle_msgs/msg/transition.hpp"
|
|
|
|
|
|
|
|
#include "rclcpp/exceptions.hpp"
|
|
|
|
#include "rclcpp/graph_listener.hpp"
|
2017-12-04 16:07:29 -08:00
|
|
|
#include "rclcpp/logger.hpp"
|
2016-12-14 09:29:27 -08:00
|
|
|
#include "rclcpp/node.hpp"
|
|
|
|
#include "rclcpp/node_interfaces/node_base.hpp"
|
2017-12-05 00:25:28 -08:00
|
|
|
#include "rclcpp/node_interfaces/node_clock.hpp"
|
2016-12-14 09:29:27 -08:00
|
|
|
#include "rclcpp/node_interfaces/node_graph.hpp"
|
2017-12-04 16:07:29 -08:00
|
|
|
#include "rclcpp/node_interfaces/node_logging.hpp"
|
2016-12-14 09:29:27 -08:00
|
|
|
#include "rclcpp/node_interfaces/node_parameters.hpp"
|
|
|
|
#include "rclcpp/node_interfaces/node_services.hpp"
|
2019-03-27 08:24:20 +09:00
|
|
|
#include "rclcpp/node_interfaces/node_time_source.hpp"
|
2016-12-14 09:29:27 -08:00
|
|
|
#include "rclcpp/node_interfaces/node_timers.hpp"
|
|
|
|
#include "rclcpp/node_interfaces/node_topics.hpp"
|
2018-11-22 14:03:51 -08:00
|
|
|
#include "rclcpp/node_interfaces/node_waitables.hpp"
|
2018-05-25 13:07:59 -07:00
|
|
|
#include "rclcpp/parameter_service.hpp"
|
2016-12-14 09:29:27 -08:00
|
|
|
|
|
|
|
#include "lifecycle_node_interface_impl.hpp" // implementation
|
|
|
|
|
|
|
|
namespace rclcpp_lifecycle
|
|
|
|
{
|
|
|
|
|
2017-04-08 02:04:41 -07:00
|
|
|
LifecycleNode::LifecycleNode(
|
|
|
|
const std::string & node_name,
|
2019-02-06 01:10:43 -06:00
|
|
|
const rclcpp::NodeOptions & options)
|
2016-12-14 09:29:27 -08:00
|
|
|
: LifecycleNode(
|
|
|
|
node_name,
|
2019-02-06 01:10:43 -06:00
|
|
|
"",
|
|
|
|
options)
|
2016-12-14 09:29:27 -08:00
|
|
|
{}
|
|
|
|
|
|
|
|
LifecycleNode::LifecycleNode(
|
|
|
|
const std::string & node_name,
|
2017-04-08 02:04:41 -07:00
|
|
|
const std::string & namespace_,
|
2019-02-06 01:10:43 -06:00
|
|
|
const rclcpp::NodeOptions & options)
|
2018-04-17 10:52:49 -07:00
|
|
|
: node_base_(new rclcpp::node_interfaces::NodeBase(
|
2019-05-08 14:24:40 -07:00
|
|
|
node_name,
|
|
|
|
namespace_,
|
|
|
|
options.context(),
|
|
|
|
*(options.get_rcl_node_options()),
|
2020-04-21 14:14:47 -07:00
|
|
|
options.use_intra_process_comms(),
|
|
|
|
options.enable_topic_statistics())),
|
2016-12-14 09:29:27 -08:00
|
|
|
node_graph_(new rclcpp::node_interfaces::NodeGraph(node_base_.get())),
|
2017-12-04 16:07:29 -08:00
|
|
|
node_logging_(new rclcpp::node_interfaces::NodeLogging(node_base_.get())),
|
2016-12-14 09:29:27 -08:00
|
|
|
node_timers_(new rclcpp::node_interfaces::NodeTimers(node_base_.get())),
|
2020-04-22 16:09:41 -07:00
|
|
|
node_topics_(new rclcpp::node_interfaces::NodeTopics(node_base_.get(), node_timers_.get())),
|
2016-12-14 09:29:27 -08:00
|
|
|
node_services_(new rclcpp::node_interfaces::NodeServices(node_base_.get())),
|
2018-12-04 14:24:48 -08:00
|
|
|
node_clock_(new rclcpp::node_interfaces::NodeClock(
|
|
|
|
node_base_,
|
|
|
|
node_topics_,
|
|
|
|
node_graph_,
|
|
|
|
node_services_,
|
|
|
|
node_logging_
|
2018-12-05 09:12:57 -08:00
|
|
|
)),
|
2016-12-14 09:29:27 -08:00
|
|
|
node_parameters_(new rclcpp::node_interfaces::NodeParameters(
|
2018-05-25 13:07:59 -07:00
|
|
|
node_base_,
|
2019-04-23 10:44:55 -07:00
|
|
|
node_logging_,
|
2018-05-25 13:07:59 -07:00
|
|
|
node_topics_,
|
|
|
|
node_services_,
|
2018-12-04 14:24:48 -08:00
|
|
|
node_clock_,
|
2019-05-29 12:12:42 -07:00
|
|
|
options.parameter_overrides(),
|
2019-02-07 08:04:53 +01:00
|
|
|
options.start_parameter_services(),
|
|
|
|
options.start_parameter_event_publisher(),
|
2019-05-08 14:24:40 -07:00
|
|
|
options.parameter_event_qos(),
|
|
|
|
options.parameter_event_publisher_options(),
|
2019-04-23 10:44:55 -07:00
|
|
|
options.allow_undeclared_parameters(),
|
2019-05-29 12:12:42 -07:00
|
|
|
options.automatically_declare_parameters_from_overrides()
|
2016-12-14 09:29:27 -08:00
|
|
|
)),
|
2019-03-27 08:24:20 +09:00
|
|
|
node_time_source_(new rclcpp::node_interfaces::NodeTimeSource(
|
|
|
|
node_base_,
|
|
|
|
node_topics_,
|
|
|
|
node_graph_,
|
|
|
|
node_services_,
|
|
|
|
node_logging_,
|
|
|
|
node_clock_,
|
|
|
|
node_parameters_
|
|
|
|
)),
|
2018-11-22 14:03:51 -08:00
|
|
|
node_waitables_(new rclcpp::node_interfaces::NodeWaitables(node_base_.get())),
|
2019-05-08 14:24:40 -07:00
|
|
|
node_options_(options),
|
2016-12-14 09:29:27 -08:00
|
|
|
impl_(new LifecycleNodeInterfaceImpl(node_base_, node_services_))
|
|
|
|
{
|
|
|
|
impl_->init();
|
|
|
|
|
2019-08-07 10:33:06 -05:00
|
|
|
register_on_configure(
|
|
|
|
std::bind(
|
|
|
|
&LifecycleNodeInterface::on_configure, this,
|
|
|
|
std::placeholders::_1));
|
2016-12-14 09:29:27 -08:00
|
|
|
register_on_cleanup(std::bind(&LifecycleNodeInterface::on_cleanup, this, std::placeholders::_1));
|
2019-08-07 10:33:06 -05:00
|
|
|
register_on_shutdown(
|
|
|
|
std::bind(
|
|
|
|
&LifecycleNodeInterface::on_shutdown, this,
|
|
|
|
std::placeholders::_1));
|
|
|
|
register_on_activate(
|
|
|
|
std::bind(
|
|
|
|
&LifecycleNodeInterface::on_activate, this,
|
|
|
|
std::placeholders::_1));
|
|
|
|
register_on_deactivate(
|
|
|
|
std::bind(
|
|
|
|
&LifecycleNodeInterface::on_deactivate, this,
|
|
|
|
std::placeholders::_1));
|
2016-12-14 09:29:27 -08:00
|
|
|
register_on_error(std::bind(&LifecycleNodeInterface::on_error, this, std::placeholders::_1));
|
|
|
|
}
|
|
|
|
|
|
|
|
LifecycleNode::~LifecycleNode()
|
|
|
|
{}
|
|
|
|
|
|
|
|
const char *
|
|
|
|
LifecycleNode::get_name() const
|
|
|
|
{
|
|
|
|
return node_base_->get_name();
|
|
|
|
}
|
|
|
|
|
2017-06-01 14:01:18 -07:00
|
|
|
const char *
|
|
|
|
LifecycleNode::get_namespace() const
|
|
|
|
{
|
|
|
|
return node_base_->get_namespace();
|
|
|
|
}
|
|
|
|
|
2017-12-04 16:07:29 -08:00
|
|
|
rclcpp::Logger
|
|
|
|
LifecycleNode::get_logger() const
|
|
|
|
{
|
|
|
|
return node_logging_->get_logger();
|
|
|
|
}
|
|
|
|
|
2020-04-23 15:28:45 -07:00
|
|
|
rclcpp::CallbackGroup::SharedPtr
|
2016-12-14 09:29:27 -08:00
|
|
|
LifecycleNode::create_callback_group(
|
2020-04-23 15:28:45 -07:00
|
|
|
rclcpp::CallbackGroupType group_type)
|
2016-12-14 09:29:27 -08:00
|
|
|
{
|
|
|
|
return node_base_->create_callback_group(group_type);
|
|
|
|
}
|
|
|
|
|
2019-05-15 15:15:40 -07:00
|
|
|
const rclcpp::ParameterValue &
|
|
|
|
LifecycleNode::declare_parameter(
|
|
|
|
const std::string & name,
|
|
|
|
const rclcpp::ParameterValue & default_value,
|
|
|
|
const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor)
|
|
|
|
{
|
|
|
|
return this->node_parameters_->declare_parameter(name, default_value, parameter_descriptor);
|
|
|
|
}
|
|
|
|
|
|
|
|
void
|
|
|
|
LifecycleNode::undeclare_parameter(const std::string & name)
|
|
|
|
{
|
|
|
|
this->node_parameters_->undeclare_parameter(name);
|
|
|
|
}
|
|
|
|
|
|
|
|
bool
|
|
|
|
LifecycleNode::has_parameter(const std::string & name) const
|
|
|
|
{
|
|
|
|
return this->node_parameters_->has_parameter(name);
|
|
|
|
}
|
|
|
|
|
|
|
|
rcl_interfaces::msg::SetParametersResult
|
|
|
|
LifecycleNode::set_parameter(const rclcpp::Parameter & parameter)
|
|
|
|
{
|
|
|
|
return this->set_parameters_atomically({parameter});
|
|
|
|
}
|
|
|
|
|
2016-12-14 09:29:27 -08:00
|
|
|
bool
|
2020-04-23 15:28:45 -07:00
|
|
|
LifecycleNode::group_in_node(rclcpp::CallbackGroup::SharedPtr group)
|
2016-12-14 09:29:27 -08:00
|
|
|
{
|
|
|
|
return node_base_->callback_group_in_node(group);
|
|
|
|
}
|
|
|
|
|
|
|
|
std::vector<rcl_interfaces::msg::SetParametersResult>
|
|
|
|
LifecycleNode::set_parameters(
|
2018-06-01 11:48:56 -07:00
|
|
|
const std::vector<rclcpp::Parameter> & parameters)
|
2016-12-14 09:29:27 -08:00
|
|
|
{
|
|
|
|
return node_parameters_->set_parameters(parameters);
|
|
|
|
}
|
|
|
|
|
|
|
|
rcl_interfaces::msg::SetParametersResult
|
|
|
|
LifecycleNode::set_parameters_atomically(
|
2018-06-01 11:48:56 -07:00
|
|
|
const std::vector<rclcpp::Parameter> & parameters)
|
2016-12-14 09:29:27 -08:00
|
|
|
{
|
|
|
|
return node_parameters_->set_parameters_atomically(parameters);
|
|
|
|
}
|
|
|
|
|
2018-06-01 11:48:56 -07:00
|
|
|
std::vector<rclcpp::Parameter>
|
2016-12-14 09:29:27 -08:00
|
|
|
LifecycleNode::get_parameters(
|
|
|
|
const std::vector<std::string> & names) const
|
|
|
|
{
|
|
|
|
return node_parameters_->get_parameters(names);
|
|
|
|
}
|
|
|
|
|
2018-06-01 11:48:56 -07:00
|
|
|
rclcpp::Parameter
|
2016-12-14 09:29:27 -08:00
|
|
|
LifecycleNode::get_parameter(const std::string & name) const
|
|
|
|
{
|
|
|
|
return node_parameters_->get_parameter(name);
|
|
|
|
}
|
|
|
|
|
2019-05-15 15:15:40 -07:00
|
|
|
bool
|
|
|
|
LifecycleNode::get_parameter(
|
2017-09-28 11:57:18 -07:00
|
|
|
const std::string & name,
|
2018-06-01 11:48:56 -07:00
|
|
|
rclcpp::Parameter & parameter) const
|
2016-12-14 09:29:27 -08:00
|
|
|
{
|
|
|
|
return node_parameters_->get_parameter(name, parameter);
|
|
|
|
}
|
|
|
|
|
2019-05-15 15:15:40 -07:00
|
|
|
rcl_interfaces::msg::ParameterDescriptor
|
|
|
|
LifecycleNode::describe_parameter(const std::string & name) const
|
|
|
|
{
|
|
|
|
auto result = node_parameters_->describe_parameters({name});
|
|
|
|
if (0 == result.size()) {
|
|
|
|
throw rclcpp::exceptions::ParameterNotDeclaredException(name);
|
|
|
|
}
|
|
|
|
if (result.size() > 1) {
|
|
|
|
throw std::runtime_error("number of described parameters unexpectedly more than one");
|
|
|
|
}
|
|
|
|
return result.front();
|
|
|
|
}
|
|
|
|
|
2016-12-14 09:29:27 -08:00
|
|
|
std::vector<rcl_interfaces::msg::ParameterDescriptor>
|
|
|
|
LifecycleNode::describe_parameters(
|
|
|
|
const std::vector<std::string> & names) const
|
|
|
|
{
|
|
|
|
return node_parameters_->describe_parameters(names);
|
|
|
|
}
|
|
|
|
|
|
|
|
std::vector<uint8_t>
|
|
|
|
LifecycleNode::get_parameter_types(
|
|
|
|
const std::vector<std::string> & names) const
|
|
|
|
{
|
|
|
|
return node_parameters_->get_parameter_types(names);
|
|
|
|
}
|
|
|
|
|
|
|
|
rcl_interfaces::msg::ListParametersResult
|
|
|
|
LifecycleNode::list_parameters(
|
|
|
|
const std::vector<std::string> & prefixes, uint64_t depth) const
|
|
|
|
{
|
|
|
|
return node_parameters_->list_parameters(prefixes, depth);
|
|
|
|
}
|
|
|
|
|
2020-05-26 11:47:53 -07:00
|
|
|
rclcpp::Node::OnSetParametersCallbackHandle::SharedPtr
|
|
|
|
LifecycleNode::add_on_set_parameters_callback(OnParametersSetCallbackType callback)
|
|
|
|
{
|
|
|
|
return node_parameters_->add_on_set_parameters_callback(callback);
|
|
|
|
}
|
|
|
|
|
|
|
|
void
|
|
|
|
LifecycleNode::remove_on_set_parameters_callback(const OnSetParametersCallbackHandle * const callback)
|
|
|
|
{
|
|
|
|
return node_parameters_->remove_on_set_parameters_callback(callback);
|
2020-05-26 12:17:41 -07:00
|
|
|
}
|
2020-05-26 11:47:53 -07:00
|
|
|
|
2019-05-15 15:15:40 -07:00
|
|
|
rclcpp::Node::OnParametersSetCallbackType
|
|
|
|
LifecycleNode::set_on_parameters_set_callback(rclcpp::Node::OnParametersSetCallbackType callback)
|
|
|
|
{
|
|
|
|
return node_parameters_->set_on_parameters_set_callback(callback);
|
|
|
|
}
|
|
|
|
|
2018-07-06 06:15:09 +05:30
|
|
|
std::vector<std::string>
|
|
|
|
LifecycleNode::get_node_names() const
|
|
|
|
{
|
|
|
|
return node_graph_->get_node_names();
|
|
|
|
}
|
|
|
|
|
2017-06-16 18:03:16 -07:00
|
|
|
std::map<std::string, std::vector<std::string>>
|
|
|
|
LifecycleNode::get_topic_names_and_types(bool no_demangle) const
|
2016-12-14 09:29:27 -08:00
|
|
|
{
|
2017-06-16 18:03:16 -07:00
|
|
|
return node_graph_->get_topic_names_and_types(no_demangle);
|
|
|
|
}
|
|
|
|
|
|
|
|
std::map<std::string, std::vector<std::string>>
|
|
|
|
LifecycleNode::get_service_names_and_types() const
|
|
|
|
{
|
|
|
|
return node_graph_->get_service_names_and_types();
|
2016-12-14 09:29:27 -08:00
|
|
|
}
|
|
|
|
|
2020-05-26 10:26:51 -07:00
|
|
|
std::map<std::string, std::vector<std::string>>
|
|
|
|
LifecycleNode::get_service_names_and_types_by_node(
|
|
|
|
const std::string & node_name,
|
|
|
|
const std::string & namespace_) const
|
|
|
|
{
|
|
|
|
return node_graph_->get_service_names_and_types_by_node(
|
|
|
|
node_name, namespace_);
|
|
|
|
}
|
|
|
|
|
2016-12-14 09:29:27 -08:00
|
|
|
size_t
|
|
|
|
LifecycleNode::count_publishers(const std::string & topic_name) const
|
|
|
|
{
|
|
|
|
return node_graph_->count_publishers(topic_name);
|
|
|
|
}
|
|
|
|
|
|
|
|
size_t
|
|
|
|
LifecycleNode::count_subscribers(const std::string & topic_name) const
|
|
|
|
{
|
|
|
|
return node_graph_->count_subscribers(topic_name);
|
|
|
|
}
|
|
|
|
|
2020-02-15 04:25:03 +08:00
|
|
|
std::vector<rclcpp::TopicEndpointInfo>
|
|
|
|
LifecycleNode::get_publishers_info_by_topic(const std::string & topic_name, bool no_mangle) const
|
|
|
|
{
|
|
|
|
return node_graph_->get_publishers_info_by_topic(topic_name, no_mangle);
|
|
|
|
}
|
|
|
|
|
|
|
|
std::vector<rclcpp::TopicEndpointInfo>
|
|
|
|
LifecycleNode::get_subscriptions_info_by_topic(const std::string & topic_name, bool no_mangle) const
|
|
|
|
{
|
|
|
|
return node_graph_->get_subscriptions_info_by_topic(topic_name, no_mangle);
|
|
|
|
}
|
|
|
|
|
2020-04-23 15:28:45 -07:00
|
|
|
const std::vector<rclcpp::CallbackGroup::WeakPtr> &
|
2016-12-14 09:29:27 -08:00
|
|
|
LifecycleNode::get_callback_groups() const
|
|
|
|
{
|
|
|
|
return node_base_->get_callback_groups();
|
|
|
|
}
|
|
|
|
|
2017-12-05 15:02:00 -08:00
|
|
|
rclcpp::Event::SharedPtr
|
2016-12-14 09:29:27 -08:00
|
|
|
LifecycleNode::get_graph_event()
|
|
|
|
{
|
|
|
|
return node_graph_->get_graph_event();
|
|
|
|
}
|
|
|
|
|
|
|
|
void
|
|
|
|
LifecycleNode::wait_for_graph_change(
|
2017-12-05 15:02:00 -08:00
|
|
|
rclcpp::Event::SharedPtr event,
|
2016-12-14 09:29:27 -08:00
|
|
|
std::chrono::nanoseconds timeout)
|
|
|
|
{
|
|
|
|
node_graph_->wait_for_graph_change(event, timeout);
|
|
|
|
}
|
|
|
|
|
2017-12-05 00:25:28 -08:00
|
|
|
rclcpp::Clock::SharedPtr
|
|
|
|
LifecycleNode::get_clock()
|
|
|
|
{
|
|
|
|
return node_clock_->get_clock();
|
|
|
|
}
|
|
|
|
|
2019-12-06 14:03:58 -08:00
|
|
|
rclcpp::Clock::ConstSharedPtr
|
|
|
|
LifecycleNode::get_clock() const
|
|
|
|
{
|
|
|
|
return node_clock_->get_clock();
|
|
|
|
}
|
|
|
|
|
2017-12-05 00:25:28 -08:00
|
|
|
rclcpp::Time
|
2019-12-06 14:03:58 -08:00
|
|
|
LifecycleNode::now() const
|
2017-12-05 00:25:28 -08:00
|
|
|
{
|
|
|
|
return node_clock_->get_clock()->now();
|
|
|
|
}
|
|
|
|
|
2016-12-14 09:29:27 -08:00
|
|
|
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr
|
|
|
|
LifecycleNode::get_node_base_interface()
|
|
|
|
{
|
|
|
|
return node_base_;
|
|
|
|
}
|
|
|
|
|
2017-12-05 00:25:28 -08:00
|
|
|
rclcpp::node_interfaces::NodeClockInterface::SharedPtr
|
|
|
|
LifecycleNode::get_node_clock_interface()
|
|
|
|
{
|
|
|
|
return node_clock_;
|
|
|
|
}
|
|
|
|
|
2016-12-14 09:29:27 -08:00
|
|
|
rclcpp::node_interfaces::NodeGraphInterface::SharedPtr
|
|
|
|
LifecycleNode::get_node_graph_interface()
|
|
|
|
{
|
|
|
|
return node_graph_;
|
|
|
|
}
|
|
|
|
|
2019-03-06 13:12:38 -08:00
|
|
|
rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr
|
|
|
|
LifecycleNode::get_node_logging_interface()
|
|
|
|
{
|
|
|
|
return node_logging_;
|
|
|
|
}
|
|
|
|
|
2019-03-27 08:24:20 +09:00
|
|
|
rclcpp::node_interfaces::NodeTimeSourceInterface::SharedPtr
|
|
|
|
LifecycleNode::get_node_time_source_interface()
|
|
|
|
{
|
|
|
|
return node_time_source_;
|
|
|
|
}
|
|
|
|
|
2016-12-14 09:29:27 -08:00
|
|
|
rclcpp::node_interfaces::NodeTimersInterface::SharedPtr
|
|
|
|
LifecycleNode::get_node_timers_interface()
|
|
|
|
{
|
|
|
|
return node_timers_;
|
|
|
|
}
|
|
|
|
|
|
|
|
rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr
|
|
|
|
LifecycleNode::get_node_topics_interface()
|
|
|
|
{
|
|
|
|
return node_topics_;
|
|
|
|
}
|
|
|
|
|
|
|
|
rclcpp::node_interfaces::NodeServicesInterface::SharedPtr
|
|
|
|
LifecycleNode::get_node_services_interface()
|
|
|
|
{
|
|
|
|
return node_services_;
|
|
|
|
}
|
|
|
|
|
|
|
|
rclcpp::node_interfaces::NodeParametersInterface::SharedPtr
|
|
|
|
LifecycleNode::get_node_parameters_interface()
|
|
|
|
{
|
|
|
|
return node_parameters_;
|
|
|
|
}
|
|
|
|
|
2018-11-22 14:03:51 -08:00
|
|
|
rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr
|
|
|
|
LifecycleNode::get_node_waitables_interface()
|
|
|
|
{
|
|
|
|
return node_waitables_;
|
|
|
|
}
|
|
|
|
|
2019-05-08 14:24:40 -07:00
|
|
|
const rclcpp::NodeOptions &
|
|
|
|
LifecycleNode::get_node_options() const
|
|
|
|
{
|
|
|
|
return node_options_;
|
|
|
|
}
|
2016-12-14 09:29:27 -08:00
|
|
|
|
|
|
|
////
|
|
|
|
bool
|
2017-08-02 14:04:34 -07:00
|
|
|
LifecycleNode::register_on_configure(
|
2018-10-11 14:03:57 -07:00
|
|
|
std::function<LifecycleNodeInterface::CallbackReturn(const State &)> fcn)
|
2016-12-14 09:29:27 -08:00
|
|
|
{
|
2017-08-02 14:04:34 -07:00
|
|
|
return impl_->register_callback(
|
|
|
|
lifecycle_msgs::msg::State::TRANSITION_STATE_CONFIGURING, fcn);
|
2016-12-14 09:29:27 -08:00
|
|
|
}
|
|
|
|
|
|
|
|
bool
|
2017-08-02 14:04:34 -07:00
|
|
|
LifecycleNode::register_on_cleanup(
|
2018-10-11 14:03:57 -07:00
|
|
|
std::function<LifecycleNodeInterface::CallbackReturn(const State &)> fcn)
|
2016-12-14 09:29:27 -08:00
|
|
|
{
|
2017-08-02 14:04:34 -07:00
|
|
|
return impl_->register_callback(
|
|
|
|
lifecycle_msgs::msg::State::TRANSITION_STATE_CLEANINGUP, fcn);
|
2016-12-14 09:29:27 -08:00
|
|
|
}
|
|
|
|
|
|
|
|
bool
|
2017-08-02 14:04:34 -07:00
|
|
|
LifecycleNode::register_on_shutdown(
|
2018-10-11 14:03:57 -07:00
|
|
|
std::function<LifecycleNodeInterface::CallbackReturn(const State &)> fcn)
|
2016-12-14 09:29:27 -08:00
|
|
|
{
|
2017-08-02 14:04:34 -07:00
|
|
|
return impl_->register_callback(
|
|
|
|
lifecycle_msgs::msg::State::TRANSITION_STATE_SHUTTINGDOWN, fcn);
|
2016-12-14 09:29:27 -08:00
|
|
|
}
|
|
|
|
|
|
|
|
bool
|
2017-08-02 14:04:34 -07:00
|
|
|
LifecycleNode::register_on_activate(
|
2018-10-11 14:03:57 -07:00
|
|
|
std::function<LifecycleNodeInterface::CallbackReturn(const State &)> fcn)
|
2016-12-14 09:29:27 -08:00
|
|
|
{
|
2017-08-02 14:04:34 -07:00
|
|
|
return impl_->register_callback(
|
|
|
|
lifecycle_msgs::msg::State::TRANSITION_STATE_ACTIVATING, fcn);
|
2016-12-14 09:29:27 -08:00
|
|
|
}
|
|
|
|
|
|
|
|
bool
|
2017-08-02 14:04:34 -07:00
|
|
|
LifecycleNode::register_on_deactivate(
|
2018-10-11 14:03:57 -07:00
|
|
|
std::function<LifecycleNodeInterface::CallbackReturn(const State &)> fcn)
|
2016-12-14 09:29:27 -08:00
|
|
|
{
|
2017-08-02 14:04:34 -07:00
|
|
|
return impl_->register_callback(
|
|
|
|
lifecycle_msgs::msg::State::TRANSITION_STATE_DEACTIVATING, fcn);
|
2016-12-14 09:29:27 -08:00
|
|
|
}
|
|
|
|
|
|
|
|
bool
|
2017-08-02 14:04:34 -07:00
|
|
|
LifecycleNode::register_on_error(
|
2018-10-11 14:03:57 -07:00
|
|
|
std::function<LifecycleNodeInterface::CallbackReturn(const State &)> fcn)
|
2016-12-14 09:29:27 -08:00
|
|
|
{
|
2017-08-02 14:04:34 -07:00
|
|
|
return impl_->register_callback(
|
|
|
|
lifecycle_msgs::msg::State::TRANSITION_STATE_ERRORPROCESSING, fcn);
|
2016-12-14 09:29:27 -08:00
|
|
|
}
|
|
|
|
|
|
|
|
const State &
|
|
|
|
LifecycleNode::get_current_state()
|
|
|
|
{
|
|
|
|
return impl_->get_current_state();
|
|
|
|
}
|
|
|
|
|
|
|
|
std::vector<State>
|
|
|
|
LifecycleNode::get_available_states()
|
|
|
|
{
|
|
|
|
return impl_->get_available_states();
|
|
|
|
}
|
|
|
|
|
|
|
|
std::vector<Transition>
|
|
|
|
LifecycleNode::get_available_transitions()
|
|
|
|
{
|
|
|
|
return impl_->get_available_transitions();
|
|
|
|
}
|
|
|
|
|
|
|
|
const State &
|
|
|
|
LifecycleNode::trigger_transition(const Transition & transition)
|
|
|
|
{
|
|
|
|
return trigger_transition(transition.id());
|
|
|
|
}
|
|
|
|
|
2017-07-27 07:55:15 -07:00
|
|
|
const State &
|
|
|
|
LifecycleNode::trigger_transition(
|
2018-10-11 14:03:57 -07:00
|
|
|
const Transition & transition, LifecycleNodeInterface::CallbackReturn & cb_return_code)
|
2017-07-27 07:55:15 -07:00
|
|
|
{
|
|
|
|
return trigger_transition(transition.id(), cb_return_code);
|
|
|
|
}
|
|
|
|
|
2016-12-14 09:29:27 -08:00
|
|
|
const State &
|
2017-02-27 21:07:57 -08:00
|
|
|
LifecycleNode::trigger_transition(uint8_t transition_id)
|
2016-12-14 09:29:27 -08:00
|
|
|
{
|
|
|
|
return impl_->trigger_transition(transition_id);
|
|
|
|
}
|
|
|
|
|
2017-07-27 07:55:15 -07:00
|
|
|
const State &
|
|
|
|
LifecycleNode::trigger_transition(
|
2018-10-11 14:03:57 -07:00
|
|
|
uint8_t transition_id, LifecycleNodeInterface::CallbackReturn & cb_return_code)
|
2017-07-27 07:55:15 -07:00
|
|
|
{
|
|
|
|
return impl_->trigger_transition(transition_id, cb_return_code);
|
|
|
|
}
|
|
|
|
|
2017-06-05 18:24:12 -07:00
|
|
|
const State &
|
|
|
|
LifecycleNode::configure()
|
|
|
|
{
|
|
|
|
return impl_->trigger_transition(
|
|
|
|
lifecycle_msgs::msg::Transition::TRANSITION_CONFIGURE);
|
|
|
|
}
|
|
|
|
|
2017-07-27 07:55:15 -07:00
|
|
|
const State &
|
2018-10-11 14:03:57 -07:00
|
|
|
LifecycleNode::configure(LifecycleNodeInterface::CallbackReturn & cb_return_code)
|
2017-07-27 07:55:15 -07:00
|
|
|
{
|
|
|
|
return impl_->trigger_transition(
|
|
|
|
lifecycle_msgs::msg::Transition::TRANSITION_CONFIGURE, cb_return_code);
|
|
|
|
}
|
|
|
|
|
2017-06-05 18:24:12 -07:00
|
|
|
const State &
|
|
|
|
LifecycleNode::cleanup()
|
|
|
|
{
|
|
|
|
return impl_->trigger_transition(
|
|
|
|
lifecycle_msgs::msg::Transition::TRANSITION_CLEANUP);
|
|
|
|
}
|
|
|
|
|
2017-07-27 07:55:15 -07:00
|
|
|
const State &
|
2018-10-11 14:03:57 -07:00
|
|
|
LifecycleNode::cleanup(LifecycleNodeInterface::CallbackReturn & cb_return_code)
|
2017-07-27 07:55:15 -07:00
|
|
|
{
|
|
|
|
return impl_->trigger_transition(
|
|
|
|
lifecycle_msgs::msg::Transition::TRANSITION_CLEANUP, cb_return_code);
|
|
|
|
}
|
|
|
|
|
2017-06-05 18:24:12 -07:00
|
|
|
const State &
|
|
|
|
LifecycleNode::activate()
|
|
|
|
{
|
|
|
|
return impl_->trigger_transition(
|
|
|
|
lifecycle_msgs::msg::Transition::TRANSITION_ACTIVATE);
|
|
|
|
}
|
|
|
|
|
2017-07-27 07:55:15 -07:00
|
|
|
const State &
|
2018-10-11 14:03:57 -07:00
|
|
|
LifecycleNode::activate(LifecycleNodeInterface::CallbackReturn & cb_return_code)
|
2017-07-27 07:55:15 -07:00
|
|
|
{
|
|
|
|
return impl_->trigger_transition(
|
|
|
|
lifecycle_msgs::msg::Transition::TRANSITION_ACTIVATE, cb_return_code);
|
|
|
|
}
|
|
|
|
|
2017-06-05 18:24:12 -07:00
|
|
|
const State &
|
|
|
|
LifecycleNode::deactivate()
|
|
|
|
{
|
|
|
|
return impl_->trigger_transition(
|
|
|
|
lifecycle_msgs::msg::Transition::TRANSITION_DEACTIVATE);
|
|
|
|
}
|
|
|
|
|
2017-07-27 07:55:15 -07:00
|
|
|
const State &
|
2018-10-11 14:03:57 -07:00
|
|
|
LifecycleNode::deactivate(LifecycleNodeInterface::CallbackReturn & cb_return_code)
|
2017-07-27 07:55:15 -07:00
|
|
|
{
|
|
|
|
return impl_->trigger_transition(
|
|
|
|
lifecycle_msgs::msg::Transition::TRANSITION_DEACTIVATE, cb_return_code);
|
|
|
|
}
|
|
|
|
|
2017-06-05 18:24:12 -07:00
|
|
|
const State &
|
|
|
|
LifecycleNode::shutdown()
|
|
|
|
{
|
|
|
|
return impl_->trigger_transition(
|
2018-10-11 14:03:57 -07:00
|
|
|
rcl_lifecycle_shutdown_label);
|
2017-06-05 18:24:12 -07:00
|
|
|
}
|
|
|
|
|
2017-07-27 07:55:15 -07:00
|
|
|
const State &
|
2018-10-11 14:03:57 -07:00
|
|
|
LifecycleNode::shutdown(LifecycleNodeInterface::CallbackReturn & cb_return_code)
|
2017-07-27 07:55:15 -07:00
|
|
|
{
|
|
|
|
return impl_->trigger_transition(
|
2018-10-11 14:03:57 -07:00
|
|
|
rcl_lifecycle_shutdown_label, cb_return_code);
|
2017-07-27 07:55:15 -07:00
|
|
|
}
|
|
|
|
|
2016-12-14 09:29:27 -08:00
|
|
|
void
|
|
|
|
LifecycleNode::add_publisher_handle(
|
|
|
|
std::shared_ptr<rclcpp_lifecycle::LifecyclePublisherInterface> pub)
|
|
|
|
{
|
|
|
|
impl_->add_publisher_handle(pub);
|
|
|
|
}
|
|
|
|
|
|
|
|
void
|
2017-12-05 15:02:00 -08:00
|
|
|
LifecycleNode::add_timer_handle(std::shared_ptr<rclcpp::TimerBase> timer)
|
2016-12-14 09:29:27 -08:00
|
|
|
{
|
|
|
|
impl_->add_timer_handle(timer);
|
|
|
|
}
|
|
|
|
|
|
|
|
} // namespace rclcpp_lifecycle
|