Attribute.h
Go to the documentation of this file.
1 // this is for emacs file handling -*- mode: c++; c-basic-offset: 2;
2 // indent-tabs-mode: nil -*-
3 
4 #pragma once
5 #include <boost/variant/variant.hpp>
6 #include <memory>
7 #include <string>
8 
12 
13 namespace lanelet {
14 namespace internal {
15 template <typename ValueT>
16 struct ValueOf {
17  using Type = std::decay_t<ValueT>;
18 };
19 template <typename ValueT>
20 struct ValueOf<Optional<ValueT>> {
21  using Type = ValueT;
22 };
23 } // namespace internal
32 class Attribute {
33  template <typename T>
35 
36  public:
37  using Cache = boost::variant<bool, double, Id, int, Velocity>;
38 
39  Attribute() = default;
40  Attribute(const std::string& value) : value_{value} {} // NOLINT
41  Attribute(std::string&& value) : value_{std::move(value)} {} // NOLINT
42  Attribute(const char* value) : value_(value) {} // NOLINT
43  Attribute(bool value); // NOLINT
44  Attribute(Id value); // NOLINT
45  Attribute(int value); // NOLINT
46  Attribute(double value); // NOLINT
47  Attribute(const Velocity& value); // NOLINT
48 
54  Optional<bool> asBool() const;
55 
60  Optional<double> asDouble() const;
61 
66  Optional<Id> asId() const;
67 
72  Optional<int> asInt() const;
73 
84  Optional<Velocity> asVelocity() const;
85 
89  template <typename T>
90  Optional<ValueOfT<T>> as() const;
91 
96  const std::string& value() const { return value_; }
97 
102  void setValue(const std::string& value);
103 
104  private:
105  std::string value_;
106  mutable std::shared_ptr<Cache> cache_;
107 };
108 
109 template <>
110 inline Optional<double> Attribute::as<double>() const {
111  return asDouble();
112 }
113 
114 template <>
115 inline Optional<double> Attribute::as<Optional<double>>() const {
116  return asDouble();
117 }
118 
119 template <>
120 inline Optional<int> Attribute::as<int>() const {
121  return asInt();
122 }
123 
124 template <>
125 inline Optional<int> Attribute::as<Optional<int>>() const {
126  return asInt();
127 }
128 
129 template <>
130 inline Optional<bool> Attribute::as<bool>() const {
131  return asBool();
132 }
133 
134 template <>
135 inline Optional<bool> Attribute::as<Optional<bool>>() const {
136  return asBool();
137 }
138 
139 template <>
140 inline Optional<Id> Attribute::as<Id>() const {
141  return asId();
142 }
143 
144 template <>
145 inline Optional<Id> Attribute::as<Optional<Id>>() const {
146  return asId();
147 }
148 
149 template <>
150 inline Optional<Velocity> Attribute::as<Velocity>() const {
151  return asVelocity();
152 }
153 
154 template <>
155 inline Optional<Velocity> Attribute::as<Optional<Velocity>>() const {
156  return asVelocity();
157 }
158 
159 template <>
160 inline Optional<std::string> Attribute::as<std::string>() const {
161  return value();
162 }
163 
164 template <>
165 inline Optional<std::string> Attribute::as<Optional<std::string>>() const {
166  return value();
167 }
168 
169 template <>
170 inline Optional<const char*> Attribute::as<const char*>() const {
171  return value().c_str();
172 }
173 
174 template <>
175 inline Optional<const char*> Attribute::as<Optional<const char*>>() const {
176  return value().c_str();
177 }
178 
179 inline bool operator==(const Attribute& lhs, const Attribute& rhs) { return lhs.value() == rhs.value(); }
180 inline bool operator!=(const Attribute& lhs, const Attribute& rhs) { return !(lhs == rhs); }
181 
185 enum class AttributeName {
186  Type,
187  Subtype,
188  OneWay,
191  SpeedLimit,
192  Location,
193  Dynamic
194 };
195 
196 using AttributeNamesItem = std::pair<const char*, const AttributeName>;
197 
204  static constexpr const char Type[] = "type";
205  static constexpr const char Subtype[] = "subtype";
206  static constexpr const char OneWay[] = "one_way";
207  static constexpr const char ParticipantVehicle[] = "participant:vehicle";
208  static constexpr const char ParticipantPedestrian[] = "participant:pedestrian";
209  static constexpr const char SpeedLimit[] = "speed_limit";
210  static constexpr const char Location[] = "location";
211  static constexpr const char Dynamic[] = "dynamic";
212  static constexpr const char Color[] = "color";
213 
214  // attributes not used in fast lookup
215  // on points
216  static constexpr const char Ele[] = "ele";
217 
218  // on linestrings
219  static constexpr const char LaneChange[] = "lane_change";
220  static constexpr const char LaneChangeLeft[] = "lane_change:left";
221  static constexpr const char LaneChangeRight[] = "lane_change:right";
222  static constexpr const char Name[] = "name";
223  static constexpr const char Region[] = "region";
224 
225  // on lanelets/areas
226  static constexpr const char SpeedLimitMandatory[] = "speed_limit_mandatory";
227  static constexpr const char Participant[] = "participant";
228  static constexpr const char Area[] = "area";
229  static constexpr const char Fallback[] = "fallback";
230  static constexpr const char Width[] = "width";
231  static constexpr const char Height[] = "height";
232  static constexpr const char Temporary[] = "temporary";
233 
234  // on regulatory elements
235  static constexpr const char SignType[] = "sign_type";
236 
237  static constexpr AttributeNamesItem Map[] = {{Type, AttributeName::Type},
238  {Subtype, AttributeName::Subtype},
239  {OneWay, AttributeName::OneWay},
240  {ParticipantVehicle, AttributeName::ParticipantVehicle},
241  {ParticipantPedestrian, AttributeName::ParticipantPedestrian},
242  {SpeedLimit, AttributeName::SpeedLimit},
243  {Location, AttributeName::Location},
244  {Dynamic, AttributeName::Dynamic}};
245 };
246 
248 struct Participants {
250  static std::string tag(const std::string& participant) {
251  return AttributeNamesString::Participant + (":" + participant);
252  }
253  static constexpr const char Vehicle[] = "vehicle";
254  static constexpr const char VehicleBus[] = "vehicle:bus";
255  static constexpr const char VehicleCar[] = "vehicle:car";
256  static constexpr const char VehicleCarElectric[] = "vehicle:car:electric";
257  static constexpr const char VehicleCarCombustion[] = "vehicle:car:combustion";
258  static constexpr const char VehicleTruck[] = "vehicle:truck";
259  static constexpr const char VehicleMotorcycle[] = "vehicle:motorcycle";
260  static constexpr const char VehicleTaxi[] = "vehicle:taxi";
261  static constexpr const char VehicleEmergency[] = "vehicle:emergency";
262  static constexpr const char Pedestrian[] = "pedestrian";
263  static constexpr const char Bicycle[] = "bicycle";
264  static constexpr const char Train[] = "train";
265 };
272  // lanelet types
273  static constexpr const char Node[] = "node";
274  static constexpr const char Way[] = "way";
275  static constexpr const char Relation[] = "relation";
276  static constexpr const char Lanelet[] = "lanelet";
277  static constexpr const char RegulatoryElement[] = "regulatory_element";
278  static constexpr const char Multipolygon[] = "multipolygon";
279 
280  // line types
281  static constexpr const char LineThick[] = "line_thick";
282  static constexpr const char LineThin[] = "line_thin";
283  static constexpr const char Curbstone[] = "curbstone";
284  static constexpr const char GuardRail[] = "guard_rail";
285  static constexpr const char RoadBorder[] = "road_border";
286  static constexpr const char Wall[] = "wall";
287  static constexpr const char Fence[] = "fence";
288  static constexpr const char Zebra[] = "zebra_marking";
289  static constexpr const char PedestrianMarking[] = "pedestrian_marking";
290  static constexpr const char BikeMarking[] = "bike_marking";
291  static constexpr const char Keepout[] = "keepout";
292  static constexpr const char StopLine[] = "stop_line";
293  static constexpr const char Virtual[] = "virtual";
294  static constexpr const char Visualization[] = "visualization";
295  static constexpr const char ZigZag[] = "zig-zag";
296  static constexpr const char LiftGate[] = "lift_gate";
297  static constexpr const char JerseyBarrier[] = "jersey_barrier";
298  static constexpr const char Gate[] = "gate";
299  static constexpr const char Door[] = "door";
300  static constexpr const char Trajectory[] = "trajectory";
301  static constexpr const char Rail[] = "rail";
302  static constexpr const char Bump[] = "bump";
303 
304  // line subtypes
305  static constexpr const char Solid[] = "solid";
306  static constexpr const char Dashed[] = "dashed";
307  static constexpr const char DashedSolid[] = "dashed_solid";
308  static constexpr const char SolidDashed[] = "solid_dashed";
309  static constexpr const char SolidSolid[] = "solid_solid";
310  static constexpr const char Straight[] = "straight";
311  static constexpr const char Left[] = "left";
312  static constexpr const char Right[] = "right";
313  static constexpr const char StraightLeft[] = "straight_left";
314  static constexpr const char StraightRight[] = "straight_right";
315  static constexpr const char LeftRight[] = "left_right";
316  static constexpr const char High[] = "high";
317  static constexpr const char Low[] = "low";
318 
319  // Node types
320  static constexpr const char Arrow[] = "arrow";
321  static constexpr const char Pole[] = "pole";
322  static constexpr const char Post[] = "post";
323  static constexpr const char Symbol[] = "symbol";
324  static constexpr const char Start[] = "start";
325  static constexpr const char End[] = "end";
326  static constexpr const char Dot[] = "dot";
327 
328  // Color / traffic light types
329  static constexpr const char RedYellowGreen[] = "red_yellow_green";
330  static constexpr const char RedGreen[] = "red_green";
331  static constexpr const char RedYellow[] = "red_yellow";
332  static constexpr const char Red[] = "red";
333  static constexpr const char Yellow[] = "yellow";
334  static constexpr const char White[] = "white";
335 
336  // Lanelet types
337  static constexpr const char Road[] = "road";
338  static constexpr const char Highway[] = "highway";
339  static constexpr const char PlayStreet[] = "play_street";
340  static constexpr const char EmergencyLane[] = "emergency_lane";
341  static constexpr const char BusLane[] = "bus_lane";
342  static constexpr const char BicycleLane[] = "bicycle_lane";
343  static constexpr const char Walkway[] = "walkway";
344  static constexpr const char SharedWalkway[] = "shared_walkway";
345  static constexpr const char Crosswalk[] = "crosswalk";
346  static constexpr const char Stairs[] = "stairs";
347 
348  // Lanelet location tag
349  static constexpr const char Nonurban[] = "nonurban";
350  static constexpr const char Urban[] = "urban";
351  static constexpr const char Private[] = "private";
352 
353  // Area types
354  static constexpr const char Parking[] = "parking";
355  static constexpr const char Freespace[] = "freespace";
356  static constexpr const char Vegetation[] = "vegetation";
357  static constexpr const char Building[] = "building";
358  static constexpr const char TrafficIsland[] = "traffic_island";
359  static constexpr const char Exit[] = "exit";
360 
361  // Regulatory elements
362  static constexpr const char TrafficLight[] = "traffic_light";
363  static constexpr const char TrafficSign[] = "traffic_sign";
364  static constexpr const char SpeedLimit[] = "speed_limit";
365  static constexpr const char RightOfWay[] = "right_of_way";
366  static constexpr const char AllWayStop[] = "all_way_stop";
367 };
368 
369 inline std::ostream& operator<<(std::ostream& stream, const Attribute& obj) { return stream << obj.value(); }
370 
372 
373 inline std::ostream& operator<<(std::ostream& stream, const AttributeMap& obj) {
374  for (const auto& o : obj) {
375  stream << o.first << ": " << o.second << " ";
376  }
377  return stream;
378 }
379 } // namespace lanelet
Attribute(std::string &&value)
Definition: Attribute.h:41
Represents a speed limit that affects a laneletA speed limit is defined by one ore more traffic signs...
boost::variant< bool, double, Id, int, Velocity > Cache
Definition: Attribute.h:37
int64_t Id
Definition: Forward.h:198
std::ostream & operator<<(std::ostream &stream, const Attribute &obj)
Definition: Attribute.h:369
const std::string & value() const
gets the value of this attribute
Definition: Attribute.h:96
Attribute(const char *value)
Definition: Attribute.h:42
The famous (mutable) lanelet class.
bool operator==(const Attribute &lhs, const Attribute &rhs)
Definition: Attribute.h:179
Defines right of way restrictions.
Represents a traffic light restriction on the lanelet.
static constexpr const char Participant[]
Definition: Attribute.h:227
std::decay_t< ValueT > Type
Definition: Attribute.h:17
boost::optional< T > Optional
Definition: Optional.h:7
Common values for attributes are defined here.
Definition: Attribute.h:271
bool operator!=(const Attribute &lhs, const Attribute &rhs)
Definition: Attribute.h:180
Lists which attribute strings are mapped to which enum value.
Definition: Attribute.h:203
Attribute(const std::string &value)
Definition: Attribute.h:40
static std::string tag(const std::string &participant)
Obtain the tag for the participant override.
Definition: Attribute.h:250
std::shared_ptr< Cache > cache_
cache for the last queried value
Definition: Attribute.h:106
parts of tag that have to be combined with either Participants:, OneWay: or SpeedLimit to generate an...
Definition: Attribute.h:248
An attribute represents one value of a tag of a lanelet primitive.
Definition: Attribute.h:32
Famous Area class that represents a basic area as element of the map.
typename internal::ValueOf< T >::Type ValueOfT
Definition: Attribute.h:34
std::string value_
internal value of this parameter
Definition: Attribute.h:105
A general rule or limitation for a lanelet (abstract base class)
Expresses a generic traffic sign rule.
std::pair< const char *, const AttributeName > AttributeNamesItem
Definition: Attribute.h:196
Defines an all way stop. These are a special form of right of way, where all lanelets have to yield...
AttributeName
Typical Attributes names within lanelet.
Definition: Attribute.h:185
units::MPSQuantity Velocity
Definition: Forward.h:210


lanelet2_core
Author(s): Fabian Poggenhans
autogenerated on Tue Jun 6 2023 02:23:32