38 #include <rclcpp/node.hpp>
60 void initialize(
const rclcpp::Node::SharedPtr& parent_node,
const DataWarehousePtr& config_data)
64 logger_ = std::make_shared<rclcpp::Logger>(parent_node->get_logger().get_child(
getName()));
Contains all of the non-GUI code necessary for doing one "screen" worth of setup.
SetupStep & operator=(SetupStep &&)=default
rclcpp::Node::SharedPtr parent_node_
SetupStep & operator=(const SetupStep &)=default
DataWarehousePtr config_data_
virtual std::string getName() const =0
Returns the name of the setup step.
virtual ~SetupStep()=default
SetupStep(SetupStep &&)=default
SetupStep(const SetupStep &)=default
virtual void onInit()
Overridable initialization method.
const rclcpp::Logger & getLogger() const
Makes a namespaced logger for this step available to the widget.
std::shared_ptr< rclcpp::Logger > logger_
void initialize(const rclcpp::Node::SharedPtr &parent_node, const DataWarehousePtr &config_data)
Called after construction to initialize the step.
virtual bool isReady() const
Return true if the data necessary to proceed with this step has been configured.