Updating and adding new lane record classes. Updating map builder to create instances of these classes for the parser
This commit is contained in:
parent
cab00065d2
commit
5f82b80b2a
|
@ -5,8 +5,22 @@
|
|||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#include "carla/road/MapBuilder.h"
|
||||
#include "carla/road/element/RoadElevationInfo.h"
|
||||
#include "carla/road/element/RoadInfoLaneAccess.h"
|
||||
#include "carla/road/element/RoadInfoLaneBorder.h"
|
||||
#include "carla/road/element/RoadInfoLaneHeight.h"
|
||||
#include "carla/road/element/RoadInfoLaneMaterial.h"
|
||||
#include "carla/road/element/RoadInfoLaneOffset.h"
|
||||
#include "carla/road/element/RoadInfoLaneRule.h"
|
||||
#include "carla/road/element/RoadInfoLaneVisibility.h"
|
||||
#include "carla/road/element/RoadInfoLaneWidth.h"
|
||||
#include "carla/road/element/RoadInfoMarkRecord.h"
|
||||
#include "carla/road/element/RoadInfoMarkTypeLine.h"
|
||||
#include "carla/road/element/RoadInfoVelocity.h"
|
||||
#include "carla/road/element/RoadInfoVisitor.h"
|
||||
|
||||
#include <iterator>
|
||||
#include <memory>
|
||||
|
||||
using namespace carla::road::element;
|
||||
|
||||
|
@ -25,6 +39,171 @@ namespace road {
|
|||
return Map{std::move(_map_data)};
|
||||
}
|
||||
|
||||
// called from profiles parser
|
||||
void AddRoadElevationProfile(
|
||||
const int32_t /*road_id*/,
|
||||
const double s,
|
||||
const double a,
|
||||
const double b,
|
||||
const double c,
|
||||
const double d) {
|
||||
auto elevation = std::unique_ptr<RoadElevationInfo>(new RoadElevationInfo(s, a, b, c, d));
|
||||
}
|
||||
|
||||
// called from lane parser
|
||||
void MapBuilder::CreateLaneAccess(
|
||||
const int32_t /*road_id*/,
|
||||
const int32_t /*lane_section_id*/,
|
||||
const int32_t /*lane_id*/,
|
||||
const float s,
|
||||
const std::string restriction) {
|
||||
auto access = std::unique_ptr<RoadInfoLaneAccess>(new RoadInfoLaneAccess(s, restriction));
|
||||
}
|
||||
|
||||
void MapBuilder::CreateLaneBorder(
|
||||
const int32_t /*road_id*/,
|
||||
const int32_t /*lane_section_id*/,
|
||||
const int32_t /*lane_id*/,
|
||||
const float s,
|
||||
const float a,
|
||||
const float b,
|
||||
const float c,
|
||||
const float d) {
|
||||
auto border = std::unique_ptr<RoadInfoLaneBorder>(new RoadInfoLaneBorder(s, a, b, c, d));
|
||||
}
|
||||
|
||||
void MapBuilder::CreateLaneHeight(
|
||||
const int32_t /*road_id*/,
|
||||
const int32_t /*lane_section_id*/,
|
||||
const int32_t /*lane_id*/,
|
||||
const float s,
|
||||
const float inner,
|
||||
const float outer) {
|
||||
auto height = std::unique_ptr<RoadInfoLaneHeight>(new RoadInfoLaneHeight(s, inner, outer));
|
||||
}
|
||||
|
||||
void MapBuilder::CreateLaneMaterial(
|
||||
const int32_t /*road_id*/,
|
||||
const int32_t /*lane_section_id*/,
|
||||
const int32_t /*lane_id*/,
|
||||
const float s,
|
||||
const std::string surface,
|
||||
const float friction,
|
||||
const float roughness) {
|
||||
auto material =
|
||||
std::unique_ptr<RoadInfoLaneMaterial>(new RoadInfoLaneMaterial(s, surface, friction, roughness));
|
||||
}
|
||||
|
||||
void MapBuilder::CreateLaneOffset(
|
||||
const int32_t /*road_id*/,
|
||||
const int32_t /*lane_section_id*/,
|
||||
const int32_t /*lane_id*/,
|
||||
const float s,
|
||||
const float a,
|
||||
const float b,
|
||||
const float c,
|
||||
const float d) {
|
||||
auto offset = std::unique_ptr<RoadInfoLaneOffset>(new RoadInfoLaneOffset(s, a, b, c, d));
|
||||
}
|
||||
|
||||
void MapBuilder::CreateLaneRule(
|
||||
const int32_t /*road_id*/,
|
||||
const int32_t /*lane_section_id*/,
|
||||
const int32_t /*lane_id*/,
|
||||
const float s,
|
||||
const std::string value) {
|
||||
auto rule = std::unique_ptr<RoadInfoLaneRule>(new RoadInfoLaneRule(s, value));
|
||||
}
|
||||
|
||||
void MapBuilder::CreateLaneVisibility(
|
||||
const int32_t /*road_id*/,
|
||||
const int32_t /*lane_section_id*/,
|
||||
const int32_t /*lane_id*/,
|
||||
const float s,
|
||||
const float forward,
|
||||
const float back,
|
||||
const float left,
|
||||
const float right) {
|
||||
auto visibility =
|
||||
std::unique_ptr<RoadInfoLaneVisibility>(new RoadInfoLaneVisibility(s, forward, back, left, right));
|
||||
}
|
||||
|
||||
void MapBuilder::CreateLaneWidth(
|
||||
const int32_t /*road_id*/,
|
||||
const int32_t /*lane_section_id*/,
|
||||
const int32_t /*lane_id*/,
|
||||
const float s,
|
||||
const float a,
|
||||
const float b,
|
||||
const float c,
|
||||
const float d) {
|
||||
auto width = std::unique_ptr<RoadInfoLaneWidth>(new RoadInfoLaneWidth(s, a, b, c, d));
|
||||
}
|
||||
|
||||
void MapBuilder::CreateRoadMark(
|
||||
const int32_t /*road_id*/,
|
||||
const int32_t /*lane_section_id*/,
|
||||
const int32_t /*lane_id*/,
|
||||
const int road_mark_id,
|
||||
const float s,
|
||||
const std::string type,
|
||||
const std::string weight,
|
||||
const std::string color,
|
||||
const std::string material,
|
||||
const float width,
|
||||
const std::string lane_change,
|
||||
const float height,
|
||||
const std::string type_name,
|
||||
const float type_width) {
|
||||
RoadInfoMarkRecord::LaneChange lc;
|
||||
|
||||
// to lower case.
|
||||
auto tl = [](auto) -> std::string { throw_exception(std::runtime_error("not implemented")); };
|
||||
|
||||
if (tl(lane_change) == "increase") {
|
||||
lc = RoadInfoMarkRecord::LaneChange::Increase;
|
||||
} else if (tl(lane_change) == "decrease") {
|
||||
lc = RoadInfoMarkRecord::LaneChange::Decrease;
|
||||
} else if (tl(lane_change) == "both") {
|
||||
lc = RoadInfoMarkRecord::LaneChange::Both;
|
||||
} else {
|
||||
lc = RoadInfoMarkRecord::LaneChange::None;
|
||||
}
|
||||
auto mark =
|
||||
std::unique_ptr<RoadInfoMarkRecord>(new RoadInfoMarkRecord(s, road_mark_id, type, weight, color,
|
||||
material, width, lc, height, type_name, type_width));
|
||||
}
|
||||
|
||||
void MapBuilder::CreateRoadMarkTypeLine(
|
||||
const int32_t /*road_id*/,
|
||||
const int32_t /*lane_section_id*/,
|
||||
const int32_t /*lane_id*/,
|
||||
const int road_mark_id,
|
||||
const float length,
|
||||
const float space,
|
||||
const float tOffset,
|
||||
const float s,
|
||||
const std::string rule,
|
||||
const float width) {
|
||||
auto line =
|
||||
std::unique_ptr<RoadInfoMarkTypeLine>(new RoadInfoMarkTypeLine(s, road_mark_id, length, space,
|
||||
tOffset, rule, width));
|
||||
// Find the parent road mark record using the ids provided and then add this
|
||||
// line to its lise of lines
|
||||
// road_mark.GetLines().push_back(std::move(line);
|
||||
|
||||
}
|
||||
|
||||
void MapBuilder::CreateLaneSpeed(
|
||||
const int32_t /*road_id*/,
|
||||
const int /*lane_section_id*/,
|
||||
const int32_t /*lane_id*/,
|
||||
const float s,
|
||||
const float max,
|
||||
const std::string /*unit*/) {
|
||||
auto speed = std::unique_ptr<RoadInfoVelocity>(new RoadInfoVelocity(s, max));
|
||||
}
|
||||
|
||||
void MapBuilder::AddSignal(
|
||||
const uint32_t road_id,
|
||||
const uint32_t signal_id,
|
||||
|
@ -46,13 +225,19 @@ namespace road {
|
|||
const float pitch,
|
||||
const float roll) {
|
||||
|
||||
_map_data.GetRoad(road_id)->getSignals().emplace(signal_id, signal::Signal(road_id, signal_id, s, t, name, dynamic,
|
||||
_map_data.GetRoad(road_id)->getSignals().emplace(signal_id,
|
||||
signal::Signal(road_id, signal_id, s, t, name, dynamic,
|
||||
orientation, zOffset, country, type, subtype, value, unit, height, width,
|
||||
text, hOffset, pitch, roll));
|
||||
}
|
||||
|
||||
void MapBuilder::AddValidityToLastAddedSignal(uint32_t road_id, uint32_t signal_id, int32_t from_lane, int32_t to_lane) {
|
||||
_map_data.GetRoad(road_id)->GetSignal(signal_id).AddValidity(general::Validity(signal_id, from_lane, to_lane));
|
||||
void MapBuilder::AddValidityToLastAddedSignal(
|
||||
uint32_t road_id,
|
||||
uint32_t signal_id,
|
||||
int32_t from_lane,
|
||||
int32_t to_lane) {
|
||||
_map_data.GetRoad(road_id)->GetSignal(signal_id).AddValidity(general::Validity(signal_id, from_lane,
|
||||
to_lane));
|
||||
}
|
||||
|
||||
// build road objects
|
||||
|
@ -98,7 +283,6 @@ namespace road {
|
|||
sec->_lane_offset = cubic;
|
||||
}
|
||||
|
||||
|
||||
void MapBuilder::AddRoadSectionLane(
|
||||
const uint32_t road_id,
|
||||
const uint32_t section_index,
|
||||
|
@ -132,7 +316,8 @@ namespace road {
|
|||
lane->_lane_section = section;
|
||||
lane->_level = lane_level;
|
||||
lane->_type = lane_type;
|
||||
// we save id as pointers temporally, later will be processed in the right way
|
||||
// we save id as pointers temporally, later will be processed in the right
|
||||
// way
|
||||
lane->_next_lanes.emplace_back(reinterpret_cast<Lane *>(successor));
|
||||
lane->_prev_lanes.emplace_back(reinterpret_cast<Lane *>(predecessor));
|
||||
}
|
||||
|
|
|
@ -16,7 +16,6 @@ namespace carla {
|
|||
namespace road {
|
||||
|
||||
class MapBuilder {
|
||||
|
||||
public:
|
||||
|
||||
boost::optional<Map> Build();
|
||||
|
@ -164,7 +163,11 @@ namespace road {
|
|||
const float pitch,
|
||||
const float roll);
|
||||
|
||||
void AddValidityToLastAddedSignal(uint32_t road_id, uint32_t signal_id, int32_t from_lane, int32_t to_lane);
|
||||
void AddValidityToLastAddedSignal(
|
||||
uint32_t road_id,
|
||||
uint32_t signal_id,
|
||||
int32_t from_lane,
|
||||
int32_t to_lane);
|
||||
|
||||
// called from junction parser
|
||||
void AddJunction(const int32_t id, const std::string name);
|
||||
|
@ -181,6 +184,24 @@ namespace road {
|
|||
const int32_t from,
|
||||
const int32_t to);
|
||||
|
||||
void AddRoadSection(
|
||||
const uint32_t road_id,
|
||||
const uint32_t section_index,
|
||||
const double s,
|
||||
const double a,
|
||||
const double b,
|
||||
const double c,
|
||||
const double d);
|
||||
|
||||
void SetRoadLaneLink(
|
||||
const uint32_t road_id,
|
||||
const int32_t section_index,
|
||||
const int32_t lane_id,
|
||||
const std::string lane_type,
|
||||
const bool lane_level,
|
||||
const int32_t predecessor,
|
||||
const int32_t successor);
|
||||
|
||||
// called from lane parser
|
||||
void CreateLaneAccess(
|
||||
const int32_t road_id,
|
||||
|
|
|
@ -0,0 +1,46 @@
|
|||
// Copyright (c) 2017 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/road/element/RoadInfo.h"
|
||||
#include <string>
|
||||
|
||||
namespace carla {
|
||||
namespace road {
|
||||
namespace element {
|
||||
|
||||
// This record defines access restrictions for certain types of road users. The record can be used to
|
||||
// complement restrictions resulting from signs or signals in order to control the traffic flow in a scenario.
|
||||
// Each entry is valid in direction of the increasing s co-ordinate until a new entry is defined. If multiple
|
||||
// entries are defined, they must be listed in increasing order.
|
||||
class RoadInfoLaneAccess : public RoadInfo {
|
||||
|
||||
public:
|
||||
|
||||
void AcceptVisitor(RoadInfoVisitor &v) override final {
|
||||
v.Visit(*this);
|
||||
}
|
||||
|
||||
RoadInfoLaneAccess(
|
||||
float s, // start position relative to the position of the preceding lane section
|
||||
std::string restriction)
|
||||
: RoadInfo(s),
|
||||
_restriction(restriction) {}
|
||||
|
||||
std::string GetRestriction() const {
|
||||
return _restriction;
|
||||
}
|
||||
|
||||
private:
|
||||
|
||||
std::string _restriction; // Examples: Simulator, Autonomous Traffic, Pedestrian and None
|
||||
|
||||
};
|
||||
|
||||
} // namespace element
|
||||
} // namespace road
|
||||
} // namespace carla
|
|
@ -0,0 +1,54 @@
|
|||
// Copyright (c) 2017 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/road/element/RoadInfo.h"
|
||||
#include "carla/geom/CubicPolynomial.h"
|
||||
|
||||
namespace carla {
|
||||
namespace road {
|
||||
namespace element {
|
||||
|
||||
// Instead of describing lanes by their width entries and, thus, invariably
|
||||
// depending on influences of inner
|
||||
// lanes on outer lanes, it might be more convenient to just describe the
|
||||
// outer border of each lane
|
||||
// independent of any inner lanes’ parameters. Especially in cases where road
|
||||
// data is derived from
|
||||
// measurements, this type of definition will provide a more convenient method
|
||||
// without the need to
|
||||
// tesselate road sections into too many parts. Note. Lane borders and widths
|
||||
// are mutually exclusive.
|
||||
class RoadInfoLaneBorder : public RoadInfo {
|
||||
public:
|
||||
|
||||
void AcceptVisitor(RoadInfoVisitor &v) final {
|
||||
v.Visit(*this);
|
||||
}
|
||||
|
||||
RoadInfoLaneBorder(
|
||||
float s,
|
||||
float a,
|
||||
float b,
|
||||
float c,
|
||||
float d)
|
||||
: RoadInfo(s),
|
||||
_border(a, b, c, d, s) {}
|
||||
|
||||
const geom::CubicPolynomial &GetPolynomial() const {
|
||||
return _border;
|
||||
}
|
||||
|
||||
private:
|
||||
|
||||
geom::CubicPolynomial _border;
|
||||
|
||||
};
|
||||
|
||||
} // namespace element
|
||||
} // namespace road
|
||||
} // namespace carla
|
|
@ -0,0 +1,53 @@
|
|||
// Copyright (c) 2017 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/road/element/RoadInfo.h"
|
||||
#include "carla/geom/CubicPolynomial.h"
|
||||
|
||||
namespace carla {
|
||||
namespace road {
|
||||
namespace element {
|
||||
|
||||
// The surface of a lane may be offset from the plane defined by the reference line and the
|
||||
// corresponding elevation and crossfall entries (e.g. pedestrian walkways are typically a few centimeters
|
||||
// above road level). The height record provides a simplified method to describe this offset by setting an
|
||||
// inner and outer offset from road level at discrete positions along the lane profile.
|
||||
class RoadInfoLaneHeight : public RoadInfo {
|
||||
public:
|
||||
|
||||
void AcceptVisitor(RoadInfoVisitor &v) final {
|
||||
v.Visit(*this);
|
||||
}
|
||||
|
||||
RoadInfoLaneHeight(
|
||||
float s, // start position relative to the position of the preceding lane section
|
||||
float inner,
|
||||
float outer)
|
||||
: RoadInfo(s),
|
||||
_inner(inner),
|
||||
_outer(outer) {}
|
||||
|
||||
float GetInner() const {
|
||||
return _inner;
|
||||
}
|
||||
|
||||
float GetOuter() const {
|
||||
return _outer;
|
||||
}
|
||||
|
||||
private:
|
||||
|
||||
float _inner; // inner offset from road level
|
||||
|
||||
float _outer; // outer offset from road level
|
||||
|
||||
};
|
||||
|
||||
} // namespace element
|
||||
} // namespace road
|
||||
} // namespace carla
|
|
@ -0,0 +1,58 @@
|
|||
// Copyright (c) 2017 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/road/element/RoadInfo.h"
|
||||
#include <string>
|
||||
|
||||
namespace carla {
|
||||
namespace road {
|
||||
namespace element {
|
||||
|
||||
class RoadInfoLaneMaterial : public RoadInfo {
|
||||
|
||||
public:
|
||||
|
||||
void AcceptVisitor(RoadInfoVisitor &v) override final {
|
||||
v.Visit(*this);
|
||||
}
|
||||
|
||||
RoadInfoLaneMaterial(
|
||||
float s, // start position relative to the position of the preceding
|
||||
// lane section
|
||||
std::string surface,
|
||||
float friction,
|
||||
float roughness)
|
||||
: RoadInfo(s),
|
||||
_surface(surface),
|
||||
_friction(friction),
|
||||
_roughness(roughness) {}
|
||||
|
||||
const std::string& GetSurface() const {
|
||||
return _surface;
|
||||
}
|
||||
|
||||
float GetFriction() const {
|
||||
return _friction;
|
||||
}
|
||||
|
||||
float GetRoughness() const {
|
||||
return _roughness;
|
||||
}
|
||||
|
||||
private:
|
||||
|
||||
std::string _surface;
|
||||
|
||||
float _friction;
|
||||
|
||||
float _roughness;
|
||||
};
|
||||
|
||||
} // namespace element
|
||||
} // namespace road
|
||||
} // namespace carla
|
|
@ -27,11 +27,11 @@ namespace element {
|
|||
}
|
||||
|
||||
RoadInfoLaneOffset(
|
||||
double s,
|
||||
double a,
|
||||
double b,
|
||||
double c,
|
||||
double d)
|
||||
float s,
|
||||
float a,
|
||||
float b,
|
||||
float c,
|
||||
float d)
|
||||
: RoadInfo(s),
|
||||
_offset(a, b, c, d, s) {}
|
||||
|
||||
|
|
|
@ -0,0 +1,44 @@
|
|||
// Copyright (c) 2017 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/road/element/RoadInfo.h"
|
||||
#include <string>
|
||||
|
||||
namespace carla {
|
||||
namespace road {
|
||||
namespace element {
|
||||
|
||||
// This record defines rules that can be applied to lanes to describe additonal properties
|
||||
// not covered by the other attributes.
|
||||
class RoadInfoLaneRule : public RoadInfo {
|
||||
|
||||
public:
|
||||
|
||||
void AcceptVisitor(RoadInfoVisitor &v) override final {
|
||||
v.Visit(*this);
|
||||
}
|
||||
|
||||
RoadInfoLaneRule(
|
||||
float s, // start position relative to the position of the preceding lane section
|
||||
std::string value)
|
||||
: RoadInfo(s),
|
||||
_value(value) {}
|
||||
|
||||
std::string GetValue() const {
|
||||
return _value;
|
||||
}
|
||||
|
||||
private:
|
||||
|
||||
std::string _value; // Recommended values: No Stopping At Any Time, Disabled Parking and Car Pool
|
||||
|
||||
};
|
||||
|
||||
} // namespace element
|
||||
} // namespace road
|
||||
} // namespace carla
|
|
@ -0,0 +1,73 @@
|
|||
// Copyright (c) 2017 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/road/element/RoadInfo.h"
|
||||
|
||||
namespace carla {
|
||||
namespace road {
|
||||
namespace element {
|
||||
|
||||
// Each lane within a road cross section may be provided with several entries
|
||||
// defining the visibility in four
|
||||
// directions relative to the lane’s direction. Each entry is valid until a
|
||||
// new entry is defined. If multiple
|
||||
// entries are defined, they must be listed in increasing order.
|
||||
//
|
||||
// For left lanes (positive ID), the forward direction is oriented opposite to
|
||||
// the track’s direction, for right
|
||||
// lanes, the forward direction and the track’s direction are identical.
|
||||
class RoadInfoLaneVisibility : public RoadInfo {
|
||||
public:
|
||||
|
||||
void AcceptVisitor(RoadInfoVisitor &v) final {
|
||||
v.Visit(*this);
|
||||
}
|
||||
|
||||
RoadInfoLaneVisibility(
|
||||
float s, // start position relative to the position of the preceding
|
||||
// lane section
|
||||
float forward,
|
||||
float back,
|
||||
float left,
|
||||
float right)
|
||||
: RoadInfo(s),
|
||||
_forward(forward),
|
||||
_back(back),
|
||||
_left(left),
|
||||
_right(right) {}
|
||||
|
||||
float GetForward() const {
|
||||
return _forward;
|
||||
}
|
||||
|
||||
float GetBack() const {
|
||||
return _back;
|
||||
}
|
||||
|
||||
float GetLeft() const {
|
||||
return _left;
|
||||
}
|
||||
|
||||
float GetRight() const {
|
||||
return _right;
|
||||
}
|
||||
|
||||
private:
|
||||
|
||||
float _forward;
|
||||
|
||||
float _back;
|
||||
|
||||
float _left;
|
||||
|
||||
float _right;
|
||||
};
|
||||
|
||||
} // namespace element
|
||||
} // namespace road
|
||||
} // namespace carla
|
|
@ -7,8 +7,10 @@
|
|||
#pragma once
|
||||
|
||||
#include "carla/road/element/RoadInfo.h"
|
||||
|
||||
#include "carla/road/element/RoadInfoMarkTypeLine.h"
|
||||
#include <string>
|
||||
#include <vector>
|
||||
#include <memory>
|
||||
|
||||
namespace carla {
|
||||
namespace road {
|
||||
|
@ -34,33 +36,48 @@ namespace element {
|
|||
Both = 0x03 //11
|
||||
};
|
||||
|
||||
RoadInfoMarkRecord(float d)
|
||||
: RoadInfo(d),
|
||||
RoadInfoMarkRecord(
|
||||
float s,
|
||||
int road_mark_id)
|
||||
: RoadInfo(s),
|
||||
_road_mark_id(road_mark_id),
|
||||
_type(""),
|
||||
_weight(""),
|
||||
_color("white"),
|
||||
_material("standard"),
|
||||
_width(0.15),
|
||||
_lane_change(LaneChange::None),
|
||||
_height(0.0) {}
|
||||
_height(0.0),
|
||||
_type_name(""),
|
||||
_type_width(0.0) {}
|
||||
|
||||
RoadInfoMarkRecord(
|
||||
float d,
|
||||
float s,
|
||||
int road_mark_id,
|
||||
std::string type,
|
||||
std::string weight,
|
||||
std::string color,
|
||||
std::string material,
|
||||
float width,
|
||||
LaneChange lane_change,
|
||||
float height)
|
||||
: RoadInfo(d),
|
||||
float height,
|
||||
std::string type_name,
|
||||
float type_width)
|
||||
: RoadInfo(s),
|
||||
_road_mark_id(road_mark_id),
|
||||
_type(type),
|
||||
_weight(weight),
|
||||
_color(color),
|
||||
_material(material),
|
||||
_width(width),
|
||||
_lane_change(lane_change),
|
||||
_height(height) {}
|
||||
_height(height),
|
||||
_type_name(type_name),
|
||||
_type_width(type_width) {}
|
||||
|
||||
int GetRoadMarkId() const {
|
||||
return _road_mark_id;
|
||||
}
|
||||
|
||||
const std::string &GetType() const {
|
||||
return _type;
|
||||
|
@ -90,12 +107,21 @@ namespace element {
|
|||
return _height;
|
||||
}
|
||||
|
||||
float GetLaneId() const {
|
||||
return _height;
|
||||
const std::string &GetTypeName() const {
|
||||
return _type_name;
|
||||
}
|
||||
|
||||
float GetTypeWidth() const {
|
||||
return _type_width;
|
||||
}
|
||||
|
||||
std::vector<std::unique_ptr<RoadInfoMarkTypeLine>> &GetLines() {
|
||||
return _lines;
|
||||
}
|
||||
|
||||
private:
|
||||
|
||||
int _road_mark_id; // Unique identifer for the road mark
|
||||
std::string _type; // Type of the road mark
|
||||
std::string _weight; // Weight of the road mark
|
||||
std::string _color; // Color of the road mark
|
||||
|
@ -109,6 +135,12 @@ namespace element {
|
|||
// valid.
|
||||
float _height; // Physical distance of top edge of road mark from
|
||||
// reference plane of the lane
|
||||
|
||||
std::string _type_name; // Name of the road mark type if it has one
|
||||
|
||||
float _type_width; // Width of the road mark type if it has one
|
||||
|
||||
std::vector<std::unique_ptr<RoadInfoMarkTypeLine>> _lines;
|
||||
};
|
||||
|
||||
} // namespace element
|
||||
|
|
|
@ -0,0 +1,82 @@
|
|||
// Copyright (c) 2017 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/road/element/RoadInfo.h"
|
||||
#include <string>
|
||||
|
||||
namespace carla {
|
||||
namespace road {
|
||||
namespace element {
|
||||
|
||||
class RoadInfoMarkTypeLine : public RoadInfo {
|
||||
|
||||
public:
|
||||
|
||||
void AcceptVisitor(RoadInfoVisitor &v) override final {
|
||||
v.Visit(*this);
|
||||
}
|
||||
|
||||
RoadInfoMarkTypeLine(
|
||||
float s,
|
||||
int road_mark_id,
|
||||
float length,
|
||||
float space,
|
||||
float tOffset,
|
||||
std::string rule,
|
||||
float width)
|
||||
: RoadInfo(s),
|
||||
_road_mark_id(road_mark_id),
|
||||
_length(length),
|
||||
_space(space),
|
||||
_tOffset(tOffset),
|
||||
_rule(rule),
|
||||
_width(width) {}
|
||||
|
||||
int GetRoadMarkId() const {
|
||||
return _road_mark_id;
|
||||
}
|
||||
|
||||
float GetLength() const {
|
||||
return _length;
|
||||
}
|
||||
|
||||
float GetSpace() const {
|
||||
return _space;
|
||||
}
|
||||
|
||||
float GetTOffset() const {
|
||||
return _tOffset;
|
||||
}
|
||||
|
||||
const std::string& GetRule() const {
|
||||
return _rule;
|
||||
}
|
||||
|
||||
float GetWidth() const {
|
||||
return _width;
|
||||
}
|
||||
|
||||
private:
|
||||
|
||||
int _road_mark_id;
|
||||
|
||||
float _length;
|
||||
|
||||
float _space;
|
||||
|
||||
float _tOffset;
|
||||
|
||||
std::string _rule;
|
||||
|
||||
float _width;
|
||||
|
||||
};
|
||||
|
||||
} // namespace element
|
||||
} // namespace road
|
||||
} // namespace carla
|
|
@ -20,18 +20,18 @@ namespace element {
|
|||
v.Visit(*this);
|
||||
}
|
||||
|
||||
RoadInfoVelocity(double vel) : velocity(vel) {}
|
||||
RoadInfoVelocity(double d, double vel)
|
||||
: RoadInfo(d),
|
||||
RoadInfoVelocity(float vel) : velocity(vel) {}
|
||||
RoadInfoVelocity(float s, float vel)
|
||||
: RoadInfo(s),
|
||||
velocity(vel) {}
|
||||
|
||||
double GetVelocity() {
|
||||
float GetVelocity() {
|
||||
return velocity;
|
||||
}
|
||||
|
||||
private:
|
||||
|
||||
double velocity;
|
||||
float velocity;
|
||||
};
|
||||
|
||||
} // namespace element
|
||||
|
|
|
@ -13,31 +13,39 @@ namespace carla {
|
|||
namespace road {
|
||||
namespace element {
|
||||
|
||||
class RoadElevationInfo;
|
||||
class RoadGeneralInfo;
|
||||
class RoadInfo;
|
||||
class RoadInfoLane;
|
||||
class RoadGeneralInfo;
|
||||
class RoadInfoVelocity;
|
||||
class RoadElevationInfo;
|
||||
class RoadInfoLaneAccess;
|
||||
class RoadInfoLaneBorder;
|
||||
class RoadInfoLaneHeight;
|
||||
class RoadInfoLaneMaterial;
|
||||
class RoadInfoLaneOffset;
|
||||
class RoadInfoLaneRule;
|
||||
class RoadInfoLaneVisibility;
|
||||
class RoadInfoLaneWidth;
|
||||
class RoadInfoMarkRecord;
|
||||
class RoadInfoLaneOffset;
|
||||
class RoadInfoMarkTypeLine;
|
||||
class RoadInfoVelocity;
|
||||
|
||||
class RoadInfoVisitor {
|
||||
public:
|
||||
|
||||
virtual void Visit(RoadInfoLane &) {}
|
||||
|
||||
virtual void Visit(RoadGeneralInfo &) {}
|
||||
|
||||
virtual void Visit(RoadInfoVelocity &) {}
|
||||
|
||||
virtual void Visit(RoadElevationInfo &) {}
|
||||
|
||||
virtual void Visit(RoadInfoLaneWidth &) {}
|
||||
|
||||
virtual void Visit(RoadInfoMarkRecord &) {}
|
||||
|
||||
virtual void Visit(RoadGeneralInfo &) {}
|
||||
virtual void Visit(RoadInfoLane &) {}
|
||||
virtual void Visit(RoadInfoLaneAccess &) {}
|
||||
virtual void Visit(RoadInfoLaneBorder &) {}
|
||||
virtual void Visit(RoadInfoLaneHeight &) {}
|
||||
virtual void Visit(RoadInfoLaneMaterial &) {}
|
||||
virtual void Visit(RoadInfoLaneOffset &) {}
|
||||
virtual void Visit(RoadInfoLaneRule &) {}
|
||||
virtual void Visit(RoadInfoLaneVisibility &) {}
|
||||
virtual void Visit(RoadInfoLaneWidth &) {}
|
||||
virtual void Visit(RoadInfoMarkRecord &) {}
|
||||
virtual void Visit(RoadInfoMarkTypeLine &) {}
|
||||
virtual void Visit(RoadInfoVelocity &) {}
|
||||
};
|
||||
|
||||
template <typename T, typename IT>
|
||||
|
|
Loading…
Reference in New Issue