Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

added more flexibility in encoding georeference inside map.osm #99

Merged
merged 1 commit into from
May 8, 2020
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,9 @@ class AutowareOsmParser : public OsmParser

/**
* [parseMapParams parses GeoReference (i.e. map parameters) info from osm file and loads default ECEF proj strings]
* NOTE: projector_type = 0 is currently not supported by CARMA
* NOTE: geoReference is expected to be encoded inside bracket:<geoReference>string</geoReference>, or as "v" or "value"
* attributes: <geoReference v="string"/> or <geoReference value="string"/>
* projector_type = 0 is currently not supported by CARMA
* +geoidgrids is also currently not a supported georeference field by the parser
* @param filename [path to osm file]
* @param projector_type [parsed information about map projector_type: Currently it supposes 0 as Autoware default MGRSProjector and 1 as CARMA LocalFrameProjector]
Expand Down
35 changes: 26 additions & 9 deletions common/lanelet2_extension/lib/autoware_osm_parser.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -110,10 +110,33 @@ void AutowareOsmParser::parseMapParams (const std::string& filename, int* projec

auto osmNode = doc.child("osm");
auto geoRef = osmNode.child("geoReference");

if (geoRef && std::string(geoRef.child_value()) != "")
std::string raw_geo_ref = "";

if (geoRef)
{
// check common ways the geoReference might have been encoded in the map
if (std::string(geoRef.child_value()) != "")
{
raw_geo_ref = geoRef.child_value();
}
else if(geoRef.attribute("v"))
{
raw_geo_ref = geoRef.attribute("v").value();
}
else if (geoRef.attribute("value"))
{
raw_geo_ref = geoRef.attribute("value").value();
}
}
// parser was not able to find a valid geoReference from the map
if (raw_geo_ref == "")
{
throw lanelet::ParseError(std::string("In function ") + __FUNCTION__ +
std::string(":\nWhile parsing .osm file, geoReference was not found! Please check geoReference syntax in vector_map.osm"));
return;
}
else
{
std::string raw_geo_ref = geoRef.child_value();
// Filter unnecessary part out of georeference.
std::vector<std::string> buffer;
boost::split(buffer, raw_geo_ref, boost::is_any_of(" "));
Expand All @@ -127,12 +150,6 @@ void AutowareOsmParser::parseMapParams (const std::string& filename, int* projec
}
}
}
else
{
throw lanelet::ParseError(std::string("In function ") + __FUNCTION__ +
std::string(":\nWhile parsing .osm file, geoReference was not found! Please check geoReference syntax in vector_map.osm"));
return;
}

// Default values
*projector_type = 1; // default value for autoware.ai projector type for CARMA purposes
Expand Down
1 change: 1 addition & 0 deletions common/lanelet2_extension/test/resources/test_map.osm
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
<?xml version="1.0"?>
<osm version="0.6" generator="lanelet2">
<geoReference>+proj=tmerc +lat_0=39.46636844371259 +lon_0=-76.16919523566943 +k=1 +x_0=0 +y_0=0 +datum=WGS84 +units=m +geoidgrids=egm96_15.gtx +vunits=m +no_defs</geoReference>
<node id="1339" visible="true" version="1" lat="0.00000898315" lon="0" />
<node id="1340" visible="true" version="1" lat="0.00001796631" lon="0" />
<node id="1342" visible="true" version="1" lat="0.00000898315" lon="0.00000898315" />
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,88 @@
<?xml version="1.0"?>
<osm version="0.6" generator="lanelet2">
<!-- Same map as test_map, but geoReference is missing. This is to test parseMapParams-->
<node id="1339" visible="true" version="1" lat="0.00000898315" lon="0" />
<node id="1340" visible="true" version="1" lat="0.00001796631" lon="0" />
<node id="1342" visible="true" version="1" lat="0.00000898315" lon="0.00000898315" />
<node id="1343" visible="true" version="1" lat="0.00001796631" lon="0.00000898315" />

<!-- Lanlet Bounds -->
<!-- Left -->
<way id="1347" visible="true" version="1">
<nd ref="1339" />
<nd ref="1340" />
<tag k="subtype" v="solid_solid" />
<tag k="type" v="line_thin" />
</way>
<!-- Right -->
<way id="1348" visible="true" version="1">
<nd ref="1342" />
<nd ref="1343" />
<tag k="subtype" v="solid" />
<tag k="type" v="line_thin" />
</way>

<!-- Lanelet -->
<relation id="1349" visible="true" version="1">
<member type="way" ref="1347" role="left" />
<member type="way" ref="1348" role="right" />
<tag k="dynamic" v="no" />
<tag k="location" v="urban" />
<tag k="one_way" v="yes" />
<tag k="subtype" v="road" />
<tag k="type" v="lanelet" />

<!-- Speed Limit -->
<member type='relation' ref='45218' role='regulatory_element' />
<!-- Access Rule -->
<member type='relation' ref='45219' role='regulatory_element' />
<!-- Direction Of Travel -->
<member type='relation' ref='45220' role='regulatory_element' />
<!-- Control Line Left -->
<member type='relation' ref='45221' role='regulatory_element' />
<!-- Control Line Right -->
<member type='relation' ref='45222' role='regulatory_element' />
</relation>

<!-- Regulatory speed limit -->
<relation id='45218' visible='true' version='1'>
<member type='lanelet' ref='1349' role='refers' />
<tag k='limit' v='5 mph' /> <!-- Speed limit value must have units one of the following m/s, mps, km/h, kmh, m/h, mph -->
<tag k='subtype' v='digital_speed_limit' />
<tag k='type' v='regulatory_element' />
<tag k='participant:vehicle' v='yes' />
</relation>

<!-- Regulatory Region Access Rule -->
<relation id='45219' visible='true' version='1'>
<member type='lanelet' ref='1349' role='refers' />
<tag k='subtype' v='region_access_rule' />
<tag k='type' v='regulatory_element' />
<tag k='participant:vehicle:car' v='yes' /> <!-- Allow cars but not trucks -->
</relation>

<!-- Regulatory Direction Of Travel -->
<relation id='45220' visible='true' version='1'>
<member type='lanelet' ref='1349' role='refers' />
<tag k='subtype' v='direction_of_travel' />
<tag k='type' v='regulatory_element' />
<tag k='direction' v='one_way' /> <!-- One Way -->
<tag k='participant:vehicle' v='yes' />
</relation>

<!-- Regulatory Control Line Left -->
<relation id='45221' visible='true' version='1'>
<member type="way" ref="1347" role="ref_line" />
<tag k='subtype' v='passing_control_line' />
<tag k='type' v='regulatory_element' />
<tag k='participant:vehicle' v='from_both' /> <!-- Both ways -->
</relation>

<!-- Regulatory Control Line Right -->
<relation id='45222' visible='true' version='1'>
<member type="way" ref="1348" role="ref_line" />
<tag k='subtype' v='passing_control_line' />
<tag k='type' v='regulatory_element' />
<!-- No crossing -->
</relation>
</osm>
88 changes: 88 additions & 0 deletions common/lanelet2_extension/test/resources/test_map_v.osm
Original file line number Diff line number Diff line change
@@ -0,0 +1,88 @@
<?xml version="1.0"?>
<osm version="0.6" generator="lanelet2">
<geoReference v= "+proj=tmerc +lat_0=39.46636844371259 +lon_0=-76.16919523566943 +k=1 +x_0=0 +y_0=0 +datum=WGS84 +units=m +geoidgrids=egm96_15.gtx +vunits=m +no_defs"/>
<node id="1339" visible="true" version="1" lat="0.00000898315" lon="0" />
<node id="1340" visible="true" version="1" lat="0.00001796631" lon="0" />
<node id="1342" visible="true" version="1" lat="0.00000898315" lon="0.00000898315" />
<node id="1343" visible="true" version="1" lat="0.00001796631" lon="0.00000898315" />

<!-- Lanlet Bounds -->
<!-- Left -->
<way id="1347" visible="true" version="1">
<nd ref="1339" />
<nd ref="1340" />
<tag k="subtype" v="solid_solid" />
<tag k="type" v="line_thin" />
</way>
<!-- Right -->
<way id="1348" visible="true" version="1">
<nd ref="1342" />
<nd ref="1343" />
<tag k="subtype" v="solid" />
<tag k="type" v="line_thin" />
</way>

<!-- Lanelet -->
<relation id="1349" visible="true" version="1">
<member type="way" ref="1347" role="left" />
<member type="way" ref="1348" role="right" />
<tag k="dynamic" v="no" />
<tag k="location" v="urban" />
<tag k="one_way" v="yes" />
<tag k="subtype" v="road" />
<tag k="type" v="lanelet" />

<!-- Speed Limit -->
<member type='relation' ref='45218' role='regulatory_element' />
<!-- Access Rule -->
<member type='relation' ref='45219' role='regulatory_element' />
<!-- Direction Of Travel -->
<member type='relation' ref='45220' role='regulatory_element' />
<!-- Control Line Left -->
<member type='relation' ref='45221' role='regulatory_element' />
<!-- Control Line Right -->
<member type='relation' ref='45222' role='regulatory_element' />
</relation>

<!-- Regulatory speed limit -->
<relation id='45218' visible='true' version='1'>
<member type='lanelet' ref='1349' role='refers' />
<tag k='limit' v='5 mph' /> <!-- Speed limit value must have units one of the following m/s, mps, km/h, kmh, m/h, mph -->
<tag k='subtype' v='digital_speed_limit' />
<tag k='type' v='regulatory_element' />
<tag k='participant:vehicle' v='yes' />
</relation>

<!-- Regulatory Region Access Rule -->
<relation id='45219' visible='true' version='1'>
<member type='lanelet' ref='1349' role='refers' />
<tag k='subtype' v='region_access_rule' />
<tag k='type' v='regulatory_element' />
<tag k='participant:vehicle:car' v='yes' /> <!-- Allow cars but not trucks -->
</relation>

<!-- Regulatory Direction Of Travel -->
<relation id='45220' visible='true' version='1'>
<member type='lanelet' ref='1349' role='refers' />
<tag k='subtype' v='direction_of_travel' />
<tag k='type' v='regulatory_element' />
<tag k='direction' v='one_way' /> <!-- One Way -->
<tag k='participant:vehicle' v='yes' />
</relation>

<!-- Regulatory Control Line Left -->
<relation id='45221' visible='true' version='1'>
<member type="way" ref="1347" role="ref_line" />
<tag k='subtype' v='passing_control_line' />
<tag k='type' v='regulatory_element' />
<tag k='participant:vehicle' v='from_both' /> <!-- Both ways -->
</relation>

<!-- Regulatory Control Line Right -->
<relation id='45222' visible='true' version='1'>
<member type="way" ref="1348" role="ref_line" />
<tag k='subtype' v='passing_control_line' />
<tag k='type' v='regulatory_element' />
<!-- No crossing -->
</relation>
</osm>
89 changes: 89 additions & 0 deletions common/lanelet2_extension/test/resources/test_map_value.osm
Original file line number Diff line number Diff line change
@@ -0,0 +1,89 @@
<?xml version="1.0"?>
<osm version="0.6" generator="lanelet2">
<!-- Same map as test_map, but geoReference is encoded in a different way. This is to test parseMapParams-->
<geoReference value= "+proj=tmerc +lat_0=39.46636844371259 +lon_0=-76.16919523566943 +k=1 +x_0=0 +y_0=0 +datum=WGS84 +units=m +geoidgrids=egm96_15.gtx +vunits=m +no_defs"/>
<node id="1339" visible="true" version="1" lat="0.00000898315" lon="0" />
<node id="1340" visible="true" version="1" lat="0.00001796631" lon="0" />
<node id="1342" visible="true" version="1" lat="0.00000898315" lon="0.00000898315" />
<node id="1343" visible="true" version="1" lat="0.00001796631" lon="0.00000898315" />

<!-- Lanlet Bounds -->
<!-- Left -->
<way id="1347" visible="true" version="1">
<nd ref="1339" />
<nd ref="1340" />
<tag k="subtype" v="solid_solid" />
<tag k="type" v="line_thin" />
</way>
<!-- Right -->
<way id="1348" visible="true" version="1">
<nd ref="1342" />
<nd ref="1343" />
<tag k="subtype" v="solid" />
<tag k="type" v="line_thin" />
</way>

<!-- Lanelet -->
<relation id="1349" visible="true" version="1">
<member type="way" ref="1347" role="left" />
<member type="way" ref="1348" role="right" />
<tag k="dynamic" v="no" />
<tag k="location" v="urban" />
<tag k="one_way" v="yes" />
<tag k="subtype" v="road" />
<tag k="type" v="lanelet" />

<!-- Speed Limit -->
<member type='relation' ref='45218' role='regulatory_element' />
<!-- Access Rule -->
<member type='relation' ref='45219' role='regulatory_element' />
<!-- Direction Of Travel -->
<member type='relation' ref='45220' role='regulatory_element' />
<!-- Control Line Left -->
<member type='relation' ref='45221' role='regulatory_element' />
<!-- Control Line Right -->
<member type='relation' ref='45222' role='regulatory_element' />
</relation>

<!-- Regulatory speed limit -->
<relation id='45218' visible='true' version='1'>
<member type='lanelet' ref='1349' role='refers' />
<tag k='limit' v='5 mph' /> <!-- Speed limit value must have units one of the following m/s, mps, km/h, kmh, m/h, mph -->
<tag k='subtype' v='digital_speed_limit' />
<tag k='type' v='regulatory_element' />
<tag k='participant:vehicle' v='yes' />
</relation>

<!-- Regulatory Region Access Rule -->
<relation id='45219' visible='true' version='1'>
<member type='lanelet' ref='1349' role='refers' />
<tag k='subtype' v='region_access_rule' />
<tag k='type' v='regulatory_element' />
<tag k='participant:vehicle:car' v='yes' /> <!-- Allow cars but not trucks -->
</relation>

<!-- Regulatory Direction Of Travel -->
<relation id='45220' visible='true' version='1'>
<member type='lanelet' ref='1349' role='refers' />
<tag k='subtype' v='direction_of_travel' />
<tag k='type' v='regulatory_element' />
<tag k='direction' v='one_way' /> <!-- One Way -->
<tag k='participant:vehicle' v='yes' />
</relation>

<!-- Regulatory Control Line Left -->
<relation id='45221' visible='true' version='1'>
<member type="way" ref="1347" role="ref_line" />
<tag k='subtype' v='passing_control_line' />
<tag k='type' v='regulatory_element' />
<tag k='participant:vehicle' v='from_both' /> <!-- Both ways -->
</relation>

<!-- Regulatory Control Line Right -->
<relation id='45222' visible='true' version='1'>
<member type="way" ref="1348" role="ref_line" />
<tag k='subtype' v='passing_control_line' />
<tag k='type' v='regulatory_element' />
<!-- No crossing -->
</relation>
</osm>
27 changes: 27 additions & 0 deletions common/lanelet2_extension/test/src/MapLoadingTest.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
#include <lanelet2_io/Io.h>
#include <lanelet2_io/io_handlers/Factory.h>
#include <lanelet2_io/io_handlers/Writer.h>
#include <lanelet2_extension/io/autoware_osm_parser.h>

#include <lanelet2_extension/regulatory_elements/RegionAccessRule.h>
#include <lanelet2_extension/regulatory_elements/DigitalSpeedLimit.h>
Expand All @@ -41,6 +42,32 @@ using ::testing::ReturnArg;
namespace lanelet
{
using namespace lanelet::units::literals;
TEST(MapLoadingTest, parseMapParams)
{
int projector_type = 1; // default value
std::string target_frame, lanelet2_filename;
std::string correct_georeference = "+proj=tmerc +lat_0=39.46636844371259 +lon_0=-76.16919523566943 +k=1 +x_0=0 +y_0=0 +datum=WGS84 +units=m +vunits=m +no_defs ";
// Test regular way
lanelet2_filename = "resources/test_map.osm";
lanelet::io_handlers::AutowareOsmParser::parseMapParams(lanelet2_filename, &projector_type, &target_frame);
EXPECT_EQ(correct_georeference, target_frame);
// Test v="string" way
target_frame = "";
lanelet2_filename = "resources/test_map_v.osm";
lanelet::io_handlers::AutowareOsmParser::parseMapParams(lanelet2_filename, &projector_type, &target_frame);
EXPECT_EQ(correct_georeference, target_frame);
// Test v="string" way
target_frame = "";
lanelet2_filename = "resources/test_map_value.osm";
lanelet::io_handlers::AutowareOsmParser::parseMapParams(lanelet2_filename, &projector_type, &target_frame);
EXPECT_EQ(correct_georeference, target_frame);
// Test unsupported way
target_frame = "";
lanelet2_filename = "resources/test_map_nogeoreference.osm";
EXPECT_THROW(lanelet::io_handlers::AutowareOsmParser::parseMapParams(lanelet2_filename, &projector_type, &target_frame), lanelet::ParseError);
}



TEST(MapLoadingTest, mapLoadingTest)
{
Expand Down