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"}
35 "local_costmap_topic",
36 rclcpp::ParameterValue(std::string(
"local_costmap/costmap_raw")));
39 "global_costmap_topic",
40 rclcpp::ParameterValue(std::string(
"global_costmap/costmap_raw")));
43 "local_footprint_topic",
44 rclcpp::ParameterValue(std::string(
"local_costmap/published_footprint")));
47 "global_footprint_topic",
48 rclcpp::ParameterValue(std::string(
"global_costmap/published_footprint")));
50 declare_parameter(
"cycle_frequency", rclcpp::ParameterValue(10.0));
51 declare_parameter(
"behavior_plugins", default_ids_);
53 get_parameter(
"behavior_plugins", behavior_ids_);
54 if (behavior_ids_ == default_ids_) {
55 for (
size_t i = 0; i < default_ids_.size(); ++i) {
56 declare_parameter(default_ids_[i] +
".plugin", default_types_[i]);
62 rclcpp::ParameterValue(std::string(
"odom")));
65 rclcpp::ParameterValue(std::string(
"map")));
68 rclcpp::ParameterValue(std::string(
"base_link")));
70 "transform_tolerance",
71 rclcpp::ParameterValue(0.1));
75 BehaviorServer::~BehaviorServer()
83 RCLCPP_INFO(get_logger(),
"Configuring");
85 tf_ = std::make_shared<tf2_ros::Buffer>(get_clock());
86 auto timer_interface = std::make_shared<tf2_ros::CreateTimerROS>(
87 get_node_base_interface(),
88 get_node_timers_interface());
89 tf_->setCreateTimerInterface(timer_interface);
90 transform_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_,
this,
true);
92 behavior_types_.resize(behavior_ids_.size());
95 return nav2::CallbackReturn::FAILURE;
100 return nav2::CallbackReturn::SUCCESS;
108 for (
size_t i = 0; i != behavior_ids_.size(); i++) {
110 behavior_types_[i] = nav2::get_plugin_type_param(node, behavior_ids_[i]);
112 get_logger(),
"Creating behavior plugin %s of type %s",
113 behavior_ids_[i].c_str(), behavior_types_[i].c_str());
114 behaviors_.push_back(plugin_loader_.createUniqueInstance(behavior_types_[i]));
115 }
catch (
const std::exception & ex) {
117 get_logger(),
"Failed to create behavior %s of type %s."
118 " Exception: %s", behavior_ids_[i].c_str(), behavior_types_[i].c_str(),
131 for (
size_t i = 0; i != behavior_ids_.size(); i++) {
132 behaviors_[i]->configure(
136 local_collision_checker_,
137 global_collision_checker_);
143 std::string local_costmap_topic, global_costmap_topic;
144 std::string local_footprint_topic, global_footprint_topic;
145 std::string robot_base_frame;
146 double transform_tolerance;
147 get_parameter(
"local_costmap_topic", local_costmap_topic);
148 get_parameter(
"global_costmap_topic", global_costmap_topic);
149 get_parameter(
"local_footprint_topic", local_footprint_topic);
150 get_parameter(
"global_footprint_topic", global_footprint_topic);
151 get_parameter(
"robot_base_frame", robot_base_frame);
152 transform_tolerance = get_parameter(
"transform_tolerance").as_double();
154 bool need_local_costmap =
false;
155 bool need_global_costmap =
false;
156 for (
const auto & behavior : behaviors_) {
157 auto costmap_info = behavior->getResourceInfo();
158 if (costmap_info == nav2_core::CostmapInfoType::BOTH) {
159 need_local_costmap =
true;
160 need_global_costmap =
true;
163 if (costmap_info == nav2_core::CostmapInfoType::LOCAL) {
164 need_local_costmap =
true;
166 if (costmap_info == nav2_core::CostmapInfoType::GLOBAL) {
167 need_global_costmap =
true;
171 if (need_local_costmap) {
172 local_costmap_sub_ = std::make_unique<nav2_costmap_2d::CostmapSubscriber>(
175 local_footprint_sub_ = std::make_unique<nav2_costmap_2d::FootprintSubscriber>(
176 shared_from_this(), local_footprint_topic, *tf_, robot_base_frame, transform_tolerance);
178 local_collision_checker_ = std::make_shared<nav2_costmap_2d::CostmapTopicCollisionChecker>(
179 *local_costmap_sub_, *local_footprint_sub_, get_name());
182 if (need_global_costmap) {
183 global_costmap_sub_ = std::make_unique<nav2_costmap_2d::CostmapSubscriber>(
186 global_footprint_sub_ = std::make_unique<nav2_costmap_2d::FootprintSubscriber>(
187 shared_from_this(), global_footprint_topic, *tf_, robot_base_frame, transform_tolerance);
189 global_collision_checker_ = std::make_shared<nav2_costmap_2d::CostmapTopicCollisionChecker>(
190 *global_costmap_sub_, *global_footprint_sub_, get_name());
197 RCLCPP_INFO(get_logger(),
"Activating");
198 std::vector<pluginlib::UniquePtr<nav2_core::Behavior>>::iterator iter;
199 for (iter = behaviors_.begin(); iter != behaviors_.end(); ++iter) {
206 return nav2::CallbackReturn::SUCCESS;
212 RCLCPP_INFO(get_logger(),
"Deactivating");
214 std::vector<pluginlib::UniquePtr<nav2_core::Behavior>>::iterator iter;
215 for (iter = behaviors_.begin(); iter != behaviors_.end(); ++iter) {
216 (*iter)->deactivate();
222 return nav2::CallbackReturn::SUCCESS;
228 RCLCPP_INFO(get_logger(),
"Cleaning up");
230 std::vector<pluginlib::UniquePtr<nav2_core::Behavior>>::iterator iter;
231 for (iter = behaviors_.begin(); iter != behaviors_.end(); ++iter) {
236 transform_listener_.reset();
239 local_costmap_sub_.reset();
240 global_costmap_sub_.reset();
242 local_footprint_sub_.reset();
243 global_footprint_sub_.reset();
245 local_collision_checker_.reset();
246 global_collision_checker_.reset();
248 return nav2::CallbackReturn::SUCCESS;
254 RCLCPP_INFO(get_logger(),
"Shutting down");
255 return nav2::CallbackReturn::SUCCESS;
260 #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.
void createBond()
Create bond connection to lifecycle manager.