Nav2 Navigation Stack - humble  humble
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_ = create_service<nav_msgs::srv::GetMap>(
112  service_prefix + std::string(service_name_),
113  std::bind(&MapServer::getMapCallback, this, _1, _2, _3));
114 
115  // Create a publisher using the QoS settings to emulate a ROS1 latched topic
116  occ_pub_ = create_publisher<nav_msgs::msg::OccupancyGrid>(
117  topic_name,
118  rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable());
119 
120  // Create a service that loads the occupancy grid from a file
121  load_map_service_ = create_service<nav2_msgs::srv::LoadMap>(
122  service_prefix + std::string(load_map_service_name_),
123  std::bind(&MapServer::loadMapCallback, this, _1, _2, _3));
124 
125  return nav2_util::CallbackReturn::SUCCESS;
126 }
127 
128 nav2_util::CallbackReturn
129 MapServer::on_activate(const rclcpp_lifecycle::State & /*state*/)
130 {
131  RCLCPP_INFO(get_logger(), "Activating");
132 
133  // Publish the map using the latched topic
134  occ_pub_->on_activate();
135  if (map_available_) {
136  auto occ_grid = std::make_unique<nav_msgs::msg::OccupancyGrid>(msg_);
137  occ_pub_->publish(std::move(occ_grid));
138  }
139 
140  // create bond connection
141  createBond();
142 
143  return nav2_util::CallbackReturn::SUCCESS;
144 }
145 
146 nav2_util::CallbackReturn
147 MapServer::on_deactivate(const rclcpp_lifecycle::State & /*state*/)
148 {
149  RCLCPP_INFO(get_logger(), "Deactivating");
150 
151  occ_pub_->on_deactivate();
152 
153  // destroy bond connection
154  destroyBond();
155 
156  return nav2_util::CallbackReturn::SUCCESS;
157 }
158 
159 nav2_util::CallbackReturn
160 MapServer::on_cleanup(const rclcpp_lifecycle::State & /*state*/)
161 {
162  RCLCPP_INFO(get_logger(), "Cleaning up");
163 
164  occ_pub_.reset();
165  occ_service_.reset();
166  load_map_service_.reset();
167  map_available_ = false;
168  msg_ = nav_msgs::msg::OccupancyGrid();
169 
170  return nav2_util::CallbackReturn::SUCCESS;
171 }
172 
173 nav2_util::CallbackReturn
174 MapServer::on_shutdown(const rclcpp_lifecycle::State & /*state*/)
175 {
176  RCLCPP_INFO(get_logger(), "Shutting down");
177  return nav2_util::CallbackReturn::SUCCESS;
178 }
179 
181  const std::shared_ptr<rmw_request_id_t>/*request_header*/,
182  const std::shared_ptr<nav_msgs::srv::GetMap::Request>/*request*/,
183  std::shared_ptr<nav_msgs::srv::GetMap::Response> response)
184 {
185  // if not in ACTIVE state, ignore request
186  if (get_current_state().id() != lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE) {
187  RCLCPP_WARN(
188  get_logger(),
189  "Received GetMap request but not in ACTIVE state, ignoring!");
190  return;
191  }
192  RCLCPP_INFO(get_logger(), "Handling GetMap request");
193  response->map = msg_;
194 }
195 
197  const std::shared_ptr<rmw_request_id_t>/*request_header*/,
198  const std::shared_ptr<nav2_msgs::srv::LoadMap::Request> request,
199  std::shared_ptr<nav2_msgs::srv::LoadMap::Response> response)
200 {
201  // if not in ACTIVE state, ignore request
202  if (get_current_state().id() != lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE) {
203  RCLCPP_WARN(
204  get_logger(),
205  "Received LoadMap request but not in ACTIVE state, ignoring!");
206  response->result = response->RESULT_UNDEFINED_FAILURE;
207  return;
208  }
209  RCLCPP_INFO(get_logger(), "Handling LoadMap request");
210  // Load from file
211  if (loadMapResponseFromYaml(request->map_url, response)) {
212  auto occ_grid = std::make_unique<nav_msgs::msg::OccupancyGrid>(msg_);
213  occ_pub_->publish(std::move(occ_grid)); // publish new map
214  }
215 }
216 
218  const std::string & yaml_file,
219  std::shared_ptr<nav2_msgs::srv::LoadMap::Response> response)
220 {
221  switch (loadMapFromYaml(yaml_file, msg_)) {
222  case MAP_DOES_NOT_EXIST:
223  response->result = nav2_msgs::srv::LoadMap::Response::RESULT_MAP_DOES_NOT_EXIST;
224  return false;
225  case INVALID_MAP_METADATA:
226  response->result = nav2_msgs::srv::LoadMap::Response::RESULT_INVALID_MAP_METADATA;
227  return false;
228  case INVALID_MAP_DATA:
229  response->result = nav2_msgs::srv::LoadMap::Response::RESULT_INVALID_MAP_DATA;
230  return false;
231  case LOAD_MAP_SUCCESS:
232  // Correcting msg_ header when it belongs to specific node
233  updateMsgHeader();
234 
235  map_available_ = true;
236  response->map = msg_;
237  response->result = nav2_msgs::srv::LoadMap::Response::RESULT_SUCCESS;
238  }
239 
240  return true;
241 }
242 
244 {
245  msg_.info.map_load_time = now();
246  msg_.header.frame_id = frame_id_;
247  msg_.header.stamp = now();
248 }
249 
250 } // namespace nav2_map_server
251 
252 #include "rclcpp_components/register_node_macro.hpp"
253 
254 // Register the component with class_loader.
255 // This acts as a sort of entry point, allowing the component to be discoverable when its library
256 // is being loaded into a running process.
257 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:37
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:196
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:180
void updateMsgHeader()
Method correcting msg_ header when it belongs to instantiated object.
Definition: map_server.cpp:243
nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State &state) override
Start publishing the map using the latched topic.
Definition: map_server.cpp:129
nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State &state) override
Called when in Shutdown state.
Definition: map_server.cpp:174
nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &state) override
Stops publishing the latched topic.
Definition: map_server.cpp:147
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:217
nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State &state) override
Resets the member variables.
Definition: map_server.cpp:160
void createBond()
Create bond connection to lifecycle manager.
void destroyBond()
Destroy bond connection to lifecycle manager.