Class BehaviorServer

Inheritance Relationships

Base Type

  • public nav2_util::LifecycleNode

Class Documentation

class BehaviorServer : public nav2_util::LifecycleNode

An server hosting a map of behavior plugins.

Public Functions

explicit BehaviorServer(const rclcpp::NodeOptions &options = rclcpp::NodeOptions())

A constructor for behavior_server::BehaviorServer.

Parameters:

options – Additional options to control creation of the node.

~BehaviorServer()
bool loadBehaviorPlugins()

Loads behavior plugins from parameter file.

Returns:

bool if successfully loaded the plugins

Protected Functions

nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State &state) override

Configure lifecycle server.

nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State &state) override

Activate lifecycle server.

nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &state) override

Deactivate lifecycle server.

nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State &state) override

Cleanup lifecycle server.

nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State &state) override

Shutdown lifecycle server.

Protected Attributes

std::shared_ptr<tf2_ros::Buffer> tf_
std::shared_ptr<tf2_ros::TransformListener> transform_listener_
pluginlib::ClassLoader<nav2_core::Behavior> plugin_loader_
std::vector<pluginlib::UniquePtr<nav2_core::Behavior>> behaviors_
std::vector<std::string> default_ids_
std::vector<std::string> default_types_
std::vector<std::string> behavior_ids_
std::vector<std::string> behavior_types_
std::unique_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_sub_
std::unique_ptr<nav2_costmap_2d::FootprintSubscriber> footprint_sub_
std::shared_ptr<nav2_costmap_2d::CostmapTopicCollisionChecker> collision_checker_