19 #include "nav2_ros_common/node_utils.hpp"
20 #include "nav2_behaviors/behavior_server.hpp"
22 namespace behavior_server
26 : LifecycleNode(
"behavior_server",
"", options),
27 plugin_loader_(
"nav2_core",
"nav2_core::Behavior"),
28 default_ids_{
"spin",
"backup",
"drive_on_heading",
"wait"},
29 default_types_{
"nav2_behaviors::Spin",
30 "nav2_behaviors::BackUp",
31 "nav2_behaviors::DriveOnHeading",
32 "nav2_behaviors::Wait"}
34 declare_parameter(
"cycle_frequency", rclcpp::ParameterValue(10.0));
36 if (behavior_ids_ == default_ids_) {
37 for (
size_t i = 0; i < default_ids_.size(); ++i) {
38 declare_parameter(default_ids_[i] +
".plugin", default_types_[i]);
44 rclcpp::ParameterValue(std::string(
"odom")));
47 rclcpp::ParameterValue(std::string(
"map")));
51 BehaviorServer::~BehaviorServer()
59 RCLCPP_INFO(get_logger(),
"Configuring");
61 tf_ = std::make_shared<tf2_ros::Buffer>(get_clock());
62 auto timer_interface = std::make_shared<tf2_ros::CreateTimerROS>(
63 get_node_base_interface(),
64 get_node_timers_interface());
65 tf_->setCreateTimerInterface(timer_interface);
66 transform_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_,
this,
true);
68 behavior_types_.resize(behavior_ids_.size());
71 return nav2::CallbackReturn::FAILURE;
76 return nav2::CallbackReturn::SUCCESS;
84 for (
size_t i = 0; i != behavior_ids_.size(); i++) {
86 behavior_types_[i] = nav2::get_plugin_type_param(node, behavior_ids_[i]);
88 get_logger(),
"Creating behavior plugin %s of type %s",
89 behavior_ids_[i].c_str(), behavior_types_[i].c_str());
90 behaviors_.push_back(plugin_loader_.createUniqueInstance(behavior_types_[i]));
91 }
catch (
const std::exception & ex) {
93 get_logger(),
"Failed to create behavior %s of type %s."
94 " Exception: %s", behavior_ids_[i].c_str(), behavior_types_[i].c_str(),
107 for (
size_t i = 0; i != behavior_ids_.size(); i++) {
108 behaviors_[i]->configure(
112 local_collision_checker_,
113 global_collision_checker_);
120 "local_costmap_topic", std::string(
"local_costmap/costmap_raw"));
122 "global_costmap_topic", std::string(
"global_costmap/costmap_raw"));
124 "local_footprint_topic", std::string(
"local_costmap/published_footprint"));
126 "global_footprint_topic", std::string(
"global_costmap/published_footprint"));
128 "robot_base_frame", std::string(
"base_link"));
131 bool need_local_costmap =
false;
132 bool need_global_costmap =
false;
133 for (
const auto & behavior : behaviors_) {
134 auto costmap_info = behavior->getResourceInfo();
135 if (costmap_info == nav2_core::CostmapInfoType::BOTH) {
136 need_local_costmap =
true;
137 need_global_costmap =
true;
140 if (costmap_info == nav2_core::CostmapInfoType::LOCAL) {
141 need_local_costmap =
true;
143 if (costmap_info == nav2_core::CostmapInfoType::GLOBAL) {
144 need_global_costmap =
true;
148 if (need_local_costmap) {
149 local_costmap_sub_ = std::make_unique<nav2_costmap_2d::CostmapSubscriber>(
152 local_footprint_sub_ = std::make_unique<nav2_costmap_2d::FootprintSubscriber>(
153 shared_from_this(), local_footprint_topic, *tf_, robot_base_frame, transform_tolerance);
155 local_collision_checker_ = std::make_shared<nav2_costmap_2d::CostmapTopicCollisionChecker>(
156 *local_costmap_sub_, *local_footprint_sub_, get_name());
159 if (need_global_costmap) {
160 global_costmap_sub_ = std::make_unique<nav2_costmap_2d::CostmapSubscriber>(
163 global_footprint_sub_ = std::make_unique<nav2_costmap_2d::FootprintSubscriber>(
164 shared_from_this(), global_footprint_topic, *tf_, robot_base_frame, transform_tolerance);
166 global_collision_checker_ = std::make_shared<nav2_costmap_2d::CostmapTopicCollisionChecker>(
167 *global_costmap_sub_, *global_footprint_sub_, get_name());
174 RCLCPP_INFO(get_logger(),
"Activating");
175 std::vector<pluginlib::UniquePtr<nav2_core::Behavior>>::iterator iter;
176 for (iter = behaviors_.begin(); iter != behaviors_.end(); ++iter) {
183 return nav2::CallbackReturn::SUCCESS;
189 RCLCPP_INFO(get_logger(),
"Deactivating");
191 std::vector<pluginlib::UniquePtr<nav2_core::Behavior>>::iterator iter;
192 for (iter = behaviors_.begin(); iter != behaviors_.end(); ++iter) {
193 (*iter)->deactivate();
199 return nav2::CallbackReturn::SUCCESS;
205 RCLCPP_INFO(get_logger(),
"Cleaning up");
207 std::vector<pluginlib::UniquePtr<nav2_core::Behavior>>::iterator iter;
208 for (iter = behaviors_.begin(); iter != behaviors_.end(); ++iter) {
213 transform_listener_.reset();
216 local_costmap_sub_.reset();
217 global_costmap_sub_.reset();
219 local_footprint_sub_.reset();
220 global_footprint_sub_.reset();
222 local_collision_checker_.reset();
223 global_collision_checker_.reset();
225 return nav2::CallbackReturn::SUCCESS;
231 RCLCPP_INFO(get_logger(),
"Shutting down");
232 return nav2::CallbackReturn::SUCCESS;
237 #include "rclcpp_components/register_node_macro.hpp"
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.
void destroyBond()
Destroy bond connection to lifecycle manager.
nav2::LifecycleNode::SharedPtr shared_from_this()
Get a shared pointer of this.
ParameterT declare_or_get_parameter(const std::string ¶meter_name, const ParameterDescriptor ¶meter_descriptor=ParameterDescriptor())
Declares or gets a parameter with specified type (not value). If the parameter is already declared,...
void createBond()
Create bond connection to lifecycle manager.