40 m_enable_publish_ros_map =
false;
41 m_enable_subscribe_ros_map =
false;
58 if (Property::copyPortable(b, the_map))
61 auto it = m_maps_storage.find(map_name);
62 if (it == m_maps_storage.end())
65 m_maps_storage[map_name] = the_map;
72 m_maps_storage[map_name] = the_map;
81 yCError(MAP2DSERVER) <<
"Error in copyPortable";
87 auto it = m_maps_storage.find(name);
88 if (it != m_maps_storage.end())
93 Property::copyPortable(it->second, mapbot);
99 yCError(MAP2DSERVER) <<
"Map" << name <<
"not found";
107 for (
auto& it : m_maps_storage)
115 size_t rem = m_maps_storage.erase(name);
118 yCError(MAP2DSERVER) <<
"Map not found";
130 m_maps_storage.clear();
139 if (saveMaps(mapfile))
146 yCError(MAP2DSERVER,
"Unable to save collection");
154 if (save_locations_and_areas(locfile))
161 yCError(MAP2DSERVER,
"Unable to save collection");
168 yCError(MAP2DSERVER,
"Parser error");
178 if (loadMaps(mapfile))
185 yCError(MAP2DSERVER,
"Unable to load collection");
193 if (load_locations_and_areas(locfile))
200 yCError(MAP2DSERVER,
"Unable to load collection");
207 yCError(MAP2DSERVER,
"Parser error");
214 yCError(MAP2DSERVER,
"Invalid vocab received in Map2DServer");
229 std::map<std::string, Map2DLocation>::iterator it;
230 for (it = m_locations_storage.begin(); it != m_locations_storage.end(); ++it)
234 yCInfo(MAP2DSERVER) <<
"The following locations are currently stored in the server:" << l.
toString();
244 std::map<std::string, Map2DArea>::iterator it;
245 for (it = m_areas_storage.begin(); it != m_areas_storage.end(); ++it)
249 yCInfo(MAP2DSERVER) <<
"The following areas are currently stored in the server:" << l.
toString();
259 std::map<std::string, Map2DPath>::iterator it;
260 for (it = m_paths_storage.begin(); it != m_paths_storage.end(); ++it)
264 yCInfo(MAP2DSERVER) <<
"The following paths are currently stored in the server: " << l.
toString();
269 m_locations_storage.clear();
270 yCInfo(MAP2DSERVER) <<
"All locations deleted";
276 m_areas_storage.clear();
277 yCInfo(MAP2DSERVER) <<
"All areas deleted";
283 m_paths_storage.clear();
284 yCInfo(MAP2DSERVER) <<
"All paths deleted";
290 for (
auto it = m_maps_storage.begin(); it != m_maps_storage.end(); it++)
292 it->second.clearMapTemporaryFlags();
294 yCInfo(MAP2DSERVER) <<
"Temporary flags deleted from all maps";
302 auto it = m_maps_storage.find(name);
303 if (it != m_maps_storage.end())
305 yCInfo(MAP2DSERVER) <<
"Temporary flags cleaned" << name;
306 it->second.clearMapTemporaryFlags();
311 yCError(MAP2DSERVER,
"User requested an invalid map name");
320 std::map<std::string, Map2DLocation>::iterator it;
321 it = m_locations_storage.find(name);
322 if (it != m_locations_storage.end())
324 yCInfo(MAP2DSERVER) <<
"Deleted location" << name;
325 m_locations_storage.erase(it);
330 yCError(MAP2DSERVER,
"User requested an invalid location name");
339 std::map<std::string, Map2DPath>::iterator it;
340 it = m_paths_storage.find(name);
341 if (it != m_paths_storage.end())
343 yCInfo(MAP2DSERVER) <<
"Deleted path" << name;
344 m_paths_storage.erase(it);
349 yCError(MAP2DSERVER,
"User requested an invalid location name");
360 std::map<std::string, Map2DLocation>::iterator orig_it;
361 orig_it = m_locations_storage.find(orig_name);
362 std::map<std::string, Map2DLocation>::iterator new_it;
363 new_it = m_locations_storage.find(new_name);
365 if (orig_it != m_locations_storage.end() &&
366 new_it == m_locations_storage.end())
368 yCInfo(MAP2DSERVER) <<
"Location:" << orig_name <<
"renamed to:" << new_name;
369 auto loc = orig_it->second;
370 m_locations_storage.erase(orig_it);
371 m_locations_storage.insert(std::pair<std::string, Map2DLocation>(new_name, loc));
376 yCError(MAP2DSERVER,
"User requested an invalid rename operation");
386 std::map<std::string, Map2DArea>::iterator orig_it;
387 orig_it = m_areas_storage.find(orig_name);
388 std::map<std::string, Map2DArea>::iterator new_it;
389 new_it = m_areas_storage.find(new_name);
391 if (orig_it != m_areas_storage.end() &&
392 new_it == m_areas_storage.end())
394 yCInfo(MAP2DSERVER) <<
"Area:" << orig_name <<
"renamed to:" << new_name;
395 auto area = orig_it->second;
396 m_areas_storage.erase(orig_it);
397 m_areas_storage.insert(std::pair<std::string, Map2DArea>(new_name,area));
402 yCError(MAP2DSERVER,
"User requested an invalid rename operation");
412 std::map<std::string, Map2DPath>::iterator orig_it;
413 orig_it = m_paths_storage.find(orig_name);
414 std::map<std::string, Map2DPath>::iterator new_it;
415 new_it = m_paths_storage.find(new_name);
417 if (orig_it != m_paths_storage.end() &&
418 new_it == m_paths_storage.end())
420 yCInfo(MAP2DSERVER) <<
"Path:" << orig_name <<
"renamed to:" << new_name;
421 auto area = orig_it->second;
422 m_paths_storage.erase(orig_it);
423 m_paths_storage.insert(std::pair<std::string, Map2DPath>(new_name, area));
428 yCError(MAP2DSERVER,
"User requested an invalid rename operation");
437 std::map<std::string, Map2DArea>::iterator it;
438 it = m_areas_storage.find(name);
439 if (it != m_areas_storage.end())
441 yCInfo(MAP2DSERVER) <<
"Deleted area" << name;
442 m_areas_storage.erase(it);
447 yCError(MAP2DSERVER,
"User requested an invalid area name");
457 std::map<std::string, Map2DLocation>::iterator it;
458 it = m_locations_storage.find(name);
459 if (it != m_locations_storage.end())
463 yCInfo(MAP2DSERVER) <<
"Retrieved location" << name <<
"at" << loc.
toString();
472 yCError(MAP2DSERVER,
"User requested an invalid location name");
480 std::map<std::string, Map2DArea>::iterator it;
481 it = m_areas_storage.find(area_name);
482 if (it != m_areas_storage.end())
487 if (Property::copyPortable(areatemp, areabot) ==
false)
489 yCError(MAP2DSERVER) <<
"VOCAB_NAV_GET_X VOCAB_NAV_AREA failed copyPortable()";
494 yCInfo(MAP2DSERVER) <<
"Retrieved area" << area_name <<
"at" << area.
toString();
498 Property::copyPortable(areatemp, areabot);
504 yCError(MAP2DSERVER,
"User requested an invalid area name");
512 std::map<std::string, Map2DPath>::iterator it;
513 it = m_paths_storage.find(path_name);
514 if (it != m_paths_storage.end())
519 if (Property::copyPortable(pathtemp, pathbot) ==
false)
521 yCError(MAP2DSERVER) <<
"VOCAB_NAV_GET_X VOCAB_NAV_PATH failed copyPortable()";
526 yCInfo(MAP2DSERVER) <<
"Retrieved path" << path_name <<
"at" << path.
toString();
530 Property::copyPortable(pathtemp, pathbot);
536 yCError(MAP2DSERVER,
"User requested an invalid path name");
550 m_locations_storage.insert(std::pair<std::string, Map2DLocation>(name, location));
551 yCInfo(MAP2DSERVER) <<
"Added location" << name <<
"at" << location.
toString();
561 if (Property::copyPortable(b, area))
563 m_areas_storage.insert(std::pair<std::string, Map2DArea>(area_name, area));
564 yCInfo(MAP2DSERVER) <<
"Added area" << area_name <<
"at" << area.
toString();
569 yCError(MAP2DSERVER) <<
"VOCAB_NAV_STORE_X VOCAB_NAV_AREA failed copyPortable()";
580 if (Property::copyPortable(b, path))
582 m_paths_storage.insert(std::pair<std::string, Map2DPath>(path_name, path));
583 yCInfo(MAP2DSERVER) <<
"Added path" << path_name <<
"at" << path.
toString();
588 yCError(MAP2DSERVER) <<
"VOCAB_NAV_STORE_X VOCAB_NAV_PATH failed copyPortable()";
618 out.
addString(
"save_locations&areas failed");
629 out.
addString(
"load_locations&areas failed");
634 std::map<std::string, Map2DLocation>::iterator it;
635 for (it = m_locations_storage.begin(); it != m_locations_storage.end(); ++it)
642 std::map<std::string, Map2DArea>::iterator it;
643 for (it = m_areas_storage.begin(); it != m_areas_storage.end(); ++it)
650 std::map<std::string, Map2DPath>::iterator it;
651 for (it = m_paths_storage.begin(); it != m_paths_storage.end(); ++it)
681 std::string map_file = in.
get(2).
asString() +
".map";
682 auto p = m_maps_storage.find(map_name);
683 if (p == m_maps_storage.end())
685 out.
addString(
"save_map failed: map " + map_name +
" not found");
689 bool b = p->second.saveToFile(map_file);
692 out.
addString(map_file +
" successfully saved");
696 out.
addString(
"save_map failed: unable to save " + map_name +
" to "+ map_file);
707 auto p = m_maps_storage.find(map_name);
708 if (p == m_maps_storage.end())
710 m_maps_storage[map_name] = map;
725 std::map<std::string, MapGrid2D>::iterator it;
726 for (it = m_maps_storage.begin(); it != m_maps_storage.end(); ++it)
731 else if(in.
get(0).
asString() ==
"clear_all_locations")
733 m_locations_storage.clear();
736 else if (in.
get(0).
asString() ==
"clear_all_areas")
738 m_areas_storage.clear();
741 else if (in.
get(0).
asString() ==
"clear_all_paths")
743 m_paths_storage.clear();
748 m_maps_storage.clear();
751 else if (in.
get(0).
asString() ==
"enable_maps_compression")
754 for (
auto it=m_maps_storage.begin(); it!= m_maps_storage.end(); it++)
755 {b &= it->second.enable_map_compression_over_network(in.
get(1).
asBool());}
757 else {out.
addString(
"failed to set compression mode");}
762 out.
addString(
"'save_locations&areas <full path filename>' to save locations and areas on a file");
763 out.
addString(
"'load_locations&areas <full path filename>' to load locations and areas from a file");
764 out.
addString(
"'list_locations' to view a list of all stored locations");
765 out.
addString(
"'list_areas' to view a list of all stored areas");
766 out.
addString(
"'list_paths' to view a list of all stored paths");
767 out.
addString(
"'clear_all_locations' to clear all stored locations");
768 out.
addString(
"'clear_all_areas' to clear all stored areas");
769 out.
addString(
"'clear_all_paths' to clear all stored paths");
770 out.
addString(
"'save_maps <full path>' to save a map collection to a folder");
771 out.
addString(
"'load_maps <full path>' to load a map collection from a folder");
772 out.
addString(
"'save_map <map_name> <full path>' to save a single map");
773 out.
addString(
"'load_map <full path>' to load a single map");
774 out.
addString(
"'list_maps' to view a list of all stored maps");
775 out.
addString(
"'clear_all_maps' to clear all stored maps");
776 out.
addString(
"'enable_maps_compression <0/1>' to set the map transmission mode");
780 out.
addString(
"request not understood, call 'help' to see a list of available commands");
788 std::lock_guard<std::mutex> lock(m_mutex);
791 bool ok = in.
read(connection);
799 parse_string_command(in, out);
804 parse_vocab_command(in, out);
808 if (returnToSender !=
nullptr)
810 out.
write(*returnToSender);
814 yCError(MAP2DSERVER) <<
"Invalid return to sender";
821 if (m_maps_storage.size() == 0)
823 yCError(MAP2DSERVER) <<
"Map storage is empty";
827 file.open(mapsfile.c_str());
830 yCError(MAP2DSERVER) <<
"Sorry unable to open" << mapsfile;
834 for (
auto& it : m_maps_storage)
836 std::string map_filename = it.first +
".map";
838 file << map_filename;
840 ret &= it.second.saveToFile(map_filename);
850 file.open(mapsfile.c_str());
853 yCError(MAP2DSERVER) <<
"loadMaps() Unable to open:" << mapsfile;
860 std::getline(file,
buffer);
861 std::istringstream iss(
buffer);
866 if (dummy ==
"mapfile:")
868 std::string mapfilename;
872 std::string mapfilenameWithPath = m_rf_mapCollection.findFile(mapfilename);
878 auto p = m_maps_storage.find(map_name);
879 if (p == m_maps_storage.end())
881 if (option ==
"crop") {
882 map.
crop(-1, -1, -1, -1);
884 m_maps_storage[map_name] = map;
888 yCError(MAP2DSERVER) <<
"A map with the same name '" << map_name <<
"'was found, skipping...";
894 yCError(MAP2DSERVER) <<
"Problems opening map file" << mapfilenameWithPath;
900 yCError(MAP2DSERVER) <<
"Invalid syntax, missing mapfile tag";
910 yCWarning(MAP2DSERVER) <<
"The 'map2DServer' device is deprecated in favour of 'map2D_nws_yarp'.";
911 yCWarning(MAP2DSERVER) <<
"The old device is no longer supported, and it will be deprecated in YARP 3.6 and removed in YARP 4.";
912 yCWarning(MAP2DSERVER) <<
"Please update your scripts.";
917 std::string collection_file_name=
"maps_collection.ini";
918 std::string locations_file_name=
"locations.ini";
919 if (config.
check(
"mapCollectionFile"))
921 collection_file_name= config.
find(
"mapCollectionFile").
asString();
924 if (config.
check(
"mapCollectionContext"))
926 std::string collection_context_name= config.
find(
"mapCollectionContext").
asString();
927 m_rf_mapCollection.setDefaultContext(collection_context_name.c_str());
928 std::string collection_file_with_path = m_rf_mapCollection.findFile(collection_file_name);
929 std::string locations_file_with_path = m_rf_mapCollection.findFile(locations_file_name);
931 if (locations_file_with_path==
"")
933 yCWarning(MAP2DSERVER) <<
"Unable to find file:" << locations_file_with_path <<
"within the specified context:" << collection_context_name;
937 bool ret = load_locations_and_areas(locations_file_with_path);
938 if (
ret) {
yCInfo(MAP2DSERVER) <<
"Location file" << locations_file_with_path <<
"successfully loaded."; }
939 else {
yCError(MAP2DSERVER) <<
"Problems opening file" << locations_file_with_path; }
942 if (collection_file_with_path==
"")
944 yCWarning(MAP2DSERVER) <<
"Unable to find file:" << collection_file_name <<
"within the specified context:" << collection_context_name;
948 if (loadMaps(collection_file_with_path))
950 yCInfo(MAP2DSERVER) <<
"Map collection file:" << collection_file_with_path <<
"successfully loaded.";
951 if (m_maps_storage.size() > 0)
953 yCInfo(MAP2DSERVER) <<
"Available maps are:";
954 for (
auto& it : m_maps_storage)
956 yCInfo(MAP2DSERVER) << it.first;
961 yCInfo(MAP2DSERVER) <<
"No maps available";
963 if (m_locations_storage.size() > 0)
965 yCInfo(MAP2DSERVER) <<
"Available Locations are:";
966 for (
auto& it : m_locations_storage)
968 yCInfo(MAP2DSERVER) << it.first;
973 yCInfo(MAP2DSERVER) <<
"No locations available";
976 if (m_areas_storage.size() > 0)
978 yCInfo(MAP2DSERVER) <<
"Available areas are:";
979 for (
auto& it : m_areas_storage)
981 yCInfo(MAP2DSERVER) << it.first;
986 yCInfo(MAP2DSERVER) <<
"No areas available";
991 yCError(MAP2DSERVER) <<
"Unable to load map collection file:" << collection_file_with_path;
997 if (!config.
check(
"name"))
999 m_rpcPortName =
"/mapServer/rpc";
1007 if (!m_rpcPort.open(m_rpcPortName))
1009 yCError(MAP2DSERVER,
"Failed to open port %s", m_rpcPortName.c_str());
1012 m_rpcPort.setReader(*
this);
1015 if (config.
check(
"ROS"))
1017 yCInfo(MAP2DSERVER,
"Configuring ROS params");
1019 if (ROS_config.
check(
"enable_ros_publisher") ==
false)
1021 yCError(MAP2DSERVER) <<
"Missing 'enable_ros_publisher' in ROS group";
1024 if (ROS_config.
find(
"enable_ros_publisher").
asInt32() == 1 || ROS_config.
find(
"enable_ros_publisher").
asString() ==
"true")
1026 m_enable_publish_ros_map =
true;
1027 yCInfo(MAP2DSERVER) <<
"Enabled ROS publisher";
1029 if (ROS_config.
check(
"enable_ros_subscriber") ==
false)
1031 yCError(MAP2DSERVER) <<
"Missing 'enable_ros_subscriber' in ROS group";
1034 if (ROS_config.
find(
"enable_ros_subscriber").
asInt32() == 1 || ROS_config.
find(
"enable_ros_subscriber").
asString() ==
"true")
1036 m_enable_subscribe_ros_map =
true;
1037 yCInfo(MAP2DSERVER) <<
"Enabled ROS subscriber";
1040 if (m_enable_subscribe_ros_map || m_enable_publish_ros_map)
1042 if (m_rosNode ==
nullptr)
1046 if (m_enable_publish_ros_map && !m_rosPublisherPort_map.topic(
ROSTOPICNAME_MAP))
1048 yCError(MAP2DSERVER) <<
"Unable to publish to" <<
ROSTOPICNAME_MAP <<
"topic, check your YARP-ROS network configuration";
1057 if (m_enable_subscribe_ros_map && !m_rosSubscriberPort_map.topic(
ROSTOPICNAME_MAP))
1059 yCError(MAP2DSERVER) <<
"Unable to subscribe to " <<
ROSTOPICNAME_MAP <<
" topic, check your YARP-ROS network configuration";
1067 m_rosSubscriberPort_map.setStrict();
1068 m_rosSubscriberPort_metamap.setStrict();
1081 map_ros = m_rosSubscriberPort_map.
read(
true);
1082 metamap_ros = m_rosSubscriberPort_metamap.
read(
true);
1083 if (map_ros!=
nullptr && metamap_ros!=
nullptr)
1085 yCInfo(MAP2DSERVER) <<
"Received map for ROS";
1086 std::string map_name =
"ros_map";
1097 double orig_angle = vec[2];
1099 for (
size_t y = 0; y < map_ros->
info.
height; y++) {
1100 for (
size_t x=0; x< map_ros->
info.
width; x++)
1106 if (occ >= 0 && occ <= 70) {
1107 map.
setMapFlag(cell, MapGrid2D::MAP_CELL_FREE);
1108 }
else if (occ >= 71 && occ <= 100) {
1109 map.
setMapFlag(cell, MapGrid2D::MAP_CELL_WALL);
1111 map.
setMapFlag(cell, MapGrid2D::MAP_CELL_UNKNOWN);
1115 auto p = m_maps_storage.find(map_name);
1116 if (p == m_maps_storage.end())
1118 yCInfo(MAP2DSERVER) <<
"Added map "<< map_name <<
" to mapServer";
1119 m_maps_storage[map_name] = map;
1127 yCTrace(MAP2DSERVER,
"Close");
1128 if (m_enable_publish_ros_map)
1130 m_rosPublisherPort_map.interrupt();
1131 m_rosPublisherPort_metamap.interrupt();
1132 m_rosPublisherPort_map.close();
1133 m_rosPublisherPort_metamap.close();
1135 if (m_enable_subscribe_ros_map)
1137 m_rosSubscriberPort_map.interrupt();
1138 m_rosSubscriberPort_metamap.interrupt();
1139 m_rosSubscriberPort_map.close();
1140 m_rosSubscriberPort_metamap.close();
1145 bool Map2DServer::priv_load_locations_and_areas_v1(std::ifstream& file)
1148 std::getline(file,
buffer);
1149 if (
buffer !=
"Locations:")
1151 yCError(MAP2DSERVER) <<
"Unable to parse Locations section!";
1157 std::getline(file,
buffer);
1158 if (
buffer ==
"Areas:") {
1163 yCError(MAP2DSERVER) <<
"Unexpected End Of File";
1168 size_t bot_size = b.
size();
1171 yCError(MAP2DSERVER) <<
"Unable to parse contents of Areas section!";
1180 m_locations_storage[name] = location;
1185 yCError(MAP2DSERVER) <<
"Unable to parse Areas section!";
1192 std::getline(file,
buffer);
1199 size_t bot_size = b.
size();
1203 if (area_size <= 0 || bot_size != area_size * 2 + 3)
1205 yCError(MAP2DSERVER) <<
"Unable to parse contents of Areas section!";
1208 for (
size_t ai = 3; ai < bot_size; ai += 2)
1214 m_areas_storage[name] = area;
1219 bool Map2DServer::priv_load_locations_and_areas_v2(std::ifstream& file)
1222 std::getline(file,
buffer);
1223 if (
buffer !=
"Locations:")
1225 yCError(MAP2DSERVER) <<
"Unable to parse Locations section!";
1231 std::getline(file,
buffer);
1232 if (
buffer ==
"Areas:") {
1237 yCError(MAP2DSERVER) <<
"Unexpected End Of File";
1242 size_t bot_size = b.
size();
1245 yCError(MAP2DSERVER) <<
"Unable to parse contents of Areas section!";
1254 m_locations_storage[name] = location;
1259 yCError(MAP2DSERVER) <<
"Unable to parse Areas section!";
1266 std::getline(file,
buffer);
1267 if (
buffer ==
"Paths:") {
1276 size_t bot_size = b.
size();
1280 if (area_size <= 0 || bot_size != area_size * 2 + 3)
1282 yCError(MAP2DSERVER) <<
"Unable to parse contents of Areas section!";
1285 for (
size_t ai = 3; ai < bot_size; ai += 2)
1291 m_areas_storage[name] = area;
1296 yCError(MAP2DSERVER) <<
"Unable to parse Paths section!";
1303 std::getline(file,
buffer);
1310 size_t bot_size = b.
size();
1319 if (ll && ll->
size() == 4)
1330 yCError(MAP2DSERVER) <<
"Unable to parse contents of Paths section!";
1341 m_paths_storage[name] = path;
1350 file.open (locations_file.c_str());
1354 yCError(MAP2DSERVER) <<
"Unable to open" << locations_file <<
"locations file.";
1360 std::getline(file,
buffer);
1361 if (
buffer !=
"Version:")
1363 yCError(MAP2DSERVER) <<
"Unable to parse Version section!";
1367 std::getline(file,
buffer);
1368 int version = atoi(
buffer.c_str());
1372 if (!priv_load_locations_and_areas_v1(file))
1374 yCError(MAP2DSERVER) <<
"Call to load_locations_and_areas_v1 failed";
1379 else if (version == 2)
1381 if (!priv_load_locations_and_areas_v2(file))
1383 yCError(MAP2DSERVER) <<
"Call to load_locations_and_areas_v2 failed";
1390 yCError(MAP2DSERVER) <<
"Only versions 1,2 supported!";
1397 yCDebug(MAP2DSERVER) <<
"Locations file" << locations_file <<
"loaded, "
1398 << m_locations_storage.size() <<
"locations and "
1399 << m_areas_storage.size() <<
" areas and "
1400 << m_paths_storage.size() <<
" paths available";
1407 file.open (locations_file.c_str());
1411 yCError(MAP2DSERVER) <<
"Unable to open" << locations_file <<
"locations file.";
1420 file <<
"Version:\n";
1424 file <<
"Locations:\n";
1425 std::map<std::string, Map2DLocation>::iterator it;
1426 for (it = m_locations_storage.begin(); it != m_locations_storage.end(); ++it)
1429 file << it->first << s << loc.
map_id << s << loc.
x << s << loc.
y << s << loc.
theta <<
"\n";
1435 std::map<std::string, Map2DArea>::iterator it2;
1436 for (it2 = m_areas_storage.begin(); it2 != m_areas_storage.end(); ++it2)
1439 file << it2->first << s << area.
map_id << s << area.
points.size() << s;
1440 for (
size_t i = 0; i < area.
points.size(); i++)
1442 file << area.
points[i].x << s;
1443 file << area.
points[i].y << s;
1451 std::map<std::string, Map2DPath>::iterator it3;
1452 for (it3 = m_paths_storage.begin(); it3 != m_paths_storage.end(); ++it3)
1454 file << it3->first <<
" ";
1455 for (
size_t i=0; i<it3->second.size(); i++)
1457 loc = it3->second[i];
1458 file <<
"( " <<loc.
map_id << s << loc.
x << s << loc.
y << s << loc.
theta <<
") ";
1465 yCDebug(MAP2DSERVER) <<
"Locations file" << locations_file <<
"saved.";
1469 bool Map2DServer::updateVizMarkers()
1477 time = (uint64_t)(yarpTimeStamp * 1000000000UL);
1478 nsec_part = (time % 1000000000UL);
1479 sec_part = (time / 1000000000UL);
1480 if (sec_part > std::numeric_limits<unsigned int>::max())
1482 yCWarning(MAP2DSERVER) <<
"Timestamp exceeded the 64 bit representation, resetting it to 0";
1494 std::map<std::string, Map2DLocation>::iterator it;
1496 for (it = m_locations_storage.begin(); it != m_locations_storage.end(); ++it, ++count)
1500 rpy[2] = it->second.theta / 180 * 3.14159265359;
1508 marker.
ns =
"my_namespace";
1527 marker.
text = it->first;
1528 markers.
markers.push_back(marker);
1531 m_rosPublisherPort_markers.write();
constexpr yarp::conf::vocab32_t VOCAB_OK
constexpr yarp::conf::vocab32_t VOCAB_ERR
constexpr yarp::conf::vocab32_t VOCAB_NAV_DELETE_X
constexpr yarp::conf::vocab32_t VOCAB_INAVIGATION
constexpr yarp::conf::vocab32_t VOCAB_NAV_GET_LIST_X
constexpr yarp::conf::vocab32_t VOCAB_NAV_AREA
constexpr yarp::conf::vocab32_t VOCAB_NAV_STORE_X
constexpr yarp::conf::vocab32_t VOCAB_NAV_GET_X
constexpr yarp::conf::vocab32_t VOCAB_NAV_RENAME_X
constexpr yarp::conf::vocab32_t VOCAB_NAV_LOCATION
constexpr yarp::conf::vocab32_t VOCAB_NAV_TEMPORARY_FLAGS
constexpr yarp::conf::vocab32_t VOCAB_NAV_CLEARALL_X
constexpr yarp::conf::vocab32_t VOCAB_NAV_PATH
constexpr yarp::conf::vocab32_t VOCAB_IMAP_LOAD_X
constexpr yarp::conf::vocab32_t VOCAB_IMAP_OK
constexpr yarp::conf::vocab32_t VOCAB_IMAP_SAVE_X
constexpr yarp::conf::vocab32_t VOCAB_IMAP
constexpr yarp::conf::vocab32_t VOCAB_IMAP_GET_MAP
constexpr yarp::conf::vocab32_t VOCAB_IMAP_SET_MAP
constexpr yarp::conf::vocab32_t VOCAB_IMAP_LOCATIONS_COLLECTION
constexpr yarp::conf::vocab32_t VOCAB_IMAP_MAPS_COLLECTION
constexpr yarp::conf::vocab32_t VOCAB_IMAP_CLEAR_ALL_MAPS
constexpr yarp::conf::vocab32_t VOCAB_IMAP_ERROR
constexpr yarp::conf::vocab32_t VOCAB_IMAP_REMOVE
constexpr yarp::conf::vocab32_t VOCAB_IMAP_GET_NAMES
#define ROSTOPICNAME_MAPMETADATA
bool close() override
Close the DeviceDriver.
Map2DServer()
Map2DServer.
bool loadMaps(std::string filename)
bool saveMaps(std::string filename)
bool open(yarp::os::Searchable ¶ms) override
Open the DeviceDriver.
bool load_locations_and_areas(std::string locations_file)
bool save_locations_and_areas(std::string locations_file)
std::string toString() const
Returns text representation of the area.
std::vector< yarp::math::Vec2D< double > > points
void push_back(yarp::dev::Nav2D::Map2DLocation loc)
Inserts a new location into the path @loc the location to be inserted.
std::string toString() const
Returns text representation of the path.
bool setResolution(double resolution)
Sets the resolution of the map, i.e.
bool setOrigin(double x, double y, double theta)
Sets the origin of the map reference frame (according to ROS convention)
std::string getMapName() const
Retrieves the map name.
bool setSize_in_cells(size_t x, size_t y)
Sets the size of the map in cells.
bool setMapName(std::string map_name)
Sets the map name.
bool setMapFlag(XYCell cell, map_flags flag)
Set the flag of a specific cell of the map.
bool crop(int left, int top, int right, int bottom)
Modifies the map, cropping pixels at the boundaries.
bool setOccupancyData(XYCell cell, double occupancy)
Set the occupancy data of a specific cell of the map.
bool loadFromFile(std::string map_filename)
Loads a yarp map file from disk.
void fromRotationMatrix(const yarp::sig::Matrix &R)
Converts a rotation matrix to a quaternion.
yarp::sig::Matrix toRotationMatrix4x4() const
Converts a quaternion to a rotation matrix.
A simple collection of objects that can be described and transmitted in a portable way.
void addVocab32(yarp::conf::vocab32_t x)
Places a vocabulary item in the bottle, at the end of the list.
void fromString(const std::string &text)
Initializes bottle from a string.
Bottle & addList()
Places an empty nested list in the bottle, at the end of the list.
size_type size() const
Gets the number of elements in the bottle.
bool read(ConnectionReader &reader) override
Set the bottle's value based on input from a network connection.
void addFloat64(yarp::conf::float64_t x)
Places a 64-bit floating point number in the bottle, at the end of the list.
Value & get(size_type index) const
Reads a Value v from a certain part of the list.
bool check(const std::string &key) const override
Check if there exists a property of the given name.
void clear()
Empties the bottle of any objects it contains.
bool write(ConnectionWriter &writer) const override
Output a representation of the bottle to a network connection.
void addString(const char *str)
Places a string in the bottle, at the end of the list.
std::string toString() const override
Gives a human-readable textual representation of the bottle.
Value & find(const std::string &key) const override
Gets a value corresponding to a given keyword.
An interface for reading from a network connection.
virtual ConnectionWriter * getWriter()=0
Gets a way to reply to the message, if possible.
An interface for writing to a network connection.
A class for storing options and configuration information.
void fromString(const std::string &txt, bool wipe=true)
Interprets a string as a list of properties.
A base class for nested structures that can be searched.
virtual Value & find(const std::string &key) const =0
Gets a value corresponding to a given keyword.
virtual bool check(const std::string &key) const =0
Check if there exists a property of the given name.
virtual std::string toString() const =0
Return a standard text representation of the content of the object.
virtual Bottle & findGroup(const std::string &key) const =0
Gets a list corresponding to a given keyword.
A single value (typically within a Bottle).
virtual yarp::conf::float64_t asFloat64() const
Get 64-bit floating point value.
virtual bool isString() const
Checks if value is a string.
virtual yarp::conf::vocab32_t asVocab32() const
Get vocabulary identifier as an integer.
virtual bool asBool() const
Get boolean value.
virtual std::int32_t asInt32() const
Get 32-bit integer value.
virtual bool isList() const
Checks if value is a list.
virtual Bottle * asList() const
Get list value.
virtual bool isVocab32() const
Checks if value is a vocabulary identifier.
virtual std::string asString() const
Get string value.
yarp::rosmsg::geometry_msgs::Point position
yarp::rosmsg::geometry_msgs::Quaternion orientation
std::vector< std::int8_t > data
yarp::rosmsg::nav_msgs::MapMetaData info
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
std::vector< yarp::rosmsg::visualization_msgs::Marker > markers
yarp::rosmsg::std_msgs::ColorRGBA color
static const std::uint8_t ARROW
yarp::rosmsg::TickDuration lifetime
yarp::rosmsg::geometry_msgs::Vector3 scale
static const std::uint8_t ADD
yarp::rosmsg::geometry_msgs::Pose pose
yarp::rosmsg::std_msgs::Header header
#define yCInfo(component,...)
#define yCError(component,...)
#define yCTrace(component,...)
#define yCWarning(component,...)
#define yCDebug(component,...)
#define YARP_LOG_COMPONENT(name,...)
An interface for the device drivers.
yarp::sig::Matrix rpy2dcm(const yarp::sig::Vector &rpy)
Converts roll-pitch-yaw angles in the corresponding dcm (direction cosine matrix) rotation matrix (de...
yarp::sig::Vector dcm2rpy(const yarp::sig::Matrix &R)
Converts a dcm (direction cosine matrix) rotation matrix to roll-pitch-yaw angles (defined in Math....
double now()
Return the current time in seconds, relative to an arbitrary starting point.
An interface to the operating system, including Port based communication.
std::uint32_t NetUint32
Definition of the NetUint32 type.
std::string toString() const
Returns text representation of the location.