Compare commits

..

151 Commits

Author SHA1 Message Date
Patrick Niklaus db0db58bf8 Make gcc 4.8 happy and disable protected because of lambdas 2016-03-19 00:01:43 +01:00
Daniel Patterson 1751fedfd0 Include edge duration information. 2016-03-18 23:34:28 +01:00
Patrick Niklaus b3599ea249 Implement viewport code to fix simplification
This fixes #2083
2016-03-18 23:25:54 +01:00
Patrick Niklaus 2927d149db Add tests for coordinate transformation 2016-03-18 23:25:44 +01:00
Patrick Niklaus 0d628da3ba Consolidate math functions 2016-03-18 23:25:44 +01:00
Patrick Niklaus 497e4154a7 get_name_for_id -> GetNameForID 2016-03-18 19:29:09 +01:00
Patrick Niklaus 88db0ba90c Simplfy name change announcement 2016-03-18 18:16:20 +01:00
Moritz Kobitzsch 44e1e57790 fix division by zero 2016-03-18 17:41:55 +01:00
Moritz Kobitzsch 1a4f6cba7a restructured to only return valid turns to the outside + cleanup 2016-03-18 17:41:55 +01:00
Moritz Kobitzsch ee5020baf3 less new names, forks consider road classes, api clean-up 2016-03-18 17:41:55 +01:00
Moritz Kobitzsch 7b755eea54 implement basic turn handling 2016-03-18 17:41:55 +01:00
Moritz Kobitzsch fbdafca4f2 implements relative position feature based on coordinates 2016-03-18 17:33:05 +01:00
Patrick Niklaus 873950ee86 Don't sum up durations of merged steps since we do that in a different place now 2016-03-18 17:33:05 +01:00
Patrick Niklaus 50fcc65431 Fix foward/backwad swap 2016-03-18 17:33:05 +01:00
Patrick Niklaus 343011c3da Limit zoomlevel to 18 2016-03-18 17:33:05 +01:00
Patrick Niklaus 4c66fcafaa Fix shared memory 2016-03-18 17:33:05 +01:00
Patrick Niklaus 513fd09780 Fixup for last commit 2016-03-18 17:33:05 +01:00
Daniel Patterson f6de8f3444 Enables the use of multiple segment-speed-files on the osrm-contract
command line, and exposes the file name used for each edge in the debug
tiles.
2016-03-18 17:33:05 +01:00
Patrick Niklaus 082eac68f7 Fix ingestion fixed duration values from UnpackPath 2016-03-18 17:33:05 +01:00
Patrick Niklaus 7091331b55 Fix durations in UnpackPath 2016-03-18 17:33:05 +01:00
Moritz Kobitzsch 7149e25636 fixes a broken assertion 2016-03-18 17:33:05 +01:00
Moritz Kobitzsch f76fc7fd83 fix merging of turn instructions 2016-03-18 17:33:05 +01:00
Patrick Niklaus 6a0db71e34 Include reverse edges again 2016-03-18 17:33:05 +01:00
Patrick Niklaus d6776b3e81 Formating and logging changes for turn classification 2016-03-18 17:33:05 +01:00
Patrick Niklaus f9eb22093b Handle case of dead-end edges by inserting an invalid turn 2016-03-18 17:33:05 +01:00
Moritz Kobitzsch 9fb86bcac5 report depart/arrive in addition to waypoint 2016-03-18 17:33:05 +01:00
Patrick Niklaus 17d775588d Only install necessary headers 2016-03-18 17:33:05 +01:00
Daniel J. Hofmann 810c0f3b3e Adds the license preamble for all publicly installed eaders, closes #2036 2016-03-18 17:33:05 +01:00
Patrick Niklaus fe3005f630 Remove the encoder/decoder dependecy from Hint 2016-03-18 17:33:04 +01:00
Patrick Niklaus ab7ded02c1 Rename alternative -> alternatives 2016-03-18 17:33:04 +01:00
Patrick Niklaus bad4d4d6c7 Remove obsolete debug information 2016-03-18 17:33:04 +01:00
Patrick Niklaus 8485a99349 Just return NoSegment in map matching if all candidates are empty 2016-03-18 17:33:04 +01:00
Patrick Niklaus af6b84a432 Add failing test for map matching of outlier 2016-03-18 17:33:04 +01:00
Patrick Niklaus 1dc26585d2 Fix missing capitalization of error codes 2016-03-18 17:33:04 +01:00
Moritz Kobitzsch a95f4a8816 encapsulated into class 2016-03-18 17:33:04 +01:00
Moritz Kobitzsch 94a2072533 improving fork handling on three-way turns 2016-03-18 17:33:04 +01:00
Moritz Kobitzsch a5568f8be4 fix comparison for ramps on three-way turns 2016-03-18 17:33:04 +01:00
Patrick Niklaus dafd724923 Minor auto iterator cleanup 2016-03-18 17:33:04 +01:00
Patrick Niklaus 807f5c0014 Don't pass down unsnapped coordinates. All information is already there 2016-03-18 17:33:04 +01:00
Patrick Niklaus 956b264ece Fix camMergeTrivially 2016-03-18 17:33:04 +01:00
Moritz Kobitzsch 8967cebd10 fixes roundabout counting 2016-03-18 17:33:04 +01:00
Moritz Kobitzsch 431a8cb5c1 fixes assignment for basic turn types / invalid ramp assignment 2016-03-18 17:33:04 +01:00
Patrick Niklaus 1675ff1748 Add edge id assertions 2016-03-18 17:33:04 +01:00
Patrick Niklaus c8cd89355c Don't pass shared_ptr down to functions
"Don’t pass a smart pointer as a function parameter unless you want to
use or manipulate the smart pointer itself, such as to share or transfer
ownership."

Source:
http://herbsutter.com/2013/06/05/gotw-91-solution-smart-pointer-parameters/
2016-03-18 17:33:04 +01:00
Patrick Niklaus e50bf1062f Move bearing to public namespace 2016-03-18 17:33:04 +01:00
Daniel J. Hofmann 50cf0cf84f Properly includes needed headers in turn analysis interface 2016-03-18 17:33:04 +01:00
Daniel J. Hofmann da298f0f28 Const-correctnes for compressed geometry iterator 2016-03-18 17:33:04 +01:00
Daniel J. Hofmann d5a3d817aa Use stdint and using type-alias for discrete angle 2016-03-18 17:33:03 +01:00
Daniel J. Hofmann 5f4424482e Hide functional road classification based on tags in implementation file 2016-03-18 17:33:03 +01:00
Daniel J. Hofmann 9d0da926e5 Inline initialize functional road classification hash table 2016-03-18 17:33:03 +01:00
Daniel J. Hofmann 512dd9a5e2 256 functional road classes should be enough 2016-03-18 17:33:03 +01:00
Daniel J. Hofmann bba7e49d15 Moves route assembly into implementation file 2016-03-18 17:33:03 +01:00
Daniel J. Hofmann 70066c3ed0 Fixes remaining engine/guidance includes 2016-03-18 17:33:03 +01:00
Daniel J. Hofmann 5661628f2c Fixes accumulate living in <numeric> and not <algorithm> 2016-03-18 17:33:03 +01:00
Daniel J. Hofmann 2ff9386368 Puts step maneuver handling into implementation file 2016-03-18 17:33:03 +01:00
Daniel J. Hofmann 37e93cf96a Removes penalizing move 2016-03-18 17:33:03 +01:00
Daniel J. Hofmann a7b99b1549 Uses static_casts for underlying type in post processing 2016-03-18 17:33:03 +01:00
Daniel J. Hofmann 3443baa311 Fix asymmetry in min/max from using -max 2016-03-18 17:33:03 +01:00
Daniel J. Hofmann d88ce65385 Adapts MakeResponse to not pass vector by pointer 2016-03-18 17:33:03 +01:00
Daniel J. Hofmann 7865bd8815 Fixes multi-line comment 2016-03-18 17:33:03 +01:00
Daniel J. Hofmann 6856f00074 Runs scripts/format.sh 2016-03-18 17:33:03 +01:00
Patrick Niklaus bc67488f25 Fix coodinate include and unused warnings 2016-03-18 17:33:03 +01:00
Moritz Kobitzsch 6c5822fb45 start of four way turns 2016-03-18 17:33:03 +01:00
Moritz Kobitzsch 779ddeeb69 improved fork handling 2016-03-18 17:33:03 +01:00
Patrick Niklaus 01c4b3f7a3 Fix crash on extracting Berlin in guidance 2016-03-18 17:33:03 +01:00
Moritz Kobitzsch fecd3d27ac bugfixing/classification 2016-03-18 17:33:02 +01:00
Patrick Niklaus 0724c4a2d8 Big Restructuring / Cleanup 2016-03-18 17:33:02 +01:00
Moritz Kobitzsch cba4baf920 starting on conflict resolution 2016-03-18 17:33:02 +01:00
Lauren Budorick dda6d49f4a Fixes for gcc compiling, temporary hacks to remove later 2016-03-18 17:33:02 +01:00
Moritz Kobitzsch 6f9d8a691d handle segregated roads (merge for turn analysis) 2016-03-18 17:33:02 +01:00
Moritz Kobitzsch f713408d46 structural changes, motorway handling 2016-03-18 17:33:02 +01:00
Moritz Kobitzsch 80843ecc89 enter and exit roundabout feature - currently not showing turn 2016-03-18 17:33:02 +01:00
Moritz Kobitzsch aced4ebe56 migrated out of edge based graph factory 2016-03-18 17:33:02 +01:00
Moritz Kobitzsch df00b99d84 relative waypoint locations 2016-03-18 17:33:02 +01:00
Moritz Kobitzsch 7dfe91bba0 handling of roundabouts (simple version) 2016-03-18 17:33:02 +01:00
Moritz Kobitzsch 8753590f59 advanced guidance on 5.0 2016-03-18 17:33:02 +01:00
Patrick Niklaus 12ff303cf8 Fix numerical problems with polyline 2016-03-18 17:33:02 +01:00
Patrick Niklaus 70dfe23f0e Fix table response format to return null + double in seconds 2016-03-18 17:33:02 +01:00
Patrick Niklaus 6ca0afa212 Return NoMatch 2016-03-18 17:33:02 +01:00
Daniel J. Hofmann 31f735b08e Provides ctor from base path for EngineConfig, fixes #2030 2016-03-18 17:33:02 +01:00
Patrick Niklaus b01b7dcbca Add support for tile plugin 2016-03-18 17:33:02 +01:00
Patrick Niklaus 248a0af761 Preliminary integration of the tile plugin 2016-03-18 17:33:02 +01:00
Patrick Niklaus 49fff1d93f sources and destinations can be empty actually 2016-03-18 17:33:02 +01:00
Daniel J. Hofmann 29a72a9e1a Fixes coordinate, source and destination validation by means of backporting #2041 2016-03-18 17:33:01 +01:00
Daniel J. Hofmann b3a709b98d Fixes ownership semantics and forwarding references misplacements in the JSON factory 2016-03-18 17:33:01 +01:00
Daniel J. Hofmann aa3472cc6b Unwrap function call from identity lambda 2016-03-18 17:33:01 +01:00
Daniel J. Hofmann 3db1509855 Uses JSON's String constructor for polyline encoding 2016-03-18 17:33:01 +01:00
Daniel J. Hofmann 53f47458a2 Passes coordinates by value 2016-03-18 17:33:01 +01:00
Daniel J. Hofmann f784b85cd6 Asserts on unknown TurnInstruction 2016-03-18 17:33:01 +01:00
Daniel J. Hofmann 02c3c3e847 Fixes header includes in the JSON factory 2016-03-18 17:33:01 +01:00
Dane Springmeyer 8af3a036a7 fix compile of osrm-components 2016-03-18 17:33:01 +01:00
Patrick Niklaus 7803d6116b Fix if the last coordinate is not found 2016-03-18 17:33:01 +01:00
Patrick Niklaus 07cd80d042 Allocate correct table size 2016-03-18 17:33:01 +01:00
Patrick Niklaus fd6abcfde3 Fix travel mode passing from profiles up to the API 2016-03-18 17:33:01 +01:00
Patrick Niklaus 690a2a41a4 Fix geometries type in steps 2016-03-18 17:33:01 +01:00
Patrick Niklaus dd1f9e5a6a Fix table parameter parsing 2016-03-18 17:33:01 +01:00
Patrick Niklaus e4ed2f6a2f Fix behaviour of table if sources/destinations arrays are empty 2016-03-18 17:33:01 +01:00
Patrick Niklaus 25f86b68dc Fuck. this. shit. 2016-03-18 17:33:01 +01:00
Patrick Niklaus 5916ddda80 Change stream operator of strong typedef 2016-03-18 17:33:01 +01:00
Patrick Niklaus 2e214ac222 Fix stream operator for coordinate 2016-03-18 17:33:01 +01:00
Patrick Niklaus 5acd2ca394 Add stream operator to Rectangle 2016-03-18 17:33:01 +01:00
Patrick Niklaus ffaf0fc86f Add euclideanDistance to coordinate_calculation 2016-03-18 17:33:01 +01:00
Patrick Niklaus ef6c62d224 Simplify static_rtree tests 2016-03-18 17:33:01 +01:00
Patrick Niklaus fed2a67e42 First round of lat,lng -> lng,lat switcheroo 2016-03-18 17:33:00 +01:00
Patrick Niklaus 059ee4e350 Add rectangle unit test 2016-03-18 17:33:00 +01:00
Patrick Niklaus 53a74ce3e6 Fix match and trip API response 2016-03-18 17:33:00 +01:00
Patrick Niklaus b18c7d75da Fix out-of-bounds write in map_matching 2016-03-18 17:33:00 +01:00
Dane Springmeyer f3e5ce561a Fix compile on OS X 2016-03-18 17:33:00 +01:00
Patrick Niklaus 65d56182f2 Finish the nearest plugin 2016-03-18 17:33:00 +01:00
Patrick Niklaus 1c05d8b7ae Initialize NearestParameters correctly 2016-03-18 17:33:00 +01:00
Patrick Niklaus 6223ee887c Adapt to feedback in #519 2016-03-18 17:33:00 +01:00
Patrick Niklaus d1528dc4ac Add trip plugin 2016-03-18 17:33:00 +01:00
Patrick Niklaus 7a042e643f Hook up map matching 2016-03-18 17:33:00 +01:00
Patrick Niklaus a129e549eb First compiling version of map_match plugin 2016-03-18 17:33:00 +01:00
Daniel J. Hofmann 581b5c2ab6 Adapts example/example.cpp to new osrm api 2016-03-18 17:33:00 +01:00
Daniel J. Hofmann ece2056a13 Install _all_ transitively from public headers included header 2016-03-18 17:33:00 +01:00
Daniel J. Hofmann d6e5b79747 Fix missing headers in hint.hpp 2016-03-18 17:33:00 +01:00
Daniel J. Hofmann 2d98bacdd5 Adds $prefix/include/osrm to include dirs so that transitive header includes without osrm prefix can be found 2016-03-18 17:33:00 +01:00
Daniel J. Hofmann 8863947e86 Adapt the example to include all osrm public headers 2016-03-18 17:33:00 +01:00
Daniel J. Hofmann 27f74432a0 Fixes missing public header installations 2016-03-18 17:33:00 +01:00
Daniel J. Hofmann 03d88b3df2 Fix forward declarations in publicly facing osrm header 2016-03-18 17:33:00 +01:00
Daniel J. Hofmann bdfa072cac Enable all plugins with aStatus::Error return code fallback for not implemented ones 2016-03-18 17:33:00 +01:00
Daniel J. Hofmann 65ba774ebc Adds publicly facing alias headers for parameters 2016-03-18 17:33:00 +01:00
Daniel J. Hofmann d34c215c09 Temporarily comment out match.cpp as to not break the build process 2016-03-18 17:33:00 +01:00
Daniel J. Hofmann c88eeb89c6 We don't need templates at all, this is not CRTP? 2016-03-18 17:32:59 +01:00
Daniel J. Hofmann bde8ec1dbd Fix classes for service member function definitions 2016-03-18 17:32:59 +01:00
Daniel J. Hofmann 49a173652b Service skeletons for nearest, trip, match 2016-03-18 17:32:59 +01:00
Daniel J. Hofmann e4dace1d51 Fix grammar constraint and enable all plugin links 2016-03-18 17:32:59 +01:00
Daniel J. Hofmann 43d1e40284 Plugin grammar skeletons 2016-03-18 17:32:59 +01:00
Daniel J. Hofmann 139220058e Enforce parameter and grammar type to catch subtle bugs 2016-03-18 17:32:59 +01:00
Daniel J. Hofmann 11a92a8e54 Link parameters to grammars 2016-03-18 17:32:59 +01:00
Daniel J. Hofmann d3a2c1c41c Require a BaseParameters type at compile time via enable_if 2016-03-18 17:32:59 +01:00
Daniel J. Hofmann 566505fd0f Adapts Nearest plugin to new API 2016-03-18 17:32:59 +01:00
Daniel J. Hofmann 9dada6b46a Fix deleting incomplete type and make Engine moveable only 2016-03-18 17:32:59 +01:00
Daniel J. Hofmann f9d2440d95 Adapts publicly facing new API 2016-03-18 17:32:59 +01:00
Daniel J. Hofmann a4387f39f1 Adapts NearestParameters to new API 2016-03-18 17:32:59 +01:00
Patrick Niklaus 1902292629 Initial non-building match plugin 2016-03-18 17:32:59 +01:00
Lauren Budorick bbf2ac23b4 Include numeric in assemble_overview.cpp (needed on OSX for std::accumulate) 2016-03-18 17:32:59 +01:00
Daniel J. Hofmann 445df08fb4 Semantic action handler requires passing optional by value and fusion::vector2 2016-03-18 17:32:59 +01:00
Patrick Niklaus 27a2b061bf Add tests for bearing parsing 2016-03-18 17:32:59 +01:00
Patrick Niklaus 944947962b Add table service 2016-03-18 17:32:59 +01:00
Patrick Niklaus fda8f6ecef Add table API 2016-03-18 17:32:59 +01:00
Daniel J. Hofmann ca6c1d7bb1 Optional<T> semantic action handler takes T argument 2016-03-18 17:32:59 +01:00
Patrick Niklaus d88dda1a45 Fix parameter parsing tests 2016-03-18 17:32:59 +01:00
Patrick Niklaus 207f1d7732 Fix table plugin 2016-03-18 17:32:58 +01:00
Daniel J. Hofmann d73600387b First take at distance table API re-write 2016-03-18 17:32:58 +01:00
Daniel J. Hofmann 9194ab590c Adapts TableParameters and its validation to new API 2016-03-18 17:32:58 +01:00
Patrick Niklaus 68eeb20c5c Add viaroute suport for new API 2016-03-18 17:32:58 +01:00
Patrick Niklaus 2f3b4373f9 Also exclude the compressed flag from the data format 2016-03-18 17:30:13 +01:00
Patrick Niklaus 1b25bebeac Remove geometry indicator 2016-03-18 17:30:13 +01:00
Daniel J. Hofmann b1c84b598f Print the _local_ endpoint Boost ASIO assigns a port to, fixes #2097 2016-03-18 12:09:28 +01:00
40 changed files with 2670 additions and 1828 deletions
+202
View File
@@ -0,0 +1,202 @@
@routing @guidance
Feature: Basic Roundabout
Background:
Given the profile "testbot"
Given a grid size of 10 meters
Scenario: Ramp Exit Right
Given the node map
| a | b | c | d | e |
| | | | f | g |
And the ways
| nodes | highway |
| abcde | motorway |
| bfg | motorway_link |
When I route I should get
| waypoints | route | turns |
| a,e | abcde, abcde | depart, arrive |
| a,g | abcde, bfg, bfg | depart, ramp-slight-right, arrive |
Scenario: Ramp Exit Right Curved Right
Given the node map
| a | b | c | | |
| | | f | d | |
| | | | g | e |
And the ways
| nodes | highway |
| abcde | motorway |
| bfg | motorway_link |
When I route I should get
| waypoints | route | turns |
| a,e | abcde, abcde | depart, arrive |
| a,g | abcde, bfg, bfg | depart, ramp-slight-right, arrive |
Scenario: Ramp Exit Right Curved Left
Given the node map
| | | | | e |
| | | | d | g |
| a | b | c | f | |
And the ways
| nodes | highway |
| abcde | motorway |
| cfg | motorway_link |
When I route I should get
| waypoints | route | turns |
| a,e | abcde, abcde | depart, arrive |
| a,g | abcde, cfg, cfg | depart, ramp-slight-right, arrive |
Scenario: Ramp Exit Left
Given the node map
| | | | f | g |
| a | b | c | d | e |
And the ways
| nodes | highway |
| abcde | motorway |
| bfg | motorway_link |
When I route I should get
| waypoints | route | turns |
| a,e | abcde, abcde | depart, arrive |
| a,g | abcde, bfg, bfg | depart, ramp-slight-left, arrive |
Scenario: Ramp Exit Left Curved Left
Given the node map
| | | | g | e |
| | | f | d | |
| a | b | c | | |
And the ways
| nodes | highway |
| abcde | motorway |
| bfg | motorway_link |
When I route I should get
| waypoints | route | turns |
| a,e | abcde, abcde | depart, arrive |
| a,g | abcde, bfg, bfg | depart, ramp-slight-left, arrive |
Scenario: Ramp Exit Left Curved Right
Given the node map
| a | b | c | f | |
| | | | d | g |
| | | | | e |
And the ways
| nodes | highway |
| abcde | motorway |
| cfg | motorway_link |
When I route I should get
| waypoints | route | turns |
| a,e | abcde, abcde | depart, arrive |
| a,g | abcde, cfg, cfg | depart, ramp-slight-left, arrive |
Scenario: On Ramp Right
Given the node map
| a | b | c | d | e |
| f | g | | | |
And the ways
| nodes | highway |
| abcde | motorway |
| fgd | motorway_link |
When I route I should get
| waypoints | route | turns |
| a,e | abcde, abcde | depart, arrive |
| f,e | abcde, fgd, fgd | depart, merge-slight-left, arrive |
Scenario: On Ramp Left
Given the node map
| f | g | | | |
| a | b | c | d | e |
And the ways
| nodes | highway |
| abcde | motorway |
| fgd | motorway_link |
When I route I should get
| waypoints | route | turns |
| a,e | abcde, abcde | depart, arrive |
| f,e | abcde, fgd, fgd | depart, merge-slight-right, arrive |
Scenario: Highway Fork
Given the node map
| | | | | d | e |
| a | b | c | | | |
| | | | | f | g |
And the ways
| nodes | highway |
| abcde | motorway |
| cfg | motorway |
When I route I should get
| waypoints | route | turns |
| a,e | abcde, abcde, abcde | depart, fork-left, arrive |
| a,g | abcde, cfg, cfg | depart, fork-right, arrive |
Scenario: Fork After Ramp
Given the node map
| | | | | d | e |
| a | b | c | | | |
| | | | | f | g |
And the ways
| nodes | highway |
| abc | motorway_link |
| cde | motorway |
| cfg | motorway |
When I route I should get
| waypoints | route | turns |
| a,e | abc, cde, cde | depart, fork-left, arrive |
| a,g | abc, cfg, cfg | depart, fork-right, arrive |
Scenario: On And Off Ramp Right
Given the node map
| a | b | | c | | d | e |
| f | g | | | | h | i |
And the ways
| nodes | highway |
| abcde | motorway |
| fgc | motorway_link |
| chi | motorway_link |
When I route I should get
| waypoints | route | turns |
| a,e | abcde, abcde | depart, arrive |
| f,e | fgc, abcde, abcde | depart, merge-slight-left, arrive |
| a,i | abcde, chi, chi | depart, ramp-slight-right, arrive |
| f,i | fgc, chi, chi | depart, turn-slight-right, arrive |
Scenario: On And Off Ramp Left
Given the node map
| f | g | | | | h | i |
| a | b | | c | | d | e |
And the ways
| nodes | highway |
| abcde | motorway |
| fgc | motorway_link |
| chi | motorway_link |
When I route I should get
| waypoints | route | turns |
| a,e | abcde, abcde | depart, arrive |
| f,e | fgc, abcde, abcde | depart, merge-slight-right, arrive |
| a,i | abcde, chi, chi | depart, ramp-slight-left, arrive |
| f,i | fgc, chi, chi | depart, turn-slight-left, arrive |
+173
View File
@@ -0,0 +1,173 @@
@routing @guidance
Feature: Basic Roundabout
Background:
Given the profile "testbot"
Given a grid size of 10 meters
Scenario: Enter and Exit
Given the node map
| | | a | | |
| | | b | | |
| h | g | | c | d |
| | | e | | |
| | | f | | |
And the ways
| nodes | roundabout |
| ab | no |
| cd | no |
| ef | no |
| gh | no |
| bcegb | yes |
When I route I should get
| waypoints | route | turns |
| a,d | ab,cd,cd | depart, roundabout-exit-1, arrive |
| a,f | ab,ef,ef | depart, roundabout-exit-2, arrive |
| a,h | ab,gh,gh | depart, roundabout-exit-3, arrive |
| d,f | cd,ef,ef | depart, roundabout-exit-1, arrive |
| d,h | cd,gh,gh | depart, roundabout-exit-2, arrive |
| d,a | cd,ab,ab | depart, roundabout-exit-3, arrive |
| f,h | ef,gh,gh | depart, roundabout-exit-1, arrive |
| f,a | ef,ab,ab | depart, roundabout-exit-2, arrive |
| f,d | ef,cd,cd | depart, roundabout-exit-3, arrive |
| h,a | gh,ab,ab | depart, roundabout-exit-1, arrive |
| h,d | gh,cd,cd | depart, roundabout-exit-2, arrive |
| h,f | gh,ef,ef | depart, roundabout-exit-3, arrive |
Scenario: Only Enter
Given the node map
| | | a | | |
| | | b | | |
| h | g | | c | d |
| | | e | | |
| | | f | | |
And the ways
| nodes | roundabout |
| ab | no |
| cd | no |
| ef | no |
| gh | no |
| bcegb | yes |
When I route I should get
| waypoints | route | turns |
| a,b | ab,ab | depart, arrive |
| a,c | ab,bcegb | depart, roundabout-enter, arrive |
| a,e | ab,bcegb | depart, roundabout-enter, arrive |
| a,g | ab,bcegb | depart, roundabout-enter, arrive |
| d,c | cd,cd | depart, arrive |
| d,e | cd,bcegb | depart, roundabout-enter, arrive |
| d,g | cd,bcegb | depart, roundabout-enter, arrive |
| d,b | cd,bcegb | depart, roundabout-enter, arrive |
| f,e | ef,ef | depart, arrive |
| f,g | ef,bcegb | depart, roundabout-enter, arrive |
| f,b | ef,bcegb | depart, roundabout-enter, arrive |
| f,c | ef,bcegb | depart, roundabout-enter, arrive |
| h,g | gh,gh | depart, arrive |
| h,b | gh,bcegb | depart, roundabout-enter, arrive |
| h,c | gh,bcegb | depart, roundabout-enter, arrive |
| h,e | gh,bcegb | depart, roundabout-enter, arrive |
Scenario: Only Exit
Given the node map
| | | a | | |
| | | b | | |
| h | g | | c | d |
| | | e | | |
| | | f | | |
And the ways
| nodes | roundabout |
| ab | no |
| cd | no |
| ef | no |
| gh | no |
| bcegb | yes |
When I route I should get
| waypoints | route | turns |
| b,a | ab,ab | depart, arrive |
| b,d | bcegb,cd,cd | depart, roundabout-exit-1, arrive |
| b,f | bcegb,ef,ef | depart, roundabout-exit-2, arrive |
| b,h | bcegb,gh,gh | depart, roundabout-exit-3, arrive |
| c,d | cd,cd | depart, arrive |
| c,f | bcegb,ef,ef | depart, roundabout-exit-1, arrive |
| c,h | bcegb,gh,gh | depart, roundabout-exit-2, arrive |
| c,a | bcegb,ab,ab | depart, roundabout-exit-3, arrive |
| e,f | ef,ef | depart, arrive |
| e,h | bcegb,gh,gh | depart, roundabout-exit-1, arrive |
| e,a | bcegb,ab,ab | depart, roundabout-exit-2, arrive |
| e,d | bcegb,cd,cd | depart, roundabout-exit-3, arrive |
| g,h | gh,gh | depart, arrive |
| g,a | bcegb,ab,ab | depart, roundabout-exit-1, arrive |
| g,d | bcegb,cd,cd | depart, roundabout-exit-2, arrive |
| g,f | bcegb,ef,ef | depart, roundabout-exit-3, arrive |
Scenario: Drive Around
Given the node map
| | | a | | |
| | | b | | |
| h | g | | c | d |
| | | e | | |
| | | f | | |
And the ways
| nodes | roundabout |
| ab | no |
| cd | no |
| ef | no |
| gh | no |
| bcegb | yes |
When I route I should get
| waypoints | route | turns |
| b,c | bcegb,bcegb | depart, arrive |
| b,e | bcegb,bcegb | depart, arrive |
| b,g | bcegb,bcegb | depart, arrive |
| c,e | bcegb,bcegb | depart, arrive |
| c,g | bcegb,bcegb | depart, arrive |
| c,b | bcegb,bcegb | depart, arrive |
| e,g | bcegb,bcegb | depart, arrive |
| e,b | bcegb,bcegb | depart, arrive |
| e,c | bcegb,bcegb | depart, arrive |
| g,b | bcegb,bcegb | depart, arrive |
| g,c | bcegb,bcegb | depart, arrive |
| g,e | bcegb,bcegb | depart, arrive |
Scenario: Mixed Entry and Exit
Given the node map
| | a | | c | |
| l | | b | | d |
| | k | | e | |
| j | | h | | f |
| | i | | g | |
And the ways
| nodes | roundabout | oneway |
| abc | no | yes |
| def | no | yes |
| ghi | no | yes |
| jkl | no | yes |
| behkb | yes | yes |
When I route I should get
| waypoints | route | turns |
| a,c | abc,abc,abc | depart, roundabout-exit-1, arrive |
| a,f | abc,def,def | depart, roundabout-exit-2, arrive |
| a,i | abc,ghi,ghi | depart, roundabout-exit-3, arrive |
| a,l | abc,jkl,jkl | depart, roundabout-exit-4, arrive |
| d,f | def,def,def | depart, roundabout-exit-1, arrive |
| d,i | def,ghi,ghi | depart, roundabout-exit-2, arrive |
| d,l | def,jkl,jkl | depart, roundabout-exit-3, arrive |
| d,c | def,abc,abc | depart, roundabout-exit-4, arrive |
| g,i | ghi,ghi,ghi | depart, roundabout-exit-1, arrive |
| g,l | ghi,jkl,jkl | depart, roundabout-exit-2, arrive |
| g,c | ghi,abc,abc | depart, roundabout-exit-3, arrive |
| g,f | ghi,edf,edf | depart, roundabout-exit-4, arrive |
| j,l | jkl,jkl,jkl | depart, roundabout-exit-1, arrive |
| j,c | jkl,abc,abc | depart, roundabout-exit-2, arrive |
| j,f | jkl,def,def | depart, roundabout-exit-3, arrive |
| j,i | jkl,ghi,ghi | depart, roundabout-exit-4, arrive |
+12 -12
View File
@@ -8,6 +8,7 @@
#include "engine/hint.hpp"
#include <boost/assert.hpp>
#include <boost/range/algorithm/transform.hpp>
#include <vector>
@@ -33,24 +34,23 @@ class BaseAPI
util::json::Array waypoints;
waypoints.values.resize(parameters.coordinates.size());
waypoints.values[0] = MakeWaypoint(parameters.coordinates.front(),
segment_end_coordinates.front().source_phantom);
waypoints.values[0] = MakeWaypoint(segment_end_coordinates.front().source_phantom);
auto coord_iter = std::next(parameters.coordinates.begin());
auto out_iter = std::next(waypoints.values.begin());
for (const auto &phantoms : segment_end_coordinates)
{
*out_iter++ = MakeWaypoint(*coord_iter++, phantoms.target_phantom);
}
boost::range::transform(segment_end_coordinates, out_iter,
[this](const PhantomNodes &phantom_pair)
{
return MakeWaypoint(phantom_pair.target_phantom);
});
return waypoints;
}
protected:
util::json::Object MakeWaypoint(const util::Coordinate input_coordinate,
const PhantomNode &phantom) const
// FIXME gcc 4.8 doesn't support for lambdas to call protected member functions
// protected:
util::json::Object MakeWaypoint(const PhantomNode &phantom) const
{
return json::makeWaypoint(phantom.location, facade.get_name_for_id(phantom.name_id),
Hint{input_coordinate, phantom, facade.GetCheckSum()});
return json::makeWaypoint(phantom.location, facade.GetNameForID(phantom.name_id),
Hint{phantom, facade.GetCheckSum()});
}
const datafacade::BaseDataFacade &facade;
+4 -2
View File
@@ -48,7 +48,9 @@ class MatchAPI final : public RouteAPI
response.values["code"] = "ok";
}
protected:
// FIXME gcc 4.8 doesn't support for lambdas to call protected member functions
// protected:
// FIXME this logic is a little backwards. We should change the output format of the
// map_matching
// routing algorithm to be easier to consume here.
@@ -98,7 +100,7 @@ class MatchAPI final : public RouteAPI
}
const auto &phantom =
sub_matchings[matching_index.sub_matching_index].nodes[matching_index.point_index];
auto waypoint = BaseAPI::MakeWaypoint(parameters.coordinates[trace_index], phantom);
auto waypoint = BaseAPI::MakeWaypoint(phantom);
waypoint.values["matchings_index"] = matching_index.sub_matching_index;
waypoint.values["waypoint_index"] = matching_index.point_index;
waypoints.values.push_back(std::move(waypoint));
+1 -2
View File
@@ -38,8 +38,7 @@ class NearestAPI final : public BaseAPI
waypoints.values.begin(),
[this](const PhantomNodeWithDistance &phantom_with_distance)
{
auto waypoint = MakeWaypoint(parameters.coordinates.front(),
phantom_with_distance.phantom_node);
auto waypoint = MakeWaypoint(phantom_with_distance.phantom_node);
waypoint.values["distance"] = phantom_with_distance.distance;
return waypoint;
});
+3 -3
View File
@@ -57,7 +57,8 @@ class RouteAPI : public BaseAPI
response.values["code"] = "ok";
}
protected:
// FIXME gcc 4.8 doesn't support for lambdas to call protected member functions
// protected:
template <typename ForwardIter>
util::json::Value MakeGeometry(ForwardIter begin, ForwardIter end) const
{
@@ -93,8 +94,7 @@ class RouteAPI : public BaseAPI
auto leg_geometry = guidance::assembleGeometry(
BaseAPI::facade, path_data, phantoms.source_phantom, phantoms.target_phantom);
auto leg = guidance::assembleLeg(BaseAPI::facade, path_data, leg_geometry,
phantoms.source_phantom, phantoms.target_phantom,
reversed_source, reversed_target);
phantoms.target_phantom, reversed_target);
if (parameters.steps)
{
+16 -14
View File
@@ -17,6 +17,8 @@
#include "util/integer_range.hpp"
#include <boost/range/algorithm/transform.hpp>
namespace osrm
{
namespace engine
@@ -66,19 +68,19 @@ class TableAPI final : public BaseAPI
response.values["code"] = "ok";
}
protected:
// FIXME gcc 4.8 doesn't support for lambdas to call protected member functions
// protected:
virtual util::json::Array MakeWaypoints(const std::vector<PhantomNode> &phantoms) const
{
util::json::Array json_waypoints;
json_waypoints.values.reserve(phantoms.size());
BOOST_ASSERT(phantoms.size() == parameters.coordinates.size());
auto phantom_iter = phantoms.begin();
auto coordinate_iter = parameters.coordinates.begin();
for (; phantom_iter != phantoms.end() && coordinate_iter != parameters.coordinates.end();
++phantom_iter, ++coordinate_iter)
{
json_waypoints.values.push_back(BaseAPI::MakeWaypoint(*coordinate_iter, *phantom_iter));
}
boost::range::transform(phantoms, std::back_inserter(json_waypoints.values),
[this](const PhantomNode &phantom)
{
return BaseAPI::MakeWaypoint(phantom);
});
return json_waypoints;
}
@@ -87,12 +89,12 @@ class TableAPI final : public BaseAPI
{
util::json::Array json_waypoints;
json_waypoints.values.reserve(indices.size());
for (auto idx : indices)
{
BOOST_ASSERT(idx < phantoms.size() && idx < parameters.coordinates.size());
json_waypoints.values.push_back(
BaseAPI::MakeWaypoint(parameters.coordinates[idx], phantoms[idx]));
}
boost::range::transform(indices, std::back_inserter(json_waypoints.values),
[this, phantoms](const std::size_t idx)
{
BOOST_ASSERT(idx < phantoms.size());
return BaseAPI::MakeWaypoint(phantoms[idx]);
});
return json_waypoints;
}
+8 -7
View File
@@ -36,10 +36,10 @@ class TripAPI final : public RouteAPI
BOOST_ASSERT(sub_trips.size() == sub_routes.size());
for (auto index : util::irange<std::size_t>(0UL, sub_trips.size()))
{
auto route = MakeRoute(
sub_routes[index].segment_end_coordinates, sub_routes[index].unpacked_path_segments,
sub_routes[index].source_traversed_in_reverse,
sub_routes[index].target_traversed_in_reverse);
auto route = MakeRoute(sub_routes[index].segment_end_coordinates,
sub_routes[index].unpacked_path_segments,
sub_routes[index].source_traversed_in_reverse,
sub_routes[index].target_traversed_in_reverse);
routes.values.push_back(std::move(route));
}
response.values["waypoints"] = MakeWaypoints(sub_trips, phantoms);
@@ -47,7 +47,9 @@ class TripAPI final : public RouteAPI
response.values["code"] = "ok";
}
protected:
// FIXME gcc 4.8 doesn't support for lambdas to call protected member functions
// protected:
// FIXME this logic is a little backwards. We should change the output format of the
// trip plugin routing algorithm to be easier to consume here.
util::json::Array MakeWaypoints(const std::vector<std::vector<NodeID>> &sub_trips,
@@ -90,8 +92,7 @@ class TripAPI final : public RouteAPI
auto trip_index = input_idx_to_trip_idx[input_index];
BOOST_ASSERT(!trip_index.NotUsed());
auto waypoint =
BaseAPI::MakeWaypoint(parameters.coordinates[input_index], phantoms[input_index]);
auto waypoint = BaseAPI::MakeWaypoint(phantoms[input_index]);
waypoint.values["trips_index"] = trip_index.sub_trip_index;
waypoint.values["waypoint_index"] = trip_index.point_index;
waypoints.values.push_back(std::move(waypoint));
@@ -138,7 +138,7 @@ class BaseDataFacade
virtual unsigned GetNameIndexFromEdgeID(const unsigned id) const = 0;
virtual std::string get_name_for_id(const unsigned name_id) const = 0;
virtual std::string GetNameForID(const unsigned name_id) const = 0;
virtual std::size_t GetCoreSize() const = 0;
@@ -551,7 +551,7 @@ class InternalDataFacade final : public BaseDataFacade
return m_name_ID_list.at(id);
}
std::string get_name_for_id(const unsigned name_id) const override final
std::string GetNameForID(const unsigned name_id) const override final
{
if (std::numeric_limits<unsigned>::max() == name_id)
{
@@ -621,7 +621,7 @@ class SharedDataFacade final : public BaseDataFacade
return m_name_ID_list.at(id);
}
std::string get_name_for_id(const unsigned name_id) const override final
std::string GetNameForID(const unsigned name_id) const override final
{
if (std::numeric_limits<unsigned>::max() == name_id)
{
+12 -8
View File
@@ -244,8 +244,8 @@ template <typename RTreeT, typename DataFacadeT> class GeospatialQuery
bool has_big_component = false;
auto results = rtree.Nearest(
input_coordinate,
[this, bearing, bearing_range, &has_big_component,
&has_small_component](const EdgeData &data)
[this, bearing, bearing_range, &has_big_component, &has_small_component](
const EdgeData &data)
{
auto use_segment =
(!has_small_component || (!has_big_component && !data.component.is_tiny));
@@ -290,8 +290,8 @@ template <typename RTreeT, typename DataFacadeT> class GeospatialQuery
bool has_big_component = false;
auto results = rtree.Nearest(
input_coordinate,
[this, bearing, bearing_range, &has_big_component,
&has_small_component](const EdgeData &data)
[this, bearing, bearing_range, &has_big_component, &has_small_component](
const EdgeData &data)
{
auto use_segment =
(!has_small_component || (!has_big_component && !data.component.is_tiny));
@@ -393,10 +393,14 @@ template <typename RTreeT, typename DataFacadeT> class GeospatialQuery
reverse_weight *= 1.0 - ratio;
}
auto transformed =
PhantomNodeWithDistance{PhantomNode{data, forward_weight, forward_offset,
reverse_weight, reverse_offset, point_on_segment},
current_perpendicular_distance};
auto transformed = PhantomNodeWithDistance{PhantomNode{data,
forward_weight,
forward_offset,
reverse_weight,
reverse_offset,
point_on_segment,
input_coordinate},
current_perpendicular_distance};
return transformed;
}
+7 -17
View File
@@ -96,18 +96,12 @@ template <typename DataFacadeT>
RouteLeg assembleLeg(const DataFacadeT &facade,
const std::vector<PathData> &route_data,
const LegGeometry &leg_geometry,
const PhantomNode &source_node,
const PhantomNode &target_node,
const bool source_traversed_in_reverse,
const bool target_traversed_in_reverse)
{
const auto source_duration =
(source_traversed_in_reverse ? source_node.GetReverseWeightPlusOffset()
: source_node.GetForwardWeightPlusOffset()) /
10.;
const auto target_duration =
(target_traversed_in_reverse ? target_node.GetReverseWeightPlusOffset()
: target_node.GetForwardWeightPlusOffset()) /
(target_traversed_in_reverse ? target_node.reverse_weight
: target_node.forward_weight) /
10.;
auto distance = std::accumulate(leg_geometry.segment_distances.begin(),
@@ -136,25 +130,21 @@ RouteLeg assembleLeg(const DataFacadeT &facade,
// The phantom node of t will contain:
// `forward_weight`: duration of (d,t)
// `forward_offset`: duration of (c, d)
//
// TODO discuss, this should not be the case after danpats fixes
// The PathData will contain entries of b, c and d. But only c will contain
// a duration value since its the only point associated with a turn.
// As such we want to slice of the duration for (a,s) and add the duration for
// (c,d,t)
duration = duration - source_duration + target_duration;
// path_data will have entries for (s,b), (b, c), (c, d) but (d, t) is only
// caputed by the phantom node. So we need to add the target duration here.
duration = duration + target_duration;
auto summary_array = detail::summarizeRoute<detail::MAX_USED_SEGMENTS>(route_data);
BOOST_ASSERT(detail::MAX_USED_SEGMENTS > 0);
BOOST_ASSERT(summary_array.begin() != summary_array.end());
std::string summary =
std::accumulate(std::next(summary_array.begin()), summary_array.end(),
facade.get_name_for_id(summary_array.front()),
facade.GetNameForID(summary_array.front()),
[&facade](std::string previous, const std::uint32_t name_id)
{
if (name_id != 0)
{
previous += ", " + facade.get_name_for_id(name_id);
previous += ", " + facade.GetNameForID(name_id);
}
return previous;
});
+60 -24
View File
@@ -40,13 +40,14 @@ std::vector<RouteStep> assembleSteps(const DataFacadeT &facade,
const bool source_traversed_in_reverse,
const bool target_traversed_in_reverse)
{
const double constexpr ZERO_DURACTION = 0., ZERO_DISTANCE = 0., NO_BEARING = 0.;
const EdgeWeight source_duration =
source_traversed_in_reverse ? source_node.forward_weight : source_node.reverse_weight;
source_traversed_in_reverse ? source_node.reverse_weight : source_node.forward_weight;
const auto source_mode = source_traversed_in_reverse ? source_node.backward_travel_mode
: source_node.forward_travel_mode;
const EdgeWeight target_duration =
target_traversed_in_reverse ? target_node.forward_weight : target_node.reverse_weight;
target_traversed_in_reverse ? target_node.reverse_weight : target_node.forward_weight;
const auto target_mode = target_traversed_in_reverse ? target_node.backward_travel_mode
: target_node.forward_travel_mode;
@@ -56,10 +57,19 @@ std::vector<RouteStep> assembleSteps(const DataFacadeT &facade,
steps.reserve(number_of_segments);
std::size_t segment_index = 0;
BOOST_ASSERT(leg_geometry.locations.size() >= 2);
// We report the relative position of source/target to the road only within a range that is
// sufficiently different but not full of the path
const constexpr double MINIMAL_RELATIVE_DISTANCE = 5., MAXIMAL_RELATIVE_DISTANCE = 300.;
const auto distance_to_start = util::coordinate_calculation::haversineDistance(
source_node.input_location, leg_geometry.locations[0]);
const auto initial_modifier =
leg_geometry.locations.size() >= 3
distance_to_start >= MINIMAL_RELATIVE_DISTANCE &&
distance_to_start <= MAXIMAL_RELATIVE_DISTANCE
? angleToDirectionModifier(util::coordinate_calculation::computeAngle(
leg_geometry.locations[0], leg_geometry.locations[1], leg_geometry.locations[2]))
source_node.input_location, leg_geometry.locations[0],
leg_geometry.locations[1]))
: extractor::guidance::DirectionModifier::UTurn;
if (leg_data.size() > 0)
@@ -82,10 +92,14 @@ std::vector<RouteStep> assembleSteps(const DataFacadeT &facade,
if (path_point.turn_instruction != extractor::guidance::TurnInstruction::NO_TURN())
{
BOOST_ASSERT(segment_duration >= 0);
const auto name = facade.get_name_for_id(path_point.name_id);
const auto name = facade.GetNameForID(path_point.name_id);
const auto distance = leg_geometry.segment_distances[segment_index];
steps.push_back(RouteStep{path_point.name_id, name, segment_duration / 10.0,
distance, path_point.travel_mode, maneuver,
steps.push_back(RouteStep{path_point.name_id,
name,
segment_duration / 10.0,
distance,
path_point.travel_mode,
maneuver,
leg_geometry.FrontIndex(segment_index),
leg_geometry.BackIndex(segment_index) + 1});
maneuver = detail::stepManeuverFromGeometry(path_point.turn_instruction,
@@ -98,8 +112,12 @@ std::vector<RouteStep> assembleSteps(const DataFacadeT &facade,
const auto distance = leg_geometry.segment_distances[segment_index];
const int duration = segment_duration + target_duration;
BOOST_ASSERT(duration >= 0);
steps.push_back(RouteStep{target_node.name_id, facade.get_name_for_id(target_node.name_id),
duration / 10., distance, target_mode, maneuver,
steps.push_back(RouteStep{target_node.name_id,
facade.GetNameForID(target_node.name_id),
duration / 10.,
distance,
target_mode,
maneuver,
leg_geometry.FrontIndex(segment_index),
leg_geometry.BackIndex(segment_index) + 1});
}
@@ -112,35 +130,53 @@ std::vector<RouteStep> assembleSteps(const DataFacadeT &facade,
// |---| source_duration
// |---------| target_duration
StepManeuver maneuver = {source_node.location, 0., 0.,
StepManeuver maneuver = {source_node.location,
NO_BEARING,
NO_BEARING,
extractor::guidance::TurnInstruction{
extractor::guidance::TurnType::NoTurn, initial_modifier},
WaypointType::Depart, INVALID_EXIT_NR};
WaypointType::Depart,
INVALID_EXIT_NR};
int duration = target_duration - source_duration;
BOOST_ASSERT(duration >= 0);
steps.push_back(RouteStep{source_node.name_id, facade.get_name_for_id(source_node.name_id),
duration / 10., leg_geometry.segment_distances[segment_index], source_mode,
std::move(maneuver), leg_geometry.FrontIndex(segment_index),
steps.push_back(RouteStep{source_node.name_id,
facade.GetNameForID(source_node.name_id),
duration / 10.,
leg_geometry.segment_distances[segment_index],
source_mode,
std::move(maneuver),
leg_geometry.FrontIndex(segment_index),
leg_geometry.BackIndex(segment_index) + 1});
}
BOOST_ASSERT(segment_index == number_of_segments - 1);
const auto distance_from_end = util::coordinate_calculation::haversineDistance(
target_node.input_location, leg_geometry.locations.back());
const auto final_modifier =
leg_geometry.locations.size() >= 3
distance_from_end >= MINIMAL_RELATIVE_DISTANCE &&
distance_from_end <= MAXIMAL_RELATIVE_DISTANCE
? angleToDirectionModifier(util::coordinate_calculation::computeAngle(
leg_geometry.locations[leg_geometry.locations.size() - 3],
leg_geometry.locations[leg_geometry.locations.size() - 2],
leg_geometry.locations[leg_geometry.locations.size() - 1]))
leg_geometry.locations[leg_geometry.locations.size() - 1],
target_node.input_location))
: extractor::guidance::DirectionModifier::UTurn;
// This step has length zero, the only reason we need it is the target location
steps.push_back(RouteStep{
target_node.name_id, facade.get_name_for_id(target_node.name_id), 0., 0., target_mode,
StepManeuver{target_node.location, 0., 0.,
extractor::guidance::TurnInstruction{extractor::guidance::TurnType::NoTurn,
final_modifier},
WaypointType::Arrive, INVALID_EXIT_NR},
leg_geometry.locations.size(), leg_geometry.locations.size()});
steps.push_back(
RouteStep{target_node.name_id,
facade.GetNameForID(target_node.name_id),
ZERO_DURACTION,
ZERO_DISTANCE,
target_mode,
StepManeuver{target_node.location,
NO_BEARING,
NO_BEARING,
extractor::guidance::TurnInstruction{
extractor::guidance::TurnType::NoTurn, final_modifier},
WaypointType::Arrive,
INVALID_EXIT_NR},
leg_geometry.locations.size(),
leg_geometry.locations.size()});
return steps;
}
+1 -4
View File
@@ -43,16 +43,13 @@ namespace engine
// Is returned as a temporary identifier for snapped coodinates
struct Hint
{
util::Coordinate input_coordinate;
PhantomNode phantom;
std::uint32_t data_checksum;
template <typename DataFacadeT>
bool IsValid(const util::Coordinate new_input_coordinates, DataFacadeT &facade) const
{
auto is_same_input_coordinate = new_input_coordinates.lon == input_coordinate.lon &&
new_input_coordinates.lat == input_coordinate.lat;
return is_same_input_coordinate && phantom.IsValid(facade.GetNumberOfNodes()) &&
return phantom.IsValid(facade.GetNumberOfNodes(), new_input_coordinates) &&
facade.GetCheckSum() == data_checksum;
}
+14 -5
View File
@@ -56,6 +56,7 @@ struct PhantomNode
bool is_tiny_component,
unsigned component_id,
util::Coordinate location,
util::Coordinate input_location,
unsigned short fwd_segment_position,
extractor::TravelMode forward_travel_mode,
extractor::TravelMode backward_travel_mode)
@@ -65,8 +66,8 @@ struct PhantomNode
forward_packed_geometry_id(forward_packed_geometry_id_),
reverse_packed_geometry_id(reverse_packed_geometry_id_),
component{component_id, is_tiny_component}, location(std::move(location)),
fwd_segment_position(fwd_segment_position), forward_travel_mode(forward_travel_mode),
backward_travel_mode(backward_travel_mode)
input_location(std::move(input_location)), fwd_segment_position(fwd_segment_position),
forward_travel_mode(forward_travel_mode), backward_travel_mode(backward_travel_mode)
{
}
@@ -115,6 +116,11 @@ struct PhantomNode
(component.id != INVALID_COMPONENTID) && (name_id != INVALID_NAMEID);
}
bool IsValid(const unsigned number_of_nodes, const util::Coordinate queried_coordinate) const
{
return queried_coordinate == input_location && IsValid(number_of_nodes);
}
bool IsValid() const { return location.IsValid() && (name_id != INVALID_NAMEID); }
bool operator==(const PhantomNode &other) const { return location == other.location; }
@@ -125,7 +131,8 @@ struct PhantomNode
int forward_offset_,
int reverse_weight_,
int reverse_offset_,
const util::Coordinate foot_point)
const util::Coordinate location_,
const util::Coordinate input_location_)
{
forward_node_id = other.forward_edge_based_node_id;
reverse_node_id = other.reverse_edge_based_node_id;
@@ -143,7 +150,8 @@ struct PhantomNode
component.id = other.component.id;
component.is_tiny = other.component.is_tiny;
location = foot_point;
location = location_;
input_location = input_location_;
fwd_segment_position = other.fwd_segment_position;
forward_travel_mode = other.forward_travel_mode;
@@ -169,6 +177,7 @@ struct PhantomNode
static_assert(sizeof(ComponentType) == 4, "ComponentType needs to 4 bytes big");
#endif
util::Coordinate location;
util::Coordinate input_location;
unsigned short fwd_segment_position;
// note 4 bits would suffice for each,
// but the saved byte would be padding anyway
@@ -177,7 +186,7 @@ struct PhantomNode
};
#ifndef _MSC_VER
static_assert(sizeof(PhantomNode) == 52, "PhantomNode has more padding then expected");
static_assert(sizeof(PhantomNode) == 60, "PhantomNode has more padding then expected");
#endif
using PhantomNodePair = std::pair<PhantomNode, PhantomNode>;
@@ -299,8 +299,7 @@ template <class DataFacadeT, class Derived> class BasicRoutingInterface
weight_vector);
BOOST_ASSERT(weight_vector.size() > 0);
auto total_weight =
std::accumulate(weight_vector.begin(), weight_vector.end(), 0);
auto total_weight = std::accumulate(weight_vector.begin(), weight_vector.end(), 0);
BOOST_ASSERT(weight_vector.size() == id_vector.size());
// ed.distance should be total_weight + penalties (turn, stop, etc)
@@ -325,11 +324,15 @@ template <class DataFacadeT, class Derived> class BasicRoutingInterface
extractor::guidance::TurnInstruction::NO_TURN(), travel_mode,
INVALID_EXIT_NR});
}
BOOST_ASSERT(unpacked_path.size() > 0);
unpacked_path.back().turn_instruction = turn_instruction;
unpacked_path.back().duration_until_turn += (ed.distance - total_weight);
if (is_first_segment)
{
auto source_weight = start_traversed_in_reverse
? phantom_node_pair.source_phantom.reverse_weight
: phantom_node_pair.source_phantom.forward_weight;
// Given this geometry:
// U---v---w---x---Z
// s
@@ -337,12 +340,8 @@ template <class DataFacadeT, class Derived> class BasicRoutingInterface
// However the first segment duration needs to be adjusted to the fact that the
// source phantom is in the middle of the segment.
// We do this by subtracting v--s from the duration.
BOOST_ASSERT(unpacked_path.front().duration_until_turn >=
phantom_node_pair.source_phantom.forward_weight);
unpacked_path.front().duration_until_turn -=
start_traversed_in_reverse
? phantom_node_pair.source_phantom.forward_weight
: phantom_node_pair.source_phantom.reverse_weight;
BOOST_ASSERT(unpacked_path.front().duration_until_turn >= source_weight);
unpacked_path.front().duration_until_turn -= source_weight;
}
}
}
@@ -388,7 +387,7 @@ template <class DataFacadeT, class Derived> class BasicRoutingInterface
// s: fwd_segment 0
// t: fwd_segment 3
// -> (U, v), (v, w), (w, x)
// note that (x, t) is _not_ included but needs to
// note that (x, t) is _not_ included but needs to be added later.
for (std::size_t i = start_index; i != end_index; (start_index < end_index ? ++i : --i))
{
BOOST_ASSERT(i < id_vector.size());
@@ -403,14 +402,15 @@ template <class DataFacadeT, class Derived> class BasicRoutingInterface
if (is_local_path && unpacked_path.size() > 0)
{
auto source_weight = start_traversed_in_reverse
? phantom_node_pair.source_phantom.reverse_weight
: phantom_node_pair.source_phantom.forward_weight;
// The above code will create segments for (v, w), (w,x), (x, y) and (y, Z).
// However the first segment duration needs to be adjusted to the fact that the source
// phantom
// is in the middle of the segment. We do this by subtracting v--s from the duration.
BOOST_ASSERT(unpacked_path.front().duration_until_turn >=
phantom_node_pair.source_phantom.forward_weight);
unpacked_path.front().duration_until_turn -=
phantom_node_pair.source_phantom.forward_weight;
// phantom is in the middle of the segment. We do this by subtracting v--s from the
// duration.
BOOST_ASSERT(unpacked_path.front().duration_until_turn >= source_weight);
unpacked_path.front().duration_until_turn -= source_weight;
}
// there is no equivalent to a node-based node in an edge-expanded graph.
@@ -17,6 +17,7 @@
#include "util/node_based_graph.hpp"
#include "util/typedefs.hpp"
#include "util/deallocating_vector.hpp"
#include "util/name_table.hpp"
#include <algorithm>
#include <cstdint>
@@ -51,7 +52,8 @@ class EdgeBasedGraphFactory
const std::unordered_set<NodeID> &traffic_lights,
std::shared_ptr<const RestrictionMap> restriction_map,
const std::vector<QueryNode> &node_info_list,
SpeedProfileProperties speed_profile);
SpeedProfileProperties speed_profile,
const util::NameTable &name_table);
void Run(const std::string &original_edge_data_filename,
lua_State *lua_state,
@@ -106,6 +108,8 @@ class EdgeBasedGraphFactory
SpeedProfileProperties speed_profile;
const util::NameTable &name_table;
void CompressGeometry();
unsigned RenumberEdges();
void GenerateEdgeExpandedNodes();
+91 -9
View File
@@ -12,9 +12,11 @@
#include "extractor/guidance/classification_data.hpp"
#include "extractor/guidance/turn_instruction.hpp"
#include <algorithm>
#include <map>
#include <cmath>
#include <cstdint>
#include <string>
namespace osrm
{
@@ -249,10 +251,11 @@ inline double angularDeviation(const double angle, const double from)
return std::min(360 - deviation, deviation);
}
inline double getAngularPenalty(const double angle, TurnInstruction instruction)
inline double getAngularPenalty(const double angle, DirectionModifier modifier)
{
// these are not aligned with getTurnDirection but represent an ideal center
const double center[] = {0, 45, 90, 135, 180, 225, 270, 315};
return angularDeviation(center[static_cast<int>(instruction.direction_modifier)], angle);
return angularDeviation(center[static_cast<int>(modifier)], angle);
}
inline double getTurnConfidence(const double angle, TurnInstruction instruction)
@@ -262,8 +265,8 @@ inline double getTurnConfidence(const double angle, TurnInstruction instruction)
if (!isBasic(instruction.type) || instruction.direction_modifier == DirectionModifier::UTurn)
return 1.0;
const double deviations[] = {0, 45, 50, 35, 10, 35, 50, 45};
const double difference = getAngularPenalty(angle, instruction);
const double deviations[] = {0, 45, 50, 30, 20, 30, 50, 45};
const double difference = getAngularPenalty(angle, instruction.direction_modifier);
const double max_deviation = deviations[static_cast<int>(instruction.direction_modifier)];
return 1.0 - (difference / max_deviation) * (difference / max_deviation);
}
@@ -281,7 +284,7 @@ inline DirectionModifier getTurnDirection(const double angle)
return DirectionModifier::Right;
if (angle >= 140 && angle < 170)
return DirectionModifier::SlightRight;
if (angle >= 170 && angle <= 190)
if (angle >= 165 && angle <= 195)
return DirectionModifier::Straight;
if (angle > 190 && angle <= 220)
return DirectionModifier::SlightLeft;
@@ -295,10 +298,14 @@ inline DirectionModifier getTurnDirection(const double angle)
// swaps left <-> right modifier types
inline DirectionModifier mirrorDirectionModifier(const DirectionModifier modifier)
{
const constexpr DirectionModifier results[] = {
DirectionModifier::UTurn, DirectionModifier::SharpLeft, DirectionModifier::Left,
DirectionModifier::SlightLeft, DirectionModifier::Straight, DirectionModifier::SlightRight,
DirectionModifier::Right, DirectionModifier::SharpRight};
const constexpr DirectionModifier results[] = {DirectionModifier::UTurn,
DirectionModifier::SharpLeft,
DirectionModifier::Left,
DirectionModifier::SlightLeft,
DirectionModifier::Straight,
DirectionModifier::SlightRight,
DirectionModifier::Right,
DirectionModifier::SharpRight};
return results[modifier];
}
@@ -315,6 +322,81 @@ inline bool isLowPriorityRoadClass(const FunctionalRoadClass road_class)
road_class == FunctionalRoadClass::SERVICE;
}
inline bool isDistinct(const DirectionModifier first, const DirectionModifier second)
{
if ((first + 1) % detail::num_direction_modifiers == second)
return false;
if ((second + 1) % detail::num_direction_modifiers == first)
return false;
return true;
}
inline bool requiresNameAnnounced(const std::string &from, const std::string &to)
{
// FIXME, handle in profile to begin with?
// this uses the encoding of references in the profile, which is very BAD
// Input for this function should be a struct separating streetname, suffix (e.g. road,
// boulevard, North, West ...), and a list of references
std::string from_name;
std::string from_ref;
std::string to_name;
std::string to_ref;
// Split from the format "{name} ({ref})" -> name, ref
auto split = [](const std::string &name, std::string &out_name, std::string &out_ref)
{
const auto ref_begin = name.find_first_of('(');
if (ref_begin != std::string::npos)
{
out_name = name.substr(0, ref_begin);
out_ref = name.substr(ref_begin + 1, name.find_first_of(')') - 1);
}
else
{
out_name = name;
}
};
split(from, from_name, from_ref);
split(to, to_name, to_ref);
// check similarity of names
auto names_are_empty = from_name.empty() && to_name.empty();
auto names_are_equal = from_name == to_name;
auto name_is_removed = !from_name.empty() && to_name.empty();
// references are contained in one another
auto refs_are_empty = from_ref.empty() && to_ref.empty();
auto ref_is_contained =
!from_ref.empty() && !to_ref.empty() &&
(from_ref.find(to_ref) != std::string::npos || to_ref.find(from_ref) != std::string::npos);
auto ref_is_removed = !from_ref.empty() && to_ref.empty();
auto obvious_change = ref_is_contained || names_are_equal ||
(names_are_empty && refs_are_empty) || name_is_removed || ref_is_removed;
return !obvious_change;
}
inline int getPriority( const FunctionalRoadClass road_class )
{
//The road priorities indicate which roads can bee seen as more or less equal.
//They are used in Fork-Discovery. Possibly should be moved to profiles post v5?
//A fork can happen between road types that are at most 1 priority apart from each other
const constexpr int road_priority[] = {10, 0, 10, 2, 10, 4, 10, 6, 10, 8, 10, 11, 10, 12, 10, 14};
return road_priority[static_cast<int>(road_class)];
}
inline bool canBeSeenAsFork(const FunctionalRoadClass first, const FunctionalRoadClass second)
{
// forks require similar road categories
// Based on the priorities assigned above, we can set forks only if the road priorities match closely.
// Potentially we could include features like number of lanes here and others?
// Should also be moved to profiles
return std::abs(getPriority(first) - getPriority(second)) <= 1;
}
} // namespace guidance
} // namespace extractor
} // namespace osrm
+88 -93
View File
@@ -6,11 +6,14 @@
#include "extractor/restriction_map.hpp"
#include "extractor/compressed_edge_container.hpp"
#include "util/name_table.hpp"
#include <cstdint>
#include <string>
#include <vector>
#include <memory>
#include <utility>
#include <unordered_set>
namespace osrm
@@ -20,42 +23,59 @@ namespace extractor
namespace guidance
{
struct TurnCandidate
// What is exposed to the outside
struct TurnOperation final
{
EdgeID eid; // the id of the arc
bool valid; // a turn may be relevant to good instructions, even if we cannot take the road
double angle; // the approximated angle of the turn
TurnInstruction instruction; // a proposed instruction
double confidence; // how close to the border is the turn?
EdgeID eid;
double angle;
TurnInstruction instruction;
};
// For the turn analysis, we require a full list of all connected roads to determine the outcome.
// Invalid turns can influence the perceived angles
//
// aaa(2)aa
// a - bbbbb
// aaa(1)aa
//
// will not be perceived as a turn from (1) -> b, and as a U-turn from (1) -> (2).
// In addition, they can influence whether a turn is obvious or not.
struct ConnectedRoad final
{
ConnectedRoad(const TurnOperation turn, const bool entry_allowed = false);
TurnOperation turn;
bool entry_allowed; // a turn may be relevant to good instructions, even if we cannot take
// the road
std::string toString() const
{
std::string result = "[turn] ";
result += std::to_string(eid);
result += " valid: ";
result += std::to_string(valid);
std::string result = "[connection] ";
result += std::to_string(turn.eid);
result += " allows entry: ";
result += std::to_string(entry_allowed);
result += " angle: ";
result += std::to_string(angle);
result += std::to_string(turn.angle);
result += " instruction: ";
result += std::to_string(static_cast<std::int32_t>(instruction.type)) + " " +
std::to_string(static_cast<std::int32_t>(instruction.direction_modifier));
result += " confidence: ";
result += std::to_string(confidence);
result += std::to_string(static_cast<std::int32_t>(turn.instruction.type)) + " " +
std::to_string(static_cast<std::int32_t>(turn.instruction.direction_modifier));
return result;
}
};
class TurnAnalysis
{
public:
TurnAnalysis(const util::NodeBasedDynamicGraph &node_based_graph,
const std::vector<QueryNode> &node_info_list,
const RestrictionMap &restriction_map,
const std::unordered_set<NodeID> &barrier_nodes,
const CompressedEdgeContainer &compressed_edge_container);
const CompressedEdgeContainer &compressed_edge_container,
const util::NameTable &name_table);
// the entry into the turn analysis
std::vector<TurnCandidate> getTurns(const NodeID from_node, const EdgeID via_eid) const;
std::vector<TurnOperation> getTurns(const NodeID from_node, const EdgeID via_eid) const;
private:
const util::NodeBasedDynamicGraph &node_based_graph;
@@ -63,12 +83,14 @@ class TurnAnalysis
const RestrictionMap &restriction_map;
const std::unordered_set<NodeID> &barrier_nodes;
const CompressedEdgeContainer &compressed_edge_container;
const util::NameTable &name_table;
// Check for restrictions/barriers and generate a list of valid and invalid turns present at the
// Check for restrictions/barriers and generate a list of valid and invalid turns present at
// the
// node reached
// from `from_node` via `via_eid`
// The resulting candidates have to be analysed for their actual instructions later on.
std::vector<TurnCandidate> getTurnCandidates(const NodeID from_node,
std::vector<ConnectedRoad> getConnectedRoads(const NodeID from_node,
const EdgeID via_eid) const;
// Merge segregated roads to omit invalid turns in favor of treating segregated roads as
@@ -82,10 +104,7 @@ class TurnAnalysis
//
// The treatment results in a straight turn angle of 180º rather than a turn angle of approx
// 160
std::vector<TurnCandidate>
mergeSegregatedRoads(const NodeID from_node,
const EdgeID via_eid,
std::vector<TurnCandidate> turn_candidates) const;
std::vector<ConnectedRoad> mergeSegregatedRoads(std::vector<ConnectedRoad> intersection) const;
// TODO distinguish roundabouts and rotaries
// TODO handle bike/walk cases that allow crossing a roundabout!
@@ -93,110 +112,86 @@ class TurnAnalysis
// Processing of roundabouts
// Produces instructions to enter/exit a roundabout or to stay on it.
// Performs the distinction between roundabout and rotaries.
std::vector<TurnCandidate> handleRoundabouts(const NodeID from,
const EdgeID via_edge,
std::vector<ConnectedRoad> handleRoundabouts(const EdgeID via_edge,
const bool on_roundabout,
const bool can_enter_roundabout,
const bool can_exit_roundabout,
std::vector<TurnCandidate> turn_candidates) const;
std::vector<ConnectedRoad> intersection) const;
// Indicates a Junction containing a motoryway
bool isMotorwayJunction(const NodeID from,
const EdgeID via_edge,
const std::vector<TurnCandidate> &turn_candidates) const;
bool isMotorwayJunction(const EdgeID via_edge,
const std::vector<ConnectedRoad> &intersection) const;
// Decide whether a turn is a turn or a ramp access
TurnType findBasicTurnType(const EdgeID via_edge, const TurnCandidate &candidate) const;
TurnType findBasicTurnType(const EdgeID via_edge, const ConnectedRoad &candidate) const;
// Get the Instruction for an obvious turn
// Instruction will be a silent instruction
TurnInstruction getInstructionForObvious(const std::size_t number_of_candidates,
const EdgeID via_edge,
const TurnCandidate &candidate) const;
const ConnectedRoad &candidate) const;
// Helper Function that decides between NoTurn or NewName
TurnInstruction
noTurnOrNewName(const NodeID from, const EdgeID via_edge, const TurnCandidate &candidate) const;
noTurnOrNewName(const NodeID from, const EdgeID via_edge, const ConnectedRoad &candidate) const;
// Basic Turn Handling
// Dead end.
std::vector<TurnCandidate> handleOneWayTurn(const NodeID from,
const EdgeID via_edge,
std::vector<TurnCandidate> turn_candidates) const;
std::vector<ConnectedRoad> handleOneWayTurn(std::vector<ConnectedRoad> intersection) const;
// Mode Changes, new names...
std::vector<TurnCandidate> handleTwoWayTurn(const NodeID from,
const EdgeID via_edge,
std::vector<TurnCandidate> turn_candidates) const;
std::vector<ConnectedRoad> handleTwoWayTurn(const EdgeID via_edge,
std::vector<ConnectedRoad> intersection) const;
// Forks, T intersections and similar
std::vector<TurnCandidate> handleThreeWayTurn(const NodeID from,
const EdgeID via_edge,
std::vector<TurnCandidate> turn_candidates) const;
std::vector<ConnectedRoad> handleThreeWayTurn(const EdgeID via_edge,
std::vector<ConnectedRoad> intersection) const;
// Normal Intersection. Can still contain forks...
std::vector<TurnCandidate> handleFourWayTurn(const NodeID from,
const EdgeID via_edge,
std::vector<TurnCandidate> turn_candidates) const;
// Fallback for turns of high complexion
std::vector<TurnCandidate> handleComplexTurn(const NodeID from,
const EdgeID via_edge,
std::vector<TurnCandidate> turn_candidates) const;
// Handling of turns larger then degree three
std::vector<ConnectedRoad> handleComplexTurn(const EdgeID via_edge,
std::vector<ConnectedRoad> intersection) const;
// Any Junction containing motorways
std::vector<TurnCandidate> handleMotorwayJunction(
const NodeID from, const EdgeID via_edge, std::vector<TurnCandidate> turn_candidates) const;
std::vector<ConnectedRoad> handleMotorwayJunction(
const EdgeID via_edge, std::vector<ConnectedRoad> intersection) const;
std::vector<TurnCandidate> handleFromMotorway(
const NodeID from, const EdgeID via_edge, std::vector<TurnCandidate> turn_candidates) const;
std::vector<ConnectedRoad> handleFromMotorway(const EdgeID via_edge,
std::vector<ConnectedRoad> intersection) const;
std::vector<TurnCandidate> handleMotorwayRamp(
const NodeID from, const EdgeID via_edge, std::vector<TurnCandidate> turn_candidates) const;
std::vector<ConnectedRoad> handleMotorwayRamp(const EdgeID via_edge,
std::vector<ConnectedRoad> intersection) const;
// Utility function, setting basic turn types. Prepares for normal turn handling.
std::vector<TurnCandidate> setTurnTypes(const NodeID from,
std::vector<ConnectedRoad> setTurnTypes(const NodeID from,
const EdgeID via_edge,
std::vector<TurnCandidate> turn_candidates) const;
// Utility function to handle direction modifier conflicts if reasonably possible
std::vector<TurnCandidate> handleConflicts(const NodeID from,
const EdgeID via_edge,
std::vector<TurnCandidate> turn_candidates) const;
// Old fallbacks, to be removed
std::vector<TurnCandidate> optimizeRamps(const EdgeID via_edge,
std::vector<TurnCandidate> turn_candidates) const;
std::vector<TurnCandidate> optimizeCandidates(const EdgeID via_eid,
std::vector<TurnCandidate> turn_candidates) const;
bool isObviousChoice(const EdgeID via_eid,
const std::size_t turn_index,
const std::vector<TurnCandidate> &turn_candidates) const;
std::vector<TurnCandidate> suppressTurns(const EdgeID via_eid,
std::vector<TurnCandidate> turn_candidates) const;
// node_u -- (edge_1) --> node_v -- (edge_2) --> node_w
TurnInstruction AnalyzeTurn(const NodeID node_u,
const EdgeID edge1,
const NodeID node_v,
const EdgeID edge2,
const NodeID node_w,
const double angle) const;
std::vector<ConnectedRoad> intersection) const;
// Assignment of specific turn types
void assignFork(const EdgeID via_edge, TurnCandidate &left, TurnCandidate &right) const;
void assignFork(const EdgeID via_edge, ConnectedRoad &left, ConnectedRoad &right) const;
void assignFork(const EdgeID via_edge,
TurnCandidate &left,
TurnCandidate &center,
TurnCandidate &right) const;
ConnectedRoad &left,
ConnectedRoad &center,
ConnectedRoad &right) const;
//Type specific fallbacks
std::vector<TurnCandidate>
fallbackTurnAssignmentMotorway(std::vector<TurnCandidate> turn_candidates) const;
void
handleDistinctConflict(const EdgeID via_edge, ConnectedRoad &left, ConnectedRoad &right) const;
// Type specific fallbacks
std::vector<ConnectedRoad>
fallbackTurnAssignmentMotorway(std::vector<ConnectedRoad> intersection) const;
// Classification
std::size_t findObviousTurn(const EdgeID via_edge,
const std::vector<ConnectedRoad> &intersection) const;
std::pair<std::size_t, std::size_t>
findFork(const std::vector<ConnectedRoad> &intersection) const;
std::vector<ConnectedRoad> assignLeftTurns(const EdgeID via_edge,
std::vector<ConnectedRoad> intersection,
const std::size_t starting_at) const;
std::vector<ConnectedRoad> assignRightTurns(const EdgeID via_edge,
std::vector<ConnectedRoad> intersection,
const std::size_t up_to) const;
}; // class TurnAnalysis
@@ -42,8 +42,16 @@ enum TurnType // at the moment we can support 32 turn types, without increasing
NewName, // no turn, but name changes
Continue, // remain on a street
Turn, // basic turn
FirstTurn, // First of x turns
SecondTurn, // Second of x turns
ThirdTurn, // Third of x turns
FourthTurn, // Fourth of x turns
Merge, // merge onto a street
Ramp, // special turn (highway ramp exits)
FirstRamp, // first turn onto a ramp
SecondRamp, // second turn onto a ramp
ThirdRamp, // third turn onto a ramp
FourthRamp, // fourth turn onto a ramp
Fork, // fork road splitting up
EndOfRoad, // T intersection
EnterRoundabout, // Entering a small Roundabout
+3
View File
@@ -52,6 +52,9 @@ class Server
acceptor.set_option(boost::asio::ip::tcp::acceptor::reuse_address(true));
acceptor.bind(endpoint);
acceptor.listen();
util::SimpleLogger().Write() << "Listening on: " << acceptor.local_endpoint();
acceptor.async_accept(
new_connection->socket(),
boost::bind(&Server::HandleAccept, this, boost::asio::placeholders::error));
+25 -5
View File
@@ -3,20 +3,34 @@
#include "util/coordinate.hpp"
#include <boost/math/constants/constants.hpp>
#include <utility>
namespace osrm
{
namespace util
{
namespace coordinate_calculation
{
const constexpr long double RAD = 0.017453292519943295769236907684886;
const constexpr long double DEGREE_TO_RAD = 0.017453292519943295769236907684886;
const constexpr long double RAD_TO_DEGREE = 1. / DEGREE_TO_RAD;
// earth radius varies between 6,356.750-6,378.135 km (3,949.901-3,963.189mi)
// The IUGG value for the equatorial radius is 6378.137 km (3963.19 miles)
const constexpr long double EARTH_RADIUS = 6372797.560856;
// radius used by WGS84
const constexpr double EARTH_RADIUS_WGS84 = 6378137.0;
namespace coordinate_calculation
namespace detail
{
// earth circumference devided by 2
const constexpr double MAXEXTENT = EARTH_RADIUS_WGS84 * boost::math::constants::pi<double>();
// ^ math functions are not constexpr since they have side-effects (setting errno) :(
const double MAX_LATITUDE = RAD_TO_DEGREE * (2.0 * std::atan(std::exp(180.0 * DEGREE_TO_RAD)) - boost::math::constants::half_pi<double>());
const constexpr double MAX_LONGITUDE = 180.0;
}
//! Projects both coordinates and takes the euclidean distance of the projected points
// Does not return meters!
@@ -50,9 +64,6 @@ double perpendicularDistanceFromProjectedCoordinate(
Coordinate &nearest_location,
double &ratio);
double degToRad(const double degree);
double radToDeg(const double radian);
double bearing(const Coordinate first_coordinate, const Coordinate second_coordinate);
// Get angle of line segment (A,C)->(C,B)
@@ -64,8 +75,17 @@ Coordinate interpolateLinear(double factor, const Coordinate from, const Coordin
namespace mercator
{
// This is the global default tile size for all Mapbox Vector Tiles
const constexpr double TILE_SIZE = 256.0;
// Converts projected mercator degrees to PX
const constexpr double DEGREE_TO_PX = detail::MAXEXTENT / 180.0;
double degreeToPixel(FloatLatitude lat, unsigned zoom);
double degreeToPixel(FloatLongitude lon, unsigned zoom);
FloatLatitude yToLat(const double value);
double latToY(const FloatLatitude latitude);
void xyzToMercator(const int x, const int y, const int z, double &minx, double &miny, double &maxx, double &maxy);
void xyzToWSG84(const int x, const int y, const int z, double &minx, double &miny, double &maxx, double &maxy);
} // ns mercator
} // ns coordinate_calculation
} // ns util
+31
View File
@@ -0,0 +1,31 @@
#ifndef OSRM_UTIL_NAME_TABLE_HPP
#define OSRM_UTIL_NAME_TABLE_HPP
#include "util/shared_memory_vector_wrapper.hpp"
#include "util/range_table.hpp"
#include <string>
namespace osrm
{
namespace util
{
// While this could, theoretically, hold any names in the fitting format,
// the NameTable allows access to a part of the Datafacade to allow
// processing based on name indices.
class NameTable
{
private:
// FIXME should this use shared memory
RangeTable<16, false> m_name_table;
ShM<char, false>::vector m_names_char_list;
public:
NameTable(const std::string &filename);
std::string GetNameForID(const unsigned name_id) const;
};
} // namespace util
} // namespace osrm
#endif // OSRM_UTIL_NAME_TABLE_HPP
-87
View File
@@ -1,87 +0,0 @@
#ifndef UTIL_TILES_HPP
#define UTIL_TILES_HPP
#include "util/coordinate.hpp"
#include <boost/assert.hpp>
#include <cmath>
#include <tuple>
// This is a port of the tilebelt algorithm https://github.com/mapbox/tilebelt
namespace osrm
{
namespace util
{
namespace tiles
{
struct Tile
{
unsigned x;
unsigned y;
unsigned z;
};
namespace detail
{
// optimized for 32bit integers
static constexpr unsigned MAX_ZOOM = 32;
// Returns 1-indexed 1..32 of MSB if value > 0 or 0 if value == 0
inline unsigned getMSBPosition(std::uint32_t value)
{
if (value == 0)
return 0;
std::uint8_t pos = 1;
while (value >>= 1)
pos++;
return pos;
}
inline unsigned getBBMaxZoom(const Tile top_left, const Tile bottom_left)
{
auto x_xor = top_left.x ^ bottom_left.x;
auto y_xor = top_left.y ^ bottom_left.y;
auto lon_msb = detail::getMSBPosition(x_xor);
auto lat_msb = detail::getMSBPosition(y_xor);
return MAX_ZOOM - std::max(lon_msb, lat_msb);
}
}
inline Tile pointToTile(const FloatLongitude lon, const FloatLatitude lat)
{
auto sin_lat = std::sin(static_cast<double>(lat) * M_PI / 180.);
auto p2z = std::pow(2, detail::MAX_ZOOM);
unsigned x = p2z * (static_cast<double>(lon) / 360. + 0.5);
unsigned y = p2z * (0.5 - 0.25 * std::log((1 + sin_lat) / (1 - sin_lat)) / M_PI);
return Tile{x, y, detail::MAX_ZOOM};
}
inline Tile getBBMaxZoomTile(const FloatLongitude min_lon,
const FloatLatitude min_lat,
const FloatLongitude max_lon,
const FloatLatitude max_lat)
{
const auto top_left = pointToTile(min_lon, min_lat);
const auto bottom_left = pointToTile(max_lon, max_lat);
BOOST_ASSERT(top_left.z == detail::MAX_ZOOM);
BOOST_ASSERT(bottom_left.z == detail::MAX_ZOOM);
const auto max_zoom = detail::getBBMaxZoom(top_left, bottom_left);
if (max_zoom == 0)
{
return Tile{0, 0, 0};
}
auto x = top_left.x >> (detail::MAX_ZOOM - max_zoom);
auto y = top_left.y >> (detail::MAX_ZOOM - max_zoom);
return Tile{x, y, max_zoom};
}
}
}
}
#endif
+48
View File
@@ -0,0 +1,48 @@
#ifndef UTIL_VIEWPORT_HPP
#define UTIL_VIEWPORT_HPP
#include "util/coordinate.hpp"
#include "util/coordinate_calculation.hpp"
#include <boost/assert.hpp>
#include <cmath>
#include <tuple>
// Port of https://github.com/mapbox/geo-viewport
namespace osrm
{
namespace util
{
namespace viewport
{
namespace detail
{
static constexpr unsigned MAX_ZOOM = 18;
static constexpr unsigned MIN_ZOOM = 1;
// this is an upper bound to current display sizes
static constexpr double VIEWPORT_WIDTH = 8 * coordinate_calculation::mercator::TILE_SIZE;
static constexpr double VIEWPORT_HEIGHT = 5 * coordinate_calculation::mercator::TILE_SIZE;
static double INV_LOG_2 = 1. / std::log(2);
}
unsigned getFittedZoom(util::Coordinate south_west, util::Coordinate north_east)
{
const auto min_x = coordinate_calculation::mercator::degreeToPixel(toFloating(south_west.lon), detail::MAX_ZOOM);
const auto max_y = coordinate_calculation::mercator::degreeToPixel(toFloating(south_west.lat), detail::MAX_ZOOM);
const auto max_x = coordinate_calculation::mercator::degreeToPixel(toFloating(north_east.lon), detail::MAX_ZOOM);
const auto min_y = coordinate_calculation::mercator::degreeToPixel(toFloating(north_east.lat), detail::MAX_ZOOM);
const double width_ratio = (max_x - min_x) / detail::VIEWPORT_WIDTH;
const double height_ratio = (max_y - min_y) / detail::VIEWPORT_HEIGHT;
const auto zoom = detail::MAX_ZOOM - std::max(std::log(width_ratio), std::log(height_ratio)) * detail::INV_LOG_2;
return std::max<unsigned>(detail::MIN_ZOOM, zoom);
}
}
}
}
#endif
+5 -5
View File
@@ -40,11 +40,11 @@ const constexpr char *modifier_names[] = {"uturn",
// translations of TurnTypes. Not all types are exposed to the outside world.
// invalid types should never be returned as part of the API
const constexpr char *turn_type_names[] = {
"invalid", "no turn", "invalid", "new name", "continue", "turn",
"merge", "ramp", "fork", "end of road", "roundabout", "invalid",
"roundabout", "invalid", "traffic circle", "invalid", "traffic circle", "invalid",
"invalid", "restriction", "notification"};
"invalid", "no turn", "invalid", "new name", "continue", "turn",
"turn", "turn", "turn", "turn", "merge", "ramp",
"ramp", "ramp", "ramp", "ramp", "fork", "end of road",
"roundabout", "invalid", "roundabout", "invalid", "traffic circle", "invalid",
"traffic circle", "invalid", "invalid", "restriction", "notification"};
const constexpr char *waypoint_type_names[] = {"invalid", "arrive", "depart"};
// Check whether to include a modifier in the result of the API
+10 -8
View File
@@ -27,28 +27,30 @@ struct CoordinatePairCalculator
CoordinatePairCalculator(const util::Coordinate coordinate_a,
const util::Coordinate coordinate_b)
{
using namespace util::coordinate_calculation;
// initialize distance calculator with two fixed coordinates a, b
first_lon = static_cast<double>(toFloating(coordinate_a.lon)) * util::RAD;
first_lat = static_cast<double>(toFloating(coordinate_a.lat)) * util::RAD;
second_lon = static_cast<double>(toFloating(coordinate_b.lon)) * util::RAD;
second_lat = static_cast<double>(toFloating(coordinate_b.lat)) * util::RAD;
first_lon = static_cast<double>(toFloating(coordinate_a.lon)) * DEGREE_TO_RAD;
first_lat = static_cast<double>(toFloating(coordinate_a.lat)) * DEGREE_TO_RAD;
second_lon = static_cast<double>(toFloating(coordinate_b.lon)) * DEGREE_TO_RAD;
second_lat = static_cast<double>(toFloating(coordinate_b.lat)) * DEGREE_TO_RAD;
}
int operator()(const util::Coordinate other) const
{
using namespace util::coordinate_calculation;
// set third coordinate c
const float float_lon1 = static_cast<double>(toFloating(other.lon)) * util::RAD;
const float float_lat1 = static_cast<double>(toFloating(other.lat)) * util::RAD;
const float float_lon1 = static_cast<double>(toFloating(other.lon)) * DEGREE_TO_RAD;
const float float_lat1 = static_cast<double>(toFloating(other.lat)) * DEGREE_TO_RAD;
// compute distance (a,c)
const float x_value_1 = (first_lon - float_lon1) * cos((float_lat1 + first_lat) / 2.f);
const float y_value_1 = first_lat - float_lat1;
const float dist1 = std::hypot(x_value_1, y_value_1) * util::EARTH_RADIUS;
const float dist1 = std::hypot(x_value_1, y_value_1) * EARTH_RADIUS;
// compute distance (b,c)
const float x_value_2 = (second_lon - float_lon1) * cos((float_lat1 + second_lat) / 2.f);
const float y_value_2 = second_lat - float_lat1;
const float dist2 = std::hypot(x_value_2, y_value_2) * util::EARTH_RADIUS;
const float dist2 = std::hypot(x_value_2, y_value_2) * EARTH_RADIUS;
// return the minimum
return static_cast<int>(std::min(dist1, dist2));
+10 -13
View File
@@ -3,7 +3,7 @@
#include "engine/guidance/leg_geometry.hpp"
#include "engine/douglas_peucker.hpp"
#include "util/tiles.hpp"
#include "util/viewport.hpp"
#include <vector>
#include <tuple>
@@ -23,25 +23,22 @@ namespace
unsigned calculateOverviewZoomLevel(const std::vector<LegGeometry> &leg_geometries)
{
util::FixedLongitude min_lon{std::numeric_limits<int>::max()};
util::FixedLongitude max_lon{std::numeric_limits<int>::min()};
util::FixedLatitude min_lat{std::numeric_limits<int>::max()};
util::FixedLatitude max_lat{std::numeric_limits<int>::min()};
util::Coordinate south_west{util::FixedLongitude{std::numeric_limits<int>::max()}, util::FixedLatitude{std::numeric_limits<int>::max()}};
util::Coordinate north_east{util::FixedLongitude{std::numeric_limits<int>::min()}, util::FixedLatitude{std::numeric_limits<int>::min()}};
for (const auto &leg_geometry : leg_geometries)
{
for (const auto coord : leg_geometry.locations)
{
min_lon = std::min(min_lon, coord.lon);
max_lon = std::max(max_lon, coord.lon);
min_lat = std::min(min_lat, coord.lat);
max_lat = std::max(max_lat, coord.lat);
south_west.lon = std::min(south_west.lon, coord.lon);
south_west.lat = std::min(south_west.lat, coord.lat);
north_east.lon = std::max(north_east.lon, coord.lon);
north_east.lat = std::max(north_east.lat, coord.lat);
}
}
return util::tiles::getBBMaxZoomTile(toFloating(min_lon), toFloating(min_lat),
toFloating(max_lon), toFloating(max_lat))
.z;
return util::viewport::getFittedZoom(south_west, north_east);
}
std::vector<util::Coordinate> simplifyGeometry(const std::vector<LegGeometry> &leg_geometries,
@@ -70,7 +67,7 @@ std::vector<util::Coordinate> assembleOverview(const std::vector<LegGeometry> &l
{
if (use_simplification)
{
const auto zoom_level = calculateOverviewZoomLevel(leg_geometries);
const auto zoom_level = std::min(18u, calculateOverviewZoomLevel(leg_geometries));
return simplifyGeometry(leg_geometries, zoom_level);
}
BOOST_ASSERT(!use_simplification);
-2
View File
@@ -30,7 +30,6 @@ PathData forwardInto(PathData destination, const PathData &source)
{
// Merge a turn into a silent turn
// Overwrites turn instruction and increases exit NR
destination.duration_until_turn += source.duration_until_turn;
destination.exit = source.exit;
return destination;
}
@@ -40,7 +39,6 @@ PathData accumulateInto(PathData destination, const PathData &source)
// Merge a turn into a silent turn
// Overwrites turn instruction and increases exit NR
BOOST_ASSERT(canMergeTrivially(destination, source));
destination.duration_until_turn += source.duration_until_turn;
destination.exit = source.exit + 1;
return destination;
}
+167 -189
View File
@@ -1,6 +1,8 @@
#include "engine/plugins/plugin_base.hpp"
#include "engine/plugins/tile.hpp"
#include "util/coordinate_calculation.hpp"
#include <protozero/varint.hpp>
#include <protozero/pbf_writer.hpp>
@@ -17,89 +19,29 @@ namespace engine
{
namespace plugins
{
namespace detail
{
// Vector tiles are 4096 virtual pixels on each side
const constexpr double VECTOR_TILE_EXTENT = 4096.0;
// from mapnik/well_known_srs.hpp
const constexpr double EARTH_RADIUS = 6378137.0;
const constexpr double EARTH_DIAMETER = EARTH_RADIUS * 2.0;
const constexpr double EARTH_CIRCUMFERENCE = EARTH_DIAMETER * M_PI;
const constexpr double MAXEXTENT = EARTH_CIRCUMFERENCE / 2.0;
const constexpr double M_PI_by2 = M_PI / 2.0;
const constexpr double D2R = M_PI / 180.0;
const constexpr double R2D = 180.0 / M_PI;
const constexpr double M_PIby360 = M_PI / 360.0;
const constexpr double MAXEXTENTby180 = MAXEXTENT / 180.0;
const double MAX_LATITUDE = R2D * (2.0 * std::atan(std::exp(180.0 * D2R)) - M_PI_by2);
// ^ math functions are not constexpr since they have side-effects (setting errno) :(
// Simple container class for WSG84 coordinates
template <typename T> struct Point final
{
Point(T _x, T _y) : x(_x), y(_y) {}
const T x;
const T y;
};
// from mapnik-vector-tile
namespace detail_pbf
namespace pbf
{
inline unsigned encode_length(const unsigned len) { return (len << 3u) | 2u; }
}
// Converts a regular WSG84 lon/lat pair into
// a mercator coordinate
inline void lonlat2merc(double &x, double &y)
struct BBox final
{
if (x > 180)
x = 180;
else if (x < -180)
x = -180;
if (y > MAX_LATITUDE)
y = MAX_LATITUDE;
else if (y < -MAX_LATITUDE)
y = -MAX_LATITUDE;
x = x * MAXEXTENTby180;
y = std::log(std::tan((90 + y) * M_PIby360)) * R2D;
y = y * MAXEXTENTby180;
}
// This is the global default tile size for all Mapbox Vector Tiles
const constexpr double tile_size_ = 256.0;
//
inline void from_pixels(const double shift, double &x, double &y)
{
const double b = shift / 2.0;
x = (x - b) / (shift / 360.0);
const double g = (y - b) / -(shift / (2 * M_PI));
y = R2D * (2.0 * std::atan(std::exp(g)) - M_PI_by2);
}
// Converts a WMS tile coordinate (z,x,y) into a mercator bounding box
inline void xyz2mercator(
const int x, const int y, const int z, double &minx, double &miny, double &maxx, double &maxy)
{
minx = x * tile_size_;
miny = (y + 1.0) * tile_size_;
maxx = (x + 1.0) * tile_size_;
maxy = y * tile_size_;
const double shift = std::pow(2.0, z) * tile_size_;
from_pixels(shift, minx, miny);
from_pixels(shift, maxx, maxy);
lonlat2merc(minx, miny);
lonlat2merc(maxx, maxy);
}
// Converts a WMS tile coordinate (z,x,y) into a wsg84 bounding box
inline void xyz2wsg84(
const int x, const int y, const int z, double &minx, double &miny, double &maxx, double &maxy)
{
minx = x * tile_size_;
miny = (y + 1.0) * tile_size_;
maxx = (x + 1.0) * tile_size_;
maxy = y * tile_size_;
const double shift = std::pow(2.0, z) * tile_size_;
from_pixels(shift, minx, miny);
from_pixels(shift, maxx, maxy);
}
// emulates mapbox::box2d, just a simple container for
// a box
struct bbox final
{
bbox(const double _minx, const double _miny, const double _maxx, const double _maxy)
BBox(const double _minx, const double _miny, const double _maxx, const double _maxy)
: minx(_minx), miny(_miny), maxx(_maxx), maxy(_maxy)
{
}
@@ -113,15 +55,6 @@ struct bbox final
const double maxy;
};
// Simple container class for WSG84 coordinates
struct point_type_d final
{
point_type_d(double _x, double _y) : x(_x), y(_y) {}
const double x;
const double y;
};
// Simple container for integer coordinates (i.e. pixel coords)
struct point_type_i final
{
@@ -131,15 +64,15 @@ struct point_type_i final
const std::int64_t y;
};
using line_type = std::vector<point_type_i>;
using line_typed = std::vector<point_type_d>;
using FixedLine = std::vector<detail::Point<std::int32_t>>;
using FloatLine = std::vector<detail::Point<double>>;
// from mapnik-vector-tile
// Encodes a linestring using protobuf zigzag encoding
inline bool encode_linestring(line_type line,
protozero::packed_field_uint32 &geometry,
std::int32_t &start_x,
std::int32_t &start_y)
inline bool encodeLinestring(const FixedLine &line,
protozero::packed_field_uint32 &geometry,
std::int32_t &start_x,
std::int32_t &start_y)
{
const std::size_t line_size = line.size();
if (line_size < 2)
@@ -155,7 +88,7 @@ inline bool encode_linestring(line_type line,
geometry.add_element(protozero::encode_zigzag32(pt->y - start_y));
start_x = pt->x;
start_y = pt->y;
geometry.add_element(detail_pbf::encode_length(line_to_length));
geometry.add_element(detail::pbf::encode_length(line_to_length));
for (++pt; pt != line.end(); ++pt)
{
const std::int32_t dx = pt->x - start_x;
@@ -168,15 +101,42 @@ inline bool encode_linestring(line_type line,
return true;
}
FixedLine coordinatesToTileLine(const util::Coordinate start,
const util::Coordinate target,
const detail::BBox &tile_bbox)
{
using namespace util::coordinate_calculation;
FloatLine geo_line;
geo_line.emplace_back(static_cast<double>(util::toFloating(start.lon)),
static_cast<double>(util::toFloating(start.lat)));
geo_line.emplace_back(static_cast<double>(util::toFloating(target.lon)),
static_cast<double>(util::toFloating(target.lat)));
FixedLine tile_line;
for (auto const &pt : geo_line)
{
double px_merc = pt.x * mercator::DEGREE_TO_PX;
double py_merc = mercator::latToY(util::FloatLatitude(pt.y)) * mercator::DEGREE_TO_PX;
// convert lon/lat to tile coordinates
const auto px = std::round(
((px_merc - tile_bbox.minx) * mercator::TILE_SIZE / tile_bbox.width()) *
detail::VECTOR_TILE_EXTENT / util::coordinate_calculation::mercator::TILE_SIZE);
const auto py = std::round(
((tile_bbox.maxy - py_merc) * mercator::TILE_SIZE / tile_bbox.height()) *
detail::VECTOR_TILE_EXTENT / util::coordinate_calculation::mercator::TILE_SIZE);
tile_line.emplace_back(px, py);
}
return tile_line;
}
}
Status TilePlugin::HandleRequest(const api::TileParameters &parameters, std::string &pbf_buffer)
{
// Vector tiles are 4096 virtual pixels on each side
const double tile_extent = 4096.0;
using namespace util::coordinate_calculation;
double min_lon, min_lat, max_lon, max_lat;
// Convert the z,x,y mercator tile coordinates into WSG84 lon/lat values
xyz2wsg84(parameters.x, parameters.y, parameters.z, min_lon, min_lat, max_lon, max_lat);
mercator::xyzToWSG84(parameters.x, parameters.y, parameters.z, min_lon, min_lat, max_lon,
max_lat);
util::Coordinate southwest{util::FloatLongitude(min_lon), util::FloatLatitude(min_lat)};
util::Coordinate northeast{util::FloatLongitude(max_lon), util::FloatLatitude(max_lat)};
@@ -185,13 +145,70 @@ Status TilePlugin::HandleRequest(const api::TileParameters &parameters, std::str
// This hits the OSRM StaticRTree
const auto edges = facade.GetEdgesInBox(southwest, northeast);
std::vector<int> used_weights;
std::unordered_map<int, std::size_t> weight_offsets;
uint8_t max_datasource_id = 0;
// Loop over all edges once to tally up all the attributes we'll need.
// We need to do this so that we know the attribute offsets to use
// when we encode each feature in the tile.
for (const auto &edge : edges)
{
int forward_weight = 0, reverse_weight = 0;
uint8_t forward_datasource = 0;
uint8_t reverse_datasource = 0;
if (edge.forward_packed_geometry_id != SPECIAL_EDGEID)
{
std::vector<EdgeWeight> forward_weight_vector;
facade.GetUncompressedWeights(edge.forward_packed_geometry_id, forward_weight_vector);
forward_weight = forward_weight_vector[edge.fwd_segment_position];
std::vector<uint8_t> forward_datasource_vector;
facade.GetUncompressedDatasources(edge.forward_packed_geometry_id,
forward_datasource_vector);
forward_datasource = forward_datasource_vector[edge.fwd_segment_position];
if (weight_offsets.find(forward_weight) == weight_offsets.end())
{
used_weights.push_back(forward_weight);
weight_offsets[forward_weight] = used_weights.size() - 1;
}
}
if (edge.reverse_packed_geometry_id != SPECIAL_EDGEID)
{
std::vector<EdgeWeight> reverse_weight_vector;
facade.GetUncompressedWeights(edge.reverse_packed_geometry_id, reverse_weight_vector);
BOOST_ASSERT(edge.fwd_segment_position < reverse_weight_vector.size());
reverse_weight =
reverse_weight_vector[reverse_weight_vector.size() - edge.fwd_segment_position - 1];
if (weight_offsets.find(reverse_weight) == weight_offsets.end())
{
used_weights.push_back(reverse_weight);
weight_offsets[reverse_weight] = used_weights.size() - 1;
}
std::vector<uint8_t> reverse_datasource_vector;
facade.GetUncompressedDatasources(edge.reverse_packed_geometry_id,
reverse_datasource_vector);
reverse_datasource = reverse_datasource_vector[reverse_datasource_vector.size() -
edge.fwd_segment_position - 1];
}
// Keep track of the highest datasource seen so that we don't write unnecessary
// data to the layer attribute values
max_datasource_id = std::max(max_datasource_id, forward_datasource);
max_datasource_id = std::max(max_datasource_id, reverse_datasource);
}
// TODO: extract speed values for compressed and uncompressed geometries
// Convert tile coordinates into mercator coordinates
xyz2mercator(parameters.x, parameters.y, parameters.z, min_lon, min_lat, max_lon, max_lat);
const bbox tile_bbox{min_lon, min_lat, max_lon, max_lat};
uint8_t max_datasource_id = 0;
mercator::xyzToMercator(parameters.x, parameters.y, parameters.z, min_lon, min_lat, max_lon,
max_lat);
const detail::BBox tile_bbox{min_lon, min_lat, max_lon, max_lat};
// Protobuf serialized blocks when objects go out of scope, hence
// the extra scoping below.
@@ -263,38 +280,11 @@ Status TilePlugin::HandleRequest(const api::TileParameters &parameters, std::str
max_datasource_id = std::max(max_datasource_id, forward_datasource);
max_datasource_id = std::max(max_datasource_id, reverse_datasource);
// If this is a valid forward edge, go ahead and add it to the tile
if (forward_weight != 0 && edge.forward_edge_based_node_id != SPECIAL_NODEID)
const auto encode_tile_line = [&layer_writer, &edge, &id, &max_datasource_id](
const detail::FixedLine &tile_line, const std::uint32_t speed_kmh,
const std::size_t duration, const std::uint8_t datasource,
std::int32_t &start_x, std::int32_t &start_y)
{
std::int32_t start_x = 0;
std::int32_t start_y = 0;
line_typed geo_line;
geo_line.emplace_back(static_cast<double>(util::toFloating(a.lon)),
static_cast<double>(util::toFloating(a.lat)));
geo_line.emplace_back(static_cast<double>(util::toFloating(b.lon)),
static_cast<double>(util::toFloating(b.lat)));
// Calculate the speed for this line
std::uint32_t speed =
static_cast<std::uint32_t>(round(length / forward_weight * 10 * 3.6));
line_type tile_line;
for (auto const &pt : geo_line)
{
double px_merc = pt.x;
double py_merc = pt.y;
lonlat2merc(px_merc, py_merc);
// convert lon/lat to tile coordinates
const auto px = std::round(
((px_merc - tile_bbox.minx) * tile_extent / 16.0 / tile_bbox.width()) *
tile_extent / 256.0);
const auto py = std::round(
((tile_bbox.maxy - py_merc) * tile_extent / 16.0 / tile_bbox.height()) *
tile_extent / 256.0);
tile_line.emplace_back(px, py);
}
// Here, we save the two attributes for our feature: the speed and the
// is_small
// boolean. We onl serve up speeds from 0-139, so all we do is save the
@@ -316,18 +306,36 @@ Status TilePlugin::HandleRequest(const api::TileParameters &parameters, std::str
field.add_element(0); // "speed" tag key offset
field.add_element(
std::min(speed, 127u)); // save the speed value, capped at 127
field.add_element(1); // "is_small" tag key offset
std::min(speed_kmh, 127u)); // save the speed value, capped at 127
field.add_element(1); // "is_small" tag key offset
field.add_element(128 +
(edge.component.is_tiny ? 0 : 1)); // is_small feature
field.add_element(2); // "datasource" tag key offset
field.add_element(130 + forward_datasource); // datasource value offset
field.add_element(2); // "datasource" tag key offset
field.add_element(130 + datasource); // datasource value offset
field.add_element(3); // "duration" tag key offset
field.add_element(130 + max_datasource_id + 1 +
duration); // duration value offset
}
{
// Encode the geometry for the feature
protozero::packed_field_uint32 geometry(feature_writer, 4);
encode_linestring(tile_line, geometry, start_x, start_y);
encodeLinestring(tile_line, geometry, start_x, start_y);
}
};
// If this is a valid forward edge, go ahead and add it to the tile
if (forward_weight != 0 && edge.forward_edge_based_node_id != SPECIAL_NODEID)
{
std::int32_t start_x = 0;
std::int32_t start_y = 0;
// Calculate the speed for this line
std::uint32_t speed_kmh =
static_cast<std::uint32_t>(round(length / forward_weight * 10 * 3.6));
auto tile_line = coordinatesToTileLine(a, b, tile_bbox);
encode_tile_line(tile_line, speed_kmh, weight_offsets[forward_weight],
forward_datasource, start_x, start_y);
}
// Repeat the above for the coordinates reversed and using the `reverse`
@@ -337,49 +345,13 @@ Status TilePlugin::HandleRequest(const api::TileParameters &parameters, std::str
std::int32_t start_x = 0;
std::int32_t start_y = 0;
line_typed geo_line;
geo_line.emplace_back(static_cast<double>(util::toFloating(b.lon)),
static_cast<double>(util::toFloating(b.lat)));
geo_line.emplace_back(static_cast<double>(util::toFloating(a.lon)),
static_cast<double>(util::toFloating(a.lat)));
// Calculate the speed for this line
std::uint32_t speed_kmh =
static_cast<std::uint32_t>(round(length / reverse_weight * 10 * 3.6));
const auto speed =
static_cast<const std::uint32_t>(round(length / reverse_weight * 10 * 3.6));
line_type tile_line;
for (auto const &pt : geo_line)
{
double px_merc = pt.x;
double py_merc = pt.y;
lonlat2merc(px_merc, py_merc);
// convert to integer tile coordinat
const auto px = std::round(
((px_merc - tile_bbox.minx) * tile_extent / 16.0 / tile_bbox.width()) *
tile_extent / 256.0);
const auto py = std::round(
((tile_bbox.maxy - py_merc) * tile_extent / 16.0 / tile_bbox.height()) *
tile_extent / 256.0);
tile_line.emplace_back(px, py);
}
protozero::pbf_writer feature_writer(layer_writer, 2);
feature_writer.add_enum(3, 2); // geometry type
feature_writer.add_uint64(1, id++); // id
{
protozero::packed_field_uint32 field(feature_writer, 2);
field.add_element(0); // "speed" tag key offset
field.add_element(
std::min(speed, 127u)); // save the speed value, capped at 127
field.add_element(1); // "is_small" tag key offset
field.add_element(128 +
(edge.component.is_tiny ? 0 : 1)); // is_small feature
field.add_element(2); // "datasource" tag key offset
field.add_element(130 + reverse_datasource); // datasource value offset
}
{
protozero::packed_field_uint32 geometry(feature_writer, 4);
encode_linestring(tile_line, geometry, start_x, start_y);
}
auto tile_line = coordinatesToTileLine(b, a, tile_bbox);
encode_tile_line(tile_line, speed_kmh, weight_offsets[reverse_weight],
reverse_datasource, start_x, start_y);
}
}
}
@@ -390,18 +362,17 @@ Status TilePlugin::HandleRequest(const api::TileParameters &parameters, std::str
layer_writer.add_string(3, "speed");
layer_writer.add_string(3, "is_small");
layer_writer.add_string(3, "datasource");
layer_writer.add_string(3, "duration");
// Now, we write out the possible speed value arrays and possible is_tiny
// values. Field type 4 is the "values" field. It's a variable type field,
// so requires a two-step write (create the field, then write its value)
for (std::size_t i = 0; i < 128; i++)
{
{
// Writing field type 4 == variant type
protozero::pbf_writer values_writer(layer_writer, 4);
// Attribute value 5 == uin64 type
values_writer.add_uint64(5, i);
}
// Writing field type 4 == variant type
protozero::pbf_writer values_writer(layer_writer, 4);
// Attribute value 5 == uin64 type
values_writer.add_uint64(5, i);
}
{
protozero::pbf_writer values_writer(layer_writer, 4);
@@ -415,12 +386,19 @@ Status TilePlugin::HandleRequest(const api::TileParameters &parameters, std::str
}
for (std::size_t i = 0; i <= max_datasource_id; i++)
{
{
// Writing field type 4 == variant type
protozero::pbf_writer values_writer(layer_writer, 4);
// Attribute value 1 == string type
values_writer.add_string(1, facade.GetDatasourceName(i));
}
// Writing field type 4 == variant type
protozero::pbf_writer values_writer(layer_writer, 4);
// Attribute value 1 == string type
values_writer.add_string(1, facade.GetDatasourceName(i));
}
for (auto weight : used_weights)
{
// Writing field type 4 == variant type
protozero::pbf_writer values_writer(layer_writer, 4);
// Attribute value 2 == float type
// Durations come out of OSRM in integer deciseconds, so we convert them
// to seconds with a simple /10 for display
values_writer.add_double(3, weight / 10.);
}
}
+10 -13
View File
@@ -34,12 +34,13 @@ EdgeBasedGraphFactory::EdgeBasedGraphFactory(
const std::unordered_set<NodeID> &traffic_lights,
std::shared_ptr<const RestrictionMap> restriction_map,
const std::vector<QueryNode> &node_info_list,
SpeedProfileProperties speed_profile)
SpeedProfileProperties speed_profile,
const util::NameTable &name_table)
: m_max_edge_id(0), m_node_info_list(node_info_list),
m_node_based_graph(std::move(node_based_graph)),
m_restriction_map(std::move(restriction_map)), m_barrier_nodes(barrier_nodes),
m_traffic_lights(traffic_lights), m_compressed_edge_container(compressed_edge_container),
speed_profile(std::move(speed_profile))
speed_profile(std::move(speed_profile)), name_table(name_table)
{
}
@@ -123,10 +124,9 @@ void EdgeBasedGraphFactory::InsertEdgeBasedNode(const NodeID node_u, const NodeI
// traverse arrays from start and end respectively
for (const auto i : util::irange(0UL, geometry_size))
{
BOOST_ASSERT(
current_edge_source_coordinate_id ==
m_compressed_edge_container.GetBucketReference(edge_id_2)[geometry_size - 1 - i]
.node_id);
BOOST_ASSERT(current_edge_source_coordinate_id ==
m_compressed_edge_container.GetBucketReference(
edge_id_2)[geometry_size - 1 - i].node_id);
const NodeID current_edge_target_coordinate_id = forward_geometry[i].node_id;
BOOST_ASSERT(current_edge_target_coordinate_id != current_edge_source_coordinate_id);
@@ -302,8 +302,8 @@ void EdgeBasedGraphFactory::GenerateEdgeExpandedEdges(
// Three nested loop look super-linear, but we are dealing with a (kind of)
// linear number of turns only.
util::Percent progress(m_node_based_graph->GetNumberOfNodes());
guidance::TurnAnalysis turn_analysis( *m_node_based_graph, m_node_info_list,
*m_restriction_map, m_barrier_nodes, m_compressed_edge_container );
guidance::TurnAnalysis turn_analysis(*m_node_based_graph, m_node_info_list, *m_restriction_map,
m_barrier_nodes, m_compressed_edge_container, name_table);
for (const auto node_u : util::irange(0u, m_node_based_graph->GetNumberOfNodes()))
{
// progress.printStatus(node_u);
@@ -315,15 +315,12 @@ void EdgeBasedGraphFactory::GenerateEdgeExpandedEdges(
}
++node_based_edge_counter;
auto turn_candidates = turn_analysis.getTurns(node_u, edge_from_u);
auto possible_turns = turn_analysis.getTurns(node_u, edge_from_u);
const NodeID node_v = m_node_based_graph->GetTarget(edge_from_u);
for (const auto turn : turn_candidates)
for (const auto turn : possible_turns)
{
if (!turn.valid)
continue;
const double turn_angle = turn.angle;
// only add an edge if turn is not prohibited
+4 -1
View File
@@ -15,6 +15,7 @@
#include "util/timing_util.hpp"
#include "util/lua_util.hpp"
#include "util/graph_loader.hpp"
#include "util/name_table.hpp"
#include "util/typedefs.hpp"
@@ -521,10 +522,12 @@ Extractor::BuildEdgeExpandedGraph(std::vector<QueryNode> &internal_to_external_n
compressed_edge_container.SerializeInternalVector(config.geometry_output_path);
util::NameTable name_table(config.names_file_name);
EdgeBasedGraphFactory edge_based_graph_factory(
node_based_graph, compressed_edge_container, barrier_nodes, traffic_lights,
std::const_pointer_cast<RestrictionMap const>(restriction_map),
internal_to_external_node_map, speed_profile);
internal_to_external_node_map, speed_profile, name_table);
edge_based_graph_factory.Run(config.edge_output_path, lua_state,
config.edge_segment_lookup_path, config.edge_penalty_path,
File diff suppressed because it is too large Load Diff
-14
View File
@@ -29,20 +29,6 @@ Coordinate::Coordinate(const FloatLongitude lon_, const FloatLatitude lat_)
Coordinate::Coordinate(const FixedLongitude lon_, const FixedLatitude lat_) : lon(lon_), lat(lat_)
{
#ifndef NDEBUG
if (0 != (std::abs(static_cast<int>(lon)) >> 30))
{
std::bitset<32> x_coordinate_vector(static_cast<int>(lon));
SimpleLogger().Write(logDEBUG) << "broken lon: " << lon
<< ", bits: " << x_coordinate_vector;
}
if (0 != (std::abs(static_cast<int>(lat)) >> 30))
{
std::bitset<32> y_coordinate_vector(static_cast<int>(lat));
SimpleLogger().Write(logDEBUG) << "broken lat: " << lat
<< ", bits: " << y_coordinate_vector;
}
#endif
}
bool Coordinate::IsValid() const
+80 -18
View File
@@ -4,7 +4,6 @@
#include "util/trigonometry_table.hpp"
#include <boost/assert.hpp>
#include <boost/math/constants/constants.hpp>
#include <cmath>
@@ -14,6 +13,7 @@ namespace osrm
{
namespace util
{
namespace coordinate_calculation
{
@@ -43,11 +43,11 @@ double haversineDistance(const Coordinate coordinate_1, const Coordinate coordin
const double ln1 = lon1 / COORDINATE_PRECISION;
const double lt2 = lat2 / COORDINATE_PRECISION;
const double ln2 = lon2 / COORDINATE_PRECISION;
const double dlat1 = lt1 * (RAD);
const double dlat1 = lt1 * DEGREE_TO_RAD;
const double dlong1 = ln1 * (RAD);
const double dlat2 = lt2 * (RAD);
const double dlong2 = ln2 * (RAD);
const double dlong1 = ln1 * DEGREE_TO_RAD;
const double dlat2 = lt2 * DEGREE_TO_RAD;
const double dlong2 = ln2 * DEGREE_TO_RAD;
const double dlong = dlong1 - dlong2;
const double dlat = dlat1 - dlat2;
@@ -69,10 +69,10 @@ double greatCircleDistance(const Coordinate coordinate_1, const Coordinate coord
BOOST_ASSERT(lat2 != std::numeric_limits<int>::min());
BOOST_ASSERT(lon2 != std::numeric_limits<int>::min());
const double float_lat1 = (lat1 / COORDINATE_PRECISION) * RAD;
const double float_lon1 = (lon1 / COORDINATE_PRECISION) * RAD;
const double float_lat2 = (lat2 / COORDINATE_PRECISION) * RAD;
const double float_lon2 = (lon2 / COORDINATE_PRECISION) * RAD;
const double float_lat1 = (lat1 / COORDINATE_PRECISION) * DEGREE_TO_RAD;
const double float_lon1 = (lon1 / COORDINATE_PRECISION) * DEGREE_TO_RAD;
const double float_lat2 = (lat2 / COORDINATE_PRECISION) * DEGREE_TO_RAD;
const double float_lon2 = (lon2 / COORDINATE_PRECISION) * DEGREE_TO_RAD;
const double x_value = (float_lon2 - float_lon1) * std::cos((float_lat1 + float_lat2) / 2.0);
const double y_value = float_lat2 - float_lat1;
@@ -269,22 +269,84 @@ Coordinate interpolateLinear(double factor, const Coordinate from, const Coordin
namespace mercator
{
FloatLatitude yToLat(const double value)
FloatLatitude yToLat(const double y)
{
using namespace boost::math::constants;
const double normalized_lat = RAD_TO_DEGREE * 2. * std::atan(std::exp(y * DEGREE_TO_RAD));
return FloatLatitude(
180. * (1. / pi<long double>()) *
(2. * std::atan(std::exp(value * pi<double>() / 180.)) - half_pi<double>()));
return FloatLatitude(normalized_lat - 90.);
}
double latToY(const FloatLatitude latitude)
{
using namespace boost::math::constants;
const double normalized_lat = 90. + static_cast<double>(latitude);
return 180. * (1. / pi<double>()) *
std::log(std::tan((pi<double>() / 4.) +
static_cast<double>(latitude) * (pi<double>() / 180.) / 2.));
return RAD_TO_DEGREE * std::log(std::tan(normalized_lat * DEGREE_TO_RAD * 0.5));
}
FloatLatitude clamp(const FloatLatitude lat)
{
return std::max(std::min(lat, FloatLatitude(detail::MAX_LATITUDE)),
FloatLatitude(-detail::MAX_LATITUDE));
}
FloatLongitude clamp(const FloatLongitude lon)
{
return std::max(std::min(lon, FloatLongitude(detail::MAX_LONGITUDE)),
FloatLongitude(-detail::MAX_LONGITUDE));
}
inline void pixelToDegree(const double shift, double &x, double &y)
{
const double b = shift / 2.0;
x = (x - b) / shift * 360.0;
// FIXME needs to be simplified
const double g = (y - b) / -(shift / (2 * M_PI)) / DEGREE_TO_RAD;
static_assert(DEGREE_TO_RAD / (2 * M_PI) - 1/360. < 0.0001, "");
y = static_cast<double>(util::coordinate_calculation::mercator::yToLat(g));
}
double degreeToPixel(FloatLongitude lon, unsigned zoom)
{
const double shift = (1u << zoom) * TILE_SIZE;
const double b = shift / 2.0;
const double x = b * (1 + static_cast<double>(lon) / 180.0);
return x;
}
double degreeToPixel(FloatLatitude lat, unsigned zoom)
{
const double shift = (1u << zoom) * TILE_SIZE;
const double b = shift / 2.0;
const double y = b * (1. - latToY(lat) / 180.);
return y;
}
// Converts a WMS tile coordinate (z,x,y) into a wsg84 bounding box
void xyzToWSG84(const int x, const int y, const int z, double &minx, double &miny, double &maxx, double &maxy)
{
using util::coordinate_calculation::mercator::TILE_SIZE;
minx = x * TILE_SIZE;
miny = (y + 1.0) * TILE_SIZE;
maxx = (x + 1.0) * TILE_SIZE;
maxy = y * TILE_SIZE;
// 2^z * TILE_SIZE
const double shift = (1u << static_cast<unsigned>(z)) * TILE_SIZE;
pixelToDegree(shift, minx, miny);
pixelToDegree(shift, maxx, maxy);
}
// Converts a WMS tile coordinate (z,x,y) into a mercator bounding box
void xyzToMercator(const int x, const int y, const int z, double &minx, double &miny, double &maxx, double &maxy)
{
using namespace util::coordinate_calculation::mercator;
xyzToWSG84(x, y, z, minx, miny, maxx, maxy);
minx = static_cast<double>(clamp(util::FloatLongitude(minx))) * DEGREE_TO_PX;
miny = latToY(clamp(util::FloatLatitude(miny))) * DEGREE_TO_PX;
maxx = static_cast<double>(clamp(util::FloatLongitude(maxx))) * DEGREE_TO_PX;
maxy = latToY(clamp(util::FloatLatitude(maxy))) * DEGREE_TO_PX;
}
} // ns mercato // ns mercatorr
+62
View File
@@ -0,0 +1,62 @@
#include "util/name_table.hpp"
#include "util/simple_logger.hpp"
#include "util/exception.hpp"
#include <algorithm>
#include <limits>
#include <fstream>
#include <boost/filesystem/fstream.hpp>
namespace osrm
{
namespace util
{
NameTable::NameTable(const std::string &filename)
{
boost::filesystem::ifstream name_stream(filename, std::ios::binary);
if( !name_stream )
throw exception("Failed to open " + filename + " for reading.");
name_stream >> m_name_table;
unsigned number_of_chars = 0;
name_stream.read(reinterpret_cast<char *>(&number_of_chars), sizeof(number_of_chars));
if( !name_stream )
throw exception("Encountered invalid file, failed to read number of contained chars");
BOOST_ASSERT_MSG(0 != number_of_chars, "name file broken");
m_names_char_list.resize(number_of_chars + 1); //+1 gives sentinel element
name_stream.read(reinterpret_cast<char *>(&m_names_char_list[0]),
number_of_chars * sizeof(m_names_char_list[0]));
if( !name_stream )
throw exception("Failed to read " + std::to_string(number_of_chars) + " characters from file.");
if (0 == m_names_char_list.size())
{
util::SimpleLogger().Write(logWARNING) << "list of street names is empty";
}
}
std::string NameTable::GetNameForID(const unsigned name_id) const
{
if (std::numeric_limits<unsigned>::max() == name_id)
{
return "";
}
auto range = m_name_table.GetRange(name_id);
std::string result;
result.reserve(range.size());
if (range.begin() != range.end())
{
result.resize(range.back() - range.front() + 1);
std::copy(m_names_char_list.begin() + range.front(),
m_names_char_list.begin() + range.back() + 1, result.begin());
}
return result;
}
} // namespace util
} // namespace osrm
+66
View File
@@ -24,3 +24,69 @@ BOOST_AUTO_TEST_CASE(regression_test_1347)
BOOST_CHECK_LE(std::abs(d1 - d2), 0.01);
}
BOOST_AUTO_TEST_CASE(lon_to_pixel)
{
using namespace coordinate_calculation;
BOOST_CHECK_CLOSE(7.416042 * mercator::DEGREE_TO_PX, 825550.019142, 0.1);
BOOST_CHECK_CLOSE(7.415892 * mercator::DEGREE_TO_PX, 825533.321218, 0.1);
BOOST_CHECK_CLOSE(7.416016 * mercator::DEGREE_TO_PX, 825547.124835, 0.1);
BOOST_CHECK_CLOSE(7.41577 * mercator::DEGREE_TO_PX, 825519.74024, 0.1);
BOOST_CHECK_CLOSE(7.415808 * mercator::DEGREE_TO_PX, 825523.970381, 0.1);
}
BOOST_AUTO_TEST_CASE(lat_to_pixel)
{
using namespace coordinate_calculation;
BOOST_CHECK_CLOSE(mercator::latToY(util::FloatLatitude(43.733947)) * mercator::DEGREE_TO_PX,
5424361.75863, 0.1);
BOOST_CHECK_CLOSE(mercator::latToY(util::FloatLatitude(43.733799)) * mercator::DEGREE_TO_PX,
5424338.95731, 0.1);
BOOST_CHECK_CLOSE(mercator::latToY(util::FloatLatitude(43.733922)) * mercator::DEGREE_TO_PX,
5424357.90705, 0.1);
BOOST_CHECK_CLOSE(mercator::latToY(util::FloatLatitude(43.733697)) * mercator::DEGREE_TO_PX,
5424323.24293, 0.1);
BOOST_CHECK_CLOSE(mercator::latToY(util::FloatLatitude(43.733729)) * mercator::DEGREE_TO_PX,
5424328.17293, 0.1);
}
BOOST_AUTO_TEST_CASE(xyz_to_wgs84)
{
using namespace coordinate_calculation;
double minx_1;
double miny_1;
double maxx_1;
double maxy_1;
mercator::xyzToWSG84(2, 2, 1, minx_1, miny_1, maxx_1, maxy_1);
BOOST_CHECK_CLOSE(minx_1, 180, 0.0001);
BOOST_CHECK_CLOSE(miny_1, -89.786, 0.0001);
BOOST_CHECK_CLOSE(maxx_1, 360, 0.0001);
BOOST_CHECK_CLOSE(maxy_1, -85.0511, 0.0001);
double minx_2;
double miny_2;
double maxx_2;
double maxy_2;
mercator::xyzToWSG84(100, 0, 13, minx_2, miny_2, maxx_2, maxy_2);
BOOST_CHECK_CLOSE(minx_2, -175.6054, 0.0001);
BOOST_CHECK_CLOSE(miny_2, 85.0473, 0.0001);
BOOST_CHECK_CLOSE(maxx_2, -175.5615, 0.0001);
BOOST_CHECK_CLOSE(maxy_2, 85.0511, 0.0001);
}
BOOST_AUTO_TEST_CASE(xyz_to_mercator)
{
using namespace coordinate_calculation;
double minx;
double miny;
double maxx;
double maxy;
mercator::xyzToMercator(100, 0, 13, minx, miny, maxx, maxy);
BOOST_CHECK_CLOSE(minx, -19548311.361764118075, 0.0001);
BOOST_CHECK_CLOSE(miny, 20032616.372979003936, 0.0001);
BOOST_CHECK_CLOSE(maxx, -19543419.391953866929, 0.0001);
BOOST_CHECK_CLOSE(maxy, 20037508.342789277434, 0.0001);
}
-83
View File
@@ -1,83 +0,0 @@
#include "util/tiles.hpp"
using namespace osrm::util;
#include <boost/functional/hash.hpp>
#include <boost/test/unit_test.hpp>
#include <boost/test/test_case_template.hpp>
#include <iostream>
BOOST_AUTO_TEST_SUITE(tiles_test)
using namespace osrm;
using namespace osrm::util;
BOOST_AUTO_TEST_CASE(point_to_tile_test)
{
tiles::Tile tile_1_reference{2306375680, 1409941503, 32};
tiles::Tile tile_2_reference{2308259840, 1407668224, 32};
tiles::Tile tile_3_reference{616562688, 2805989376, 32};
tiles::Tile tile_4_reference{1417674752, 2084569088, 32};
tiles::Tile tile_5_reference{616562688, 2805989376, 32};
tiles::Tile tile_6_reference{712654285, 2671662374, 32};
auto tile_1 =
tiles::pointToTile(FloatLongitude(13.31817626953125), FloatLatitude(52.449314140869696));
auto tile_2 =
tiles::pointToTile(FloatLongitude(13.476104736328125), FloatLatitude(52.56529070208021));
auto tile_3 =
tiles::pointToTile(FloatLongitude(-128.32031249999997), FloatLatitude(-48.224672649565186));
auto tile_4 =
tiles::pointToTile(FloatLongitude(-61.17187499999999), FloatLatitude(5.266007882805498));
auto tile_5 =
tiles::pointToTile(FloatLongitude(-128.32031249999997), FloatLatitude(-48.224672649565186));
auto tile_6 =
tiles::pointToTile(FloatLongitude(-120.266007882805532), FloatLatitude(-40.17187499999999));
BOOST_CHECK_EQUAL(tile_1.x, tile_1_reference.x);
BOOST_CHECK_EQUAL(tile_1.y, tile_1_reference.y);
BOOST_CHECK_EQUAL(tile_1.z, tile_1_reference.z);
BOOST_CHECK_EQUAL(tile_2.x, tile_2_reference.x);
BOOST_CHECK_EQUAL(tile_2.y, tile_2_reference.y);
BOOST_CHECK_EQUAL(tile_2.z, tile_2_reference.z);
BOOST_CHECK_EQUAL(tile_3.x, tile_3_reference.x);
BOOST_CHECK_EQUAL(tile_3.y, tile_3_reference.y);
BOOST_CHECK_EQUAL(tile_3.z, tile_3_reference.z);
BOOST_CHECK_EQUAL(tile_4.x, tile_4_reference.x);
BOOST_CHECK_EQUAL(tile_4.y, tile_4_reference.y);
BOOST_CHECK_EQUAL(tile_4.z, tile_4_reference.z);
BOOST_CHECK_EQUAL(tile_5.x, tile_5_reference.x);
BOOST_CHECK_EQUAL(tile_5.y, tile_5_reference.y);
BOOST_CHECK_EQUAL(tile_5.z, tile_5_reference.z);
BOOST_CHECK_EQUAL(tile_6.x, tile_6_reference.x);
BOOST_CHECK_EQUAL(tile_6.y, tile_6_reference.y);
BOOST_CHECK_EQUAL(tile_6.z, tile_6_reference.z);
}
// Verify that the bearing-bounds checking function behaves as expected
BOOST_AUTO_TEST_CASE(bounding_box_to_tile_test)
{
tiles::Tile tile_1_reference{17, 10, 5};
tiles::Tile tile_2_reference{0, 0, 0};
tiles::Tile tile_3_reference{0, 2, 2};
auto tile_1 = tiles::getBBMaxZoomTile(
FloatLongitude(13.31817626953125), FloatLatitude(52.449314140869696),
FloatLongitude(13.476104736328125), FloatLatitude(52.56529070208021));
auto tile_2 = tiles::getBBMaxZoomTile(
FloatLongitude(-128.32031249999997), FloatLatitude(-48.224672649565186),
FloatLongitude(-61.17187499999999), FloatLatitude(5.266007882805498));
auto tile_3 = tiles::getBBMaxZoomTile(
FloatLongitude(-128.32031249999997), FloatLatitude(-48.224672649565186),
FloatLongitude(-120.2660078828055), FloatLatitude(-40.17187499999999));
BOOST_CHECK_EQUAL(tile_1.x, tile_1_reference.x);
BOOST_CHECK_EQUAL(tile_1.y, tile_1_reference.y);
BOOST_CHECK_EQUAL(tile_1.z, tile_1_reference.z);
BOOST_CHECK_EQUAL(tile_2.x, tile_2_reference.x);
BOOST_CHECK_EQUAL(tile_2.y, tile_2_reference.y);
BOOST_CHECK_EQUAL(tile_2.z, tile_2_reference.z);
BOOST_CHECK_EQUAL(tile_3.x, tile_3_reference.x);
BOOST_CHECK_EQUAL(tile_3.y, tile_3_reference.y);
BOOST_CHECK_EQUAL(tile_3.z, tile_3_reference.z);
}
BOOST_AUTO_TEST_SUITE_END()
+25
View File
@@ -0,0 +1,25 @@
#include "util/viewport.hpp"
using namespace osrm::util;
#include <boost/functional/hash.hpp>
#include <boost/test/unit_test.hpp>
#include <boost/test/test_case_template.hpp>
#include <iostream>
BOOST_AUTO_TEST_SUITE(viewport_test)
using namespace osrm;
using namespace osrm::util;
BOOST_AUTO_TEST_CASE(zoom_level_test)
{
BOOST_CHECK_EQUAL(
viewport::getFittedZoom(
Coordinate(FloatLongitude{5.668343999999995}, FloatLatitude{45.111511000000014}),
Coordinate(FloatLongitude{5.852471999999996}, FloatLatitude{45.26800200000002})),
12);
}
BOOST_AUTO_TEST_SUITE_END()