Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
map_server.cpp
1 /* Copyright (c) 2018 Intel Corporation
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.
14  */
15 
16 /* Copyright 2019 Rover Robotics
17  * Copyright 2010 Brian Gerkey
18  * Copyright (c) 2008, Willow Garage, Inc.
19  *
20  * All rights reserved.
21  *
22  * Redistribution and use in source and binary forms, with or without
23  * modification, are permitted provided that the following conditions are met:
24  *
25  * * Redistributions of source code must retain the above copyright
26  * notice, this list of conditions and the following disclaimer.
27  * * Redistributions in binary form must reproduce the above copyright
28  * notice, this list of conditions and the following disclaimer in the
29  * documentation and/or other materials provided with the distribution.
30  * * Neither the name of the Willow Garage, Inc. nor the names of its
31  * contributors may be used to endorse or promote products derived from
32  * this software without specific prior written permission.
33  *
34  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
35  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
36  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
37  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
38  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
39  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
40  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
41  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
42  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
43  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
44  * POSSIBILITY OF SUCH DAMAGE.
45  */
46 
47 #include "nav2_map_server/map_server.hpp"
48 
49 #include <string>
50 #include <memory>
51 #include <fstream>
52 #include <stdexcept>
53 #include <utility>
54 
55 #include "yaml-cpp/yaml.h"
56 #include "lifecycle_msgs/msg/state.hpp"
57 #include "nav2_map_server/map_io.hpp"
58 
59 using namespace std::chrono_literals;
60 using namespace std::placeholders;
61 
62 namespace nav2_map_server
63 {
64 
65 MapServer::MapServer(const rclcpp::NodeOptions & options)
66 : nav2_util::LifecycleNode("map_server", "", options), map_available_(false)
67 {
68  RCLCPP_INFO(get_logger(), "Creating");
69 
70  // Declare the node parameters
71  declare_parameter("yaml_filename", rclcpp::PARAMETER_STRING);
72  declare_parameter("topic_name", "map");
73  declare_parameter("frame_id", "map");
74 }
75 
77 {
78 }
79 
80 nav2_util::CallbackReturn
81 MapServer::on_configure(const rclcpp_lifecycle::State & /*state*/)
82 {
83  RCLCPP_INFO(get_logger(), "Configuring");
84 
85  // Get the name of the YAML file to use (can be empty if no initial map should be used)
86  std::string yaml_filename = get_parameter("yaml_filename").as_string();
87  std::string topic_name = get_parameter("topic_name").as_string();
88  frame_id_ = get_parameter("frame_id").as_string();
89 
90  // only try to load map if parameter was set
91  if (!yaml_filename.empty()) {
92  // Shared pointer to LoadMap::Response is also should be initialized
93  // in order to avoid null-pointer dereference
94  std::shared_ptr<nav2_msgs::srv::LoadMap::Response> rsp =
95  std::make_shared<nav2_msgs::srv::LoadMap::Response>();
96 
97  if (!loadMapResponseFromYaml(yaml_filename, rsp)) {
98  throw std::runtime_error("Failed to load map yaml file: " + yaml_filename);
99  }
100  } else {
101  RCLCPP_INFO(
102  get_logger(),
103  "yaml-filename parameter is empty, set map through '%s'-service",
104  load_map_service_name_.c_str());
105  }
106 
107  // Make name prefix for services
108  const std::string service_prefix = get_name() + std::string("/");
109 
110  // Create a service that provides the occupancy grid
111  occ_service_ = std::make_shared<nav2_util::ServiceServer<nav_msgs::srv::GetMap,
112  std::shared_ptr<nav2_util::LifecycleNode>>>(
113  service_prefix + std::string(service_name_),
115  std::bind(&MapServer::getMapCallback, this, _1, _2, _3));
116 
117  // Create a publisher using the QoS settings to emulate a ROS1 latched topic
118  occ_pub_ = create_publisher<nav_msgs::msg::OccupancyGrid>(
119  topic_name,
120  rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable());
121 
122  // Create a service that loads the occupancy grid from a file
123  load_map_service_ = std::make_shared<nav2_util::ServiceServer<nav2_msgs::srv::LoadMap,
124  std::shared_ptr<nav2_util::LifecycleNode>>>(
125  service_prefix + std::string(load_map_service_name_),
127  std::bind(&MapServer::loadMapCallback, this, _1, _2, _3));
128 
129  return nav2_util::CallbackReturn::SUCCESS;
130 }
131 
132 nav2_util::CallbackReturn
133 MapServer::on_activate(const rclcpp_lifecycle::State & /*state*/)
134 {
135  RCLCPP_INFO(get_logger(), "Activating");
136 
137  // Publish the map using the latched topic
138  occ_pub_->on_activate();
139  if (map_available_) {
140  auto occ_grid = std::make_unique<nav_msgs::msg::OccupancyGrid>(msg_);
141  occ_pub_->publish(std::move(occ_grid));
142  }
143 
144  // create bond connection
145  createBond();
146 
147  return nav2_util::CallbackReturn::SUCCESS;
148 }
149 
150 nav2_util::CallbackReturn
151 MapServer::on_deactivate(const rclcpp_lifecycle::State & /*state*/)
152 {
153  RCLCPP_INFO(get_logger(), "Deactivating");
154 
155  occ_pub_->on_deactivate();
156 
157  // destroy bond connection
158  destroyBond();
159 
160  return nav2_util::CallbackReturn::SUCCESS;
161 }
162 
163 nav2_util::CallbackReturn
164 MapServer::on_cleanup(const rclcpp_lifecycle::State & /*state*/)
165 {
166  RCLCPP_INFO(get_logger(), "Cleaning up");
167 
168  occ_pub_.reset();
169  occ_service_.reset();
170  load_map_service_.reset();
171  map_available_ = false;
172  msg_ = nav_msgs::msg::OccupancyGrid();
173 
174  return nav2_util::CallbackReturn::SUCCESS;
175 }
176 
177 nav2_util::CallbackReturn
178 MapServer::on_shutdown(const rclcpp_lifecycle::State & /*state*/)
179 {
180  RCLCPP_INFO(get_logger(), "Shutting down");
181  return nav2_util::CallbackReturn::SUCCESS;
182 }
183 
185  const std::shared_ptr<rmw_request_id_t>/*request_header*/,
186  const std::shared_ptr<nav_msgs::srv::GetMap::Request>/*request*/,
187  std::shared_ptr<nav_msgs::srv::GetMap::Response> response)
188 {
189  // if not in ACTIVE state, ignore request
190  if (get_current_state().id() != lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE) {
191  RCLCPP_WARN(
192  get_logger(),
193  "Received GetMap request but not in ACTIVE state, ignoring!");
194  return;
195  }
196  RCLCPP_INFO(get_logger(), "Handling GetMap request");
197  response->map = msg_;
198 }
199 
201  const std::shared_ptr<rmw_request_id_t>/*request_header*/,
202  const std::shared_ptr<nav2_msgs::srv::LoadMap::Request> request,
203  std::shared_ptr<nav2_msgs::srv::LoadMap::Response> response)
204 {
205  // if not in ACTIVE state, ignore request
206  if (get_current_state().id() != lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE) {
207  RCLCPP_WARN(
208  get_logger(),
209  "Received LoadMap request but not in ACTIVE state, ignoring!");
210  response->result = response->RESULT_UNDEFINED_FAILURE;
211  return;
212  }
213  RCLCPP_INFO(get_logger(), "Handling LoadMap request");
214  // Load from file
215  if (loadMapResponseFromYaml(request->map_url, response)) {
216  auto occ_grid = std::make_unique<nav_msgs::msg::OccupancyGrid>(msg_);
217  occ_pub_->publish(std::move(occ_grid)); // publish new map
218  }
219 }
220 
222  const std::string & yaml_file,
223  std::shared_ptr<nav2_msgs::srv::LoadMap::Response> response)
224 {
225  switch (loadMapFromYaml(yaml_file, msg_)) {
226  case MAP_DOES_NOT_EXIST:
227  response->result = nav2_msgs::srv::LoadMap::Response::RESULT_MAP_DOES_NOT_EXIST;
228  return false;
229  case INVALID_MAP_METADATA:
230  response->result = nav2_msgs::srv::LoadMap::Response::RESULT_INVALID_MAP_METADATA;
231  return false;
232  case INVALID_MAP_DATA:
233  response->result = nav2_msgs::srv::LoadMap::Response::RESULT_INVALID_MAP_DATA;
234  return false;
235  case LOAD_MAP_SUCCESS:
236  // Correcting msg_ header when it belongs to specific node
237  updateMsgHeader();
238 
239  map_available_ = true;
240  response->map = msg_;
241  response->result = nav2_msgs::srv::LoadMap::Response::RESULT_SUCCESS;
242  }
243 
244  return true;
245 }
246 
248 {
249  msg_.info.map_load_time = now();
250  msg_.header.frame_id = frame_id_;
251  msg_.header.stamp = now();
252 }
253 
254 } // namespace nav2_map_server
255 
256 #include "rclcpp_components/register_node_macro.hpp"
257 
258 // Register the component with class_loader.
259 // This acts as a sort of entry point, allowing the component to be discoverable when its library
260 // is being loaded into a running process.
261 RCLCPP_COMPONENTS_REGISTER_NODE(nav2_map_server::MapServer)
Parses the map yaml file and creates a service and a publisher that provides occupancy grid.
Definition: map_server.hpp:38
void loadMapCallback(const std::shared_ptr< rmw_request_id_t > request_header, const std::shared_ptr< nav2_msgs::srv::LoadMap::Request > request, std::shared_ptr< nav2_msgs::srv::LoadMap::Response > response)
Map loading service callback.
Definition: map_server.cpp:200
void getMapCallback(const std::shared_ptr< rmw_request_id_t > request_header, const std::shared_ptr< nav_msgs::srv::GetMap::Request > request, std::shared_ptr< nav_msgs::srv::GetMap::Response > response)
Map getting service callback.
Definition: map_server.cpp:184
void updateMsgHeader()
Method correcting msg_ header when it belongs to instantiated object.
Definition: map_server.cpp:247
nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State &state) override
Start publishing the map using the latched topic.
Definition: map_server.cpp:133
nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State &state) override
Called when in Shutdown state.
Definition: map_server.cpp:178
nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &state) override
Stops publishing the latched topic.
Definition: map_server.cpp:151
nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State &state) override
Sets up required params and services. Loads map and its parameters from the file.
Definition: map_server.cpp:81
~MapServer()
A Destructor for nav2_map_server::MapServer.
Definition: map_server.cpp:76
bool loadMapResponseFromYaml(const std::string &yaml_file, std::shared_ptr< nav2_msgs::srv::LoadMap::Response > response)
Load the map YAML, image from map file name and generate output response containing an OccupancyGrid....
Definition: map_server.cpp:221
nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State &state) override
Resets the member variables.
Definition: map_server.cpp:164
std::shared_ptr< nav2_util::LifecycleNode > shared_from_this()
Get a shared pointer of this.
void createBond()
Create bond connection to lifecycle manager.
void destroyBond()
Destroy bond connection to lifecycle manager.
A simple wrapper on ROS2 services server.