Added features to rclcpp packages (#1106)

* Added features to rclcpp packages

Signed-off-by: ahcorde <ahcorde@gmail.com>

* Added feedback

Signed-off-by: ahcorde <ahcorde@gmail.com>

* Added feedback and improved lifecycle docblock

Signed-off-by: ahcorde <ahcorde@gmail.com>

* Added feedback

Signed-off-by: ahcorde <ahcorde@gmail.com>

* Added ffedback

Signed-off-by: ahcorde <ahcorde@gmail.com>

* Fixing error

Signed-off-by: ahcorde <ahcorde@gmail.com>
This commit is contained in:
Alejandro Hernández Cordero 2020-05-15 16:41:25 +02:00 committed by GitHub
parent 0dd14baa32
commit 731558aafb
No known key found for this signature in database
GPG key ID: 4AEE18F83AFDEB23
8 changed files with 321 additions and 11 deletions

View file

@ -1,6 +1,8 @@
# `rclcpp` # `rclcpp`
The ROS client library in C++. Visit the [rclcpp API documentation](http://docs.ros2.org/latest/api/rclcpp/) for a complete list of its main components. The ROS client library in C++.
Visit the [rclcpp API documentation](http://docs.ros2.org/latest/api/rclcpp/) for a complete list of its main components and features.
## Quality Declaration ## Quality Declaration

View file

@ -1,6 +1,8 @@
# `rclcpp_action` # `rclcpp_action`
Adds action APIs for C++. Visit the [rclcpp API documentation](http://docs.ros2.org/latest/api/rclcpp_action/) for a complete list of its main components or the [design document](http://design.ros2.org/articles/actions.html). Adds action APIs for C++.
Visit the [rclcpp_action API documentation](http://docs.ros2.org/latest/api/rclcpp_action/) for a complete list of its main components and features. For more information about Actions in ROS 2, see the [design document](http://design.ros2.org/articles/actions.html).
## Quality Declaration ## Quality Declaration

View file

@ -2,6 +2,8 @@
Package containing tools for dynamically loadable components. Package containing tools for dynamically loadable components.
Visit the [rclcpp_components API documentation](http://docs.ros2.org/latest/api/rclcpp_components/) for a complete list of its main components and features.
## Quality Declaration ## Quality Declaration
This package claims to be in the **Quality Level 4** category, see the [Quality Declaration](QUALITY_DECLARATION.md) for more details. This package claims to be in the **Quality Level 4** category, see the [Quality Declaration](QUALITY_DECLARATION.md) for more details.

View file

@ -12,6 +12,32 @@
// See the License for the specific language governing permissions and // See the License for the specific language governing permissions and
// limitations under the License. // limitations under the License.
/** \mainpage rclcpp_components: Package containing tools for dynamically loadable components.
*
* - ComponentManager: Node to manage components. It has the services to load, unload and list
* current components.
* - rclcpp_components/component_manager.hpp)
* - Node factory: The NodeFactory interface is used by the class loader to instantiate components.
* - rclcpp_components/node_factory.hpp)
* - It allows for classes not derived from `rclcpp::Node` to be used as components.
* - It allows derived constructors to be called when components are loaded.
*
* Some useful abstractions and utilities:
* - [RCLCPP_COMPONENTS_REGISTER_NODE: Register a component that can be dynamically loaded
* at runtime.
* - (include/rclcpp_components/register_node_macro.hpp)
*
* Some useful internal abstractions and utilities:
* - Macros for controlling symbol visibility on the library
* - rclcpp_components/visibility_control.h
*
* Package containing CMake tools for register components:
* - `rclcpp_components_register_node` Register an rclcpp component with the ament resource index
* and create an executable.
* - `rclcpp_components_register_nodes` Register an rclcpp component with the ament resource index.
* The passed library can contain multiple nodes each registered via macro.
*/
#ifndef RCLCPP_COMPONENTS__COMPONENT_MANAGER_HPP__ #ifndef RCLCPP_COMPONENTS__COMPONENT_MANAGER_HPP__
#define RCLCPP_COMPONENTS__COMPONENT_MANAGER_HPP__ #define RCLCPP_COMPONENTS__COMPONENT_MANAGER_HPP__

View file

@ -1,6 +1,8 @@
# `rclcpp_lifecycle` # `rclcpp_lifecycle`
Package containing a prototype for lifecycle implementation. Visit the [design document](https://design.ros2.org/articles/node_lifecycle.html) for more information about this package. Package containing a prototype for lifecycle implementation.
Visit the [rclcpp_lifecycle API documentation](http://docs.ros2.org/latest/api/rclcpp_lifecycle/) for a complete list of its main components and features. For more information about LifeCycle in ROS 2, see the [design document](http://design.ros2.org/articles/node_lifecycle.html).
## Quality Declaration ## Quality Declaration

View file

@ -12,6 +12,27 @@
// See the License for the specific language governing permissions and // See the License for the specific language governing permissions and
// limitations under the License. // limitations under the License.
/** \mainpage rclcpp_lifecycle: Package containing a prototype for lifecycle implementation.
*
* - Lifecycle states: Define the State class. There are 4 primary states: Unconfigured, Inactive,
* Active and Finalized. There are also 6 transition states which are intermediate states during
* a requested transition. Configuring, CleaningUp, ShuttingDown, Activating, Deactivating and
* ErrorProcessing.
* - rclcpp_lifecycle/state.hpp
* - Lifecycle transitions Define the Transition class. There are 7 transitions exposed to a
* supervisory process, they are: create, configure, cleanup, activate, deactivate, shutdown and
* destroy.
* - rclcpp_lifecycle/transition.hpp
* - Lifecycle publisher creates a publisher that allows enabling and disabling message publication.
* - rclcpp_lifecycle/publisher.hpp
* - Lifecycle node: An optional interface class for life cycle node implementations.
* - rclcpp_lifecycle/lifecycle_node.hpp
*
* Some useful internal abstractions and utilities:
* - Macros for controlling symbol visibility on the library
* - rclcpp_lifecycle/visibility_control.h
*/
#ifndef RCLCPP_LIFECYCLE__LIFECYCLE_NODE_HPP_ #ifndef RCLCPP_LIFECYCLE__LIFECYCLE_NODE_HPP_
#define RCLCPP_LIFECYCLE__LIFECYCLE_NODE_HPP_ #define RCLCPP_LIFECYCLE__LIFECYCLE_NODE_HPP_
@ -127,29 +148,42 @@ public:
virtual ~LifecycleNode(); virtual ~LifecycleNode();
/// Get the name of the node. /// Get the name of the node.
// \return The name of the node. /**
* \return The name of the node.
*/
RCLCPP_LIFECYCLE_PUBLIC RCLCPP_LIFECYCLE_PUBLIC
const char * const char *
get_name() const; get_name() const;
/// Get the namespace of the node. /// Get the namespace of the node
// \return The namespace of the node. /**
* \return The namespace of the node.
*/
RCLCPP_LIFECYCLE_PUBLIC RCLCPP_LIFECYCLE_PUBLIC
const char * const char *
get_namespace() const; get_namespace() const;
/// Get the logger of the node. /// Get the logger of the node.
/** \return The logger of the node. */ /**
* \return The logger of the node.
*/
RCLCPP_LIFECYCLE_PUBLIC RCLCPP_LIFECYCLE_PUBLIC
rclcpp::Logger rclcpp::Logger
get_logger() const; get_logger() const;
/// Create and return a callback group. /// Create and return a callback group.
/**
* \param[in] group_type callback group type to create by this method.
* \return a callback group
*/
RCLCPP_LIFECYCLE_PUBLIC RCLCPP_LIFECYCLE_PUBLIC
rclcpp::CallbackGroup::SharedPtr rclcpp::CallbackGroup::SharedPtr
create_callback_group(rclcpp::CallbackGroupType group_type); create_callback_group(rclcpp::CallbackGroupType group_type);
/// Return the list of callback groups in the node. /// Return the list of callback groups in the node.
/**
* \return list of callback groups in the node.
*/
RCLCPP_LIFECYCLE_PUBLIC RCLCPP_LIFECYCLE_PUBLIC
const std::vector<rclcpp::CallbackGroup::WeakPtr> & const std::vector<rclcpp::CallbackGroup::WeakPtr> &
get_callback_groups() const; get_callback_groups() const;
@ -216,7 +250,10 @@ public:
CallbackT callback, CallbackT callback,
rclcpp::CallbackGroup::SharedPtr group = nullptr); rclcpp::CallbackGroup::SharedPtr group = nullptr);
/* Create and return a Client. */ /// Create and return a Client.
/**
* \sa rclcpp::Node::create_client
*/
template<typename ServiceT> template<typename ServiceT>
typename rclcpp::Client<ServiceT>::SharedPtr typename rclcpp::Client<ServiceT>::SharedPtr
create_client( create_client(
@ -224,7 +261,10 @@ public:
const rmw_qos_profile_t & qos_profile = rmw_qos_profile_services_default, const rmw_qos_profile_t & qos_profile = rmw_qos_profile_services_default,
rclcpp::CallbackGroup::SharedPtr group = nullptr); rclcpp::CallbackGroup::SharedPtr group = nullptr);
/* Create and return a Service. */ /// Create and return a Service.
/**
* \sa rclcpp::Node::create_service
*/
template<typename ServiceT, typename CallbackT> template<typename ServiceT, typename CallbackT>
typename rclcpp::Service<ServiceT>::SharedPtr typename rclcpp::Service<ServiceT>::SharedPtr
create_service( create_service(
@ -419,22 +459,42 @@ public:
set_on_parameters_set_callback( set_on_parameters_set_callback(
rclcpp_lifecycle::LifecycleNode::OnParametersSetCallbackType callback); rclcpp_lifecycle::LifecycleNode::OnParametersSetCallbackType callback);
/// Return a vector of existing node names (string).
/**
* \sa rclcpp::Node::get_node_names
*/
RCLCPP_LIFECYCLE_PUBLIC RCLCPP_LIFECYCLE_PUBLIC
std::vector<std::string> std::vector<std::string>
get_node_names() const; get_node_names() const;
/// Return a map of existing topic names to list of topic types.
/**
* \sa rclcpp::Node::get_topic_names_and_types
*/
RCLCPP_LIFECYCLE_PUBLIC RCLCPP_LIFECYCLE_PUBLIC
std::map<std::string, std::vector<std::string>> std::map<std::string, std::vector<std::string>>
get_topic_names_and_types(bool no_demangle = false) const; get_topic_names_and_types(bool no_demangle = false) const;
/// Return a map of existing service names to list of topic types.
/**
* \sa rclcpp::Node::get_service_names_and_types
*/
RCLCPP_LIFECYCLE_PUBLIC RCLCPP_LIFECYCLE_PUBLIC
std::map<std::string, std::vector<std::string>> std::map<std::string, std::vector<std::string>>
get_service_names_and_types() const; get_service_names_and_types() const;
/// Return the number of publishers that are advertised on a given topic.
/**
* \sa rclcpp::Node::count_publishers
*/
RCLCPP_LIFECYCLE_PUBLIC RCLCPP_LIFECYCLE_PUBLIC
size_t size_t
count_publishers(const std::string & topic_name) const; count_publishers(const std::string & topic_name) const;
/// Return the number of subscribers who have created a subscription for a given topic.
/**
* \sa rclcpp::Node::count_subscribers
*/
RCLCPP_LIFECYCLE_PUBLIC RCLCPP_LIFECYCLE_PUBLIC
size_t size_t
count_subscribers(const std::string & topic_name) const; count_subscribers(const std::string & topic_name) const;
@ -477,69 +537,114 @@ public:
rclcpp::Event::SharedPtr event, rclcpp::Event::SharedPtr event,
std::chrono::nanoseconds timeout); std::chrono::nanoseconds timeout);
/// Get a clock as a non-const shared pointer which is managed by the node.
/**
* \sa rclcpp::node_interfaces::NodeClock::get_clock
*/
RCLCPP_LIFECYCLE_PUBLIC RCLCPP_LIFECYCLE_PUBLIC
rclcpp::Clock::SharedPtr rclcpp::Clock::SharedPtr
get_clock(); get_clock();
/// Get a clock as a const shared pointer which is managed by the node.
/**
* \sa rclcpp::node_interfaces::NodeClock::get_clock
*/
RCLCPP_LIFECYCLE_PUBLIC RCLCPP_LIFECYCLE_PUBLIC
rclcpp::Clock::ConstSharedPtr rclcpp::Clock::ConstSharedPtr
get_clock() const; get_clock() const;
/// Returns current time from the time source specified by clock_type.
/**
* \sa rclcpp::Clock::now
*/
RCLCPP_LIFECYCLE_PUBLIC RCLCPP_LIFECYCLE_PUBLIC
rclcpp::Time rclcpp::Time
now() const; now() const;
/// Return the Node's internal NodeBaseInterface implementation. /// Return the Node's internal NodeBaseInterface implementation.
/**
* \sa rclcpp::Node::get_node_base_interface
*/
RCLCPP_LIFECYCLE_PUBLIC RCLCPP_LIFECYCLE_PUBLIC
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr rclcpp::node_interfaces::NodeBaseInterface::SharedPtr
get_node_base_interface(); get_node_base_interface();
/// Return the Node's internal NodeClockInterface implementation. /// Return the Node's internal NodeClockInterface implementation.
/**
* \sa rclcpp::Node::get_node_clock_interface
*/
RCLCPP_LIFECYCLE_PUBLIC RCLCPP_LIFECYCLE_PUBLIC
rclcpp::node_interfaces::NodeClockInterface::SharedPtr rclcpp::node_interfaces::NodeClockInterface::SharedPtr
get_node_clock_interface(); get_node_clock_interface();
/// Return the Node's internal NodeGraphInterface implementation. /// Return the Node's internal NodeGraphInterface implementation.
/**
* \sa rclcpp::Node::get_node_graph_interface
*/
RCLCPP_LIFECYCLE_PUBLIC RCLCPP_LIFECYCLE_PUBLIC
rclcpp::node_interfaces::NodeGraphInterface::SharedPtr rclcpp::node_interfaces::NodeGraphInterface::SharedPtr
get_node_graph_interface(); get_node_graph_interface();
/// Return the Node's internal NodeLoggingInterface implementation. /// Return the Node's internal NodeLoggingInterface implementation.
/**
* \sa rclcpp::Node::get_node_logging_interface
*/
RCLCPP_LIFECYCLE_PUBLIC RCLCPP_LIFECYCLE_PUBLIC
rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr
get_node_logging_interface(); get_node_logging_interface();
/// Return the Node's internal NodeTimersInterface implementation. /// Return the Node's internal NodeTimersInterface implementation.
/**
* \sa rclcpp::Node::get_node_timers_interface
*/
RCLCPP_LIFECYCLE_PUBLIC RCLCPP_LIFECYCLE_PUBLIC
rclcpp::node_interfaces::NodeTimersInterface::SharedPtr rclcpp::node_interfaces::NodeTimersInterface::SharedPtr
get_node_timers_interface(); get_node_timers_interface();
/// Return the Node's internal NodeTopicsInterface implementation. /// Return the Node's internal NodeTopicsInterface implementation.
/**
* \sa rclcpp::Node::get_node_topics_interface
*/
RCLCPP_LIFECYCLE_PUBLIC RCLCPP_LIFECYCLE_PUBLIC
rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr
get_node_topics_interface(); get_node_topics_interface();
/// Return the Node's internal NodeServicesInterface implementation. /// Return the Node's internal NodeServicesInterface implementation.
/**
* \sa rclcpp::Node::get_node_services_interface
*/
RCLCPP_LIFECYCLE_PUBLIC RCLCPP_LIFECYCLE_PUBLIC
rclcpp::node_interfaces::NodeServicesInterface::SharedPtr rclcpp::node_interfaces::NodeServicesInterface::SharedPtr
get_node_services_interface(); get_node_services_interface();
/// Return the Node's internal NodeParametersInterface implementation. /// Return the Node's internal NodeParametersInterface implementation.
/**
* \sa rclcpp::Node::get_node_parameters_interface
*/
RCLCPP_LIFECYCLE_PUBLIC RCLCPP_LIFECYCLE_PUBLIC
rclcpp::node_interfaces::NodeParametersInterface::SharedPtr rclcpp::node_interfaces::NodeParametersInterface::SharedPtr
get_node_parameters_interface(); get_node_parameters_interface();
/// Return the Node's internal NodeParametersInterface implementation. /// Return the Node's internal NodeParametersInterface implementation.
/**
* \sa rclcpp::Node::get_node_time_source_interface
*/
RCLCPP_LIFECYCLE_PUBLIC RCLCPP_LIFECYCLE_PUBLIC
rclcpp::node_interfaces::NodeTimeSourceInterface::SharedPtr rclcpp::node_interfaces::NodeTimeSourceInterface::SharedPtr
get_node_time_source_interface(); get_node_time_source_interface();
/// Return the Node's internal NodeWaitablesInterface implementation. /// Return the Node's internal NodeWaitablesInterface implementation.
/**
* \sa rclcpp::Node::get_node_waitables_interface
*/
RCLCPP_LIFECYCLE_PUBLIC RCLCPP_LIFECYCLE_PUBLIC
rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr
get_node_waitables_interface(); get_node_waitables_interface();
/// Return the NodeOptions used when creating this node. /// Return the NodeOptions used when creating this node.
/**
* \sa rclcpp::Node::get_node_options
*/
RCLCPP_LIFECYCLE_PUBLIC RCLCPP_LIFECYCLE_PUBLIC
const rclcpp::NodeOptions & const rclcpp::NodeOptions &
get_node_options() const; get_node_options() const;
@ -547,100 +652,208 @@ public:
// //
// LIFECYCLE COMPONENTS // LIFECYCLE COMPONENTS
// //
/// Return the current State.
/**
* \return the current state
*/
RCLCPP_LIFECYCLE_PUBLIC RCLCPP_LIFECYCLE_PUBLIC
const State & const State &
get_current_state(); get_current_state();
/// Return a list with the available states.
/**
* \return list with the available states.
*/
RCLCPP_LIFECYCLE_PUBLIC RCLCPP_LIFECYCLE_PUBLIC
std::vector<State> std::vector<State>
get_available_states(); get_available_states();
/// Return a list with the available transitions.
/**
* \return list with the available transitions.
*/
RCLCPP_LIFECYCLE_PUBLIC RCLCPP_LIFECYCLE_PUBLIC
std::vector<Transition> std::vector<Transition>
get_available_transitions(); get_available_transitions();
/// trigger the specified transition /// Trigger the specified transition.
/* /*
* return the new state after this transition * \return the new state after this transition
*/ */
RCLCPP_LIFECYCLE_PUBLIC RCLCPP_LIFECYCLE_PUBLIC
const State & const State &
trigger_transition(const Transition & transition); trigger_transition(const Transition & transition);
/// Trigger the specified transition and get the callback return code.
/*
* \param[out] cb_return_code transition callback return code
* \return the new state after this transition
*/
RCLCPP_LIFECYCLE_PUBLIC RCLCPP_LIFECYCLE_PUBLIC
const State & const State &
trigger_transition( trigger_transition(
const Transition & transition, LifecycleNodeInterface::CallbackReturn & cb_return_code); const Transition & transition, LifecycleNodeInterface::CallbackReturn & cb_return_code);
/// Trigger the specified transition based on an id.
/*
* \return the new state after this transition
*/
RCLCPP_LIFECYCLE_PUBLIC RCLCPP_LIFECYCLE_PUBLIC
const State & const State &
trigger_transition(uint8_t transition_id); trigger_transition(uint8_t transition_id);
/// Trigger the specified transition based on an id and get the callback return code.
/*
* \param[out] cb_return_code transition callback return code
* \return the new state after this transition
*/
RCLCPP_LIFECYCLE_PUBLIC RCLCPP_LIFECYCLE_PUBLIC
const State & const State &
trigger_transition( trigger_transition(
uint8_t transition_id, LifecycleNodeInterface::CallbackReturn & cb_return_code); uint8_t transition_id, LifecycleNodeInterface::CallbackReturn & cb_return_code);
/// Trigger the configure transition
/*
* \param[out] cb_return_code transition callback return code.
* \return the new state after this transition
*/
RCLCPP_LIFECYCLE_PUBLIC RCLCPP_LIFECYCLE_PUBLIC
const State & const State &
configure(); configure();
/// Trigger the configure transition and get the callback return code.
/*
* \param[out] cb_return_code transition callback return code
* \return the new state after this transition
*/
RCLCPP_LIFECYCLE_PUBLIC RCLCPP_LIFECYCLE_PUBLIC
const State & const State &
configure(LifecycleNodeInterface::CallbackReturn & cb_return_code); configure(LifecycleNodeInterface::CallbackReturn & cb_return_code);
/// Trigger the cleanup transition.
/*
* \return the new state after this transition
*/
RCLCPP_LIFECYCLE_PUBLIC RCLCPP_LIFECYCLE_PUBLIC
const State & const State &
cleanup(); cleanup();
/// Trigger the cleanup transition and get the callback return code.
/*
* \param[out] cb_return_code transition callback return code
* \return the new state after this transition
*/
RCLCPP_LIFECYCLE_PUBLIC RCLCPP_LIFECYCLE_PUBLIC
const State & const State &
cleanup(LifecycleNodeInterface::CallbackReturn & cb_return_code); cleanup(LifecycleNodeInterface::CallbackReturn & cb_return_code);
/// Trigger the activate transition.
/*
* \return the new state after this transition
*/
RCLCPP_LIFECYCLE_PUBLIC RCLCPP_LIFECYCLE_PUBLIC
const State & const State &
activate(); activate();
/// Trigger the activate transition and get the callback return code.
/*
* \param[out] cb_return_code transition callback return code
* \return the new state after this transition
*/
RCLCPP_LIFECYCLE_PUBLIC RCLCPP_LIFECYCLE_PUBLIC
const State & const State &
activate(LifecycleNodeInterface::CallbackReturn & cb_return_code); activate(LifecycleNodeInterface::CallbackReturn & cb_return_code);
/// Trigger the deactivate transition
/*
* \return the new state after this transition
*/
RCLCPP_LIFECYCLE_PUBLIC RCLCPP_LIFECYCLE_PUBLIC
const State & const State &
deactivate(); deactivate();
/// Trigger the deactivate transition and get the callback return code.
/*
* \param[out] cb_return_code transition callback return code
* \return the new state after this transition
*/
RCLCPP_LIFECYCLE_PUBLIC RCLCPP_LIFECYCLE_PUBLIC
const State & const State &
deactivate(LifecycleNodeInterface::CallbackReturn & cb_return_code); deactivate(LifecycleNodeInterface::CallbackReturn & cb_return_code);
/// Trigger the shutdown transition
/*
* \return the new state after this transition
*/
RCLCPP_LIFECYCLE_PUBLIC RCLCPP_LIFECYCLE_PUBLIC
const State & const State &
shutdown(); shutdown();
/// Trigger the shutdown transition and get the callback return code.
/*
* \param[out] cb_return_code transition callback return code
* \return the new state after this transition
*/
RCLCPP_LIFECYCLE_PUBLIC RCLCPP_LIFECYCLE_PUBLIC
const State & const State &
shutdown(LifecycleNodeInterface::CallbackReturn & cb_return_code); shutdown(LifecycleNodeInterface::CallbackReturn & cb_return_code);
/// Register the configure callback
/**
* This callback will be called when the transition to this state is triggered
* \param[in] fcn callback function to call
* \return always true
*/
RCLCPP_LIFECYCLE_PUBLIC RCLCPP_LIFECYCLE_PUBLIC
bool bool
register_on_configure(std::function<LifecycleNodeInterface::CallbackReturn(const State &)> fcn); register_on_configure(std::function<LifecycleNodeInterface::CallbackReturn(const State &)> fcn);
/// Register the cleanup callback
/**
* This callback will be called when the transition to this state is triggered
* \param[in] fcn callback function to call
* \return always true
*/
RCLCPP_LIFECYCLE_PUBLIC RCLCPP_LIFECYCLE_PUBLIC
bool bool
register_on_cleanup(std::function<LifecycleNodeInterface::CallbackReturn(const State &)> fcn); register_on_cleanup(std::function<LifecycleNodeInterface::CallbackReturn(const State &)> fcn);
/// Register the shutdown callback
/**
* This callback will be called when the transition to this state is triggered
* \param[in] fcn callback function to call
* \return always true
*/
RCLCPP_LIFECYCLE_PUBLIC RCLCPP_LIFECYCLE_PUBLIC
bool bool
register_on_shutdown(std::function<LifecycleNodeInterface::CallbackReturn(const State &)> fcn); register_on_shutdown(std::function<LifecycleNodeInterface::CallbackReturn(const State &)> fcn);
/// Register the activate callback
/**
* This callback will be called when the transition to this state is triggered
* \param[in] fcn callback function to call
* \return always true
*/
RCLCPP_LIFECYCLE_PUBLIC RCLCPP_LIFECYCLE_PUBLIC
bool bool
register_on_activate(std::function<LifecycleNodeInterface::CallbackReturn(const State &)> fcn); register_on_activate(std::function<LifecycleNodeInterface::CallbackReturn(const State &)> fcn);
/// Register the deactivate callback
/**
* This callback will be called when the transition to this state is triggered
* \param[in] fcn callback function to call
* \return always true
*/
RCLCPP_LIFECYCLE_PUBLIC RCLCPP_LIFECYCLE_PUBLIC
bool bool
register_on_deactivate(std::function<LifecycleNodeInterface::CallbackReturn(const State &)> fcn); register_on_deactivate(std::function<LifecycleNodeInterface::CallbackReturn(const State &)> fcn);
/// Register the error callback
/**
* This callback will be called when the transition to this state is triggered
* \param[in] fcn callback function to call
* \return always true
*/
RCLCPP_LIFECYCLE_PUBLIC RCLCPP_LIFECYCLE_PUBLIC
bool bool
register_on_error(std::function<LifecycleNodeInterface::CallbackReturn(const State &)> fcn); register_on_error(std::function<LifecycleNodeInterface::CallbackReturn(const State &)> fcn);

View file

@ -27,18 +27,33 @@ typedef struct rcl_lifecycle_state_t rcl_lifecycle_state_t;
namespace rclcpp_lifecycle namespace rclcpp_lifecycle
{ {
/// Abstract class for the Lifecycle's states.
/**
* There are 4 primary states: Unconfigured, Inactive, Active and Finalized.
*/
class State class State
{ {
public: public:
RCLCPP_LIFECYCLE_PUBLIC RCLCPP_LIFECYCLE_PUBLIC
explicit State(rcutils_allocator_t allocator = rcutils_get_default_allocator()); explicit State(rcutils_allocator_t allocator = rcutils_get_default_allocator());
/// State constructor.
/**
* \param[in] id of the state
* \param[in] label of the state
* \param[in] allocator a valid allocator used to initialized the state.
*/
RCLCPP_LIFECYCLE_PUBLIC RCLCPP_LIFECYCLE_PUBLIC
State( State(
uint8_t id, uint8_t id,
const std::string & label, const std::string & label,
rcutils_allocator_t allocator = rcutils_get_default_allocator()); rcutils_allocator_t allocator = rcutils_get_default_allocator());
/// State constructor.
/**
* \param[in] rcl_lifecycle_state_handle structure with the state details
* \param[in] allocator a valid allocator used to initialized the state.
*/
RCLCPP_LIFECYCLE_PUBLIC RCLCPP_LIFECYCLE_PUBLIC
explicit State( explicit State(
const rcl_lifecycle_state_t * rcl_lifecycle_state_handle, const rcl_lifecycle_state_t * rcl_lifecycle_state_handle,
@ -53,10 +68,18 @@ public:
RCLCPP_LIFECYCLE_PUBLIC RCLCPP_LIFECYCLE_PUBLIC
State & operator=(const State & rhs); State & operator=(const State & rhs);
/// Return the id.
/**
* \return id of the state
*/
RCLCPP_LIFECYCLE_PUBLIC RCLCPP_LIFECYCLE_PUBLIC
uint8_t uint8_t
id() const; id() const;
/// Return the label.
/**
* \return label of state
*/
RCLCPP_LIFECYCLE_PUBLIC RCLCPP_LIFECYCLE_PUBLIC
std::string std::string
label() const; label() const;

View file

@ -28,24 +28,48 @@ typedef struct rcl_lifecycle_transition_t rcl_lifecycle_transition_t;
namespace rclcpp_lifecycle namespace rclcpp_lifecycle
{ {
/// The Transition class abstract the Lifecycle's states.
/**
* There are 7 transitions exposed to a supervisory process, they are: create, configure,
* cleanup, activate, deactivate, shutdown and destroy.
*/
class Transition class Transition
{ {
public: public:
RCLCPP_LIFECYCLE_PUBLIC RCLCPP_LIFECYCLE_PUBLIC
Transition() = delete; Transition() = delete;
/// Transition constructor.
/**
* \param[in] id of the transition
* \param[in] label of the transition
* \param[in] allocator a valid allocator used to initialized the state.
*/
RCLCPP_LIFECYCLE_PUBLIC RCLCPP_LIFECYCLE_PUBLIC
explicit Transition( explicit Transition(
uint8_t id, uint8_t id,
const std::string & label = "", const std::string & label = "",
rcutils_allocator_t allocator = rcutils_get_default_allocator()); rcutils_allocator_t allocator = rcutils_get_default_allocator());
/// Transition constructor.
/**
* \param[in] id of the transition
* \param[in] label of the transition
* \param[in] start state of the transition
* \param[in] goal state of the transition
* \param[in] allocator a valid allocator used to initialized the state.
*/
RCLCPP_LIFECYCLE_PUBLIC RCLCPP_LIFECYCLE_PUBLIC
Transition( Transition(
uint8_t id, const std::string & label, uint8_t id, const std::string & label,
State && start, State && goal, State && start, State && goal,
rcutils_allocator_t allocator = rcutils_get_default_allocator()); rcutils_allocator_t allocator = rcutils_get_default_allocator());
/// Transition constructor.
/**
* \param[in] rcl_lifecycle_transition_handle structure with the transition details
* \param[in] allocator a valid allocator used to initialized the state.
*/
RCLCPP_LIFECYCLE_PUBLIC RCLCPP_LIFECYCLE_PUBLIC
explicit Transition( explicit Transition(
const rcl_lifecycle_transition_t * rcl_lifecycle_transition_handle, const rcl_lifecycle_transition_t * rcl_lifecycle_transition_handle,
@ -60,18 +84,34 @@ public:
RCLCPP_LIFECYCLE_PUBLIC RCLCPP_LIFECYCLE_PUBLIC
Transition & operator=(const Transition & rhs); Transition & operator=(const Transition & rhs);
/// Return the id.
/**
* \return id of the state
*/
RCLCPP_LIFECYCLE_PUBLIC RCLCPP_LIFECYCLE_PUBLIC
uint8_t uint8_t
id() const; id() const;
/// Return the label.
/**
* \return label of the transition
*/
RCLCPP_LIFECYCLE_PUBLIC RCLCPP_LIFECYCLE_PUBLIC
std::string std::string
label() const; label() const;
/// Return the start state of the transition.
/**
* \return start state of the transition.
*/
RCLCPP_LIFECYCLE_PUBLIC RCLCPP_LIFECYCLE_PUBLIC
State State
start_state() const; start_state() const;
/// Return the goal state of the transition.
/**
* \return goal state of the transition.
*/
RCLCPP_LIFECYCLE_PUBLIC RCLCPP_LIFECYCLE_PUBLIC
State State
goal_state() const; goal_state() const;