Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
behavior_server.cpp
1 // Copyright (c) 2018 Samsung Research America
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License. Reserved.
14 
15 #include <memory>
16 #include <string>
17 #include <vector>
18 #include <utility>
19 #include "nav2_ros_common/node_utils.hpp"
20 #include "nav2_behaviors/behavior_server.hpp"
21 
22 namespace behavior_server
23 {
24 
25 BehaviorServer::BehaviorServer(const rclcpp::NodeOptions & options)
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"}
33 {
34  declare_parameter("cycle_frequency", rclcpp::ParameterValue(10.0));
35  behavior_ids_ = declare_or_get_parameter("behavior_plugins", default_ids_);
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]);
39  }
40  }
41 
42  declare_parameter(
43  "local_frame",
44  rclcpp::ParameterValue(std::string("odom")));
45  declare_parameter(
46  "global_frame",
47  rclcpp::ParameterValue(std::string("map")));
48 }
49 
50 
51 BehaviorServer::~BehaviorServer()
52 {
53  behaviors_.clear();
54 }
55 
56 nav2::CallbackReturn
57 BehaviorServer::on_configure(const rclcpp_lifecycle::State & state)
58 {
59  RCLCPP_INFO(get_logger(), "Configuring");
60 
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);
67 
68  behavior_types_.resize(behavior_ids_.size());
69  if (!loadBehaviorPlugins()) {
70  on_cleanup(state);
71  return nav2::CallbackReturn::FAILURE;
72  }
75 
76  return nav2::CallbackReturn::SUCCESS;
77 }
78 
79 bool
81 {
82  auto node = shared_from_this();
83 
84  for (size_t i = 0; i != behavior_ids_.size(); i++) {
85  try {
86  behavior_types_[i] = nav2::get_plugin_type_param(node, behavior_ids_[i]);
87  RCLCPP_INFO(
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) {
92  RCLCPP_FATAL(
93  get_logger(), "Failed to create behavior %s of type %s."
94  " Exception: %s", behavior_ids_[i].c_str(), behavior_types_[i].c_str(),
95  ex.what());
96  return false;
97  }
98  }
99 
100  return true;
101 }
102 
104 {
105  auto node = shared_from_this();
106 
107  for (size_t i = 0; i != behavior_ids_.size(); i++) {
108  behaviors_[i]->configure(
109  node,
110  behavior_ids_[i],
111  tf_,
112  local_collision_checker_,
113  global_collision_checker_);
114  }
115 }
116 
118 {
119  std::string local_costmap_topic = declare_or_get_parameter(
120  "local_costmap_topic", std::string("local_costmap/costmap_raw"));
121  std::string global_costmap_topic = declare_or_get_parameter(
122  "global_costmap_topic", std::string("global_costmap/costmap_raw"));
123  std::string local_footprint_topic = declare_or_get_parameter(
124  "local_footprint_topic", std::string("local_costmap/published_footprint"));
125  std::string global_footprint_topic = declare_or_get_parameter(
126  "global_footprint_topic", std::string("global_costmap/published_footprint"));
127  std::string robot_base_frame = declare_or_get_parameter(
128  "robot_base_frame", std::string("base_link"));
129  double transform_tolerance = declare_or_get_parameter("transform_tolerance", 0.1);
130 
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;
138  break;
139  }
140  if (costmap_info == nav2_core::CostmapInfoType::LOCAL) {
141  need_local_costmap = true;
142  }
143  if (costmap_info == nav2_core::CostmapInfoType::GLOBAL) {
144  need_global_costmap = true;
145  }
146  }
147 
148  if (need_local_costmap) {
149  local_costmap_sub_ = std::make_unique<nav2_costmap_2d::CostmapSubscriber>(
150  shared_from_this(), local_costmap_topic);
151 
152  local_footprint_sub_ = std::make_unique<nav2_costmap_2d::FootprintSubscriber>(
153  shared_from_this(), local_footprint_topic, *tf_, robot_base_frame, transform_tolerance);
154 
155  local_collision_checker_ = std::make_shared<nav2_costmap_2d::CostmapTopicCollisionChecker>(
156  *local_costmap_sub_, *local_footprint_sub_, get_name());
157  }
158 
159  if (need_global_costmap) {
160  global_costmap_sub_ = std::make_unique<nav2_costmap_2d::CostmapSubscriber>(
161  shared_from_this(), global_costmap_topic);
162 
163  global_footprint_sub_ = std::make_unique<nav2_costmap_2d::FootprintSubscriber>(
164  shared_from_this(), global_footprint_topic, *tf_, robot_base_frame, transform_tolerance);
165 
166  global_collision_checker_ = std::make_shared<nav2_costmap_2d::CostmapTopicCollisionChecker>(
167  *global_costmap_sub_, *global_footprint_sub_, get_name());
168  }
169 }
170 
171 nav2::CallbackReturn
172 BehaviorServer::on_activate(const rclcpp_lifecycle::State & /*state*/)
173 {
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) {
177  (*iter)->activate();
178  }
179 
180  // create bond connection
181  createBond();
182 
183  return nav2::CallbackReturn::SUCCESS;
184 }
185 
186 nav2::CallbackReturn
187 BehaviorServer::on_deactivate(const rclcpp_lifecycle::State & /*state*/)
188 {
189  RCLCPP_INFO(get_logger(), "Deactivating");
190 
191  std::vector<pluginlib::UniquePtr<nav2_core::Behavior>>::iterator iter;
192  for (iter = behaviors_.begin(); iter != behaviors_.end(); ++iter) {
193  (*iter)->deactivate();
194  }
195 
196  // destroy bond connection
197  destroyBond();
198 
199  return nav2::CallbackReturn::SUCCESS;
200 }
201 
202 nav2::CallbackReturn
203 BehaviorServer::on_cleanup(const rclcpp_lifecycle::State & /*state*/)
204 {
205  RCLCPP_INFO(get_logger(), "Cleaning up");
206 
207  std::vector<pluginlib::UniquePtr<nav2_core::Behavior>>::iterator iter;
208  for (iter = behaviors_.begin(); iter != behaviors_.end(); ++iter) {
209  (*iter)->cleanup();
210  }
211 
212  behaviors_.clear();
213  transform_listener_.reset();
214  tf_.reset();
215 
216  local_costmap_sub_.reset();
217  global_costmap_sub_.reset();
218 
219  local_footprint_sub_.reset();
220  global_footprint_sub_.reset();
221 
222  local_collision_checker_.reset();
223  global_collision_checker_.reset();
224 
225  return nav2::CallbackReturn::SUCCESS;
226 }
227 
228 nav2::CallbackReturn
229 BehaviorServer::on_shutdown(const rclcpp_lifecycle::State &)
230 {
231  RCLCPP_INFO(get_logger(), "Shutting down");
232  return nav2::CallbackReturn::SUCCESS;
233 }
234 
235 } // end namespace behavior_server
236 
237 #include "rclcpp_components/register_node_macro.hpp"
238 
239 // Register the component with class_loader.
240 // This acts as a sort of entry point, allowing the component to be discoverable when its library
241 // is being loaded into a running process.
242 RCLCPP_COMPONENTS_REGISTER_NODE(behavior_server::BehaviorServer)
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 &parameter_name, const ParameterDescriptor &parameter_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.