Class Behavior

Nested Relationships

Nested Types

Inheritance Relationships

Derived Types

Class Documentation

class Behavior

Subclassed by create3_coverage::DockBehavior, create3_coverage::DriveStraightBehavior, create3_coverage::ReflexBehavior, create3_coverage::RotateBehavior, create3_coverage::SpiralBehavior, create3_coverage::UndockBehavior

Public Functions

Behavior() = default
virtual ~Behavior() = default
virtual State execute(const Data &data) = 0
virtual int32_t get_id() const = 0
inline virtual void cleanup()
struct Data

Public Members

geometry_msgs::msg::Pose pose
irobot_create_msgs::msg::HazardDetectionVector hazards
irobot_create_msgs::msg::DockStatus dock
std::vector<irobot_create_msgs::msg::IrOpcode> opcodes