server.cpp
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2020, Locus Robotics
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the copyright holder nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  */
34 
35 #include <boost/filesystem.hpp>
36 #include <ros/ros.h>
38 #include <nav_msgs/MapMetaData.h>
39 #include <nav_msgs/GetMap.h>
42 #include <yaml-cpp/yaml.h>
43 #include <string>
44 
45 class MapServer
46 {
47 public:
48  explicit MapServer(const std::string& filename) : pub_(the_map_)
49  {
50  ros::NodeHandle global_nh, private_nh("~");
51 
52  std::string image_filename;
53 
54  // The following parameters will be overwritten by the ROS parameters (if they exist), or the yaml parameters
55  std::string frame_id = "map";
56  double resolution = 0.05;
57  bool negate = false;
58  double occ_th = 0.65;
59  double free_th = 0.196;
60  std::string mode = "trinary";
61  double origin_x = 0.0;
62  double origin_y = 0.0;
63  std::string occupancy_grid_topic = "map";
64  std::string nav_grid_topic = "static_map";
65 
66  private_nh.param("frame_id", frame_id, frame_id);
67 
68  if (filename.find("yaml") != std::string::npos)
69  {
70  YAML::Node config = YAML::LoadFile(filename.c_str());
71  image_filename = config["image"].as<std::string>();
72  if (image_filename[0] != '/')
73  {
74  boost::filesystem::path yaml_path(filename);
75  boost::filesystem::path image_path = yaml_path.parent_path() / image_filename;
76  image_filename = image_path.string();
77  }
78 
79  if (config["resolution"]) resolution = config["resolution"].as<double>();
80  // Allow for either boolean or integer (0|1)
81  if (config["negate"]) negate = config["negate"].as<bool, int>(0);
82  if (config["occupied_thresh"]) occ_th = config["occupied_thresh"].as<double>();
83  if (config["free_thresh"]) free_th = config["free_thresh"].as<double>();
84  if (config["mode"]) mode = config["mode"].as<std::string>();
85  if (config["origin"])
86  {
87  origin_x = config["origin"][0].as<double>();
88  origin_y = config["origin"][1].as<double>();
89  }
90  }
91  else
92  {
93  image_filename = filename;
94  }
95 
96  // If the parameter exists, use it, otherwise use the previous value
97  private_nh.param("resolution", resolution, resolution);
98  private_nh.param("negate", negate, negate);
99  private_nh.param("occupied_thresh", occ_th, occ_th);
100  private_nh.param("free_thresh", free_th, free_th);
101  private_nh.param("mode", mode, mode);
102  private_nh.param("origin_x", origin_x, origin_x);
103  private_nh.param("origin_y", origin_y, origin_y);
104  private_nh.param("occupancy_grid_topic", occupancy_grid_topic, occupancy_grid_topic);
105  private_nh.param("nav_grid_topic", nav_grid_topic, nav_grid_topic);
106 
107  the_map_ = nav_grid_server::classicLoadMapFromFile(image_filename, resolution, negate, occ_th, free_th, mode);
108  nav_grid::NavGridInfo full_info = the_map_.getInfo();
109  full_info.frame_id = frame_id;
110  full_info.origin_x = origin_x;
111  full_info.origin_y = origin_y;
112  the_map_.setInfo(full_info);
113 
114  // To make sure get a consistent time in simulation
116  ROS_INFO_NAMED("MapServer", "Read a %d X %d map @ %.3lf m/cell",
118 
120 
121  pub_.init(global_nh, nav_grid_topic, occupancy_grid_topic, "", false);
123  pub_.publish();
124 
125  // Service provider
126  service_ = global_nh.advertiseService("static_map", &MapServer::mapCallback, this);
127 
128  // Latched publisher for metadata
129  metadata_pub_ = global_nh.advertise<nav_msgs::MapMetaData>("map_metadata", 1, true);
131  }
132 
133 private:
137 
139  nav_msgs::OccupancyGrid grid_version_;
140 
142  bool mapCallback(nav_msgs::GetMap::Request &req, nav_msgs::GetMap::Response &res)
143  {
144  // request is empty; we ignore it
145  res.map = grid_version_;
146  ROS_INFO_NAMED("MapServer", "Sending map");
147 
148  return true;
149  }
150 };
151 
152 int main(int argc, char **argv)
153 {
154  ros::init(argc, argv, "map_server", ros::init_options::AnonymousName);
155  if (argc != 2)
156  {
157  ROS_ERROR_NAMED("MapServer", "USAGE: server (map.yaml|map_image)");
158  ROS_ERROR_NAMED("MapServer", " map.yaml: map description file");
159  ROS_ERROR_NAMED("MapServer", " map_image: any valid image file");
160  exit(EXIT_FAILURE);
161  }
162 
163  try
164  {
165  MapServer ms(argv[1]);
166  ros::spin();
167  }
168  catch(std::runtime_error& e)
169  {
170  ROS_ERROR_NAMED("MapServer", "exception: %s", e.what());
171  exit(EXIT_FAILURE);
172  }
173 
174  return 0;
175 }
ros::init_options::AnonymousName
AnonymousName
ros::Publisher
MapServer::pub_
nav_grid_pub_sub::NavGridPublisher pub_
Definition: server.cpp:134
main
int main(int argc, char **argv)
Definition: server.cpp:152
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros.h
nav_grid::NavGrid::getInfo
NavGridInfo getInfo() const
nav_grid::VectorNavGrid::setInfo
void setInfo(const NavGridInfo &new_info) override
nav_grid::NavGridInfo::origin_x
double origin_x
ros::NodeHandle::advertiseService
ServiceServer advertiseService(AdvertiseServiceOptions &ops)
ROS_ERROR_NAMED
#define ROS_ERROR_NAMED(name,...)
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
ros::ServiceServer
GenericGridPublisher< unsigned char, nav_2d_msgs::NavGridOfChars, nav_2d_msgs::NavGridOfCharsUpdate >::init
void init(ros::NodeHandle &nh, const std::string &nav_grid_topic="grid", const std::string &occupancy_grid_topic="costmap", const std::string &update_area_topic="update_area", bool publish_updates=true, ros::Duration full_publish_cycle=ros::Duration(0), ros::Duration update_publish_cycle=ros::Duration(0))
MapServer
Definition: server.cpp:45
MapServer::MapServer
MapServer(const std::string &filename)
Definition: server.cpp:48
MapServer::metadata_pub_
ros::Publisher metadata_pub_
Definition: server.cpp:135
MapServer::service_
ros::ServiceServer service_
Definition: server.cpp:136
ROS_INFO_NAMED
#define ROS_INFO_NAMED(name,...)
nav_grid_pub_sub::toOccupancyGrid
nav_msgs::OccupancyGrid toOccupancyGrid(const nav_grid::NavGrid< NumericType > &grid, const NumericType min_value, const NumericType max_value, const NumericType unknown_value, const ros::Time &stamp=ros::Time(0))
nav_grid_pub_sub::NavGridPublisher::setCostInterpretation
void setCostInterpretation(const std::vector< unsigned char > &cost_interpretation_table)
nav_grid_publisher.h
occ_grid_message_utils.h
MapServer::the_map_
nav_grid::VectorNavGrid< unsigned char > the_map_
Definition: server.cpp:138
nav_grid::NavGridInfo::frame_id
std::string frame_id
nav_grid::NavGrid::getWidth
unsigned int getWidth() const
nav_grid::NavGridInfo
nav_grid::NavGrid::getHeight
unsigned int getHeight() const
nav_grid_server::classicLoadMapFromFile
nav_grid::VectorNavGrid< unsigned char > classicLoadMapFromFile(const std::string &filepath, const double resolution, const bool negate_param, const double occ_th, const double free_th, const std::string &mode)
Load an image from a file, mimicking map_server's loading style Resulting values are [0,...
Definition: image_loader.cpp:161
MapServer::grid_version_
nav_msgs::OccupancyGrid grid_version_
Definition: server.cpp:139
nav_grid::NavGrid::getResolution
double getResolution() const
MapServer::mapCallback
bool mapCallback(nav_msgs::GetMap::Request &req, nav_msgs::GetMap::Response &res)
Definition: server.cpp:142
ros::Time::waitForValid
static bool waitForValid()
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
ros::spin
ROSCPP_DECL void spin()
nav_grid_pub_sub::NavGridPublisher
nav_grid::NavGridInfo::origin_y
double origin_y
image_loader.h
GenericGridPublisher< unsigned char, nav_2d_msgs::NavGridOfChars, nav_2d_msgs::NavGridOfCharsUpdate >::publish
void publish()
nav_grid_pub_sub::RAW
static std::vector< unsigned char > RAW(0)
nav_grid::VectorNavGrid< unsigned char >
ros::NodeHandle
ros::Time::now
static Time now()


nav_grid_server
Author(s):
autogenerated on Sun May 18 2025 02:47:47