add rclcpp lifecycle
* initial state machine implementation (fix) correctly initialize default state machine uncrustify (dev) first high level api interface src/default_state_machine.c (fix) correctly initialize arrays in statemachine (dev) deactivate/activate publisher demo (dev) initial state machine implementation in rcl * (dev) demo application for a managed lifecycle node * add visibility control * correct install of c-library * fix compilation on windows * refactoring of external/internal api * (dev) generate static functions for c-callback * (fix) correct typo * (dev) cleanup for c-statemachine (dev) cleanup for c-statemachine * (dev) cpp callback map * (dev) mv source file into project folders * (dev) more helper functions for valid transition * (dev) pimpl implementation for cpp lifecyclemanager * (dev) register non-default callback functions * (dev) cleanup lifecycle node to serve as base class * (dev) new my_node child of lifecyclenode for demo purpose update stuff (cleanup) remove unused comments (fix) correct dllexport in windows (fix) correctly install libraries (fix) uncrustify (dev) composition over inheritance (dev) publish notification in state_machine transition (dev) lifecycle talker + listener demo for notification (dev) custom transition message generation (dev) publish transition message on state change (dev) correctly malloc/free c data structures (fix) use single thread executor (dev) use services for get state (fix) set freed pointer to NULL (dev) add change state service (dev) introduce services: get_state and change_state in LM (dev) asynchronous caller script for service client (fix) correct dllexport for pimpl (dev) correct constness (dev) concatenate function for topic (fix) uncrustify prepare new service api (tmp) refactor stash (fix) correctly concatenate topics (fix) correctly initialize Service wo/ copy (dev) call both service types extract demo files (fix) remove debug prints (dev) change to lifecycle_msgs (refactor) extract rcl_lifecycle package (refactor) extract lifecycle demos (fix) address review comments (fix) address review comments (fix) pass shared_ptr by value (fix) make find_package(rmw) required (fix) return to shared node handle pointer (refactor) attach sm to lifecycle node and disable lc_manager (dev) construct service from existing rcl_service_t (refactor) extract method for adding a service to a node (fix) stop mock msgs from being installed service takes rcl_node_t* correct typo add_service has to be public uncrustify initial state machine implementation (fix) correctly initialize default state machine uncrustify (dev) first high level api interface src/default_state_machine.c (fix) correctly initialize arrays in statemachine (dev) deactivate/activate publisher demo (dev) initial state machine implementation in rcl (dev) demo application for a managed lifecycle node add visibility control correct install of c-library fix compilation on windows refactoring of external/internal api (dev) generate static functions for c-callback (fix) correct typo (dev) cleanup for c-statemachine (dev) cleanup for c-statemachine (dev) cpp callback map (dev) mv source file into project folders (dev) more helper functions for valid transition (dev) pimpl implementation for cpp lifecyclemanager (dev) register non-default callback functions (dev) cleanup lifecycle node to serve as base class (dev) new my_node child of lifecyclenode for demo purpose update stuff (cleanup) remove unused comments (fix) correct dllexport in windows (fix) correctly install libraries (fix) uncrustify (dev) composition over inheritance (dev) publish notification in state_machine transition (dev) lifecycle talker + listener demo for notification (dev) custom transition message generation (dev) publish transition message on state change (dev) correctly malloc/free c data structures (fix) use single thread executor (dev) use services for get state (fix) set freed pointer to NULL (dev) add change state service (dev) introduce services: get_state and change_state in LM (dev) asynchronous caller script for service client (fix) correct dllexport for pimpl (dev) correct constness (dev) concatenate function for topic (fix) uncrustify prepare new service api (tmp) refactor stash * (dev) construct service from existing rcl_service_t * service takes rcl_node_t* * correct typo * add_service has to be public * uncrustify * (fix) correctly concatenate topics * (fix) correctly initialize Service wo/ copy * (dev) call both service types * extract demo files * (fix) remove debug prints * (dev) change to lifecycle_msgs * (refactor) extract rcl_lifecycle package * (refactor) extract lifecycle demos * (fix) address review comments (fix) address review comments * (fix) make find_package(rmw) required * (refactor) attach sm to lifecycle node and disable lc_manager * (fix) adjust code to rcl_test refactor * (dev) remove unused deps * (rebase) merge commit * (bugfix) correct rcl_ret_t error handling * (fix) depedencies * (refactor) change to lifecycle_msgs * (fix) correct find_rcl * (refactor) comply for new state machine * visibility control and test api * (rebase) change to new typesupport * uncrustify' * fix visibility control * (fix) correct whitespace * (fix) unused variable * comparison signed and unsigned * get_state returns complete state * get_available_states service * new service msgs * get available states and transitions api * (broken) state after rebase, does not compile demos * fix the way lifecycle node impl is included * fixed rebase compilation errors * remove copy&paste comment * remove empty line * (test) register custom callbacks * (dev) return codes * style * test for exception handling * refacotr new state machine * c++14 * change exception message for windows ci bug change exception message for windows ci bug
This commit is contained in:
parent
d241a730fe
commit
2c6d95946e
19 changed files with 2712 additions and 0 deletions
416
rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node.hpp
Normal file
416
rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node.hpp
Normal file
|
@ -0,0 +1,416 @@
|
|||
// 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.
|
||||
|
||||
#ifndef RCLCPP_LIFECYCLE__LIFECYCLE_NODE_HPP_
|
||||
#define RCLCPP_LIFECYCLE__LIFECYCLE_NODE_HPP_
|
||||
|
||||
#include <string>
|
||||
#include <map>
|
||||
#include <vector>
|
||||
#include <memory>
|
||||
|
||||
#include "rcl/error_handling.h"
|
||||
#include "rcl/node.h"
|
||||
|
||||
#include "rcl_interfaces/msg/list_parameters_result.hpp"
|
||||
#include "rcl_interfaces/msg/parameter_descriptor.hpp"
|
||||
#include "rcl_interfaces/msg/parameter_event.hpp"
|
||||
#include "rcl_interfaces/msg/set_parameters_result.hpp"
|
||||
|
||||
#include "rclcpp/callback_group.hpp"
|
||||
#include "rclcpp/client.hpp"
|
||||
#include "rclcpp/context.hpp"
|
||||
#include "rclcpp/event.hpp"
|
||||
#include "rclcpp/macros.hpp"
|
||||
#include "rclcpp/message_memory_strategy.hpp"
|
||||
#include "rclcpp/node_interfaces/node_base_interface.hpp"
|
||||
#include "rclcpp/node_interfaces/node_graph_interface.hpp"
|
||||
#include "rclcpp/node_interfaces/node_parameters_interface.hpp"
|
||||
#include "rclcpp/node_interfaces/node_services_interface.hpp"
|
||||
#include "rclcpp/node_interfaces/node_timers_interface.hpp"
|
||||
#include "rclcpp/node_interfaces/node_topics_interface.hpp"
|
||||
#include "rclcpp/parameter.hpp"
|
||||
#include "rclcpp/publisher.hpp"
|
||||
#include "rclcpp/service.hpp"
|
||||
#include "rclcpp/subscription.hpp"
|
||||
#include "rclcpp/timer.hpp"
|
||||
|
||||
#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"
|
||||
#include "rclcpp_lifecycle/lifecycle_publisher.hpp"
|
||||
#include "rclcpp_lifecycle/state.hpp"
|
||||
#include "rclcpp_lifecycle/transition.hpp"
|
||||
#include "rclcpp_lifecycle/visibility_control.h"
|
||||
|
||||
namespace rclcpp_lifecycle
|
||||
{
|
||||
|
||||
/// LifecycleNode for creating lifecycle components
|
||||
/**
|
||||
* has lifecycle nodeinterface for configuring this node.
|
||||
*/
|
||||
class LifecycleNode : public node_interfaces::LifecycleNodeInterface,
|
||||
public std::enable_shared_from_this<LifecycleNode>
|
||||
{
|
||||
public:
|
||||
RCLCPP_SMART_PTR_DEFINITIONS(LifecycleNode)
|
||||
|
||||
/// Create a new lifecycle node with the specified name.
|
||||
/**
|
||||
* \param[in] node_name Name of the node.
|
||||
* \param[in] use_intra_process_comms True to use the optimized intra-process communication
|
||||
* pipeline to pass messages between nodes in the same process using shared memory.
|
||||
*/
|
||||
RCLCPP_LIFECYCLE_PUBLIC
|
||||
explicit LifecycleNode(const std::string & node_name, bool use_intra_process_comms = false);
|
||||
|
||||
/// Create a node based on the node name and a rclcpp::context::Context.
|
||||
/**
|
||||
* \param[in] node_name Name of the node.
|
||||
* \param[in] context The context for the node (usually represents the state of a process).
|
||||
* \param[in] use_intra_process_comms True to use the optimized intra-process communication
|
||||
* pipeline to pass messages between nodes in the same process using shared memory.
|
||||
*/
|
||||
RCLCPP_LIFECYCLE_PUBLIC
|
||||
LifecycleNode(
|
||||
const std::string & node_name, rclcpp::context::Context::SharedPtr context,
|
||||
bool use_intra_process_comms = false);
|
||||
|
||||
RCLCPP_LIFECYCLE_PUBLIC
|
||||
virtual ~LifecycleNode();
|
||||
|
||||
/// Get the name of the node.
|
||||
// \return The name of the node.
|
||||
RCLCPP_LIFECYCLE_PUBLIC
|
||||
const char *
|
||||
get_name() const;
|
||||
|
||||
/// Create and return a callback group.
|
||||
RCLCPP_LIFECYCLE_PUBLIC
|
||||
rclcpp::callback_group::CallbackGroup::SharedPtr
|
||||
create_callback_group(rclcpp::callback_group::CallbackGroupType group_type);
|
||||
|
||||
/// Return the list of callback groups in the node.
|
||||
RCLCPP_LIFECYCLE_PUBLIC
|
||||
const std::vector<rclcpp::callback_group::CallbackGroup::WeakPtr> &
|
||||
get_callback_groups() const;
|
||||
|
||||
/// Create and return a Publisher.
|
||||
/**
|
||||
* \param[in] topic_name The topic for this publisher to publish on.
|
||||
* \param[in] qos_history_depth The depth of the publisher message queue.
|
||||
* \return Shared pointer to the created publisher.
|
||||
*/
|
||||
template<typename MessageT, typename Alloc = std::allocator<void>>
|
||||
std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<MessageT, Alloc>>
|
||||
create_publisher(
|
||||
const std::string & topic_name, size_t qos_history_depth,
|
||||
std::shared_ptr<Alloc> allocator = nullptr);
|
||||
|
||||
/// Create and return a LifecyclePublisher.
|
||||
/**
|
||||
* \param[in] topic_name The topic for this publisher to publish on.
|
||||
* \param[in] qos_history_depth The depth of the publisher message queue.
|
||||
* \return Shared pointer to the created publisher.
|
||||
*/
|
||||
template<typename MessageT, typename Alloc = std::allocator<void>>
|
||||
std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<MessageT, Alloc>>
|
||||
create_publisher(
|
||||
const std::string & topic_name,
|
||||
const rmw_qos_profile_t & qos_profile = rmw_qos_profile_default,
|
||||
std::shared_ptr<Alloc> allocator = nullptr);
|
||||
|
||||
/// Create and return a Subscription.
|
||||
/**
|
||||
* \param[in] topic_name The topic to subscribe on.
|
||||
* \param[in] callback The user-defined callback function.
|
||||
* \param[in] qos_profile The quality of service profile to pass on to the rmw implementation.
|
||||
* \param[in] group The callback group for this subscription. NULL for no callback group.
|
||||
* \param[in] ignore_local_publications True to ignore local publications.
|
||||
* \param[in] msg_mem_strat The message memory strategy to use for allocating messages.
|
||||
* \return Shared pointer to the created subscription.
|
||||
*/
|
||||
/* TODO(jacquelinekay):
|
||||
Windows build breaks when static member function passed as default
|
||||
argument to msg_mem_strat, nullptr is a workaround.
|
||||
*/
|
||||
template<
|
||||
typename MessageT,
|
||||
typename CallbackT,
|
||||
typename Alloc = std::allocator<void>,
|
||||
typename SubscriptionT = rclcpp::subscription::Subscription<MessageT, Alloc>>
|
||||
std::shared_ptr<SubscriptionT>
|
||||
create_subscription(
|
||||
const std::string & topic_name,
|
||||
CallbackT && callback,
|
||||
const rmw_qos_profile_t & qos_profile = rmw_qos_profile_default,
|
||||
rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr,
|
||||
bool ignore_local_publications = false,
|
||||
typename rclcpp::message_memory_strategy::MessageMemoryStrategy<MessageT, Alloc>::SharedPtr
|
||||
msg_mem_strat = nullptr,
|
||||
std::shared_ptr<Alloc> allocator = nullptr);
|
||||
|
||||
/// Create and return a Subscription.
|
||||
/**
|
||||
* \param[in] topic_name The topic to subscribe on.
|
||||
* \param[in] qos_history_depth The depth of the subscription's incoming message queue.
|
||||
* \param[in] callback The user-defined callback function.
|
||||
* \param[in] group The callback group for this subscription. NULL for no callback group.
|
||||
* \param[in] ignore_local_publications True to ignore local publications.
|
||||
* \param[in] msg_mem_strat The message memory strategy to use for allocating messages.
|
||||
* \return Shared pointer to the created subscription.
|
||||
*/
|
||||
/* TODO(jacquelinekay):
|
||||
Windows build breaks when static member function passed as default
|
||||
argument to msg_mem_strat, nullptr is a workaround.
|
||||
*/
|
||||
template<
|
||||
typename MessageT,
|
||||
typename CallbackT,
|
||||
typename Alloc = std::allocator<void>,
|
||||
typename SubscriptionT = rclcpp::subscription::Subscription<MessageT, Alloc>>
|
||||
std::shared_ptr<SubscriptionT>
|
||||
create_subscription(
|
||||
const std::string & topic_name,
|
||||
size_t qos_history_depth,
|
||||
CallbackT && callback,
|
||||
rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr,
|
||||
bool ignore_local_publications = false,
|
||||
typename rclcpp::message_memory_strategy::MessageMemoryStrategy<MessageT, Alloc>::SharedPtr
|
||||
msg_mem_strat = nullptr,
|
||||
std::shared_ptr<Alloc> allocator = nullptr);
|
||||
|
||||
/// Create a timer.
|
||||
/**
|
||||
* \param[in] period Time interval between triggers of the callback.
|
||||
* \param[in] callback User-defined callback function.
|
||||
* \param[in] group Callback group to execute this timer's callback in.
|
||||
*/
|
||||
template<typename DurationT = std::milli, typename CallbackT>
|
||||
typename rclcpp::timer::WallTimer<CallbackT>::SharedPtr
|
||||
create_wall_timer(
|
||||
std::chrono::duration<int64_t, DurationT> period,
|
||||
CallbackT callback,
|
||||
rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr);
|
||||
|
||||
/* Create and return a Client. */
|
||||
template<typename ServiceT>
|
||||
typename rclcpp::client::Client<ServiceT>::SharedPtr
|
||||
create_client(
|
||||
const std::string & service_name,
|
||||
const rmw_qos_profile_t & qos_profile = rmw_qos_profile_services_default,
|
||||
rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr);
|
||||
|
||||
/* Create and return a Service. */
|
||||
template<typename ServiceT, typename CallbackT>
|
||||
typename rclcpp::service::Service<ServiceT>::SharedPtr
|
||||
create_service(
|
||||
const std::string & service_name,
|
||||
CallbackT && callback,
|
||||
const rmw_qos_profile_t & qos_profile = rmw_qos_profile_services_default,
|
||||
rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr);
|
||||
|
||||
RCLCPP_LIFECYCLE_PUBLIC
|
||||
std::vector<rcl_interfaces::msg::SetParametersResult>
|
||||
set_parameters(const std::vector<rclcpp::parameter::ParameterVariant> & parameters);
|
||||
|
||||
RCLCPP_LIFECYCLE_PUBLIC
|
||||
rcl_interfaces::msg::SetParametersResult
|
||||
set_parameters_atomically(const std::vector<rclcpp::parameter::ParameterVariant> & parameters);
|
||||
|
||||
RCLCPP_LIFECYCLE_PUBLIC
|
||||
std::vector<rclcpp::parameter::ParameterVariant>
|
||||
get_parameters(const std::vector<std::string> & names) const;
|
||||
|
||||
RCLCPP_LIFECYCLE_PUBLIC
|
||||
rclcpp::parameter::ParameterVariant
|
||||
get_parameter(const std::string & name) const;
|
||||
|
||||
RCLCPP_LIFECYCLE_PUBLIC
|
||||
bool
|
||||
get_parameter(
|
||||
const std::string & name,
|
||||
rclcpp::parameter::ParameterVariant & parameter) const;
|
||||
|
||||
template<typename ParameterT>
|
||||
bool
|
||||
get_parameter(const std::string & name, ParameterT & parameter) const;
|
||||
|
||||
RCLCPP_LIFECYCLE_PUBLIC
|
||||
std::vector<rcl_interfaces::msg::ParameterDescriptor>
|
||||
describe_parameters(const std::vector<std::string> & names) const;
|
||||
|
||||
RCLCPP_LIFECYCLE_PUBLIC
|
||||
std::vector<uint8_t>
|
||||
get_parameter_types(const std::vector<std::string> & names) const;
|
||||
|
||||
RCLCPP_LIFECYCLE_PUBLIC
|
||||
rcl_interfaces::msg::ListParametersResult
|
||||
list_parameters(const std::vector<std::string> & prefixes, uint64_t depth) const;
|
||||
|
||||
/// Register the callback for parameter changes
|
||||
/**
|
||||
* \param[in] User defined callback function, It is expected to atomically set parameters.
|
||||
* \note Repeated invocations of this function will overwrite previous callbacks
|
||||
*/
|
||||
template<typename CallbackT>
|
||||
void
|
||||
register_param_change_callback(CallbackT && callback);
|
||||
|
||||
RCLCPP_LIFECYCLE_PUBLIC
|
||||
std::map<std::string, std::string>
|
||||
get_topic_names_and_types() const;
|
||||
|
||||
RCLCPP_LIFECYCLE_PUBLIC
|
||||
size_t
|
||||
count_publishers(const std::string & topic_name) const;
|
||||
|
||||
RCLCPP_LIFECYCLE_PUBLIC
|
||||
size_t
|
||||
count_subscribers(const std::string & topic_name) const;
|
||||
|
||||
/// Return a graph event, which will be set anytime a graph change occurs.
|
||||
/* The graph Event object is a loan which must be returned.
|
||||
* The Event object is scoped and therefore to return the load just let it go
|
||||
* out of scope.
|
||||
*/
|
||||
RCLCPP_LIFECYCLE_PUBLIC
|
||||
rclcpp::event::Event::SharedPtr
|
||||
get_graph_event();
|
||||
|
||||
/// Wait for a graph event to occur by waiting on an Event to become set.
|
||||
/* The given Event must be acquire through the get_graph_event() method.
|
||||
*
|
||||
* \throws InvalidEventError if the given event is nullptr
|
||||
* \throws EventNotRegisteredError if the given event was not acquired with
|
||||
* get_graph_event().
|
||||
*/
|
||||
RCLCPP_LIFECYCLE_PUBLIC
|
||||
void
|
||||
wait_for_graph_change(
|
||||
rclcpp::event::Event::SharedPtr event,
|
||||
std::chrono::nanoseconds timeout);
|
||||
|
||||
/// Return the Node's internal NodeBaseInterface implementation.
|
||||
RCLCPP_LIFECYCLE_PUBLIC
|
||||
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr
|
||||
get_node_base_interface();
|
||||
|
||||
/// Return the Node's internal NodeGraphInterface implementation.
|
||||
RCLCPP_LIFECYCLE_PUBLIC
|
||||
rclcpp::node_interfaces::NodeGraphInterface::SharedPtr
|
||||
get_node_graph_interface();
|
||||
|
||||
/// Return the Node's internal NodeTimersInterface implementation.
|
||||
RCLCPP_LIFECYCLE_PUBLIC
|
||||
rclcpp::node_interfaces::NodeTimersInterface::SharedPtr
|
||||
get_node_timers_interface();
|
||||
|
||||
/// Return the Node's internal NodeTopicsInterface implementation.
|
||||
RCLCPP_LIFECYCLE_PUBLIC
|
||||
rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr
|
||||
get_node_topics_interface();
|
||||
|
||||
/// Return the Node's internal NodeServicesInterface implementation.
|
||||
RCLCPP_LIFECYCLE_PUBLIC
|
||||
rclcpp::node_interfaces::NodeServicesInterface::SharedPtr
|
||||
get_node_services_interface();
|
||||
|
||||
/// Return the Node's internal NodeParametersInterface implementation.
|
||||
RCLCPP_LIFECYCLE_PUBLIC
|
||||
rclcpp::node_interfaces::NodeParametersInterface::SharedPtr
|
||||
get_node_parameters_interface();
|
||||
|
||||
//
|
||||
// LIFECYCLE COMPONENTS
|
||||
//
|
||||
RCLCPP_LIFECYCLE_PUBLIC
|
||||
const State &
|
||||
get_current_state();
|
||||
|
||||
RCLCPP_LIFECYCLE_PUBLIC
|
||||
std::vector<State>
|
||||
get_available_states();
|
||||
|
||||
RCLCPP_LIFECYCLE_PUBLIC
|
||||
std::vector<Transition>
|
||||
get_available_transitions();
|
||||
|
||||
/// trigger the specified transition
|
||||
/*
|
||||
* return the new state after this transition
|
||||
*/
|
||||
RCLCPP_LIFECYCLE_PUBLIC
|
||||
const State &
|
||||
trigger_transition(const Transition & transition);
|
||||
|
||||
RCLCPP_LIFECYCLE_PUBLIC
|
||||
const State &
|
||||
trigger_transition(unsigned int transition_id);
|
||||
|
||||
RCLCPP_LIFECYCLE_PUBLIC
|
||||
bool
|
||||
register_on_configure(std::function<rcl_lifecycle_ret_t(const State &)> fcn);
|
||||
RCLCPP_LIFECYCLE_PUBLIC
|
||||
bool
|
||||
register_on_cleanup(std::function<rcl_lifecycle_ret_t(const State &)> fcn);
|
||||
RCLCPP_LIFECYCLE_PUBLIC
|
||||
bool
|
||||
register_on_shutdown(std::function<rcl_lifecycle_ret_t(const State &)> fcn);
|
||||
RCLCPP_LIFECYCLE_PUBLIC
|
||||
bool
|
||||
register_on_activate(std::function<rcl_lifecycle_ret_t(const State &)> fcn);
|
||||
RCLCPP_LIFECYCLE_PUBLIC
|
||||
bool
|
||||
register_on_deactivate(std::function<rcl_lifecycle_ret_t(const State &)> fcn);
|
||||
RCLCPP_LIFECYCLE_PUBLIC
|
||||
bool
|
||||
register_on_error(std::function<rcl_lifecycle_ret_t(const State &)> fcn);
|
||||
|
||||
protected:
|
||||
RCLCPP_LIFECYCLE_PUBLIC
|
||||
void
|
||||
add_publisher_handle(std::shared_ptr<rclcpp_lifecycle::LifecyclePublisherInterface> pub);
|
||||
|
||||
RCLCPP_LIFECYCLE_PUBLIC
|
||||
void
|
||||
add_timer_handle(std::shared_ptr<rclcpp::timer::TimerBase> timer);
|
||||
|
||||
private:
|
||||
RCLCPP_DISABLE_COPY(LifecycleNode)
|
||||
|
||||
RCLCPP_LIFECYCLE_PUBLIC
|
||||
bool
|
||||
group_in_node(rclcpp::callback_group::CallbackGroup::SharedPtr group);
|
||||
|
||||
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_;
|
||||
rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph_;
|
||||
rclcpp::node_interfaces::NodeTimersInterface::SharedPtr node_timers_;
|
||||
rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_;
|
||||
rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services_;
|
||||
rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_parameters_;
|
||||
|
||||
bool use_intra_process_comms_;
|
||||
|
||||
class LifecycleNodeInterfaceImpl;
|
||||
std::unique_ptr<LifecycleNodeInterfaceImpl> impl_;
|
||||
};
|
||||
|
||||
} // namespace rclcpp_lifecycle
|
||||
|
||||
#ifndef RCLCPP_LIFECYCLE__LIFECYCLE_NODE_IMPL_HPP_
|
||||
// Template implementations
|
||||
#include "rclcpp_lifecycle/lifecycle_node_impl.hpp"
|
||||
#endif
|
||||
|
||||
#endif // RCLCPP_LIFECYCLE__LIFECYCLE_NODE_HPP_
|
Loading…
Add table
Add a link
Reference in a new issue