Class ControlledLifecycleNode

Inheritance Relationships

Base Type

  • public rclcpp_lifecycle::LifecycleNode

Derived Type

Class Documentation

class ControlledLifecycleNode : public rclcpp_lifecycle::LifecycleNode

Subclassed by mocap4r2_control::AuxiliarNode

Public Functions

explicit ControlledLifecycleNode(const std::string &system_id, const rclcpp::NodeOptions &node_options = rclcpp::NodeOptions())

Protected Types

using CallbackReturnT = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn

Protected Functions

template<typename MessageT, typename AllocatorT = std::allocator<void>>
inline std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<MessageT, AllocatorT>> create_publisher(const std::string &topic_name, const rclcpp::QoS &qos, const rclcpp::PublisherOptionsWithAllocator<AllocatorT> &options = (rclcpp_lifecycle::create_default_publisher_options<AllocatorT>()))
CallbackReturnT on_configure(const rclcpp_lifecycle::State &state)
CallbackReturnT on_activate(const rclcpp_lifecycle::State &state)
CallbackReturnT on_deactivate(const rclcpp_lifecycle::State &state)
CallbackReturnT on_shutdown(const rclcpp_lifecycle::State &state)
CallbackReturnT on_cleanup(const rclcpp_lifecycle::State &state)
inline virtual void control_start(const mocap4r2_control_msgs::msg::Control::SharedPtr msg)
inline virtual void control_stop(const mocap4r2_control_msgs::msg::Control::SharedPtr msg)

Protected Attributes

std::set<std::string> topics_