21 #include "nav2_ros_common/lifecycle_node.hpp"
22 #include "tf2_ros/transform_listener.hpp"
23 #include "tf2_ros/create_timer_ros.hpp"
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());
67 nav2::CallbackReturn
on_configure(
const rclcpp_lifecycle::State & state)
override;
72 nav2::CallbackReturn
on_activate(
const rclcpp_lifecycle::State & state)
override;
77 nav2::CallbackReturn
on_deactivate(
const rclcpp_lifecycle::State & state)
override;
82 nav2::CallbackReturn
on_cleanup(
const rclcpp_lifecycle::State & state)
override;
87 nav2::CallbackReturn
on_shutdown(
const rclcpp_lifecycle::State & state)
override;
89 std::shared_ptr<tf2_ros::Buffer> tf_;
90 std::shared_ptr<tf2_ros::TransformListener> transform_listener_;
93 pluginlib::ClassLoader<nav2_core::Behavior> plugin_loader_;
94 std::vector<pluginlib::UniquePtr<nav2_core::Behavior>> behaviors_;
95 std::vector<std::string> default_ids_;
96 std::vector<std::string> default_types_;
97 std::vector<std::string> behavior_ids_;
98 std::vector<std::string> behavior_types_;
101 std::unique_ptr<nav2_costmap_2d::CostmapSubscriber> local_costmap_sub_;
102 std::unique_ptr<nav2_costmap_2d::FootprintSubscriber> local_footprint_sub_;
103 std::shared_ptr<nav2_costmap_2d::CostmapTopicCollisionChecker> local_collision_checker_;
105 std::unique_ptr<nav2_costmap_2d::CostmapSubscriber> global_costmap_sub_;
106 std::unique_ptr<nav2_costmap_2d::FootprintSubscriber> global_footprint_sub_;
107 std::shared_ptr<nav2_costmap_2d::CostmapTopicCollisionChecker> global_collision_checker_;
An server hosting a map of behavior plugins.
BehaviorServer(const rclcpp::NodeOptions &options=rclcpp::NodeOptions())
A constructor for behavior_server::BehaviorServer.
nav2::CallbackReturn on_cleanup(const rclcpp_lifecycle::State &state) override
Cleanup lifecycle server.
nav2::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &state) override
Deactivate lifecycle server.
nav2::CallbackReturn on_shutdown(const rclcpp_lifecycle::State &state) override
Shutdown lifecycle server.
void configureBehaviorPlugins()
configures behavior plugins
nav2::CallbackReturn on_activate(const rclcpp_lifecycle::State &state) override
Activate lifecycle server.
void setupResourcesForBehaviorPlugins()
configures behavior plugins
nav2::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.