Added MeshFactory + improved code architecture

This commit is contained in:
Marc Garcia Puig 2020-04-03 13:03:06 +02:00 committed by bernat
parent 910c8f795a
commit 832b293a33
10 changed files with 378 additions and 223 deletions

View File

@ -37,6 +37,7 @@ namespace geom {
return true;
}
// e.g:
// 1 3 5 7
// #---#---#---#
// | / | / | / |
@ -65,13 +66,12 @@ namespace geom {
}
}
// 6 5
// #---#
// | / |
// 1 #---# 4
// | \ |
// #---#
// 2 3
// e.g:
// 2 1 6
// #---#---#
// | / | \ |
// #---#---#
// 3 4 5
void Mesh::AddTriangleFan(const std::vector<Mesh::vertex_type> &vertices) {
DEBUG_ASSERT(vertices.size() >= 3);
const size_t initial_index = GetVerticesNum() + 1;

View File

@ -0,0 +1,84 @@
// 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/geom/MeshFactory.h>
#include <vector>
#include <carla/geom/Vector3D.h>
namespace carla {
namespace geom {
/// We use this epsilon to shift the waypoints away from the edges of the lane
/// sections to avoid floating point precision errors.
static constexpr double EPSILON = 10.0 * std::numeric_limits<double>::epsilon();
std::unique_ptr<Mesh> MeshFactory::Generate(const road::Road &road) const {
geom::Mesh out_mesh;
for (auto &&lane_section : road.GetLaneSections()) {
out_mesh += *Generate(lane_section);
}
return std::make_unique<Mesh>(out_mesh);
}
std::unique_ptr<Mesh> MeshFactory::Generate(const road::LaneSection &lane_section) const {
geom::Mesh out_mesh;
for (auto &&lane_pair : lane_section.GetLanes()) {
out_mesh += *Generate(lane_pair.second);
}
return std::make_unique<Mesh>(out_mesh);
}
std::unique_ptr<Mesh> MeshFactory::Generate(const road::Lane &lane) const {
RELEASE_ASSERT(road_param.resolution > 0.0);
// The lane with lane_id 0 have no physical representation in OpenDRIVE
geom::Mesh out_mesh;
if (lane.GetId() == 0) {
return std::make_unique<Mesh>(out_mesh);
}
const auto end_distance = lane.GetDistance() + lane.GetLength() - EPSILON;
double current_s = lane.GetLaneSection()->GetDistance() + EPSILON;
std::vector<geom::Vector3D> vertices;
if (lane.IsStraight()) {
// Mesh optimization: If the lane is straight just add vertices at the
// begining and at the end of it
const auto edges = lane.GetCornerPositions(current_s, road_param.extra_lane_width);
vertices.push_back(edges.first);
vertices.push_back(edges.second);
} else {
// Iterate over the lane's 's' and store the vertices based on it's width
do {
// Get the location of the edges of the current lane at the current waypoint
const auto edges = lane.GetCornerPositions(current_s, road_param.extra_lane_width);
vertices.push_back(edges.first);
vertices.push_back(edges.second);
// Update the current waypoint's "s"
current_s += road_param.resolution;
} while(current_s < end_distance);
}
// This ensures the mesh is constant and have no gaps between roads,
// adding geometry at the very end of the lane
if (end_distance - (current_s - road_param.resolution) > EPSILON) {
current_s = end_distance;
const auto edges = lane.GetCornerPositions(current_s, road_param.extra_lane_width);
vertices.push_back(edges.first);
vertices.push_back(edges.second);
}
// Add the adient material, create the strip and close the material
out_mesh.AddMaterial(
lane.GetType() == road::Lane::LaneType::Sidewalk ? "sidewalk" : "road");
out_mesh.AddTriangleStrip(vertices);
out_mesh.EndMaterial();
return std::make_unique<Mesh>(out_mesh);
}
} // namespace geom
} // namespace carla

View File

@ -0,0 +1,54 @@
// 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 <memory>
#include <carla/geom/Mesh.h>
#include <carla/road/Road.h>
#include <carla/road/LaneSection.h>
#include <carla/road/Lane.h>
namespace carla {
namespace geom {
/// Mesh helper generator static
class MeshFactory {
public:
MeshFactory() = default;
// =========================================================================
// -- Map Related ----------------------------------------------------------
// =========================================================================
/// Generates a mesh that defines a road
std::unique_ptr<Mesh> Generate(const road::Road &road) const;
/// Generates a mesh that defines a lane section
std::unique_ptr<Mesh> Generate(const road::LaneSection &lane_section) const;
/// Generates a mesh that defines a lane
std::unique_ptr<Mesh> Generate(const road::Lane &lane) const;
// =========================================================================
// -- Generation parameters ------------------------------------------------
// =========================================================================
/// Generates a mesh that defines a lane
struct RoadParameters {
float resolution = 2.0f;
float extra_lane_width = 1.0f;
float wall_height = 0.6f;
};
RoadParameters road_param;
};
} // namespace geom
} // namespace carla

View File

@ -1,16 +1,23 @@
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
// 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/Debug.h"
#include "carla/road/Lane.h"
#include "carla/road/LaneSection.h"
#include "carla/road/Road.h"
#include <limits>
#include "carla/Debug.h"
#include "carla/road/element/Geometry.h"
#include "carla/road/element/RoadInfoElevation.h"
#include "carla/road/element/RoadInfoGeometry.h"
#include "carla/road/element/RoadInfoLaneOffset.h"
#include "carla/road/element/RoadInfoLaneWidth.h"
#include "carla/road/LaneSection.h"
#include "carla/road/MapData.h"
#include "carla/road/Road.h"
namespace carla {
namespace road {
@ -47,5 +54,174 @@ namespace road {
return road->UpperBound(s) - s;
}
double Lane::GetWidth(const double s) const {
RELEASE_ASSERT(s <= GetRoad()->GetLength());
const auto width_info = GetInfo<element::RoadInfoLaneWidth>(s);
RELEASE_ASSERT(width_info != nullptr);
return width_info->GetPolynomial().Evaluate(s);
}
bool Lane::IsStraight() const {
Road *road = GetRoad();
RELEASE_ASSERT(road != nullptr);
auto *geometry = road->GetInfo<element::RoadInfoGeometry>(GetDistance());
DEBUG_ASSERT(geometry != nullptr);
auto geometry_type = geometry->GetGeometry().GetType();
if (geometry_type != element::GeometryType::LINE) {
return false;
}
if(GetDistance() < geometry->GetDistance() ||
GetDistance() + GetLength() >
geometry->GetDistance() + geometry->GetGeometry().GetLength()) {
return false;
}
auto lane_offsets = GetInfos<element::RoadInfoLaneOffset>();
for (auto *lane_offset : lane_offsets) {
if (std::abs(lane_offset->GetPolynomial().GetC()) > 0 ||
std::abs(lane_offset->GetPolynomial().GetD()) > 0) {
return false;
}
}
auto elevations = road->GetInfos<element::RoadInfoElevation>();
for (auto *elevation : elevations) {
if (std::abs(elevation->GetPolynomial().GetC()) > 0 ||
std::abs(elevation->GetPolynomial().GetD()) > 0) {
return false;
}
}
return true;
}
/// Returns a pair containing first = width, second = tangent,
/// for an specific Lane given an s and a iterator over lanes
template <typename T>
static std::pair<double, double> ComputeTotalLaneWidth(
const T container,
const double s,
const LaneId lane_id) {
// lane_id can't be 0
RELEASE_ASSERT(lane_id != 0);
const bool negative_lane_id = lane_id < 0;
double dist = 0.0;
double tangent = 0.0;
for (const auto &lane : container) {
auto info = lane.second.template GetInfo<element::RoadInfoLaneWidth>(s);
RELEASE_ASSERT(info != nullptr);
const auto current_polynomial = info->GetPolynomial();
auto current_dist = current_polynomial.Evaluate(s);
auto current_tang = current_polynomial.Tangent(s);
if (lane.first != lane_id) {
dist += negative_lane_id ? current_dist : -current_dist;
tangent += current_tang;
} else if (lane.first == lane_id) {
current_dist *= 0.5;
dist += negative_lane_id ? current_dist : -current_dist;
tangent += current_tang * 0.5;
break;
}
}
return std::make_pair(dist, tangent);
}
geom::Transform Lane::ComputeTransform(const double s) const {
const Road *road = GetRoad();
DEBUG_ASSERT(road != nullptr);
// must s be smaller (or eq) than road lenght and bigger (or eq) than 0?
RELEASE_ASSERT(s <= road->GetLength());
RELEASE_ASSERT(s >= 0.0);
const auto *lane_section = GetLaneSection();
DEBUG_ASSERT(lane_section != nullptr);
const std::map<LaneId, Lane> &lanes = lane_section->GetLanes();
// check that lane_id exists on the current s
RELEASE_ASSERT(!lanes.empty());
RELEASE_ASSERT(GetId() >= lanes.begin()->first);
RELEASE_ASSERT(GetId() <= lanes.rbegin()->first);
float lane_width = 0.0f;
float lane_tangent = 0.0f;
if (GetId() < 0) {
// right lane
const auto side_lanes = MakeListView(
std::make_reverse_iterator(lanes.lower_bound(0)), lanes.rend());
const auto computed_width =
ComputeTotalLaneWidth(side_lanes, s, GetId());
lane_width = static_cast<float>(computed_width.first);
lane_tangent = static_cast<float>(computed_width.second);
} else if (GetId() > 0) {
// left lane
const auto side_lanes = MakeListView(lanes.lower_bound(1), lanes.end());
const auto computed_width =
ComputeTotalLaneWidth(side_lanes, s, GetId());
lane_width = static_cast<float>(computed_width.first);
lane_tangent = static_cast<float>(computed_width.second);
}
// get a directed point in s and apply the computed lateral offet
element::DirectedPoint dp = road->GetDirectedPointIn(s);
// compute the tangent of the laneOffset
const auto lane_offset_info = road->GetInfo<element::RoadInfoLaneOffset>(s);
const auto lane_offset_tangent = static_cast<float>(lane_offset_info->GetPolynomial().Tangent(s));
lane_tangent -= lane_offset_tangent;
// Unreal's Y axis hack
lane_tangent *= -1;
geom::Rotation rot(
geom::Math::ToDegrees(static_cast<float>(dp.pitch)),
geom::Math::ToDegrees(-static_cast<float>(dp.tangent)), // Unreal's Y axis hack
0.0f);
dp.ApplyLateralOffset(lane_width);
if (GetId() > 0) {
rot.yaw += 180.0f + geom::Math::ToDegrees(lane_tangent);
rot.pitch = 360.0f - rot.pitch;
} else {
rot.yaw -= geom::Math::ToDegrees(lane_tangent);
}
// Unreal's Y axis hack
dp.location.y *= -1;
return geom::Transform(dp.location, rot);
}
std::pair<geom::Vector3D, geom::Vector3D> Lane::GetCornerPositions(
const double s, const float extra_width) const {
DEBUG_ASSERT(GetRoad() != nullptr);
float lane_width = static_cast<float>(GetWidth(s)) / 2.0f;
if (extra_width != 0.f && GetRoad()->IsJunction() && GetType() == Lane::LaneType::Driving) {
lane_width += extra_width;
}
lane_width = GetId() > 0 ? -lane_width : lane_width;
const geom::Transform wp_trnsf = ComputeTransform(s);
const auto wp_right_distance = wp_trnsf.GetRightVector() * lane_width;
auto loc_r = static_cast<geom::Vector3D>(wp_trnsf.location) + wp_right_distance;
auto loc_l = static_cast<geom::Vector3D>(wp_trnsf.location) - wp_right_distance;
// Apply an offset to the Sidewalks
if (GetType() == LaneType::Sidewalk) {
// RoadRunner doesn't export it right now and as a workarround where 15.24 cm
// is the exact height that match with most of the RoadRunner sidewalks
loc_r.z += 0.1524f;
loc_l.z += 0.1524f;
/// TODO: use the OpenDRIVE 5.3.7.2.1.1.9 Lane Height Record
}
return std::make_pair(loc_r, loc_l);
}
} // road
} // carla

View File

@ -1,4 +1,4 @@
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
// 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.
@ -6,6 +6,8 @@
#pragma once
#include "carla/geom/Mesh.h"
#include "carla/geom/Transform.h"
#include "carla/road/InformationSet.h"
#include "carla/road/RoadTypes.h"
@ -105,6 +107,18 @@ namespace road {
double GetLength() const;
/// Returns the total lane width given a s
double GetWidth(const double s) const;
/// Checks whether the geometry is straight or not
bool IsStraight() const;
geom::Transform ComputeTransform(const double s) const;
/// Computes the location of the edges given a s
std::pair<geom::Vector3D, geom::Vector3D> GetCornerPositions(
const double s, const float extra_width = 0.f) const;
private:
friend MapBuilder;

View File

@ -1,4 +1,4 @@
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
// 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.
@ -6,11 +6,11 @@
#pragma once
#include "carla/geom/CubicPolynomial.h"
#include "carla/NonCopyable.h"
#include "carla/road/Lane.h"
#include "carla/road/RoadElementSet.h"
#include "carla/road/RoadTypes.h"
#include "carla/geom/CubicPolynomial.h"
#include <map>
#include <vector>

View File

@ -1,4 +1,4 @@
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
// 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.
@ -7,15 +7,16 @@
#include "carla/road/Map.h"
#include "carla/Exception.h"
#include "carla/geom/Math.h"
#include "carla/geom/MeshFactory.h"
#include "carla/road/element/LaneCrossingCalculator.h"
#include "carla/road/element/RoadInfoGeometry.h"
#include "carla/road/element/RoadInfoLaneWidth.h"
#include "carla/road/element/RoadInfoMarkRecord.h"
#include "carla/road/element/RoadInfoLaneOffset.h"
#include "carla/road/element/RoadInfoCrosswalk.h"
#include "carla/road/element/RoadInfoElevation.h"
#include "carla/road/element/RoadInfoGeometry.h"
#include "carla/road/element/RoadInfoLaneOffset.h"
#include "carla/road/element/RoadInfoLaneWidth.h"
#include "carla/road/element/RoadInfoMarkRecord.h"
#include "carla/road/element/RoadInfoSignal.h"
#include "carla/geom/Math.h"
#include <stdexcept>
@ -141,39 +142,6 @@ namespace road {
}
}
/// Returns a pair containing first = width, second = tangent,
/// for an specific Lane given an s and a iterator over lanes
template <typename T>
static std::pair<double, double> ComputeTotalLaneWidth(
const T container,
const double s,
const LaneId lane_id) {
// lane_id can't be 0
RELEASE_ASSERT(lane_id != 0);
const bool negative_lane_id = lane_id < 0;
double dist = 0.0;
double tangent = 0.0;
for (const auto &lane : container) {
auto info = lane.second.template GetInfo<RoadInfoLaneWidth>(s);
RELEASE_ASSERT(info != nullptr);
const auto current_polynomial = info->GetPolynomial();
auto current_dist = current_polynomial.Evaluate(s);
auto current_tang = current_polynomial.Tangent(s);
if (lane.first != lane_id) {
dist += negative_lane_id ? current_dist : -current_dist;
tangent += current_tang;
} else if (lane.first == lane_id) {
current_dist *= 0.5;
dist += negative_lane_id ? current_dist : -current_dist;
tangent += current_tang * 0.5;
break;
}
}
return std::make_pair(dist, tangent);
}
/// Assumes road_id and section_id are valid.
static bool IsLanePresent(const MapData &data, Waypoint waypoint) {
const auto &section = data.GetRoad(waypoint.road_id).GetLaneSectionById(waypoint.section_id);
@ -294,70 +262,7 @@ namespace road {
}
geom::Transform Map::ComputeTransform(Waypoint waypoint) const {
const auto &road = _data.GetRoad(waypoint.road_id);
// must s be smaller (or eq) than road lenght and bigger (or eq) than 0?
RELEASE_ASSERT(waypoint.s <= road.GetLength());
RELEASE_ASSERT(waypoint.s >= 0.0);
const auto &lane_section = road.GetLaneSectionById(waypoint.section_id);
const std::map<LaneId, Lane> &lanes = lane_section.GetLanes();
// check that lane_id exists on the current s
RELEASE_ASSERT(!lanes.empty());
RELEASE_ASSERT(waypoint.lane_id >= lanes.begin()->first);
RELEASE_ASSERT(waypoint.lane_id <= lanes.rbegin()->first);
float lane_width = 0.0f;
float lane_tangent = 0.0f;
if (waypoint.lane_id < 0) {
// right lane
const auto side_lanes = MakeListView(
std::make_reverse_iterator(lanes.lower_bound(0)), lanes.rend());
const auto computed_width =
ComputeTotalLaneWidth(side_lanes, waypoint.s, waypoint.lane_id);
lane_width = static_cast<float>(computed_width.first);
lane_tangent = static_cast<float>(computed_width.second);
} else if (waypoint.lane_id > 0) {
// left lane
const auto side_lanes = MakeListView(lanes.lower_bound(1), lanes.end());
const auto computed_width =
ComputeTotalLaneWidth(side_lanes, waypoint.s, waypoint.lane_id);
lane_width = static_cast<float>(computed_width.first);
lane_tangent = static_cast<float>(computed_width.second);
}
// get a directed point in s and apply the computed lateral offet
DirectedPoint dp = road.GetDirectedPointIn(waypoint.s);
// compute the tangent of the laneOffset
const auto lane_offset_info = road.GetInfo<RoadInfoLaneOffset>(waypoint.s);
const auto lane_offset_tangent = static_cast<float>(lane_offset_info->GetPolynomial().Tangent(waypoint.s));
lane_tangent -= lane_offset_tangent;
// Unreal's Y axis hack
lane_tangent *= -1;
geom::Rotation rot(
geom::Math::ToDegrees(static_cast<float>(dp.pitch)),
geom::Math::ToDegrees(-static_cast<float>(dp.tangent)), // Unreal's Y axis hack
0.0f);
dp.ApplyLateralOffset(lane_width);
if (waypoint.lane_id > 0) {
rot.yaw += 180.0f + geom::Math::ToDegrees(lane_tangent);
rot.pitch = 360.0f - rot.pitch;
} else {
rot.yaw -= geom::Math::ToDegrees(lane_tangent);
}
// Unreal's Y axis hack
dp.location.y *= -1;
return geom::Transform(dp.location, rot);
return GetLane(waypoint).ComputeTransform(waypoint.s);
}
// ===========================================================================
@ -865,40 +770,8 @@ namespace road {
// -- Map: Private functions -------------------------------------------------
// ===========================================================================
// Checks whether the geometry is straight or not
bool IsLaneStraight(const Lane &lane) {
Road *road = lane.GetRoad();
auto *geometry = road->GetInfo<RoadInfoGeometry>(lane.GetDistance());
DEBUG_ASSERT(geometry != nullptr);
auto geometry_type = geometry->GetGeometry().GetType();
if (geometry_type != element::GeometryType::LINE) {
return false;
}
if(lane.GetDistance() < geometry->GetDistance() ||
lane.GetDistance() + lane.GetLength() >
geometry->GetDistance() + geometry->GetGeometry().GetLength()) {
return false;
}
auto lane_offsets = lane.GetInfos<element::RoadInfoLaneOffset>();
for (auto *lane_offset : lane_offsets) {
if (std::abs(lane_offset->GetPolynomial().GetC()) > 0 ||
std::abs(lane_offset->GetPolynomial().GetD()) > 0) {
return false;
}
}
auto elevations = road->GetInfos<element::RoadInfoElevation>();
for (auto *elevation : elevations) {
if (std::abs(elevation->GetPolynomial().GetC()) > 0 ||
std::abs(elevation->GetPolynomial().GetD()) > 0) {
return false;
}
}
return true;
}
// Adds a new element to the rtree element list using the position of the
// waypoints
// both ends of the segment
// waypoints both ends of the segment
void Map::AddElementToRtree(
std::vector<Rtree::TreeElement> &rtree_elements,
geom::Transform &current_transform,
@ -961,8 +834,8 @@ namespace road {
});
}
std::vector<Rtree::TreeElement> rtree_elements; // container of segments and
// waypoints
// Container of segments and waypoints
std::vector<Rtree::TreeElement> rtree_elements;
// Loop through all lanes
for (auto &waypoint : topology) {
auto &lane_start_waypoint = waypoint;
@ -974,7 +847,7 @@ namespace road {
geom::Transform current_transform = ComputeTransform(current_waypoint);
// Save computation time in straight lines
if (IsLaneStraight(lane)) {
if (lane.IsStraight()) {
double delta_s = min_delta_s;
double remaining_length =
GetRemainingLength(lane, current_waypoint.s);
@ -1091,60 +964,15 @@ namespace road {
geom::Mesh Map::GenerateMesh(const double distance, const float extra_width) const {
RELEASE_ASSERT(distance > 0.0);
geom::MeshFactory mesh_factory;
geom::Mesh out_mesh;
// Iterate each lane in each lane_section in each road
for (const auto &pair : _data.GetRoads()) {
mesh_factory.road_param.resolution = static_cast<float>(distance);
mesh_factory.road_param.extra_lane_width = extra_width;
for (auto &&pair : _data.GetRoads()) {
const auto &road = pair.second;
for (const auto &lane_section : road.GetLaneSections()) {
for (const auto &lane_pair : lane_section.GetLanes()) {
// Get the lane reference
const auto &lane = lane_pair.second;
// The lane with lane_id 0 have no physical representation in OpenDRIVE
if (lane.GetId() == 0) {
continue;
}
const auto end_distance = lane.GetDistance() + lane.GetLength() - EPSILON;
Waypoint current_wp {
road.GetId(),
lane_section.GetId(),
lane.GetId(),
lane_section.GetDistance() + EPSILON };
std::vector<geom::Vector3D> vertices;
if (IsLaneStraight(lane)) {
// Mesh optimization: If the lane is straight just add vertices at the
// begining and at the end of it
const auto edges = GetWaypointCornerPositions(*this, current_wp, lane, extra_width);
vertices.push_back(edges.first);
vertices.push_back(edges.second);
} else {
// Iterate over the lane's 's' and store the vertices based on it's width
do {
// Get the location of the edges of the current lane at the current waypoint
const auto edges = GetWaypointCornerPositions(*this, current_wp, lane, extra_width);
vertices.push_back(edges.first);
vertices.push_back(edges.second);
// Update the current waypoint's "s"
current_wp.s += distance;
} while(current_wp.s < end_distance);
}
// This ensures the mesh is constant and have no gaps between roads,
// adding geometry at the very end of the lane
if (end_distance - (current_wp.s - distance) > EPSILON) {
current_wp.s = end_distance;
const auto edges = GetWaypointCornerPositions(*this, current_wp, lane, extra_width);
vertices.push_back(edges.first);
vertices.push_back(edges.second);
}
// Add the adient material, create the strip and close the material
out_mesh.AddMaterial(
lane.GetType() == Lane::LaneType::Sidewalk ? "sidewalk" : "road");
out_mesh.AddTriangleStrip(vertices);
out_mesh.EndMaterial();
}
}
out_mesh += *mesh_factory.Generate(road);
}
return out_mesh;
@ -1221,7 +1049,7 @@ namespace road {
std::vector<geom::Vector3D> r_vertices;
std::vector<geom::Vector3D> l_vertices;
if (IsLaneStraight(lane)) {
if (lane.IsStraight()) {
// Mesh optimization: If the lane is straight just add vertices at the
// begining and at the end of it
const auto edges = GetWaypointCornerPositions(*this, current_wp, lane);

View File

@ -1,4 +1,4 @@
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
// 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.
@ -6,15 +6,15 @@
#pragma once
#include "carla/NonCopyable.h"
#include "carla/geom/Transform.h"
#include "carla/road/MapData.h"
#include "carla/geom/Mesh.h"
#include "carla/road/RoadTypes.h"
#include "carla/geom/Rtree.h"
#include "carla/geom/Transform.h"
#include "carla/NonCopyable.h"
#include "carla/road/element/LaneMarking.h"
#include "carla/road/element/RoadInfoMarkRecord.h"
#include "carla/road/element/Waypoint.h"
#include "carla/geom/Rtree.h"
#include "carla/road/MapData.h"
#include "carla/road/RoadTypes.h"
#include <boost/optional.hpp>

View File

@ -1,22 +1,22 @@
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
// 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/Exception.h"
#include "carla/ListView.h"
#include "carla/Logging.h"
#include "carla/geom/CubicPolynomial.h"
#include "carla/geom/Location.h"
#include "carla/geom/Math.h"
#include "carla/road/Lane.h"
#include "carla/road/MapData.h"
#include "carla/road/Road.h"
#include "carla/ListView.h"
#include "carla/Logging.h"
#include "carla/road/element/RoadInfoElevation.h"
#include "carla/road/element/RoadInfoGeometry.h"
#include "carla/road/element/RoadInfoLaneOffset.h"
#include "carla/road/element/RoadInfoLaneWidth.h"
#include "carla/road/Lane.h"
#include "carla/road/MapData.h"
#include "carla/road/Road.h"
#include <stdexcept>

View File

@ -1,4 +1,4 @@
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
// 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.
@ -6,17 +6,18 @@
#pragma once
#include "carla/geom/Mesh.h"
#include "carla/Iterator.h"
#include "carla/ListView.h"
#include "carla/NonCopyable.h"
#include "carla/road/element/Geometry.h"
#include "carla/road/element/RoadInfo.h"
#include "carla/road/InformationSet.h"
#include "carla/road/Junction.h"
#include "carla/road/LaneSection.h"
#include "carla/road/LaneSectionMap.h"
#include "carla/road/RoadElementSet.h"
#include "carla/road/RoadTypes.h"
#include "carla/road/element/Geometry.h"
#include "carla/road/element/RoadInfo.h"
#include <unordered_map>
#include <vector>
@ -162,8 +163,6 @@ namespace road {
return _lane_sections.GetById(id);
}
/// Return the upper bound "s", i.e., the end distance of the lane section
/// at @a s (clamped at road's length).
double UpperBound(double s) const {