Class ROS2BaseLCNode

Inheritance Relationships

Base Type

  • public rclcpp_lifecycle::LifecycleNode

Class Documentation

class ROS2BaseLCNode : public rclcpp_lifecycle::LifecycleNode

Public Functions

explicit ROS2BaseLCNode(const std::string &node_name, const rclcpp::NodeOptions &options = rclcpp::NodeOptions())
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_configure(const rclcpp_lifecycle::State&) override
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_cleanup(const rclcpp_lifecycle::State&) override
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_shutdown(const rclcpp_lifecycle::State &state) override
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_activate(const rclcpp_lifecycle::State&) override
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_deactivate(const rclcpp_lifecycle::State&) override
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_error(const rclcpp_lifecycle::State&) override
template<typename T>
inline void registerParameter(const std::string &name, const T &value, const ParameterSetAccessRights &rights, std::function<bool(const T&)> on_change_callback)
template<typename T>
inline void registerStaticParameter(const std::string &name, const T &value, const ParameterSetAccessRights &rights, std::function<bool(const T&)> on_change_callback)
const ParameterHandler &getParameterHandler() const

Protected Functions

rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr ParamCallback() const

Protected Static Attributes

static const rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn SUCCESS = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS
static const rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn ERROR = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::ERROR
static const rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn FAILURE = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::FAILURE