Class SetMode
Defined in File set_mode.h
Inheritance Relationships
Base Type
public hateb_local_planner::StatefulActionNodeROS(Class StatefulActionNodeROS)
Class Documentation
-
class SetMode : public hateb_local_planner::StatefulActionNodeROS
Class implementing a behavior tree action node to set planning mode.
This class provides functionality to set planning modes in CoHAN. It inherits from StatefulActionNodeROS to integrate with ROS and behavior tree framework.
Public Functions
-
SetMode(ros::NodeHandle &nh, const std::string &name, const BT::NodeConfig &config)
Constructor with ROS node handle and behavior tree configuration.
- Parameters:
nh – The ROS node handle for communication
name – Name of the behavior tree node
config – Configuration for the behavior tree node
-
SetMode() = delete
Deleted default constructor to enforce proper initialization.
-
~SetMode() override
Virtual destructor for cleanup.
-
virtual BT::NodeStatus onStart() override
Method called when the node is first ticked.
- Returns:
Status of the node after starting
-
virtual BT::NodeStatus onRunning() override
Method called while the node is running.
- Returns:
Current status of the node
-
virtual void onHalted() override
Method called when the node is halted.
Public Static Functions
-
static inline BT::PortsList providedPorts()
Defines input and output ports for the behavior tree node.
- Returns:
Ports list containing plan_type and predict_type as inputs and mode as output
-
SetMode(ros::NodeHandle &nh, const std::string &name, const BT::NodeConfig &config)