Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
layer.cpp
1 /*
2  * Copyright (c) 2013, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #include "nav2_costmap_2d/layer.hpp"
31 
32 #include <string>
33 #include <vector>
34 #include "nav2_util/node_utils.hpp"
35 
36 namespace nav2_costmap_2d
37 {
38 
40 : layered_costmap_(nullptr),
41  name_(),
42  tf_(nullptr),
43  current_(false),
44  enabled_(false)
45 {}
46 
47 void
49  LayeredCostmap * parent,
50  std::string name,
51  tf2_ros::Buffer * tf,
52  const nav2_util::LifecycleNode::WeakPtr & node,
53  rclcpp::CallbackGroup::SharedPtr callback_group)
54 {
55  layered_costmap_ = parent;
56  name_ = name;
57  tf_ = tf;
58  node_ = node;
59  callback_group_ = callback_group;
60  {
61  auto node_shared_ptr = node_.lock();
62  logger_ = node_shared_ptr->get_logger();
63  clock_ = node_shared_ptr->get_clock();
64  }
65 
66  onInitialize();
67 }
68 
69 const std::vector<geometry_msgs::msg::Point> &
71 {
72  return layered_costmap_->getFootprint();
73 }
74 
75 void
77  const std::string & param_name,
78  const rclcpp::ParameterValue & value)
79 {
80  auto node = node_.lock();
81  if (!node) {
82  throw std::runtime_error{"Failed to lock node"};
83  }
84  local_params_.insert(param_name);
85  nav2_util::declare_parameter_if_not_declared(
86  node, getFullName(param_name), value);
87 }
88 
89 void
91  const std::string & param_name,
92  const rclcpp::ParameterType & param_type)
93 {
94  auto node = node_.lock();
95  if (!node) {
96  throw std::runtime_error{"Failed to lock node"};
97  }
98  local_params_.insert(param_name);
99  nav2_util::declare_parameter_if_not_declared(
100  node, getFullName(param_name), param_type);
101 }
102 
103 bool
104 Layer::hasParameter(const std::string & param_name)
105 {
106  auto node = node_.lock();
107  if (!node) {
108  throw std::runtime_error{"Failed to lock node"};
109  }
110  return node->has_parameter(getFullName(param_name));
111 }
112 
113 std::string
114 Layer::getFullName(const std::string & param_name)
115 {
116  return std::string(name_ + "." + param_name);
117 }
118 
119 
120 std::string
121 Layer::joinWithParentNamespace(const std::string & topic)
122 {
123  auto node = node_.lock();
124  if (!node) {
125  throw std::runtime_error{"Failed to lock node"};
126  }
127 
128  if (topic[0] != '/') {
129  std::string node_namespace = node->get_namespace();
130  std::string parent_namespace = node_namespace.substr(0, node_namespace.rfind("/"));
131  return parent_namespace + "/" + topic;
132  }
133 
134  return topic;
135 }
136 
137 } // end namespace nav2_costmap_2d
std::string joinWithParentNamespace(const std::string &topic)
Definition: layer.cpp:121
bool hasParameter(const std::string &param_name)
Convenience functions for declaring ROS parameters.
Definition: layer.cpp:104
void declareParameter(const std::string &param_name, const rclcpp::ParameterValue &value)
Convenience functions for declaring ROS parameters.
Definition: layer.cpp:76
virtual void onInitialize()
This is called at the end of initialize(). Override to implement subclass-specific initialization.
Definition: layer.hpp:196
void initialize(LayeredCostmap *parent, std::string name, tf2_ros::Buffer *tf, const nav2_util::LifecycleNode::WeakPtr &node, rclcpp::CallbackGroup::SharedPtr callback_group)
Initialization process of layer on startup.
Definition: layer.cpp:48
const std::vector< geometry_msgs::msg::Point > & getFootprint() const
Convenience function for layered_costmap_->getFootprint().
Definition: layer.cpp:70
Layer()
A constructor.
Definition: layer.cpp:39
std::string getFullName(const std::string &param_name)
Convenience functions for declaring ROS parameters.
Definition: layer.cpp:114
Instantiates different layer plugins and aggregates them into one score.
const std::vector< geometry_msgs::msg::Point > & getFootprint()
Returns the latest footprint stored with setFootprint().