Class WallFollowBehavior

Class Documentation

class WallFollowBehavior

This class allows to create and manage the WallFollow action server. Uses a simplistic wall follow implementation that is not intended to exactly mimic the behavior of the robot. The robot will follow tighter than this simple implementation.

Public Functions

WallFollowBehavior(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface, rclcpp::node_interfaces::NodeClockInterface::SharedPtr node_clock_interface, rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging_interface, rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_interface, rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr node_waitables_interface, std::shared_ptr<BehaviorsScheduler> behavior_scheduler)
~WallFollowBehavior() = default
void hazard_vector_callback(irobot_create_msgs::msg::HazardDetectionVector::ConstSharedPtr msg)