Class MapServer

Inheritance Relationships

Base Type

  • public nav2_util::LifecycleNode

Class Documentation

class MapServer : public nav2_util::LifecycleNode

Parses the map yaml file and creates a service and a publisher that provides occupancy grid.

Public Functions

explicit MapServer(const rclcpp::NodeOptions &options = rclcpp::NodeOptions())

A constructor for nav2_map_server::MapServer.

Parameters:

options – Additional options to control creation of the node.

~MapServer()

A Destructor for nav2_map_server::MapServer.

Protected Functions

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.

Parameters:

state – Lifecycle Node’s state

Returns:

Success or Failure

nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State &state) override

Start publishing the map using the latched topic.

Parameters:

state – Lifecycle Node’s state

Returns:

Success or Failure

nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &state) override

Stops publishing the latched topic.

Parameters:

state – Lifecycle Node’s state

Returns:

Success or Failure

nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State &state) override

Resets the member variables.

Parameters:

state – Lifecycle Node’s state

Returns:

Success or Failure

nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State &state) override

Called when in Shutdown state.

Parameters:

state – Lifecycle Node’s state

Returns:

Success or Failure

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. Update msg_ class variable.

Parameters:
  • yaml_file – name of input YAML file

  • response – Output response with loaded OccupancyGrid map

Returns:

true or false

void updateMsgHeader()

Method correcting msg_ header when it belongs to instantiated object.

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.

Parameters:
  • request_header – Service request header

  • request – Service request

  • response – Service 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)

Map loading service callback.

Parameters:
  • request_header – Service request header

  • request – Service request

  • response – Service response

Protected Attributes

const std::string service_name_ = {"map"}
const std::string load_map_service_name_ = {"load_map"}
rclcpp::Service<nav_msgs::srv::GetMap>::SharedPtr occ_service_
rclcpp::Service<nav2_msgs::srv::LoadMap>::SharedPtr load_map_service_
rclcpp_lifecycle::LifecyclePublisher<nav_msgs::msg::OccupancyGrid>::SharedPtr occ_pub_
std::string frame_id_
nav_msgs::msg::OccupancyGrid msg_
bool map_available_