3 #include <boost/lexical_cast.hpp> 4 #include <boost/variant/get.hpp> 12 Optional<Velocity> getUnit(
const std::string& value,
size_t pos) {
13 using namespace units::literals;
14 if (pos >= value.size()) {
17 auto unit = value.substr(pos);
18 const auto flags = std::regex::ECMAScript;
20 if (std::regex_search(unit, std::regex(
"\\s*(m/s)|(mps)", flags))) {
23 if (std::regex_search(unit, std::regex(
"\\s*(km/h)|(kmh)", flags))) {
26 if (std::regex_search(unit, std::regex(
"\\s*(m/h)|(mph)", flags))) {
33 T store(std::shared_ptr<Attribute::Cache>& cache, T&& value) {
34 auto newCache = std::make_shared<Attribute::Cache>(value);
35 std::atomic_store_explicit(&cache, newCache, std::memory_order_release);
40 T* load(
const std::shared_ptr<Attribute::Cache>& cache) {
41 auto c = std::atomic_load_explicit(&cache, std::memory_order_acquire);
45 return boost::get<T>(&*cache);
63 auto* val = load<bool>(
cache_);
69 return boost::lexical_cast<
bool>(
value());
70 }
catch (boost::bad_lexical_cast&) {
72 return store(
cache_,
true);
75 return store(
cache_,
false);
83 auto* val = load<double>(
cache_);
89 return store(
cache_, boost::lexical_cast<double>(
value()));
90 }
catch (boost::bad_lexical_cast&) {
97 auto* val = load<Id>(
cache_);
103 return store(
cache_, boost::lexical_cast<Id>(
value()));
104 }
catch (boost::bad_lexical_cast&) {
111 auto* val = load<int>(
cache_);
112 if (val !=
nullptr) {
117 return store(
cache_, boost::lexical_cast<int>(
value()));
118 }
catch (boost::bad_lexical_cast&) {
125 auto* val = load<Velocity>(
cache_);
126 if (val !=
nullptr) {
138 const auto velocity = std::stod(
value(), &idx);
139 auto unit = getUnit(
value(), idx);
141 return store(
cache_, velocity * *unit);
143 }
catch (std::exception&) {
150 std::atomic_store_explicit(&
cache_, std::shared_ptr<Cache>(), std::memory_order_release);
154 #if __cplusplus < 201703L static constexpr const char PedestrianMarking[]
static constexpr AttributeNamesItem Map[]
static constexpr const char SpeedLimitMandatory[]
static constexpr const char End[]
static constexpr const char RedYellowGreen[]
static constexpr const char RedGreen[]
static constexpr const char Stairs[]
static constexpr const char ParticipantVehicle[]
Optional< bool > asBool() const
interpret this attribute as bool value
static constexpr const char ZigZag[]
static constexpr const char Symbol[]
static constexpr const char Gate[]
static constexpr const char Fallback[]
static constexpr const char Road[]
static constexpr const char Nonurban[]
static constexpr const char Vehicle[]
static constexpr const char Location[]
static constexpr const char Region[]
static constexpr const char LineThick[]
static constexpr const char Area[]
static constexpr const char Arrow[]
static constexpr const char Curbstone[]
static constexpr const char Trajectory[]
static constexpr const char BikeMarking[]
static constexpr const char Height[]
static constexpr const char Low[]
static constexpr const char LaneChangeLeft[]
static constexpr const char Lanelet[]
static constexpr const char LineThin[]
static constexpr const char BusLane[]
static constexpr const char GuardRail[]
static constexpr const char RedYellow[]
boost::units::divide_typeof_helper< Km, Hour >::type KmH
const std::string & value() const
gets the value of this attribute
static constexpr const char Walkway[]
static constexpr const char SolidSolid[]
static constexpr const char StraightRight[]
static constexpr const char Relation[]
static constexpr const char Multipolygon[]
static constexpr const char VehicleCar[]
static constexpr const char Pole[]
static constexpr const char Dot[]
static constexpr const char SpeedLimit[]
static constexpr const char BicycleLane[]
static constexpr const char Highway[]
static constexpr const char Start[]
static constexpr const char Red[]
static constexpr const char LeftRight[]
static constexpr const char StopLine[]
static constexpr const char Freespace[]
static constexpr const char Train[]
static constexpr const char Participant[]
static constexpr const char Fence[]
static constexpr const char RegulatoryElement[]
static constexpr const char Node[]
static constexpr const char Pedestrian[]
static constexpr const char Solid[]
static constexpr const char VehicleMotorcycle[]
static constexpr const char Right[]
static constexpr const char SharedWalkway[]
static constexpr const char TrafficLight[]
static constexpr const char Bump[]
static constexpr const char White[]
static constexpr const char Type[]
boost::optional< T > Optional
static constexpr const char PlayStreet[]
void setValue(const std::string &value)
set the value of this attribute
Optional< Velocity > asVelocity() const
interpret this attribute as Velocity
static constexpr const char Bicycle[]
static constexpr const char ParticipantPedestrian[]
static constexpr const char StraightLeft[]
static constexpr const char Private[]
static constexpr const char Left[]
static constexpr const char Post[]
static constexpr const char VehicleTruck[]
static constexpr const char RoadBorder[]
static constexpr const char VehicleCarElectric[]
static constexpr const char Width[]
static constexpr const char TrafficIsland[]
static constexpr const char TrafficSign[]
std::shared_ptr< Cache > cache_
cache for the last queried value
static constexpr const char Building[]
static constexpr const char Door[]
static constexpr const char Rail[]
static constexpr const char EmergencyLane[]
static constexpr const char Urban[]
static constexpr const char JerseyBarrier[]
static constexpr const char Parking[]
static constexpr const char Exit[]
static constexpr const char Straight[]
static constexpr const char VehicleTaxi[]
static constexpr const char Keepout[]
static constexpr const char High[]
std::string value_
internal value of this parameter
static constexpr const char Visualization[]
static constexpr const char Crosswalk[]
static constexpr const char Ele[]
static constexpr const char Subtype[]
static constexpr const char Name[]
static constexpr const char Virtual[]
static constexpr const char Wall[]
static constexpr const char LiftGate[]
static constexpr const char OneWay[]
static constexpr const char Temporary[]
static constexpr const char AllWayStop[]
static constexpr const char SolidDashed[]
boost::units::quantity< KmH > KmHQuantity
static constexpr const char Dashed[]
static constexpr const char VehicleBus[]
Optional< double > asDouble() const
interpret this attribute as double value
static constexpr const char DashedSolid[]
std::pair< const char *, const AttributeName > AttributeNamesItem
static constexpr const char LaneChange[]
static constexpr const char Zebra[]
static constexpr const char SpeedLimit[]
Optional< Id > asId() const
interpret this attribute as an id
static constexpr const char SignType[]
static constexpr const char Color[]
static constexpr const char Vegetation[]
static constexpr const char Way[]
static constexpr const char VehicleCarCombustion[]
static constexpr const char VehicleEmergency[]
static constexpr const char LaneChangeRight[]
static constexpr const char Dynamic[]
static constexpr const char RightOfWay[]
units::MPSQuantity Velocity
Optional< int > asInt() const
interpret this attribute as an int
static constexpr const char Yellow[]