3#include <lifecycle_msgs/msg/state.hpp>
4#include <rclcpp_lifecycle/lifecycle_node.hpp>
6#include "modulo_components/ComponentInterface.hpp"
31 friend class LifecycleComponentPublicInterface;
109 template<
typename DataT>
135 rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
136 on_configure(
const rclcpp_lifecycle::State&
previous_state)
override;
143 bool handle_configure();
154 rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
155 on_cleanup(
const rclcpp_lifecycle::State&
previous_state)
override;
162 bool handle_cleanup();
174 rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
175 on_activate(
const rclcpp_lifecycle::State&
previous_state)
override;
182 bool handle_activate();
193 rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
194 on_deactivate(
const rclcpp_lifecycle::State&
previous_state)
override;
201 bool handle_deactivate();
212 rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
213 on_shutdown(
const rclcpp_lifecycle::State&
previous_state)
override;
220 bool handle_shutdown();
232 rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
246 void step()
override;
252 bool configure_outputs();
258 bool activate_outputs();
264 bool deactivate_outputs();
278 using rclcpp_lifecycle::LifecycleNode::get_parameter;
282 std::function<std::shared_ptr<modulo_core::communication::PublisherInterface>(
const std::string&
topic_name)>>
283 custom_output_configuration_callables_;
286template<
typename DataT>
288 const std::string& signal_name,
const std::shared_ptr<DataT>& data,
const std::string& default_topic,
289 bool fixed_topic,
bool publish_on_step) {
290 if (this->
get_lifecycle_state().
id() != lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED
291 && this->
get_lifecycle_state().
id() != lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE) {
305 if (
message_pair->get_type() == modulo_core::communication::MessageType::CUSTOM_MESSAGE) {
307 this->custom_output_configuration_callables_.insert_or_assign(
310 return std::make_shared<PublisherHandler<rclcpp_lifecycle::LifecyclePublisher<DataT>,
DataT>>(
311 PublisherType::LIFECYCLE_PUBLISHER,
publisher)
Base interface class for modulo components to wrap a ROS Node with custom behaviour.
void publish_outputs()
Helper function to publish all output signals.
std::map< std::string, std::shared_ptr< modulo_core::communication::PublisherInterface > > outputs_
Map of outputs.
std::shared_ptr< state_representation::ParameterInterface > get_parameter(const std::string &name) const
Get a parameter by name.
void finalize_interfaces()
Finalize all interfaces.
T get_parameter_value(const std::string &name) const
Get a parameter value by name.
void publish_predicates()
Helper function to publish all predicates.
std::string create_output(modulo_core::communication::PublisherType publisher_type, const std::string &signal_name, const std::shared_ptr< DataT > &data, const std::string &default_topic, bool fixed_topic, bool publish_on_step)
Helper function to parse the signal name and add an unconfigured PublisherInterface to the map of out...
rclcpp::QoS get_qos() const
Getter of the Quality of Service attribute.
std::map< std::string, std::shared_ptr< modulo_core::communication::SubscriptionInterface > > inputs_
Map of inputs.
void evaluate_periodic_callbacks()
Helper function to evaluate all periodic function callbacks.
std::map< std::string, bool > periodic_outputs_
Map of outputs with periodic publishing flag.
A wrapper for rclcpp_lifecycle::LifecycleNode to simplify application composition through unified com...
void raise_error() override
Trigger the shutdown and error transitions.
virtual bool on_shutdown_callback()
Steps to execute when shutting down the component.
virtual bool on_deactivate_callback()
Steps to execute when deactivating the component.
void add_output(const std::string &signal_name, const std::shared_ptr< DataT > &data, const std::string &default_topic="", bool fixed_topic=false, bool publish_on_step=true)
Add an output signal of the component.
std::shared_ptr< state_representation::ParameterInterface > get_parameter(const std::string &name) const
Get a parameter by name.
virtual bool on_activate_callback()
Steps to execute when activating the component.
virtual bool on_cleanup_callback()
Steps to execute when cleaning up the component.
virtual ~LifecycleComponent()=default
Virtual default destructor.
virtual bool on_error_callback()
Steps to execute when handling errors.
virtual bool on_configure_callback()
Steps to execute when configuring the component.
rclcpp_lifecycle::State get_lifecycle_state() const
Get the current lifecycle state of the component.
The PublisherHandler handles different types of ROS publishers to activate, deactivate and publish da...
An exception class to notify errors when adding a signal.
PublisherType
Enum of supported ROS publisher types for the PublisherInterface.