Program Listing for File map_server.hpp
↰ Return to documentation for file (include/nav2_map_server/map_server.hpp
)
// Copyright (c) 2018 Intel Corporation
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#ifndef NAV2_MAP_SERVER__MAP_SERVER_HPP_
#define NAV2_MAP_SERVER__MAP_SERVER_HPP_
#include <string>
#include <memory>
#include <functional>
#include "rclcpp/rclcpp.hpp"
#include "nav2_util/lifecycle_node.hpp"
#include "nav_msgs/msg/occupancy_grid.hpp"
#include "nav_msgs/srv/get_map.hpp"
#include "nav2_msgs/srv/load_map.hpp"
namespace nav2_map_server
{
class MapServer : public nav2_util::LifecycleNode
{
public:
explicit MapServer(const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
~MapServer();
protected:
nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State & state) override;
nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State & state) override;
nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & state) override;
nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State & state) override;
nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override;
bool loadMapResponseFromYaml(
const std::string & yaml_file,
std::shared_ptr<nav2_msgs::srv::LoadMap::Response> response);
void updateMsgHeader();
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);
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);
// The name of the service for getting a map
const std::string service_name_{"map"};
// The name of the service for loading a map
const std::string load_map_service_name_{"load_map"};
// A service to provide the occupancy grid (GetMap) and the message to return
rclcpp::Service<nav_msgs::srv::GetMap>::SharedPtr occ_service_;
// A service to load the occupancy grid from file at run time (LoadMap)
rclcpp::Service<nav2_msgs::srv::LoadMap>::SharedPtr load_map_service_;
// A topic on which the occupancy grid will be published
rclcpp_lifecycle::LifecyclePublisher<nav_msgs::msg::OccupancyGrid>::SharedPtr occ_pub_;
// The frame ID used in the returned OccupancyGrid message
std::string frame_id_;
// The message to publish on the occupancy grid topic
nav_msgs::msg::OccupancyGrid msg_;
// true if msg_ was initialized
bool map_available_;
};
} // namespace nav2_map_server
#endif // NAV2_MAP_SERVER__MAP_SERVER_HPP_