47 #include "nav2_map_server/map_server.hpp"
55 #include "yaml-cpp/yaml.h"
56 #include "lifecycle_msgs/msg/state.hpp"
57 #include "nav2_map_server/map_io.hpp"
59 using namespace std::chrono_literals;
60 using namespace std::placeholders;
62 namespace nav2_map_server
65 MapServer::MapServer(
const rclcpp::NodeOptions & options)
66 : nav2_util::LifecycleNode(
"map_server",
"", options), map_available_(false)
68 RCLCPP_INFO(get_logger(),
"Creating");
71 declare_parameter(
"yaml_filename", rclcpp::PARAMETER_STRING);
72 declare_parameter(
"topic_name",
"map");
73 declare_parameter(
"frame_id",
"map");
80 nav2_util::CallbackReturn
83 RCLCPP_INFO(get_logger(),
"Configuring");
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();
91 if (!yaml_filename.empty()) {
94 std::shared_ptr<nav2_msgs::srv::LoadMap::Response> rsp =
95 std::make_shared<nav2_msgs::srv::LoadMap::Response>();
98 throw std::runtime_error(
"Failed to load map yaml file: " + yaml_filename);
103 "yaml-filename parameter is empty, set map through '%s'-service",
104 load_map_service_name_.c_str());
108 const std::string service_prefix = get_name() + std::string(
"/");
112 std::shared_ptr<nav2_util::LifecycleNode>>>(
113 service_prefix + std::string(service_name_),
118 occ_pub_ = create_publisher<nav_msgs::msg::OccupancyGrid>(
120 rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable());
124 std::shared_ptr<nav2_util::LifecycleNode>>>(
125 service_prefix + std::string(load_map_service_name_),
129 return nav2_util::CallbackReturn::SUCCESS;
132 nav2_util::CallbackReturn
135 RCLCPP_INFO(get_logger(),
"Activating");
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));
147 return nav2_util::CallbackReturn::SUCCESS;
150 nav2_util::CallbackReturn
153 RCLCPP_INFO(get_logger(),
"Deactivating");
155 occ_pub_->on_deactivate();
160 return nav2_util::CallbackReturn::SUCCESS;
163 nav2_util::CallbackReturn
166 RCLCPP_INFO(get_logger(),
"Cleaning up");
169 occ_service_.reset();
170 load_map_service_.reset();
171 map_available_ =
false;
172 msg_ = nav_msgs::msg::OccupancyGrid();
174 return nav2_util::CallbackReturn::SUCCESS;
177 nav2_util::CallbackReturn
180 RCLCPP_INFO(get_logger(),
"Shutting down");
181 return nav2_util::CallbackReturn::SUCCESS;
185 const std::shared_ptr<rmw_request_id_t>,
186 const std::shared_ptr<nav_msgs::srv::GetMap::Request>,
187 std::shared_ptr<nav_msgs::srv::GetMap::Response> response)
190 if (get_current_state().
id() != lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE) {
193 "Received GetMap request but not in ACTIVE state, ignoring!");
196 RCLCPP_INFO(get_logger(),
"Handling GetMap request");
197 response->map = msg_;
201 const std::shared_ptr<rmw_request_id_t>,
202 const std::shared_ptr<nav2_msgs::srv::LoadMap::Request> request,
203 std::shared_ptr<nav2_msgs::srv::LoadMap::Response> response)
206 if (get_current_state().
id() != lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE) {
209 "Received LoadMap request but not in ACTIVE state, ignoring!");
210 response->result = response->RESULT_UNDEFINED_FAILURE;
213 RCLCPP_INFO(get_logger(),
"Handling LoadMap request");
216 auto occ_grid = std::make_unique<nav_msgs::msg::OccupancyGrid>(msg_);
217 occ_pub_->publish(std::move(occ_grid));
222 const std::string & yaml_file,
223 std::shared_ptr<nav2_msgs::srv::LoadMap::Response> response)
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;
229 case INVALID_MAP_METADATA:
230 response->result = nav2_msgs::srv::LoadMap::Response::RESULT_INVALID_MAP_METADATA;
232 case INVALID_MAP_DATA:
233 response->result = nav2_msgs::srv::LoadMap::Response::RESULT_INVALID_MAP_DATA;
235 case LOAD_MAP_SUCCESS:
239 map_available_ =
true;
240 response->map = msg_;
241 response->result = nav2_msgs::srv::LoadMap::Response::RESULT_SUCCESS;
249 msg_.info.map_load_time = now();
250 msg_.header.frame_id = frame_id_;
251 msg_.header.stamp = now();
256 #include "rclcpp_components/register_node_macro.hpp"
Parses the map yaml file and creates a service and a publisher that provides occupancy grid.
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.
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.
void updateMsgHeader()
Method correcting msg_ header when it belongs to instantiated object.
nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State &state) override
Start publishing the map using the latched topic.
nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State &state) override
Called when in Shutdown state.
nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &state) override
Stops publishing the latched topic.
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.
~MapServer()
A Destructor for nav2_map_server::MapServer.
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....
nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State &state) override
Resets the member variables.
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.