Axel1092/extend map api (#2380)
* Added GetPrevious function * Added functions GetNextUntilLaneEnd and GetPreviousUntilLaneStart. Fixed GetPrevious issue. * Added junction class. * Added documentation for the python API. Fixed a bug regarding bounding box computation. * Fixed formatting. * Updated CHANGELOG.md. * Fixed python format. * Added GetPrevious function * Added functions GetNextUntilLaneEnd and GetPreviousUntilLaneStart. Fixed GetPrevious issue. * Added junction class. * Added documentation for the python API. Fixed a bug regarding bounding box computation. * Fixed formatting. * Updated CHANGELOG.md. * Fixed python format. * Updated map API documentation * updated mkdocs * Prettified code. * Removed nested carla repository * Review fixes. * Fixed small tab issues * Improved code and comments. * Small code fixes * Small fix. * Fixed until lane end and until lane start. * Style fix Co-authored-by: bernat <bernatx@gmail.com> Co-authored-by: Marc Garcia Puig <marcgpuig@gmail.com>
This commit is contained in:
parent
1449b1d139
commit
49a09ff841
13
CHANGELOG.md
13
CHANGELOG.md
|
@ -1,20 +1,21 @@
|
|||
## latest
|
||||
* Fixed linkage between waypoints in InMemoryMap.
|
||||
* Vehicles get destroyed when they are stuck.
|
||||
* Implemented intersection anticipation algorithm
|
||||
* Added new methods to BoundingBox: contains, get_local_vertices and get_world_vertices.
|
||||
* Added junction class as queryable object from waypoint
|
||||
* Fixed linkage between waypoints in InMemoryMap in Traffic Manager
|
||||
* Vehicles get destroyed when they are stuck in Traffic Manager
|
||||
* Implemented intersection anticipation algorithm in Traffic Manager
|
||||
* New weather system: night time, fog, rain ripples, and now wind affects vegetation and rain (not car physics)
|
||||
* Fixed Low/Epic quality settings transition
|
||||
* Enabled Mesh distance fields
|
||||
* API extensions:
|
||||
- Added new methods to `BoundingBox`: `contains()`, `get_local_vertices()` and `get_world_vertices(transform)`
|
||||
- Added new function to get a waypoint specifying parameters from the openDRIVE: `map.get_waypoint_xodr(road_id, lane_id, s)`
|
||||
- Added 3 new parameters for the `carla.Weather`: `fog_density`, `fog_distance`, and (ground) `wetness`
|
||||
* New python clients:
|
||||
- `weather.py`: allows weather changes using the new weather parameters
|
||||
* Fixed docker build of .BIN for pedestrian navigation
|
||||
* Fixed typos
|
||||
* Fixed agent failures due to API changes in is_within_distance_ahead()
|
||||
* Fixed incorrect doppler velocity for RADAR sensors.
|
||||
* Fixed agent failures due to API changes in `is_within_distance_ahead()`
|
||||
* Fixed incorrect doppler velocity for RADAR sensor
|
||||
|
||||
|
||||
## CARLA 0.9.7
|
||||
|
|
|
@ -136,37 +136,37 @@ _</font>
|
|||
---
|
||||
|
||||
## carla.LaneChange<a name="carla.LaneChange"></a> <sub><sup>_class_</sup></sub>
|
||||
Class that defines the lane change options. Check out this [`recipe`](../python_cookbook/#lanes-recipe)!
|
||||
Class that defines the permission to turn either left, right, both or none (meaning only going straight is allowed). This information is stored for every [carla.Waypoint](#carla.Waypoint) according to the OpenDRIVE file. In this [recipe](../python_cookbook/#lanes-recipe) the user creates a waypoint for a current vehicle position and learns which turns are permitted.
|
||||
|
||||
<h3>Instance Variables</h3>
|
||||
- <a name="carla.LaneChange.NONE"></a>**<font color="#f8805a">NONE</font>**
|
||||
Traffic rules do not allow turning right or left, only going straight.
|
||||
- <a name="carla.LaneChange.Right"></a>**<font color="#f8805a">Right</font>**
|
||||
Traffic rules allow turning right.
|
||||
- <a name="carla.LaneChange.Both"></a>**<font color="#f8805a">Both</font>**
|
||||
Traffic rules allow turning either right or left.
|
||||
- <a name="carla.LaneChange.Left"></a>**<font color="#f8805a">Left</font>**
|
||||
Traffic rules allow turning left.
|
||||
- <a name="carla.LaneChange.Both"></a>**<font color="#f8805a">Both</font>**
|
||||
Traffic rules allow turning right or left.
|
||||
- <a name="carla.LaneChange.Right"></a>**<font color="#f8805a">Right</font>**
|
||||
Traffic rules allow turning right.
|
||||
|
||||
---
|
||||
|
||||
## carla.LaneMarking<a name="carla.LaneMarking"></a> <sub><sup>_class_</sup></sub>
|
||||
Class that defines a lane marking.
|
||||
Class that gathers all the information regarding a lane marking according to [OpenDRIVE 1.4 standard](http://www.opendrive.org/docs/OpenDRIVEFormatSpecRev1.4H.pdf) standard.
|
||||
|
||||
<h3>Instance Variables</h3>
|
||||
- <a name="carla.LaneMarking.type"></a>**<font color="#f8805a">type</font>** (_[carla.LaneMarkingType](#carla.LaneMarkingType)_)
|
||||
Lane marking type.
|
||||
- <a name="carla.LaneMarking.color"></a>**<font color="#f8805a">color</font>** (_[carla.Color](#carla.Color)_)
|
||||
- <a name="carla.LaneMarking.color"></a>**<font color="#f8805a">color</font>** (_[carla.LaneMarkingColor](#carla.LaneMarkingColor)_)
|
||||
Actual color of the marking.
|
||||
- <a name="carla.LaneMarking.lane_change"></a>**<font color="#f8805a">lane_change</font>** (_[carla.LaneChange](#carla.LaneChange)_)
|
||||
Lane change availability.
|
||||
Permissions for said lane marking to be crossed.
|
||||
- <a name="carla.LaneMarking.type"></a>**<font color="#f8805a">type</font>** (_[carla.LaneMarkingType](#carla.LaneMarkingType)_)
|
||||
Lane marking type.
|
||||
- <a name="carla.LaneMarking.width"></a>**<font color="#f8805a">width</font>** (_float_)
|
||||
Horizontal lane marking thickness.
|
||||
|
||||
---
|
||||
|
||||
## carla.LaneMarkingColor<a name="carla.LaneMarkingColor"></a> <sub><sup>_class_</sup></sub>
|
||||
Class that defines the lane marking colors.
|
||||
Class that defines the lane marking colors according to OpenDRIVE 1.4.
|
||||
|
||||
<h3>Instance Variables</h3>
|
||||
- <a name="carla.LaneMarkingColor.Standard"></a>**<font color="#f8805a">Standard</font>**
|
||||
|
@ -181,54 +181,54 @@ White by default.
|
|||
---
|
||||
|
||||
## carla.LaneMarkingType<a name="carla.LaneMarkingType"></a> <sub><sup>_class_</sup></sub>
|
||||
Class that defines the lane marking types accepted by OpenDRIVE. Check out this [`recipe`](../python_cookbook/#lanes-recipe)!
|
||||
Class that defines the lane marking types accepted by OpenDRIVE 1.4. Take a look at this [recipe](../python_cookbook/#lanes-recipe) where the user creates a [carla.Waypoint](#carla.Waypoint) for a vehicle location and retrieves from it the information about adjacent lane markings.
|
||||
|
||||
<h3>Instance Variables</h3>
|
||||
- <a name="carla.LaneMarkingType.NONE"></a>**<font color="#f8805a">NONE</font>**
|
||||
- <a name="carla.LaneMarkingType.Other"></a>**<font color="#f8805a">Other</font>**
|
||||
- <a name="carla.LaneMarkingType.BottsDots"></a>**<font color="#f8805a">BottsDots</font>**
|
||||
- <a name="carla.LaneMarkingType.Broken"></a>**<font color="#f8805a">Broken</font>**
|
||||
- <a name="carla.LaneMarkingType.Solid"></a>**<font color="#f8805a">Solid</font>**
|
||||
- <a name="carla.LaneMarkingType.SolidSolid"></a>**<font color="#f8805a">SolidSolid</font>**
|
||||
For double solid line.
|
||||
- <a name="carla.LaneMarkingType.SolidBroken"></a>**<font color="#f8805a">SolidBroken</font>**
|
||||
- <a name="carla.LaneMarkingType.BrokenBroken"></a>**<font color="#f8805a">BrokenBroken</font>**
|
||||
From inside to outside except for center lane which is from left to right.
|
||||
- <a name="carla.LaneMarkingType.BrokenSolid"></a>**<font color="#f8805a">BrokenSolid</font>**
|
||||
From inside to outside except for center lane which is from left to right.
|
||||
- <a name="carla.LaneMarkingType.BrokenBroken"></a>**<font color="#f8805a">BrokenBroken</font>**
|
||||
From inside to outside except for center lane which is from left to right.
|
||||
- <a name="carla.LaneMarkingType.BottsDots"></a>**<font color="#f8805a">BottsDots</font>**
|
||||
- <a name="carla.LaneMarkingType.Grass"></a>**<font color="#f8805a">Grass</font>**
|
||||
Grass edge.
|
||||
- <a name="carla.LaneMarkingType.Curb"></a>**<font color="#f8805a">Curb</font>**
|
||||
- <a name="carla.LaneMarkingType.Grass"></a>**<font color="#f8805a">Grass</font>**
|
||||
- <a name="carla.LaneMarkingType.Solid"></a>**<font color="#f8805a">Solid</font>**
|
||||
- <a name="carla.LaneMarkingType.SolidBroken"></a>**<font color="#f8805a">SolidBroken</font>**
|
||||
From inside to outside except for center lane which is from left to right.
|
||||
- <a name="carla.LaneMarkingType.SolidSolid"></a>**<font color="#f8805a">SolidSolid</font>**
|
||||
For double solid line.
|
||||
- <a name="carla.LaneMarkingType.Other"></a>**<font color="#f8805a">Other</font>**
|
||||
|
||||
---
|
||||
|
||||
## carla.LaneType<a name="carla.LaneType"></a> <sub><sup>_class_</sup></sub>
|
||||
All the possible lane types accepted by OpenDRIVE. Check out this [`recipe`](../python_cookbook/#lanes-recipe)!
|
||||
Class that defines the possible lane types accepted by OpenDRIVE 1.4. This standards define the road information. For instance in this [recipe](../python_cookbook/#lanes-recipe) the user creates a [carla.Waypoint](#carla.Waypoint) for the current location of a vehicle and uses it to get the current and adjacent lane types.
|
||||
|
||||
<h3>Instance Variables</h3>
|
||||
- <a name="carla.LaneType.NONE"></a>**<font color="#f8805a">NONE</font>**
|
||||
- <a name="carla.LaneType.Driving"></a>**<font color="#f8805a">Driving</font>**
|
||||
- <a name="carla.LaneType.Stop"></a>**<font color="#f8805a">Stop</font>**
|
||||
- <a name="carla.LaneType.Shoulder"></a>**<font color="#f8805a">Shoulder</font>**
|
||||
- <a name="carla.LaneType.Biking"></a>**<font color="#f8805a">Biking</font>**
|
||||
- <a name="carla.LaneType.Sidewalk"></a>**<font color="#f8805a">Sidewalk</font>**
|
||||
- <a name="carla.LaneType.Border"></a>**<font color="#f8805a">Border</font>**
|
||||
- <a name="carla.LaneType.Restricted"></a>**<font color="#f8805a">Restricted</font>**
|
||||
- <a name="carla.LaneType.Parking"></a>**<font color="#f8805a">Parking</font>**
|
||||
- <a name="carla.LaneType.Any"></a>**<font color="#f8805a">Any</font>**
|
||||
Every type except for NONE.
|
||||
- <a name="carla.LaneType.Bidirectional"></a>**<font color="#f8805a">Bidirectional</font>**
|
||||
- <a name="carla.LaneType.Biking"></a>**<font color="#f8805a">Biking</font>**
|
||||
- <a name="carla.LaneType.Border"></a>**<font color="#f8805a">Border</font>**
|
||||
- <a name="carla.LaneType.Driving"></a>**<font color="#f8805a">Driving</font>**
|
||||
- <a name="carla.LaneType.Entry"></a>**<font color="#f8805a">Entry</font>**
|
||||
- <a name="carla.LaneType.Exit"></a>**<font color="#f8805a">Exit</font>**
|
||||
- <a name="carla.LaneType.Median"></a>**<font color="#f8805a">Median</font>**
|
||||
- <a name="carla.LaneType.OffRamp"></a>**<font color="#f8805a">OffRamp</font>**
|
||||
- <a name="carla.LaneType.OnRamp"></a>**<font color="#f8805a">OnRamp</font>**
|
||||
- <a name="carla.LaneType.Parking"></a>**<font color="#f8805a">Parking</font>**
|
||||
- <a name="carla.LaneType.Rail"></a>**<font color="#f8805a">Rail</font>**
|
||||
- <a name="carla.LaneType.Restricted"></a>**<font color="#f8805a">Restricted</font>**
|
||||
- <a name="carla.LaneType.RoadWorks"></a>**<font color="#f8805a">RoadWorks</font>**
|
||||
- <a name="carla.LaneType.Shoulder"></a>**<font color="#f8805a">Shoulder</font>**
|
||||
- <a name="carla.LaneType.Sidewalk"></a>**<font color="#f8805a">Sidewalk</font>**
|
||||
- <a name="carla.LaneType.Special1"></a>**<font color="#f8805a">Special1</font>**
|
||||
- <a name="carla.LaneType.Special2"></a>**<font color="#f8805a">Special2</font>**
|
||||
- <a name="carla.LaneType.Special3"></a>**<font color="#f8805a">Special3</font>**
|
||||
- <a name="carla.LaneType.RoadWorks"></a>**<font color="#f8805a">RoadWorks</font>**
|
||||
- <a name="carla.LaneType.Stop"></a>**<font color="#f8805a">Stop</font>**
|
||||
- <a name="carla.LaneType.Tram"></a>**<font color="#f8805a">Tram</font>**
|
||||
- <a name="carla.LaneType.Rail"></a>**<font color="#f8805a">Rail</font>**
|
||||
- <a name="carla.LaneType.Entry"></a>**<font color="#f8805a">Entry</font>**
|
||||
- <a name="carla.LaneType.Exit"></a>**<font color="#f8805a">Exit</font>**
|
||||
- <a name="carla.LaneType.OffRamp"></a>**<font color="#f8805a">OffRamp</font>**
|
||||
- <a name="carla.LaneType.OnRamp"></a>**<font color="#f8805a">OnRamp</font>**
|
||||
- <a name="carla.LaneType.Any"></a>**<font color="#f8805a">Any</font>**
|
||||
|
||||
---
|
||||
|
||||
|
@ -706,29 +706,56 @@ Height regarding ground level.
|
|||
|
||||
---
|
||||
|
||||
## carla.Junction<a name="carla.Junction"></a> <sub><sup>_class_</sup></sub>
|
||||
Class that embodies the intersections on the road described in the OpenDRIVE file according to OpenDRIVE 1.4 standards.
|
||||
|
||||
<h3>Instance Variables</h3>
|
||||
- <a name="carla.Junction.id"></a>**<font color="#f8805a">id</font>** (_int_)
|
||||
Identificator found in the OpenDRIVE file.
|
||||
- <a name="carla.Junction.bounding_box"></a>**<font color="#f8805a">bounding_box</font>** (_[carla.BoundingBox](#carla.BoundingBox)_)
|
||||
Bounding box encapsulating the junction lanes.
|
||||
|
||||
<h3>Methods</h3>
|
||||
- <a name="carla.Junction.get_waypoints"></a>**<font color="#7fb800">get_waypoints</font>**(<font color="#00a6ed">**self**</font>, <font color="#00a6ed">**lane_type**</font>)
|
||||
Returns a list of pairs of waypoints. Every tuple on the list contains first an initial and then a final waypoint within the intersection boundaries that describe the beginning and the end of said lane along the junction. Lanes follow their OpenDRIVE definitions so there may be many different tuples with the same starting waypoint due to possible deviations, as this are considered different lanes.
|
||||
- **Parameters:**
|
||||
- `lane_type` (_[carla.LaneType](#carla.LaneType)_) – Type of lanes to get the waypoints.
|
||||
- **Return:** _list(tuple([carla.Waypoint](#carla.Waypoint)))_
|
||||
|
||||
---
|
||||
|
||||
## carla.Map<a name="carla.Map"></a> <sub><sup>_class_</sup></sub>
|
||||
Map description that provides a Waypoint query system, that extracts the information from the OpenDRIVE file.
|
||||
Class containing the road information and waypoint managing. Data is retrieved from an OpenDRIVE file that describes the road. A query system is defined which works hand in hand with [carla.Waypoint](#carla.Waypoint) to translate geometrical information from the .xodr to natural world points. CARLA is currently working with [OpenDRIVE 1.4 standard](http://www.opendrive.org/docs/OpenDRIVEFormatSpecRev1.4H.pdf).
|
||||
|
||||
<h3>Instance Variables</h3>
|
||||
- <a name="carla.Map.name"></a>**<font color="#f8805a">name</font>** (_str_)
|
||||
Map name. Comes from the Unreal's UMap name if loaded from a Carla server.
|
||||
The name of the map. It corresponds to the .umap from Unreal Engine that is loaded from a CARLA server, which then references to the .xodr road description.
|
||||
|
||||
<h3>Methods</h3>
|
||||
- <a name="carla.Map.__init__"></a>**<font color="#7fb800">\__init__</font>**(<font color="#00a6ed">**self**</font>, <font color="#00a6ed">**name**</font>, <font color="#00a6ed">**xodr_content**</font>)
|
||||
Constructor for this class useful if you want to use a `XODR` (OpenDRIVE) file without importing it from any Carla server running.
|
||||
Constructor for this class. Though a map is automatically generated when initializing the world, using this method in no-rendering mode facilitates working with an .xodr without any CARLA server running.
|
||||
- **Parameters:**
|
||||
- `name` (_str_) – Name of the current map.
|
||||
- `xodr_content` (_str_) – XODR content as string.
|
||||
- `xodr_content` (_str_) – .xodr content in string format.
|
||||
- **Return:** _list([carla.Transform](#carla.Transform))_
|
||||
- <a name="carla.Map.get_spawn_points"></a>**<font color="#7fb800">get_spawn_points</font>**(<font color="#00a6ed">**self**</font>)
|
||||
Returns a list of transformations corresponding to the recommended spawn points over the map.
|
||||
- **Return:** _list([carla.Transform](#carla.Transform))_
|
||||
- <a name="carla.Map.get_waypoint"></a>**<font color="#7fb800">get_waypoint</font>**(<font color="#00a6ed">**self**</font>, <font color="#00a6ed">**location**</font>, <font color="#00a6ed">**project_to_road**=True</font>, <font color="#00a6ed">**lane_type**=[carla.LaneType.Driving](#carla.LaneType.Driving)</font>)
|
||||
- <a name="carla.Map.generate_waypoints"></a>**<font color="#7fb800">generate_waypoints</font>**(<font color="#00a6ed">**self**</font>, <font color="#00a6ed">**distance**</font>)
|
||||
Returns a list of waypoints with a certain distance between them for every lane and centered inside of it. Waypoints are not listed in any particular order. Remember that waypoints closer than 2cm within the same road, section and lane will have the same identificator.
|
||||
- **Parameters:**
|
||||
- `location` (_[carla.Location](#carla.Location)_) – Location where you want to get the [carla.Waypoint](#carla.Waypoint).
|
||||
- `project_to_road` (_bool_) – If **True**, the waypoint will be at the center of the nearest lane.
|
||||
If **False**, the waypoint will be at the given location. Also, in this second case, the result may be `None` if the waypoint is not found.
|
||||
- `lane_type` (_[carla.LaneType](#carla.LaneType)_) – This parameter is used to limit the search on a certain lane type. This can be used like a flag: `LaneType.Driving & LaneType.Shoulder`.
|
||||
- `distance` (_float_) – Approximate distance between waypoints.
|
||||
- **Return:** _list([carla.Waypoint](#carla.Waypoint))_
|
||||
- <a name="carla.Map.get_spawn_points"></a>**<font color="#7fb800">get_spawn_points</font>**(<font color="#00a6ed">**self**</font>)
|
||||
Returns a list of recommendations made by creators of the map to be used spawning points for vehicles. The list includes [carla.Tranform](#carla.Tranform) objects with certain location and orientation. Said locations are slightly on-air and vehicles fall for a bit before starting their way.
|
||||
- **Return:** _list([carla.Transform](#carla.Transform))_
|
||||
- <a name="carla.Map.get_topology"></a>**<font color="#7fb800">get_topology</font>**(<font color="#00a6ed">**self**</font>)
|
||||
Returns a list of tuples describing a minimal graph of the topology of the OpenDRIVE file. The tuples contain pairs of waypoints located either at the point a road begins or ends. The first one is the origin and the second one represents another road end that can be reached. This graph can be loaded into [NetworkX](https://networkx.github.io/) to work with. Output could look like this: <b>[(w0, w1), (w0, w2), (w1, w3), (w2, w3), (w0, w4)]</b>.
|
||||
- **Return:** _list(tuple([carla.Waypoint](#carla.Waypoint), [carla.Waypoint](#carla.Waypoint)))_
|
||||
- <a name="carla.Map.get_waypoint"></a>**<font color="#7fb800">get_waypoint</font>**(<font color="#00a6ed">**self**</font>, <font color="#00a6ed">**location**</font>, <font color="#00a6ed">**project_to_road**=True</font>, <font color="#00a6ed">**lane_type**=[carla.LaneType.Driving](#carla.LaneType.Driving)</font>)
|
||||
Returns a waypoint that can be located in an exact location or translated to the center of the nearest lane. Said lane type can be defined using flags such as `LaneType.Driving & LaneType.Shoulder`.
|
||||
The method will return <b>None</b> if the waypoint is not found, which may happen only when trying to retrieve a waypoint for an exact location. That eases checking if a point is inside a certain road, as otherwise, it will return the corresponding waypoint.
|
||||
- **Parameters:**
|
||||
- `location` (_[carla.Location](#carla.Location)_) – Location used as reference for the [carla.Waypoint](#carla.Waypoint).
|
||||
- `project_to_road` (_bool_) – If **True**, the waypoint will be at the center of the closest lane. This is the default setting. If **False**, the waypoint will be exactly in `location`. <b>None</b> means said location does not belong to a road.
|
||||
- `lane_type` (_[carla.LaneType](#carla.LaneType)_) – Limits the search for nearest lane to one or various lane types that can be flagged.
|
||||
- **Return:** _[carla.Waypoint](#carla.Waypoint)_
|
||||
- <a name="carla.Map.get_waypoint_xodr"></a>**<font color="#7fb800">get_waypoint_xodr</font>**(<font color="#00a6ed">**self**</font>, <font color="#00a6ed">**road_id**</font>, <font color="#00a6ed">**lane_id**</font>, <font color="#00a6ed">**s**</font>)
|
||||
Get a waypoint if all the parameters passed are correct, otherwise return None.
|
||||
|
@ -741,22 +768,22 @@ Get a waypoint if all the parameters passed are correct, otherwise return None.
|
|||
It provides a minimal graph of the topology of the current OpenDRIVE file. It is constituted by a list of pairs of waypoints, where the first waypoint is the origin and the second one is the destination. It can be loaded into [NetworkX](https://networkx.github.io/). A valid output could be: `[ (w0, w1), (w0, w2), (w1, w3), (w2, w3), (w0, w4) ]`.
|
||||
- **Return:** _list(tuple([carla.Waypoint](#carla.Waypoint), [carla.Waypoint](#carla.Waypoint)))_
|
||||
- <a name="carla.Map.generate_waypoints"></a>**<font color="#7fb800">generate_waypoints</font>**(<font color="#00a6ed">**self**</font>, <font color="#00a6ed">**distance**</font>)
|
||||
Returns a list of waypoints positioned on the center of the lanes all over the map with an approximate distance between them.
|
||||
Returns a list of waypoints positioned on the center of the lanes all over the map with an approximate distance between them.
|
||||
- **Parameters:**
|
||||
- `distance` (_float_) – Approximate distance between the waypoints.
|
||||
- **Return:** _list([carla.Waypoint](#carla.Waypoint))_
|
||||
- <a name="carla.Map.transform_to_geolocation"></a>**<font color="#7fb800">transform_to_geolocation</font>**(<font color="#00a6ed">**self**</font>, <font color="#00a6ed">**location**</font>)
|
||||
Converts a given [carla.Location](#carla.Location) `(x, y, z)` to a [carla.GeoLocation](#carla.GeoLocation) `(lat, lon, alt)`.
|
||||
- <a name="carla.Map.transform_to_geolocation"></a>**<font color="#7fb800">transform_to_geolocation</font>**(<font color="#00a6ed">**self**</font>, <font color="#00a6ed">**path**</font>)
|
||||
Saves the .xodr OpenDRIVE file of the current map to disk.
|
||||
- **Parameters:**
|
||||
- `location` (_[carla.Location](#carla.Location)_) – Location to convert.
|
||||
- **Return:** _[carla.GeoLocation](#carla.GeoLocation)_
|
||||
- `path` – Path where the file will be saved.
|
||||
- <a name="carla.Map.to_opendrive"></a>**<font color="#7fb800">to_opendrive</font>**(<font color="#00a6ed">**self**</font>)
|
||||
Returns the OpenDRIVE of the current map as string.
|
||||
Returns the .xodr OpenDRIVe file of the current map as string.
|
||||
- **Return:** _str_
|
||||
- <a name="carla.Map.save_to_disk"></a>**<font color="#7fb800">save_to_disk</font>**(<font color="#00a6ed">**self**</font>, <font color="#00a6ed">**path**</font>)
|
||||
Save the OpenDRIVE of the current map to disk.
|
||||
- <a name="carla.Map.transform_to_geolocation"></a>**<font color="#7fb800">transform_to_geolocation</font>**(<font color="#00a6ed">**self**</font>, <font color="#00a6ed">**location**</font>)
|
||||
Converts a given `location`, a point in the simulation, to a [carla.GeoLocation](#carla.GeoLocation), which represents world coordinates. The geographical location of the map is defined inside OpenDRIVE within the tag <b><georeference></b>.
|
||||
- **Parameters:**
|
||||
- `path` – Path where it will be saved.
|
||||
- `location` (_[carla.Location](#carla.Location)_)
|
||||
- **Return:** _[carla.GeoLocation](#carla.GeoLocation)_
|
||||
- <a name="carla.Map.__str__"></a>**<font color="#7fb800">\__str__</font>**(<font color="#00a6ed">**self**</font>)
|
||||
|
||||
---
|
||||
|
@ -1119,51 +1146,65 @@ WalkerControl constructor.
|
|||
---
|
||||
|
||||
## carla.Waypoint<a name="carla.Waypoint"></a> <sub><sup>_class_</sup></sub>
|
||||
3D directed point that stores information about the road definition provided by OpenDRIVE.
|
||||
Waypoints in CARLA are described as 3D directed points. They store a certain [carla.Transform](#carla.Transform) which locates the waypoint in a road and orientates it according to the lane. They also store the road information belonging to said point regarding its lane and lane markings. All of this information is retrieved as provided by the OpenDRIVE file.
|
||||
|
||||
<h3>Instance Variables</h3>
|
||||
- <a name="carla.Waypoint.id"></a>**<font color="#f8805a">id</font>** (_int_)
|
||||
Waypoint id, it's generated using a hash combination of its `road_id`, `section_id`, `lane_id` and `s` values, all them come from the OpenDRIVE. The `s` precision is set to 2 centimeters, so 2 waypoints at a distance `s` less than 2 centimeters in the same road, section and lane, will have the same `id`.
|
||||
The identificator is generated using a hash combination of the <b>road</b>, <b>section</b>, <b>lane</b> and <b>s</b> values that correspond to said point in the OpenDRIVE geometry. The <b>s</b> precision is set to 2 centimeters, so 2 waypoints closer than 2 centimeters in the same road, section and lane, will have the same identificator.
|
||||
- <a name="carla.Waypoint.transform"></a>**<font color="#f8805a">transform</font>** (_[carla.Transform](#carla.Transform)_)
|
||||
Transform indicating it's position and orientation according to the current lane information.
|
||||
- <a name="carla.Waypoint.is_intersection"></a>**<font color="#f8805a">is_intersection</font>** (_bool_)
|
||||
_Deprecated, use is_junction instead_.
|
||||
- <a name="carla.Waypoint.is_junction"></a>**<font color="#f8805a">is_junction</font>** (_bool_)
|
||||
True if the current Waypoint is on a junction.
|
||||
- <a name="carla.Waypoint.lane_width"></a>**<font color="#f8805a">lane_width</font>** (_float_)
|
||||
Horizontal size of the road at current `s`.
|
||||
Position and orientation of the waypoint according to the current lane information. This data is computed the first time it is accessed. It is not created right away in order to ease computing costs when lots of waypoints are created but their specific transform is not needed.
|
||||
- <a name="carla.Waypoint.road_id"></a>**<font color="#f8805a">road_id</font>** (_int_)
|
||||
OpenDRIVE road's id.
|
||||
- <a name="carla.Waypoint.section_id"></a>**<font color="#f8805a">section_id</font>** (_int_)
|
||||
OpenDRIVE section's id, based on the order that they are originally defined.
|
||||
- <a name="carla.Waypoint.lane_id"></a>**<font color="#f8805a">lane_id</font>** (_int_)
|
||||
OpenDRIVE lane's id, this value can be positive or negative which represents the direction of the current lane with respect to the road. For more information refer to OpenDRIVE [documentation](http://www.opendrive.org/docs/OpenDRIVEFormatSpecRev1.4H.pdf#page=20).
|
||||
OpenDRIVE lane's id, this value can be positive or negative which represents the direction of the current lane with respect to the road. For more information refer to OpenDRIVE [documentation](http://www.opendrive.org/docs/OpenDRIVEFormatSpecRev1.4H.pdf#page=20).
|
||||
- <a name="carla.Waypoint.s"></a>**<font color="#f8805a">s</font>** (_float_)
|
||||
OpenDRIVE `s` value of the current position.
|
||||
OpenDRIVE <b>s</b> value of the current position.
|
||||
- <a name="carla.Waypoint.is_junction"></a>**<font color="#f8805a">is_junction</font>** (_bool_)
|
||||
<b>True</b> if the current Waypoint is on a junction as defined by OpenDRIVE.
|
||||
- <a name="carla.Waypoint.lane_width"></a>**<font color="#f8805a">lane_width</font>** (_float_)
|
||||
Horizontal size of the road at current <b>s</b>.
|
||||
- <a name="carla.Waypoint.lane_change"></a>**<font color="#f8805a">lane_change</font>** (_[carla.LaneChange](#carla.LaneChange)_)
|
||||
Lane change definition of the current Waypoint's location, based on the traffic rules defined in the OpenDRIVE file. Basically, it tells you if a lane change can be done and in which direction.
|
||||
Lane change definition of the current Waypoint's location, based on the traffic rules defined in the OpenDRIVE file. It states if a lane change can be done and in which direction.
|
||||
- <a name="carla.Waypoint.lane_type"></a>**<font color="#f8805a">lane_type</font>** (_[carla.LaneType](#carla.LaneType)_)
|
||||
The lane type of the current Waypoint, based on OpenDRIVE types.
|
||||
The lane type of the current Waypoint, based on OpenDRIVE 1.4 standard.
|
||||
- <a name="carla.Waypoint.right_lane_marking"></a>**<font color="#f8805a">right_lane_marking</font>** (_[carla.LaneMarking](#carla.LaneMarking)_)
|
||||
The right lane marking information based on the direction of the Waypoint.
|
||||
- <a name="carla.Waypoint.left_lane_marking"></a>**<font color="#f8805a">left_lane_marking</font>** (_[carla.LaneMarking](#carla.LaneMarking)_)
|
||||
The left lane marking information based on the direction of the Waypoint.
|
||||
|
||||
<h3>Methods</h3>
|
||||
- <a name="carla.Waypoint.get_left_lane"></a>**<font color="#7fb800">get_left_lane</font>**(<font color="#00a6ed">**self**</font>)
|
||||
Generates a Waypoint at the center of the left lane based on the direction of the current Waypoint, regardless if the lane change is allowed in this location.
|
||||
Can return <b>None</b> if the lane does not exist.
|
||||
- **Return:** _[carla.Waypoint](#carla.Waypoint)_
|
||||
- <a name="carla.Waypoint.get_right_lane"></a>**<font color="#7fb800">get_right_lane</font>**(<font color="#00a6ed">**self**</font>)
|
||||
Generates a waypoint at the center of the right lane based on the direction of the current waypoint, regardless if the lane change is allowed in this location.
|
||||
Can return <b>None</b> if the lane does not exist.
|
||||
- **Return:** _[carla.Waypoint](#carla.Waypoint)_
|
||||
- <a name="carla.Waypoint.next"></a>**<font color="#7fb800">next</font>**(<font color="#00a6ed">**self**</font>, <font color="#00a6ed">**distance**</font>)
|
||||
Returns a list of Waypoints at a certain approximate distance from the current Waypoint, taking into account the shape of the road and its possible deviations, without performing any lane change.
|
||||
Returns a list of waypoints at a certain approximate `distance` from the current one. It takes into account the road and its possible deviations without performing any lane change and returns one waypoint per option.
|
||||
The list may be empty if the road ends before the specified distance, for instance, a lane ending with the only option of incorporating to another road.
|
||||
- **Parameters:**
|
||||
- `distance` (_float_) – The approximate distance where to get the next Waypoints.
|
||||
- `distance` (_float_) – The approximate distance where to get the next waypoints.
|
||||
- **Return:** _list([carla.Waypoint](#carla.Waypoint))_
|
||||
- <a name="carla.Waypoint.next_until_lane_end"></a>**<font color="#7fb800">next_until_lane_end</font>**(<font color="#00a6ed">**self**</font>, <font color="#00a6ed">**distance**</font>)
|
||||
Returns a list of waypoints from this to the end of the lane separated by a certain `distance`.
|
||||
- **Parameters:**
|
||||
- `distance` (_float_) – The approximate distance between waypoints.
|
||||
- **Return:** _list([carla.Waypoint](#carla.Waypoint))_
|
||||
- <a name="carla.Waypoint.previous"></a>**<font color="#7fb800">previous</font>**(<font color="#00a6ed">**self**</font>, <font color="#00a6ed">**distance**</font>)
|
||||
This method does not return the waypoint previously visited by an actor, but a list of waypoints at an approximate `distance` but in the opposite direction of the lane. Similarly to **<font color="#7fb800">next()</font>**, it takes into account the road and its possible deviations without performing any lane change and returns one waypoint per option.
|
||||
The list may be empty if the road ends before the specified distance, for instance, a lane ending with the only option of incorporating to another road.
|
||||
- **Parameters:**
|
||||
- `distance` (_float_) – The approximate distance where to get the previous waypoints.
|
||||
- **Return:** _list([carla.Waypoint](#carla.Waypoint))_
|
||||
- <a name="carla.Waypoint.previous_until_lane_start"></a>**<font color="#7fb800">previous_until_lane_start</font>**(<font color="#00a6ed">**self**</font>, <font color="#00a6ed">**distance**</font>)
|
||||
Returns a list of waypoints from this to the start of the lane separated by a certain `distance`.
|
||||
- **Parameters:**
|
||||
- `distance` (_float_) – The approximate distance between waypoints.
|
||||
- **Return:** _list([carla.Waypoint](#carla.Waypoint))_
|
||||
- <a name="carla.Waypoint.get_right_lane"></a>**<font color="#7fb800">get_right_lane</font>**(<font color="#00a6ed">**self**</font>)
|
||||
Generates a Waypoint at the center of the right lane based on the direction of the current Waypoint, regardless if the lane change is allowed in this location.
|
||||
Can return `None` if the lane does not exist.
|
||||
- **Return:** _[carla.Waypoint](#carla.Waypoint)_
|
||||
- <a name="carla.Waypoint.get_left_lane"></a>**<font color="#7fb800">get_left_lane</font>**(<font color="#00a6ed">**self**</font>)
|
||||
Generates a Waypoint at the center of the left lane based on the direction of the current Waypoint, regardless if the lane change is allowed in this location.
|
||||
Can return `None` if the lane does not exist.
|
||||
- **Return:** _[carla.Waypoint](#carla.Waypoint)_
|
||||
- <a name="carla.Waypoint.__str__"></a>**<font color="#7fb800">\__str__</font>**(<font color="#00a6ed">**self**</font>)
|
||||
|
||||
---
|
||||
|
|
|
@ -0,0 +1,29 @@
|
|||
// Copyright (c) 2020 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#include "carla/client/Junction.h"
|
||||
#include "carla/client/Map.h"
|
||||
#include "carla/road/element/Waypoint.h"
|
||||
|
||||
namespace carla {
|
||||
namespace client {
|
||||
|
||||
Junction::Junction(SharedPtr<const Map> parent, const road::Junction *junction) : _parent(parent) {
|
||||
_bounding_box = junction->GetBoundingBox();
|
||||
_id = junction->GetId();
|
||||
}
|
||||
|
||||
std::vector<std::pair<SharedPtr<Waypoint>, SharedPtr<Waypoint>>> Junction::GetWaypoints(
|
||||
road::Lane::LaneType type) const {
|
||||
return _parent->GetJunctionWaypoints(GetId(), type);
|
||||
}
|
||||
|
||||
geom::BoundingBox Junction::GetBoundingBox() const {
|
||||
return _bounding_box;
|
||||
}
|
||||
|
||||
} // namespace client
|
||||
} // namespace carla
|
|
@ -0,0 +1,52 @@
|
|||
// Copyright (c) 2020 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "carla/Memory.h"
|
||||
#include "carla/NonCopyable.h"
|
||||
#include "carla/road/Junction.h"
|
||||
#include "carla/road/RoadTypes.h"
|
||||
#include "carla/geom/BoundingBox.h"
|
||||
#include "carla/client/Waypoint.h"
|
||||
|
||||
#include <vector>
|
||||
|
||||
namespace carla {
|
||||
namespace client {
|
||||
|
||||
class Map;
|
||||
|
||||
class Junction
|
||||
: public EnableSharedFromThis<Junction>,
|
||||
private NonCopyable
|
||||
{
|
||||
public:
|
||||
|
||||
carla::road::JuncId GetId() const {
|
||||
return _id;
|
||||
}
|
||||
|
||||
std::vector<std::pair<SharedPtr<Waypoint>,SharedPtr<Waypoint>>> GetWaypoints(
|
||||
road::Lane::LaneType type = road::Lane::LaneType::Driving) const;
|
||||
|
||||
geom::BoundingBox GetBoundingBox() const;
|
||||
|
||||
private:
|
||||
|
||||
friend class Map;
|
||||
|
||||
Junction(SharedPtr<const Map> parent, const road::Junction *junction);
|
||||
|
||||
SharedPtr<const Map> _parent;
|
||||
|
||||
geom::BoundingBox _bounding_box;
|
||||
|
||||
road::JuncId _id;
|
||||
};
|
||||
|
||||
} // namespace client
|
||||
} // namespace carla
|
|
@ -6,6 +6,7 @@
|
|||
|
||||
#include "carla/client/Map.h"
|
||||
|
||||
#include "carla/client/Junction.h"
|
||||
#include "carla/client/Waypoint.h"
|
||||
#include "carla/opendrive/OpenDriveParser.h"
|
||||
#include "carla/road/Map.h"
|
||||
|
@ -31,16 +32,16 @@ namespace client {
|
|||
|
||||
Map::Map(std::string name, std::string xodr_content)
|
||||
: Map(rpc::MapInfo{
|
||||
std::move(name),
|
||||
std::move(xodr_content),
|
||||
std::vector<geom::Transform>{}}) {}
|
||||
std::move(name),
|
||||
std::move(xodr_content),
|
||||
std::vector<geom::Transform>{}}) {}
|
||||
|
||||
Map::~Map() = default;
|
||||
|
||||
SharedPtr<Waypoint> Map::GetWaypoint(
|
||||
const geom::Location &location,
|
||||
bool project_to_road,
|
||||
uint32_t lane_type) const {
|
||||
const geom::Location &location,
|
||||
bool project_to_road,
|
||||
uint32_t lane_type) const {
|
||||
boost::optional<road::element::Waypoint> waypoint;
|
||||
if (project_to_road) {
|
||||
waypoint = _map.GetClosestWaypointOnRoad(location, lane_type);
|
||||
|
@ -48,8 +49,8 @@ namespace client {
|
|||
waypoint = _map.GetWaypoint(location, lane_type);
|
||||
}
|
||||
return waypoint.has_value() ?
|
||||
SharedPtr<Waypoint>(new Waypoint{shared_from_this(), *waypoint}) :
|
||||
nullptr;
|
||||
SharedPtr<Waypoint>(new Waypoint{shared_from_this(), *waypoint}) :
|
||||
nullptr;
|
||||
}
|
||||
|
||||
SharedPtr<Waypoint> Map::GetWaypointXODR(
|
||||
|
@ -82,8 +83,8 @@ namespace client {
|
|||
result.reserve(topology.size());
|
||||
for (const auto &pair : topology) {
|
||||
result.emplace_back(
|
||||
get_or_make_waypoint(pair.first),
|
||||
get_or_make_waypoint(pair.second));
|
||||
get_or_make_waypoint(pair.first),
|
||||
get_or_make_waypoint(pair.second));
|
||||
}
|
||||
return result;
|
||||
}
|
||||
|
@ -99,8 +100,8 @@ namespace client {
|
|||
}
|
||||
|
||||
std::vector<road::element::LaneMarking> Map::CalculateCrossedLanes(
|
||||
const geom::Location &origin,
|
||||
const geom::Location &destination) const {
|
||||
const geom::Location &origin,
|
||||
const geom::Location &destination) const {
|
||||
return _map.CalculateCrossedLanes(origin, destination);
|
||||
}
|
||||
|
||||
|
@ -108,9 +109,28 @@ namespace client {
|
|||
return _map.GetGeoReference();
|
||||
}
|
||||
|
||||
std::vector<geom::Location> Map::GetAllCrosswalkZones() const{
|
||||
std::vector<geom::Location> Map::GetAllCrosswalkZones() const {
|
||||
return _map.GetAllCrosswalkZones();
|
||||
}
|
||||
|
||||
SharedPtr<Junction> Map::GetJunction(const Waypoint &waypoint) const {
|
||||
const road::Junction *juncptr = GetMap().GetJunction(waypoint.GetJunctionId());
|
||||
auto junction = SharedPtr<Junction>(new Junction(shared_from_this(), juncptr));
|
||||
return junction;
|
||||
}
|
||||
|
||||
std::vector<std::pair<SharedPtr<Waypoint>, SharedPtr<Waypoint>>> Map::GetJunctionWaypoints(
|
||||
road::JuncId id,
|
||||
road::Lane::LaneType lane_type) const {
|
||||
std::vector<std::pair<SharedPtr<Waypoint>, SharedPtr<Waypoint>>> result;
|
||||
auto junction_waypoints = GetMap().GetJunctionWaypoints(id, lane_type);
|
||||
for (auto &waypoint_pair : junction_waypoints) {
|
||||
result.emplace_back(
|
||||
std::make_pair(SharedPtr<Waypoint>(new Waypoint(shared_from_this(), waypoint_pair.first)),
|
||||
SharedPtr<Waypoint>(new Waypoint(shared_from_this(), waypoint_pair.second))));
|
||||
}
|
||||
return result;
|
||||
}
|
||||
|
||||
} // namespace client
|
||||
} // namespace carla
|
||||
|
|
|
@ -21,10 +21,11 @@ namespace geom { class GeoLocation; }
|
|||
namespace client {
|
||||
|
||||
class Waypoint;
|
||||
class Junction;
|
||||
|
||||
class Map
|
||||
: public EnableSharedFromThis<Map>,
|
||||
private NonCopyable {
|
||||
private NonCopyable {
|
||||
public:
|
||||
|
||||
explicit Map(rpc::MapInfo description);
|
||||
|
@ -50,9 +51,9 @@ namespace client {
|
|||
}
|
||||
|
||||
SharedPtr<Waypoint> GetWaypoint(
|
||||
const geom::Location &location,
|
||||
bool project_to_road = true,
|
||||
uint32_t lane_type = static_cast<uint32_t>(road::Lane::LaneType::Driving)) const;
|
||||
const geom::Location &location,
|
||||
bool project_to_road = true,
|
||||
uint32_t lane_type = static_cast<uint32_t>(road::Lane::LaneType::Driving)) const;
|
||||
|
||||
SharedPtr<Waypoint> GetWaypointXODR(
|
||||
carla::road::RoadId road_id,
|
||||
|
@ -66,13 +67,20 @@ namespace client {
|
|||
std::vector<SharedPtr<Waypoint>> GenerateWaypoints(double distance) const;
|
||||
|
||||
std::vector<road::element::LaneMarking> CalculateCrossedLanes(
|
||||
const geom::Location &origin,
|
||||
const geom::Location &destination) const;
|
||||
const geom::Location &origin,
|
||||
const geom::Location &destination) const;
|
||||
|
||||
const geom::GeoLocation &GetGeoReference() const;
|
||||
|
||||
std::vector<geom::Location> GetAllCrosswalkZones() const;
|
||||
|
||||
SharedPtr<Junction> GetJunction(const Waypoint &waypoint) const;
|
||||
|
||||
/// Returns a pair of waypoints (start and end) for each lane in the
|
||||
/// junction
|
||||
std::vector<std::pair<SharedPtr<Waypoint>, SharedPtr<Waypoint>>> GetJunctionWaypoints(
|
||||
road::JuncId id, road::Lane::LaneType type) const;
|
||||
|
||||
private:
|
||||
|
||||
const rpc::MapInfo _description;
|
||||
|
|
|
@ -7,6 +7,7 @@
|
|||
#include "carla/client/Waypoint.h"
|
||||
|
||||
#include "carla/client/Map.h"
|
||||
#include "carla/client/Junction.h"
|
||||
|
||||
namespace carla {
|
||||
namespace client {
|
||||
|
@ -27,6 +28,13 @@ namespace client {
|
|||
return _parent->GetMap().IsJunction(_waypoint.road_id);
|
||||
}
|
||||
|
||||
SharedPtr<Junction> Waypoint::GetJunction() const {
|
||||
if (IsJunction()) {
|
||||
return _parent->GetJunction(*this);
|
||||
}
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
double Waypoint::GetLaneWidth() const {
|
||||
return _parent->GetMap().GetLaneWidth(_waypoint);
|
||||
|
||||
|
@ -46,6 +54,68 @@ namespace client {
|
|||
return result;
|
||||
}
|
||||
|
||||
std::vector<SharedPtr<Waypoint>> Waypoint::GetPrevious(double distance) const {
|
||||
auto waypoints = _parent->GetMap().GetPrevious(_waypoint, distance);
|
||||
std::vector<SharedPtr<Waypoint>> result;
|
||||
result.reserve(waypoints.size());
|
||||
for (auto &waypoint : waypoints) {
|
||||
result.emplace_back(SharedPtr<Waypoint>(new Waypoint(_parent, std::move(waypoint))));
|
||||
}
|
||||
return result;
|
||||
}
|
||||
|
||||
std::vector<SharedPtr<Waypoint>> Waypoint::GetNextUntilLaneEnd(double distance) const {
|
||||
std::vector<SharedPtr<Waypoint>> result;
|
||||
std::vector<SharedPtr<Waypoint>> next = GetNext(distance);
|
||||
|
||||
while (next.size() == 1 && next.front()->GetRoadId() == GetRoadId()) {
|
||||
result.emplace_back(next.front());
|
||||
next = result.back()->GetNext(distance);
|
||||
}
|
||||
double current_s = GetDistance();
|
||||
if(result.size()) {
|
||||
current_s = result.back()->GetDistance();
|
||||
}
|
||||
double remaining_length;
|
||||
double road_length = _parent->GetMap().GetLane(_waypoint).GetRoad()->GetLength();
|
||||
if(_waypoint.lane_id < 0) {
|
||||
remaining_length = road_length - current_s;
|
||||
} else {
|
||||
remaining_length = current_s;
|
||||
}
|
||||
remaining_length -= std::numeric_limits<double>::epsilon();
|
||||
result.emplace_back(result.back()->GetNext(remaining_length).front());
|
||||
|
||||
return result;
|
||||
}
|
||||
|
||||
std::vector<SharedPtr<Waypoint>> Waypoint::GetPreviousUntilLaneStart(double distance) const {
|
||||
std::vector<SharedPtr<Waypoint>> result;
|
||||
std::vector<SharedPtr<Waypoint>> prev = GetPrevious(distance);
|
||||
|
||||
while (prev.size() == 1 && prev.front()->GetRoadId() == GetRoadId()) {
|
||||
result.emplace_back(prev.front());
|
||||
prev = result.back()->GetPrevious(distance);
|
||||
}
|
||||
|
||||
double current_s = GetDistance();
|
||||
if(result.size()) {
|
||||
current_s = result.back()->GetDistance();
|
||||
}
|
||||
|
||||
double remaining_length;
|
||||
double road_length = _parent->GetMap().GetLane(_waypoint).GetRoad()->GetLength();
|
||||
if(_waypoint.lane_id < 0) {
|
||||
remaining_length = road_length - current_s;
|
||||
} else {
|
||||
remaining_length = current_s;
|
||||
}
|
||||
remaining_length -= std::numeric_limits<double>::epsilon();
|
||||
result.emplace_back(result.back()->GetPrevious(remaining_length).front());
|
||||
|
||||
return result;
|
||||
}
|
||||
|
||||
SharedPtr<Waypoint> Waypoint::GetRight() const {
|
||||
auto right_lane_waypoint =
|
||||
_parent->GetMap().GetRight(_waypoint);
|
||||
|
|
|
@ -21,10 +21,11 @@ namespace carla {
|
|||
namespace client {
|
||||
|
||||
class Map;
|
||||
class Junction;
|
||||
|
||||
class Waypoint
|
||||
: public EnableSharedFromThis<Waypoint>,
|
||||
private NonCopyable {
|
||||
private NonCopyable {
|
||||
public:
|
||||
|
||||
~Waypoint();
|
||||
|
@ -61,12 +62,24 @@ namespace client {
|
|||
|
||||
bool IsJunction() const;
|
||||
|
||||
SharedPtr<Junction> GetJunction() const;
|
||||
|
||||
double GetLaneWidth() const;
|
||||
|
||||
road::Lane::LaneType GetType() const;
|
||||
|
||||
std::vector<SharedPtr<Waypoint>> GetNext(double distance) const;
|
||||
|
||||
std::vector<SharedPtr<Waypoint>> GetPrevious(double distance) const;
|
||||
|
||||
/// Returns a list of waypoints separated by distance from the current waypoint
|
||||
/// to the end of the lane
|
||||
std::vector<SharedPtr<Waypoint>> GetNextUntilLaneEnd(double distance) const;
|
||||
|
||||
/// Returns a list of waypoints separated by distance from the current waypoint
|
||||
/// to the start of the lane
|
||||
std::vector<SharedPtr<Waypoint>> GetPreviousUntilLaneStart(double distance) const;
|
||||
|
||||
SharedPtr<Waypoint> GetRight() const;
|
||||
|
||||
SharedPtr<Waypoint> GetLeft() const;
|
||||
|
|
|
@ -6,6 +6,7 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include "carla/geom/BoundingBox.h"
|
||||
#include "carla/NonCopyable.h"
|
||||
#include "carla/road/RoadTypes.h"
|
||||
|
||||
|
@ -64,6 +65,14 @@ namespace road {
|
|||
return _connections;
|
||||
}
|
||||
|
||||
std::unordered_map<ConId, Connection> GetConnections() const {
|
||||
return _connections;
|
||||
}
|
||||
|
||||
carla::geom::BoundingBox GetBoundingBox() const{
|
||||
return _bounding_box;
|
||||
}
|
||||
|
||||
private:
|
||||
|
||||
friend MapBuilder;
|
||||
|
@ -73,6 +82,8 @@ namespace road {
|
|||
std::string _name;
|
||||
|
||||
std::unordered_map<ConId, Connection> _connections;
|
||||
|
||||
carla::geom::BoundingBox _bounding_box;
|
||||
};
|
||||
|
||||
} // road
|
||||
|
|
|
@ -46,7 +46,7 @@ namespace road {
|
|||
Exit = 0x1 << 18,
|
||||
OffRamp = 0x1 << 19,
|
||||
OnRamp = 0x1 << 20,
|
||||
Any = 0xFFFFFFFF
|
||||
Any = 0xFFFFFFFE
|
||||
};
|
||||
|
||||
public:
|
||||
|
|
|
@ -77,6 +77,25 @@ namespace road {
|
|||
}
|
||||
}
|
||||
|
||||
template <typename FuncT>
|
||||
static void ForEachLaneImpl(
|
||||
RoadId road_id,
|
||||
const LaneSection &lane_section,
|
||||
double distance,
|
||||
Lane::LaneType lane_type,
|
||||
FuncT &&func) {
|
||||
for (const auto &pair : lane_section.GetLanes()) {
|
||||
const auto &lane = pair.second;
|
||||
if ((static_cast<uint32_t>(lane.GetType()) & static_cast<uint32_t>(lane_type)) > 0) {
|
||||
std::forward<FuncT>(func)(Waypoint{
|
||||
road_id,
|
||||
lane_section.GetId(),
|
||||
lane.GetId(),
|
||||
distance < 0.0 ? GetDistanceAtStartOfLane(lane) : distance});
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/// Return a waypoint for each drivable lane on each lane section of @a road.
|
||||
template <typename FuncT>
|
||||
static void ForEachDrivableLane(const Road &road, FuncT &&func) {
|
||||
|
@ -84,7 +103,20 @@ namespace road {
|
|||
ForEachDrivableLaneImpl(
|
||||
road.GetId(),
|
||||
lane_section,
|
||||
-1.0,
|
||||
-1.0, // At start of the lane
|
||||
std::forward<FuncT>(func));
|
||||
}
|
||||
}
|
||||
|
||||
/// Return a waypoint for each drivable lane of the specified type on each lane section of @a road.
|
||||
template <typename FuncT>
|
||||
static void ForEachLane(const Road &road, Lane::LaneType lane_type, FuncT &&func) {
|
||||
for (const auto &lane_section : road.GetLaneSections()) {
|
||||
ForEachLaneImpl(
|
||||
road.GetId(),
|
||||
lane_section,
|
||||
-1.0, // At start of the lane
|
||||
lane_type,
|
||||
std::forward<FuncT>(func));
|
||||
}
|
||||
}
|
||||
|
@ -539,6 +571,39 @@ namespace road {
|
|||
return result;
|
||||
}
|
||||
|
||||
std::vector<Waypoint> Map::GetPrevious(
|
||||
const Waypoint waypoint,
|
||||
const double distance) const {
|
||||
RELEASE_ASSERT(distance > 0.0);
|
||||
const auto &lane = GetLane(waypoint);
|
||||
const bool forward = !(waypoint.lane_id <= 0);
|
||||
const double signed_distance = forward ? distance : -distance;
|
||||
const double relative_s = waypoint.s - lane.GetDistance() + EPSILON;
|
||||
const double remaining_lane_length = forward ? lane.GetLength() - relative_s : relative_s;
|
||||
DEBUG_ASSERT(remaining_lane_length >= 0.0);
|
||||
|
||||
// If after subtracting the distance we are still in the same lane, return
|
||||
// same waypoint with the extra distance.
|
||||
if (distance <= remaining_lane_length) {
|
||||
Waypoint result = waypoint;
|
||||
result.s += signed_distance;
|
||||
result.s += forward ? -EPSILON : EPSILON;
|
||||
RELEASE_ASSERT(result.s > 0.0);
|
||||
return { result };
|
||||
}
|
||||
|
||||
// If we run out of remaining_lane_length we have to go to the successors.
|
||||
std::vector<Waypoint> result;
|
||||
for (const auto &successor : GetPredecessors(waypoint)) {
|
||||
DEBUG_ASSERT(
|
||||
successor.road_id != waypoint.road_id ||
|
||||
successor.section_id != waypoint.section_id ||
|
||||
successor.lane_id != waypoint.lane_id);
|
||||
result = ConcatVectors(result, GetPrevious(successor, distance - remaining_lane_length));
|
||||
}
|
||||
return result;
|
||||
}
|
||||
|
||||
boost::optional<Waypoint> Map::GetRight(Waypoint waypoint) const {
|
||||
RELEASE_ASSERT(waypoint.lane_id != 0);
|
||||
if (waypoint.lane_id > 0) {
|
||||
|
@ -615,6 +680,22 @@ namespace road {
|
|||
return result;
|
||||
}
|
||||
|
||||
std::vector<std::pair<Waypoint, Waypoint>> Map::GetJunctionWaypoints(JuncId id, Lane::LaneType lane_type) const {
|
||||
std::vector<std::pair<Waypoint, Waypoint>> result;
|
||||
const Junction * junction = GetJunction(id);
|
||||
for(auto &connections : junction->GetConnections()) {
|
||||
const Road &road = _data.GetRoad(connections.second.connecting_road);
|
||||
ForEachLane(road, lane_type, [&](auto &&waypoint) {
|
||||
const auto& lane = GetLane(waypoint);
|
||||
const double final_s = GetDistanceAtEndOfLane(lane);
|
||||
Waypoint lane_end(waypoint);
|
||||
lane_end.s = final_s;
|
||||
result.push_back({waypoint, lane_end});
|
||||
});
|
||||
}
|
||||
return result;
|
||||
}
|
||||
|
||||
// ===========================================================================
|
||||
// -- Map: Private functions -------------------------------------------------
|
||||
// ===========================================================================
|
||||
|
@ -623,5 +704,13 @@ namespace road {
|
|||
return _data.GetRoad(waypoint.road_id).GetLaneById(waypoint.section_id, waypoint.lane_id);
|
||||
}
|
||||
|
||||
Junction* Map::GetJunction(JuncId id) {
|
||||
return _data.GetJunction(id);
|
||||
}
|
||||
|
||||
const Junction* Map::GetJunction(JuncId id) const {
|
||||
return _data.GetJunction(id);
|
||||
}
|
||||
|
||||
} // namespace road
|
||||
} // namespace carla
|
||||
|
|
|
@ -95,6 +95,9 @@ namespace road {
|
|||
/// Return the list of waypoints at @a distance such that a vehicle at @a
|
||||
/// waypoint could drive to.
|
||||
std::vector<Waypoint> GetNext(Waypoint waypoint, double distance) const;
|
||||
/// Return the list of waypoints at @a distance in the reversed direction
|
||||
/// that a vehicle at @a waypoint could drive to.
|
||||
std::vector<Waypoint> GetPrevious(Waypoint waypoint, double distance) const;
|
||||
|
||||
/// Return a waypoint at the lane of @a waypoint's right lane.
|
||||
boost::optional<Waypoint> GetRight(Waypoint waypoint) const;
|
||||
|
@ -112,6 +115,13 @@ namespace road {
|
|||
/// map. The waypoints are placed at the entrance of each lane.
|
||||
std::vector<std::pair<Waypoint, Waypoint>> GenerateTopology() const;
|
||||
|
||||
//Generate waypoints of the junction
|
||||
std::vector<std::pair<Waypoint, Waypoint>> GetJunctionWaypoints(JuncId id, Lane::LaneType lane_type) const;
|
||||
|
||||
Junction* GetJunction(JuncId id);
|
||||
|
||||
const Junction* GetJunction(JuncId id) const;
|
||||
|
||||
#ifdef LIBCARLA_WITH_GTEST
|
||||
MapData &GetMap() {
|
||||
return _data;
|
||||
|
@ -120,6 +130,7 @@ namespace road {
|
|||
|
||||
private:
|
||||
|
||||
friend MapBuilder;
|
||||
MapData _data;
|
||||
};
|
||||
|
||||
|
|
|
@ -63,7 +63,10 @@ namespace road {
|
|||
// _map_data is a memeber of MapBuilder so you must especify if
|
||||
// you want to keep it (will return copy -> Map(const Map &))
|
||||
// or move it (will return move -> Map(Map &&))
|
||||
return Map{std::move(_map_data)};
|
||||
Map map(std::move(_map_data));
|
||||
CreateJunctionBoundingBoxes(map);
|
||||
|
||||
return map;
|
||||
}
|
||||
|
||||
// called from profiles parser
|
||||
|
@ -691,5 +694,70 @@ namespace road {
|
|||
}
|
||||
}
|
||||
|
||||
void MapBuilder::CreateJunctionBoundingBoxes(Map &map) {
|
||||
for (auto &junctionpair : map._data.GetJunctions()) {
|
||||
auto* junction = map.GetJunction(junctionpair.first);
|
||||
auto waypoints = map.GetJunctionWaypoints(junction->GetId(), Lane::LaneType::Any);
|
||||
const int number_intervals = 10;
|
||||
|
||||
float minx = std::numeric_limits<float>::max();
|
||||
float miny = std::numeric_limits<float>::max();
|
||||
float minz = std::numeric_limits<float>::max();
|
||||
float maxx = -std::numeric_limits<float>::max();
|
||||
float maxy = -std::numeric_limits<float>::max();
|
||||
float maxz = -std::numeric_limits<float>::max();
|
||||
|
||||
auto get_min_max = [&](geom::Location position) {
|
||||
if (position.x < minx) {
|
||||
minx = position.x;
|
||||
}
|
||||
if (position.y < miny) {
|
||||
miny = position.y;
|
||||
}
|
||||
if (position.z < minz) {
|
||||
minz = position.z;
|
||||
}
|
||||
|
||||
if (position.x > maxx) {
|
||||
maxx = position.x;
|
||||
}
|
||||
if (position.y > maxy) {
|
||||
maxy = position.y;
|
||||
}
|
||||
if (position.z > maxz) {
|
||||
maxz = position.z;
|
||||
}
|
||||
};
|
||||
|
||||
for (auto &waypoint_p : waypoints) {
|
||||
auto &waypoint_start = waypoint_p.first;
|
||||
auto &waypoint_end = waypoint_p.second;
|
||||
double interval = (waypoint_end.s - waypoint_start.s) / static_cast<double>(number_intervals);
|
||||
auto next_wp = waypoint_end;
|
||||
auto location = map.ComputeTransform(next_wp).location;
|
||||
|
||||
get_min_max(location);
|
||||
|
||||
next_wp = waypoint_start;
|
||||
location = map.ComputeTransform(next_wp).location;
|
||||
|
||||
get_min_max(location);
|
||||
|
||||
for (int i = 0; i < number_intervals; ++i) {
|
||||
if (interval < std::numeric_limits<double>::epsilon())
|
||||
break;
|
||||
next_wp = map.GetNext(next_wp, interval).back();
|
||||
|
||||
location = map.ComputeTransform(next_wp).location;
|
||||
get_min_max(location);
|
||||
}
|
||||
}
|
||||
carla::geom::Location location(0.5f * (maxx + minx), 0.5f * (maxy + miny), 0.5f * (maxz + minz));
|
||||
carla::geom::Vector3D extent(0.5f * (maxx - minx), 0.5f * (maxy - miny), 0.5f * (maxz - minz));
|
||||
|
||||
junction->_bounding_box = carla::geom::BoundingBox(location, extent);
|
||||
}
|
||||
}
|
||||
|
||||
} // namespace road
|
||||
} // namespace carla
|
||||
|
|
|
@ -349,6 +349,9 @@ namespace road {
|
|||
/// Create the pointers between RoadSegments based on the ids.
|
||||
void CreatePointersBetweenRoadSegments();
|
||||
|
||||
/// Create the bounding boxes of each junction
|
||||
void CreateJunctionBoundingBoxes(Map &map);
|
||||
|
||||
/// Return the pointer to a lane object.
|
||||
Lane *GetEdgeLanePointer(RoadId road_id, bool from_start, LaneId lane_id);
|
||||
|
||||
|
|
|
@ -34,5 +34,12 @@ namespace road {
|
|||
return nullptr;
|
||||
}
|
||||
|
||||
const Junction *MapData::GetJunction(JuncId id) const {
|
||||
const auto search = _junctions.find(id);
|
||||
if (search != _junctions.end()) {
|
||||
return &search->second;
|
||||
}
|
||||
return nullptr;
|
||||
}
|
||||
} // namespace road
|
||||
} // namespace carla
|
||||
|
|
|
@ -49,6 +49,8 @@ namespace road {
|
|||
|
||||
Junction *GetJunction(JuncId id);
|
||||
|
||||
const Junction *GetJunction(JuncId id) const;
|
||||
|
||||
template <typename T>
|
||||
auto GetRoadInfo(const RoadId id, const double s) {
|
||||
return GetRoad(id).template GetInfo<T>(s);
|
||||
|
|
|
@ -6,6 +6,7 @@
|
|||
|
||||
#include <carla/FileSystem.h>
|
||||
#include <carla/PythonUtil.h>
|
||||
#include <carla/client/Junction.h>
|
||||
#include <carla/client/Map.h>
|
||||
#include <carla/client/Waypoint.h>
|
||||
#include <carla/road/element/LaneMarking.h>
|
||||
|
@ -49,6 +50,16 @@ static auto GetTopology(const carla::client::Map &self) {
|
|||
return result;
|
||||
}
|
||||
|
||||
static auto GetJunctionWaypoints(const carla::client::Junction &self, const carla::road::Lane::LaneType lane_type) {
|
||||
namespace py = boost::python;
|
||||
auto topology = self.GetWaypoints(lane_type);
|
||||
py::list result;
|
||||
for (auto &pair : topology) {
|
||||
result.append(py::make_tuple(pair.first, pair.second));
|
||||
}
|
||||
return result;
|
||||
}
|
||||
|
||||
static carla::geom::GeoLocation ToGeolocation(
|
||||
const carla::client::Map &self,
|
||||
const carla::geom::Location &location) {
|
||||
|
@ -167,8 +178,18 @@ void export_map() {
|
|||
.add_property("right_lane_marking", CALL_RETURNING_OPTIONAL(cc::Waypoint, GetRightLaneMarking))
|
||||
.add_property("left_lane_marking", CALL_RETURNING_OPTIONAL(cc::Waypoint, GetLeftLaneMarking))
|
||||
.def("next", CALL_RETURNING_LIST_1(cc::Waypoint, GetNext, double), (args("distance")))
|
||||
.def("previous", CALL_RETURNING_LIST_1(cc::Waypoint, GetPrevious, double), (args("distance")))
|
||||
.def("next_until_lane_end", CALL_RETURNING_LIST_1(cc::Waypoint, GetNextUntilLaneEnd, double), (args("distance")))
|
||||
.def("previous_until_lane_start", CALL_RETURNING_LIST_1(cc::Waypoint, GetPreviousUntilLaneStart, double), (args("distance")))
|
||||
.def("get_right_lane", &cc::Waypoint::GetRight)
|
||||
.def("get_left_lane", &cc::Waypoint::GetLeft)
|
||||
.def("get_junction", &cc::Waypoint::GetJunction, (args("lane_type")))
|
||||
.def(self_ns::str(self_ns::self))
|
||||
;
|
||||
|
||||
class_<cc::Junction, boost::noncopyable, boost::shared_ptr<cc::Junction>>("Junction", no_init)
|
||||
.add_property("id", &cc::Junction::GetId)
|
||||
.add_property("bounding_box", &cc::Junction::GetBoundingBox)
|
||||
.def("get_waypoints", &GetJunctionWaypoints)
|
||||
;
|
||||
}
|
||||
|
|
|
@ -6,30 +6,43 @@
|
|||
- class_name: LaneType
|
||||
# - DESCRIPTION ------------------------
|
||||
doc: >
|
||||
All the possible lane types accepted by OpenDRIVE. Check out this [`recipe`](../python_cookbook/#lanes-recipe)!
|
||||
Class that defines the possible lane types accepted by OpenDRIVE 1.4. This standards define the road information. For instance in this [recipe](../python_cookbook/#lanes-recipe) the user creates a carla.Waypoint for the current location of a vehicle and uses it to get the current and adjacent lane types.
|
||||
# - PROPERTIES -------------------------
|
||||
instance_variables:
|
||||
- var_name: NONE
|
||||
doc: >
|
||||
- var_name: Driving
|
||||
- var_name: Any
|
||||
doc: >
|
||||
- var_name: Stop
|
||||
doc: >
|
||||
- var_name: Shoulder
|
||||
Every type except for NONE.
|
||||
- var_name: Bidirectional
|
||||
doc: >
|
||||
- var_name: Biking
|
||||
doc: >
|
||||
- var_name: Sidewalk
|
||||
doc: >
|
||||
- var_name: Border
|
||||
doc: >
|
||||
- var_name: Restricted
|
||||
- var_name: Driving
|
||||
doc: >
|
||||
- var_name: Entry
|
||||
doc: >
|
||||
- var_name: Exit
|
||||
doc: >
|
||||
- var_name: Median
|
||||
doc: >
|
||||
- var_name: OffRamp
|
||||
doc: >
|
||||
- var_name: OnRamp
|
||||
doc: >
|
||||
- var_name: Parking
|
||||
doc: >
|
||||
- var_name: Bidirectional
|
||||
- var_name: Rail
|
||||
doc: >
|
||||
- var_name: Median
|
||||
- var_name: Restricted
|
||||
doc: >
|
||||
- var_name: RoadWorks
|
||||
doc: >
|
||||
- var_name: Shoulder
|
||||
doc: >
|
||||
- var_name: Sidewalk
|
||||
doc: >
|
||||
- var_name: Special1
|
||||
doc: >
|
||||
|
@ -37,51 +50,39 @@
|
|||
doc: >
|
||||
- var_name: Special3
|
||||
doc: >
|
||||
- var_name: RoadWorks
|
||||
- var_name: Stop
|
||||
doc: >
|
||||
- var_name: Tram
|
||||
doc: >
|
||||
- var_name: Rail
|
||||
doc: >
|
||||
- var_name: Entry
|
||||
doc: >
|
||||
- var_name: Exit
|
||||
doc: >
|
||||
- var_name: OffRamp
|
||||
doc: >
|
||||
- var_name: OnRamp
|
||||
doc: >
|
||||
- var_name: Any
|
||||
doc: >
|
||||
|
||||
- class_name: LaneChange
|
||||
# - DESCRIPTION ------------------------
|
||||
doc: >
|
||||
Class that defines the lane change options. Check out this [`recipe`](../python_cookbook/#lanes-recipe)!
|
||||
Class that defines the permission to turn either left, right, both or none (meaning only going straight is allowed). This information is stored for every carla.Waypoint according to the OpenDRIVE file. In this [recipe](../python_cookbook/#lanes-recipe) the user creates a waypoint for a current vehicle position and learns which turns are permitted.
|
||||
# - PROPERTIES -------------------------
|
||||
instance_variables:
|
||||
- var_name: NONE
|
||||
doc: >
|
||||
Traffic rules do not allow turning right or left, only going straight
|
||||
- var_name: Right
|
||||
doc: >
|
||||
Traffic rules allow turning right
|
||||
- var_name: Left
|
||||
doc: >
|
||||
Traffic rules allow turning left
|
||||
Traffic rules do not allow turning right or left, only going straight.
|
||||
- var_name: Both
|
||||
doc: >
|
||||
Traffic rules allow turning right or left
|
||||
Traffic rules allow turning either right or left.
|
||||
- var_name: Left
|
||||
doc: >
|
||||
Traffic rules allow turning left.
|
||||
- var_name: Right
|
||||
doc: >
|
||||
Traffic rules allow turning right.
|
||||
|
||||
- class_name: LaneMarkingColor
|
||||
# - DESCRIPTION ------------------------
|
||||
doc: >
|
||||
Class that defines the lane marking colors.
|
||||
Class that defines the lane marking colors according to OpenDRIVE 1.4.
|
||||
# - PROPERTIES -------------------------
|
||||
instance_variables:
|
||||
- var_name: Standard
|
||||
doc: >
|
||||
White by default
|
||||
White by default.
|
||||
- var_name: Blue
|
||||
doc: >
|
||||
- var_name: Green
|
||||
|
@ -98,90 +99,101 @@
|
|||
- class_name: LaneMarkingType
|
||||
# - DESCRIPTION ------------------------
|
||||
doc: >
|
||||
Class that defines the lane marking types accepted by OpenDRIVE. Check out this [`recipe`](../python_cookbook/#lanes-recipe)!
|
||||
Class that defines the lane marking types accepted by OpenDRIVE 1.4. Take a look at this [recipe](../python_cookbook/#lanes-recipe) where the user creates a carla.Waypoint for a vehicle location and retrieves from it the information about adjacent lane markings.
|
||||
# - PROPERTIES -------------------------
|
||||
instance_variables:
|
||||
- var_name: NONE
|
||||
doc: >
|
||||
- var_name: Other
|
||||
- var_name: BottsDots
|
||||
doc: >
|
||||
- var_name: Broken
|
||||
doc: >
|
||||
- var_name: Solid
|
||||
doc: >
|
||||
- var_name: SolidSolid
|
||||
doc: >
|
||||
For double solid line.
|
||||
- var_name: SolidBroken
|
||||
- var_name: BrokenBroken
|
||||
doc: >
|
||||
From inside to outside except for center lane which is from left to right.
|
||||
- var_name: BrokenSolid
|
||||
doc: >
|
||||
From inside to outside except for center lane which is from left to right.
|
||||
- var_name: BrokenBroken
|
||||
doc: >
|
||||
From inside to outside except for center lane which is from left to right.
|
||||
- var_name: BottsDots
|
||||
- var_name: Curb
|
||||
doc: >
|
||||
- var_name: Grass
|
||||
doc: >
|
||||
Grass edge.
|
||||
- var_name: Curb
|
||||
- var_name: Solid
|
||||
doc: >
|
||||
- var_name: SolidBroken
|
||||
doc: >
|
||||
From inside to outside except for center lane which is from left to right.
|
||||
- var_name: SolidSolid
|
||||
doc: >
|
||||
For double solid line.
|
||||
- var_name: Other
|
||||
doc: >
|
||||
|
||||
- class_name: Map
|
||||
# - DESCRIPTION ------------------------
|
||||
doc: >
|
||||
Map description that provides a Waypoint query system, that extracts
|
||||
the information from the OpenDRIVE file
|
||||
Class containing the road information and waypoint managing. Data is retrieved from an OpenDRIVE file that describes the road. A query system is defined which works hand in hand with carla.Waypoint to translate geometrical information from the .xodr to natural world points. CARLA is currently working with [OpenDRIVE 1.4 standard](http://www.opendrive.org/docs/OpenDRIVEFormatSpecRev1.4H.pdf).
|
||||
# - PROPERTIES -------------------------
|
||||
instance_variables:
|
||||
- var_name: name
|
||||
type: str
|
||||
doc: >
|
||||
Map name. Comes from the Unreal's UMap name if loaded from a Carla server
|
||||
The name of the map. It corresponds to the .umap from Unreal Engine that is loaded from a CARLA server, which then references to the .xodr road description.
|
||||
# - METHODS ----------------------------
|
||||
methods:
|
||||
- def_name: __init__
|
||||
params:
|
||||
- param_name: name
|
||||
type: str
|
||||
doc: >
|
||||
Name of the current map
|
||||
doc: >
|
||||
Name of the current map.
|
||||
- param_name: xodr_content
|
||||
type: str
|
||||
doc: >
|
||||
XODR content as string
|
||||
.xodr content in string format.
|
||||
return: list(carla.Transform)
|
||||
doc: >
|
||||
Constructor for this class useful if you want to use a `XODR` (OpenDRIVE) file without
|
||||
importing it from any Carla server running
|
||||
Constructor for this class. Though a map is automatically generated when initializing the world, using this method in no-rendering mode facilitates working with an .xodr without any CARLA server running.
|
||||
# --------------------------------------
|
||||
- def_name: generate_waypoints
|
||||
params:
|
||||
- param_name: distance
|
||||
type: float
|
||||
doc: >
|
||||
Approximate distance between waypoints.
|
||||
return: list(carla.Waypoint)
|
||||
doc: >
|
||||
Returns a list of waypoints with a certain distance between them for every lane and centered inside of it. Waypoints are not listed in any particular order. Remember that waypoints closer than 2cm within the same road, section and lane will have the same identificator.
|
||||
# --------------------------------------
|
||||
- def_name: get_spawn_points
|
||||
return: list(carla.Transform)
|
||||
doc: >
|
||||
Returns a list of transformations corresponding to the recommended spawn points over the map
|
||||
Returns a list of recommendations made by creators of the map to be used spawning points for vehicles. The list includes carla.Tranform objects with certain location and orientation. Said locations are slightly on-air and vehicles fall for a bit before starting their way.
|
||||
# --------------------------------------
|
||||
- def_name: get_topology
|
||||
doc: >
|
||||
Returns a list of tuples describing a minimal graph of the topology of the OpenDRIVE file. The tuples contain pairs of waypoints located either at the point a road begins or ends. The first one is the origin and the second one represents another road end that can be reached. This graph can be loaded into [NetworkX](https://networkx.github.io/) to work with. Output could look like this: <b>[(w0, w1), (w0, w2), (w1, w3), (w2, w3), (w0, w4)]</b>.
|
||||
return: list(tuple(carla.Waypoint, carla.Waypoint))
|
||||
# --------------------------------------
|
||||
- def_name: get_waypoint
|
||||
doc: >
|
||||
Returns a waypoint that can be located in an exact location or translated to the center of the nearest lane. Said lane type can be defined using flags such as `LaneType.Driving & LaneType.Shoulder`.
|
||||
The method will return <b>None</b> if the waypoint is not found, which may happen only when trying to retrieve a waypoint for an exact location. That eases checking if a point is inside a certain road, as otherwise, it will return the corresponding waypoint.
|
||||
params:
|
||||
- param_name: location
|
||||
type: carla.Location
|
||||
doc: >
|
||||
Location where you want to get the carla.Waypoint
|
||||
doc: >
|
||||
Location used as reference for the carla.Waypoint.
|
||||
- param_name: project_to_road
|
||||
type: bool
|
||||
default: "True"
|
||||
doc: >
|
||||
If **True**, the waypoint will be at the center of the nearest lane.
|
||||
|
||||
If **False**, the waypoint will be at the given location. Also, in this second case, the result may be
|
||||
`None` if the waypoint is not found
|
||||
doc: >
|
||||
If **True**, the waypoint will be at the center of the closest lane. This is the default setting. If **False**, the waypoint will be exactly in `location`. <b>None</b> means said location does not belong to a road.
|
||||
- param_name: lane_type
|
||||
type: carla.LaneType
|
||||
default: carla.LaneType.Driving
|
||||
doc: >
|
||||
This parameter is used to limit the search on a certain lane type.
|
||||
This can be used like a flag: `LaneType.Driving & LaneType.Shoulder`
|
||||
doc: >
|
||||
Limits the search for nearest lane to one or various lane types that can be flagged.
|
||||
return: carla.Waypoint
|
||||
# --------------------------------------
|
||||
- def_name: get_waypoint_xodr
|
||||
|
@ -190,15 +202,15 @@
|
|||
params:
|
||||
- param_name: road_id
|
||||
type: int
|
||||
doc: >
|
||||
doc: >
|
||||
Id of the road from where getting the waypoint
|
||||
- param_name: lane_id
|
||||
type: int
|
||||
doc: >
|
||||
doc: >
|
||||
Id of the lane to get the waypoint.
|
||||
- param_name: s
|
||||
type: float
|
||||
doc: >
|
||||
doc: >
|
||||
Specify the length from the road start
|
||||
return: carla.Waypoint
|
||||
# --------------------------------------
|
||||
|
@ -218,158 +230,198 @@
|
|||
Approximate distance between the waypoints
|
||||
return: list(carla.Waypoint)
|
||||
doc: >
|
||||
Returns a list of waypoints positioned on the center of the lanes
|
||||
Returns a list of waypoints positioned on the center of the lanes
|
||||
all over the map with an approximate distance between them.
|
||||
# --------------------------------------
|
||||
- def_name: transform_to_geolocation
|
||||
params:
|
||||
- param_name: path
|
||||
doc: >
|
||||
Path where the file will be saved.
|
||||
doc: >
|
||||
Saves the .xodr OpenDRIVE file of the current map to disk.
|
||||
# --------------------------------------
|
||||
- def_name: to_opendrive
|
||||
doc: >
|
||||
Returns the .xodr OpenDRIVe file of the current map as string.
|
||||
return: str
|
||||
# --------------------------------------
|
||||
- def_name: transform_to_geolocation
|
||||
params:
|
||||
- param_name: location
|
||||
type: carla.Location
|
||||
doc: >
|
||||
Location to convert
|
||||
return: carla.GeoLocation
|
||||
doc: >
|
||||
Converts a given carla.Location `(x, y, z)` to a carla.GeoLocation `(lat, lon, alt)`.
|
||||
# --------------------------------------
|
||||
- def_name: to_opendrive
|
||||
doc: >
|
||||
Returns the OpenDRIVE of the current map as string
|
||||
return: str
|
||||
# --------------------------------------
|
||||
- def_name: save_to_disk
|
||||
params:
|
||||
- param_name: path
|
||||
doc: >
|
||||
Path where it will be saved
|
||||
doc: >
|
||||
Save the OpenDRIVE of the current map to disk
|
||||
Converts a given `location`, a point in the simulation, to a carla.GeoLocation, which represents world coordinates. The geographical location of the map is defined inside OpenDRIVE within the tag <b><georeference></b>.
|
||||
# --------------------------------------
|
||||
- def_name: __str__
|
||||
doc: >
|
||||
# --------------------------------------
|
||||
|
||||
- class_name: LaneMarking
|
||||
# - DESCRIPTION ------------------------
|
||||
doc: >
|
||||
Class that defines a lane marking
|
||||
Class that gathers all the information regarding a lane marking according to [OpenDRIVE 1.4 standard](http://www.opendrive.org/docs/OpenDRIVEFormatSpecRev1.4H.pdf) standard.
|
||||
# - PROPERTIES -------------------------
|
||||
instance_variables:
|
||||
- var_name: type
|
||||
type: carla.LaneMarkingType
|
||||
doc: >
|
||||
Lane marking type
|
||||
- var_name: color
|
||||
type: carla.Color
|
||||
type: carla.LaneMarkingColor
|
||||
doc: >
|
||||
Actual color of the marking
|
||||
Actual color of the marking.
|
||||
- var_name: lane_change
|
||||
type: carla.LaneChange
|
||||
doc: >
|
||||
Lane change availability
|
||||
Permissions for said lane marking to be crossed.
|
||||
- var_name: type
|
||||
type: carla.LaneMarkingType
|
||||
doc: >
|
||||
Lane marking type.
|
||||
- var_name: width
|
||||
type: float
|
||||
doc: >
|
||||
Horizontal lane marking thickness
|
||||
Horizontal lane marking thickness.
|
||||
# --------------------------------------
|
||||
|
||||
- class_name: Waypoint
|
||||
# - DESCRIPTION ------------------------
|
||||
doc: >
|
||||
3D directed point that stores information about the road definition provided by OpenDRIVE.
|
||||
Waypoints in CARLA are described as 3D directed points. They store a certain carla.Transform which locates the waypoint in a road and orientates it according to the lane. They also store the road information belonging to said point regarding its lane and lane markings. All of this information is retrieved as provided by the OpenDRIVE file.
|
||||
# - PROPERTIES -------------------------
|
||||
instance_variables:
|
||||
- var_name: id
|
||||
type: int
|
||||
doc: >
|
||||
Waypoint id, it's generated using a hash combination of its `road_id`, `section_id`,
|
||||
`lane_id` and `s` values, all them come from the OpenDRIVE. The `s` precision is set
|
||||
to 2 centimeters, so 2 waypoints at a distance `s` less than 2 centimeters in the same
|
||||
road, section and lane, will have the same `id`.
|
||||
The identificator is generated using a hash combination of the <b>road</b>, <b>section</b>, <b>lane</b> and <b>s</b> values that correspond to said point in the OpenDRIVE geometry. The <b>s</b> precision is set to 2 centimeters, so 2 waypoints closer than 2 centimeters in the same road, section and lane, will have the same identificator.
|
||||
- var_name: transform
|
||||
type: carla.Transform
|
||||
doc: >
|
||||
Transform indicating it's position and orientation according to the current lane information.
|
||||
- var_name: is_intersection
|
||||
type: bool
|
||||
doc: >
|
||||
_Deprecated, use is_junction instead_
|
||||
- var_name: is_junction
|
||||
type: bool
|
||||
doc: >
|
||||
True if the current Waypoint is on a junction
|
||||
- var_name: lane_width
|
||||
type: float
|
||||
doc: >
|
||||
Horizontal size of the road at current `s`
|
||||
Position and orientation of the waypoint according to the current lane information. This data is computed the first time it is accessed. It is not created right away in order to ease computing costs when lots of waypoints are created but their specific transform is not needed.
|
||||
- var_name: road_id
|
||||
type: int
|
||||
doc: >
|
||||
OpenDRIVE road's id
|
||||
OpenDRIVE road's id.
|
||||
- var_name: section_id
|
||||
type: int
|
||||
doc: >
|
||||
OpenDRIVE section's id, based on the order that they are originally defined
|
||||
OpenDRIVE section's id, based on the order that they are originally defined.
|
||||
- var_name: lane_id
|
||||
type: int
|
||||
doc: >
|
||||
OpenDRIVE lane's id, this value can be positive or negative which represents the direction of the
|
||||
current lane with respect to the road. For more information refer to OpenDRIVE
|
||||
[documentation](http://www.opendrive.org/docs/OpenDRIVEFormatSpecRev1.4H.pdf#page=20)
|
||||
OpenDRIVE lane's id, this value can be positive or negative which represents the direction of the current lane with respect to the road. For more information refer to OpenDRIVE [documentation](http://www.opendrive.org/docs/OpenDRIVEFormatSpecRev1.4H.pdf#page=20)
|
||||
- var_name: s
|
||||
type: float
|
||||
doc: >
|
||||
OpenDRIVE `s` value of the current position
|
||||
OpenDRIVE <b>s</b> value of the current position.
|
||||
- var_name: is_junction
|
||||
type: bool
|
||||
doc: >
|
||||
<b>True</b> if the current Waypoint is on a junction as defined by OpenDRIVE.
|
||||
- var_name: lane_width
|
||||
type: float
|
||||
doc: >
|
||||
Horizontal size of the road at current <b>s</b>.
|
||||
- var_name: lane_change
|
||||
type: carla.LaneChange
|
||||
doc: >
|
||||
Lane change definition of the current Waypoint's location, based on the traffic rules defined in
|
||||
the OpenDRIVE file. Basically, it tells you if a lane change can be done and in which direction.
|
||||
Lane change definition of the current Waypoint's location, based on the traffic rules defined in the OpenDRIVE file. It states if a lane change can be done and in which direction.
|
||||
- var_name: lane_type
|
||||
type: carla.LaneType
|
||||
doc: >
|
||||
The lane type of the current Waypoint, based on OpenDRIVE types.
|
||||
The lane type of the current Waypoint, based on OpenDRIVE 1.4 standard.
|
||||
- var_name: right_lane_marking
|
||||
type: carla.LaneMarking
|
||||
doc: >
|
||||
The right lane marking information based on the direction of the Waypoint
|
||||
The right lane marking information based on the direction of the Waypoint.
|
||||
- var_name: left_lane_marking
|
||||
type: carla.LaneMarking
|
||||
doc: >
|
||||
The left lane marking information based on the direction of the Waypoint
|
||||
The left lane marking information based on the direction of the Waypoint.
|
||||
# - METHODS ----------------------------
|
||||
methods:
|
||||
- def_name: get_left_lane
|
||||
return: carla.Waypoint
|
||||
doc: >
|
||||
Generates a Waypoint at the center of the left lane based on the direction of the current Waypoint, regardless if the lane change is allowed in this location.
|
||||
|
||||
Can return <b>None</b> if the lane does not exist
|
||||
# --------------------------------------
|
||||
- def_name: get_right_lane
|
||||
return: carla.Waypoint
|
||||
doc: >
|
||||
Generates a waypoint at the center of the right lane based on the direction of the current waypoint, regardless if the lane change is allowed in this location.
|
||||
|
||||
Can return <b>None</b> if the lane does not exist.
|
||||
# --------------------------------------
|
||||
- def_name: next
|
||||
params:
|
||||
- param_name: distance
|
||||
type: float
|
||||
doc: >
|
||||
The approximate distance where to get the next Waypoints
|
||||
The approximate distance where to get the next waypoints.
|
||||
return: list(carla.Waypoint)
|
||||
doc: >
|
||||
Returns a list of Waypoints at a certain approximate distance from the current Waypoint,
|
||||
taking into account the shape of the road and its possible deviations, without performing
|
||||
any lane change.
|
||||
Returns a list of waypoints at a certain approximate `distance` from the current one. It takes into account the road and its possible deviations without performing any lane change and returns one waypoint per option.
|
||||
|
||||
The list may be empty if the road ends before the specified distance, for instance,
|
||||
a lane ending with the only option of incorporating to another road.
|
||||
The list may be empty if the road ends before the specified distance, for instance, a lane ending with the only option of incorporating to another road.
|
||||
# --------------------------------------
|
||||
- def_name: get_right_lane
|
||||
return: carla.Waypoint
|
||||
- def_name: next_until_lane_end
|
||||
params:
|
||||
- param_name: distance
|
||||
type: float
|
||||
doc: >
|
||||
The approximate distance between waypoints
|
||||
return: list(carla.Waypoint)
|
||||
doc: >
|
||||
Generates a Waypoint at the center of the right lane based on the direction of the current
|
||||
Waypoint, regardless if the lane change is allowed in this location.
|
||||
|
||||
Can return `None` if the lane does not exist.
|
||||
Returns a list of waypoints from this to the end of the lane separated by a certain `distance`.
|
||||
# --------------------------------------
|
||||
- def_name: get_left_lane
|
||||
return: carla.Waypoint
|
||||
- def_name: previous
|
||||
params:
|
||||
- param_name: distance
|
||||
type: float
|
||||
doc: >
|
||||
The approximate distance where to get the previous waypoints.
|
||||
return: list(carla.Waypoint)
|
||||
doc: >
|
||||
Generates a Waypoint at the center of the left lane based on the direction of the current
|
||||
Waypoint, regardless if the lane change is allowed in this location.
|
||||
This method does not return the waypoint previously visited by an actor, but a list of waypoints at an approximate `distance` but in the opposite direction of the lane. Similarly to **<font color="#7fb800">next()</font>**, it takes into account the road and its possible deviations without performing any lane change and returns one waypoint per option.
|
||||
|
||||
Can return `None` if the lane does not exist
|
||||
The list may be empty if the road ends before the specified distance, for instance, a lane ending with the only option of incorporating to another road.
|
||||
# --------------------------------------
|
||||
- def_name: previous_until_lane_start
|
||||
params:
|
||||
- param_name: distance
|
||||
type: float
|
||||
doc: >
|
||||
The approximate distance between waypoints
|
||||
return: list(carla.Waypoint)
|
||||
doc: >
|
||||
Returns a list of waypoints from this to the start of the lane separated by a certain `distance`.
|
||||
# --------------------------------------
|
||||
- def_name: __str__
|
||||
# --------------------------------------
|
||||
|
||||
- class_name: Junction
|
||||
# - DESCRIPTION ------------------------
|
||||
doc: >
|
||||
Class that embodies the intersections on the road described in the OpenDRIVE file according to OpenDRIVE 1.4 standards.
|
||||
# - PROPERTIES -------------------------
|
||||
instance_variables:
|
||||
- var_name: id
|
||||
type: int
|
||||
doc: >
|
||||
Identificator found in the OpenDRIVE file.
|
||||
- var_name: bounding_box
|
||||
type: carla.BoundingBox
|
||||
doc: >
|
||||
Bounding box encapsulating the junction lanes.
|
||||
# - METHODS ----------------------------
|
||||
methods:
|
||||
- def_name: get_waypoints
|
||||
params:
|
||||
- param_name: lane_type
|
||||
type: carla.LaneType
|
||||
doc: >
|
||||
Type of lanes to get the waypoints.
|
||||
return: list(tuple(carla.Waypoint))
|
||||
doc: >
|
||||
Returns a list of pairs of waypoints. Every tuple on the list contains first an initial and then a final waypoint within the intersection boundaries that describe the beginning and the end of said lane along the junction. Lanes follow their OpenDRIVE definitions so there may be many different tuples with the same starting waypoint due to possible deviations, as this are considered different lanes.
|
||||
# --------------------------------------
|
||||
...
|
||||
|
|
|
@ -61,6 +61,38 @@ def draw_waypoint_info(debug, w, lt=5):
|
|||
debug.draw_string(w_loc + carla.Location(z=1.0), "road: " + str(w.road_id), False, blue, lt)
|
||||
debug.draw_string(w_loc + carla.Location(z=-.5), str(w.lane_change), False, red, lt)
|
||||
|
||||
def draw_junction(debug, junction, l_time=10):
|
||||
"""Draws a junction bounding box and the initial and final waypoint of every lane."""
|
||||
# draw bounding box
|
||||
box = junction.bounding_box
|
||||
point1 = box.location + carla.Location(x=box.extent.x, y=box.extent.y, z=2)
|
||||
point2 = box.location + carla.Location(x=-box.extent.x, y=box.extent.y, z=2)
|
||||
point3 = box.location + carla.Location(x=-box.extent.x, y=-box.extent.y, z=2)
|
||||
point4 = box.location + carla.Location(x=box.extent.x, y=-box.extent.y, z=2)
|
||||
debug.draw_line(
|
||||
point1, point2,
|
||||
thickness=0.1, color=orange, life_time=l_time, persistent_lines=False)
|
||||
debug.draw_line(
|
||||
point2, point3,
|
||||
thickness=0.1, color=orange, life_time=l_time, persistent_lines=False)
|
||||
debug.draw_line(
|
||||
point3, point4,
|
||||
thickness=0.1, color=orange, life_time=l_time, persistent_lines=False)
|
||||
debug.draw_line(
|
||||
point4, point1,
|
||||
thickness=0.1, color=orange, life_time=l_time, persistent_lines=False)
|
||||
# draw junction pairs (begin-end) of every lane
|
||||
junction_w = junction.get_waypoints(carla.LaneType.Any)
|
||||
for pair_w in junction_w:
|
||||
draw_transform(debug, pair_w[0].transform, orange, l_time)
|
||||
debug.draw_point(
|
||||
pair_w[0].transform.location + carla.Location(z=0.75), 0.1, orange, l_time, False)
|
||||
draw_transform(debug, pair_w[1].transform, orange, l_time)
|
||||
debug.draw_point(
|
||||
pair_w[1].transform.location + carla.Location(z=0.75), 0.1, orange, l_time, False)
|
||||
debug.draw_line(
|
||||
pair_w[0].transform.location + carla.Location(z=0.75),
|
||||
pair_w[1].transform.location + carla.Location(z=0.75), 0.1, white, l_time, False)
|
||||
|
||||
def main():
|
||||
argparser = argparse.ArgumentParser()
|
||||
|
@ -156,6 +188,11 @@ def main():
|
|||
draw_waypoint_union(debug, current_w, p, red, trail_life_time)
|
||||
draw_transform(debug, p.transform, white, trail_life_time)
|
||||
|
||||
# draw all junction waypoints and bounding box
|
||||
if next_w.is_junction:
|
||||
junction = next_w.get_junction()
|
||||
draw_junction(debug, junction, trail_life_time)
|
||||
|
||||
# update the current waypoint and sleep for some time
|
||||
current_w = next_w
|
||||
time.sleep(args.tick_time)
|
||||
|
|
Loading…
Reference in New Issue