35 #include <mrpt_bridge/map.h> 37 #include <mrpt/system/filesystem.h> 38 #include <mrpt/version.h> 39 #if MRPT_VERSION >= 0x199 40 #include <mrpt/config/CConfigFile.h> 41 using namespace mrpt::config;
43 #include <mrpt/utils/CConfigFile.h> 47 #include <mrpt/maps/COccupancyGridMap2D.h> 48 #include <mrpt/maps/CMultiMetricMap.h> 49 using mrpt::maps::CMultiMetricMap;
50 using mrpt::maps::COccupancyGridMap2D;
60 ROS_INFO(
"debug: %s", (debug_ ?
"true" :
"false"));
62 ROS_INFO(
"ini_file: %s", ini_file.c_str());
63 n_param_.
param<std::string>(
"map_file", map_file,
"map.simplemap");
64 ROS_INFO(
"map_file: %s", map_file.c_str());
66 "frame_id",
resp_ros_.map.header.frame_id,
"map");
67 ROS_INFO(
"frame_id: %s",
resp_ros_.map.header.frame_id.c_str());
69 ROS_INFO(
"frequency: %f", frequency_);
73 n_.
advertise<nav_msgs::MapMetaData>(
"map_metadata", 1,
true);
77 if (!mrpt::system::fileExists(ini_file))
79 ROS_ERROR(
"ini_file: %s does not exit", ini_file.c_str());
81 if (!mrpt::system::fileExists(map_file))
83 ROS_ERROR(
"map_file: %s does not exit", map_file.c_str());
85 ASSERT_FILE_EXISTS_(ini_file);
86 CConfigFile config_file;
87 config_file.setFileName(ini_file);
89 mrpt_bridge::MapHdl::loadMap(
90 *
metric_map_, config_file, map_file,
"metricMap", debug_);
92 #if MRPT_VERSION >= 0x199 93 const COccupancyGridMap2D& grid =
96 const COccupancyGridMap2D& grid = *
metric_map_->m_gridMaps[0];
101 "gridMap[0]: %i x %i @ %4.3fm/p, %4.3f, %4.3f, %4.3f, %4.3f\n",
102 grid.getSizeX(), grid.getSizeY(), grid.getResolution(),
103 grid.getXMin(), grid.getYMin(), grid.getXMax(), grid.getYMax());
105 mrpt_bridge::convert(grid,
resp_ros_.map);
108 "msg: %i x %i @ %4.3fm/p, %4.3f, %4.3f, %4.3f, %4.3f\n",
119 nav_msgs::GetMap::Request& req, nav_msgs::GetMap::Response& res)
121 ROS_INFO(
"mapCallback: service requested!\n");
159 int main(
int argc,
char** argv)
162 ros::init(argc, argv,
"mrpt_map_server");
void publish(const boost::shared_ptr< M > &message) const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
nav_msgs::GetMap::Response resp_ros_
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
ROSCPP_DECL void spin(Spinner &spinner)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
boost::shared_ptr< CMultiMetricMap > metric_map_
MapServer(ros::NodeHandle &n)
ros::ServiceServer service_map_
uint32_t getNumSubscribers() const
ros::Publisher pub_map_ros_
int main(int argc, char **argv)
ROSCPP_DECL void spinOnce()
bool mapCallback(nav_msgs::GetMap::Request &req, nav_msgs::GetMap::Response &res)
unsigned long loop_count_
ros::Publisher pub_metadata_