21 #include "nav2_util/lifecycle_node.hpp"
22 #include "tf2_ros/transform_listener.h"
23 #include "tf2_ros/create_timer_ros.h"
24 #include "pluginlib/class_loader.hpp"
25 #include "pluginlib/class_list_macros.hpp"
26 #include "nav2_core/behavior.hpp"
28 #ifndef NAV2_BEHAVIORS__BEHAVIOR_SERVER_HPP_
29 #define NAV2_BEHAVIORS__BEHAVIOR_SERVER_HPP_
31 namespace behavior_server
45 explicit BehaviorServer(
const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
58 nav2_util::CallbackReturn
on_configure(
const rclcpp_lifecycle::State & state)
override;
63 nav2_util::CallbackReturn
on_activate(
const rclcpp_lifecycle::State & state)
override;
68 nav2_util::CallbackReturn
on_deactivate(
const rclcpp_lifecycle::State & state)
override;
73 nav2_util::CallbackReturn
on_cleanup(
const rclcpp_lifecycle::State & state)
override;
78 nav2_util::CallbackReturn
on_shutdown(
const rclcpp_lifecycle::State & state)
override;
80 std::shared_ptr<tf2_ros::Buffer> tf_;
81 std::shared_ptr<tf2_ros::TransformListener> transform_listener_;
84 pluginlib::ClassLoader<nav2_core::Behavior> plugin_loader_;
85 std::vector<pluginlib::UniquePtr<nav2_core::Behavior>> behaviors_;
86 std::vector<std::string> default_ids_;
87 std::vector<std::string> default_types_;
88 std::vector<std::string> behavior_ids_;
89 std::vector<std::string> behavior_types_;
92 std::unique_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_sub_;
93 std::unique_ptr<nav2_costmap_2d::FootprintSubscriber> footprint_sub_;
94 std::shared_ptr<nav2_costmap_2d::CostmapTopicCollisionChecker> collision_checker_;
An server hosting a map of behavior plugins.
nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State &state) override
Cleanup lifecycle server.
BehaviorServer(const rclcpp::NodeOptions &options=rclcpp::NodeOptions())
A constructor for behavior_server::BehaviorServer.
nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &state) override
Deactivate lifecycle server.
nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State &state) override
Activate lifecycle server.
nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State &state) override
Shutdown lifecycle server.
nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State &state) override
Configure lifecycle server.
bool loadBehaviorPlugins()
Loads behavior plugins from parameter file.
A lifecycle node wrapper to enable common Nav2 needs such as manipulating parameters.