Go to the documentation of this file.
3 #include <lanelet2_core/primitives/Lanelet.h>
38 lanelet.addRegulatoryElement(trafficLightRegelem);
39 assert(
lanelet.regulatoryElements().size() == 1);
46 std::vector<TrafficLight::Ptr> trafficLightRegelems =
lanelet.regulatoryElementsAs<
TrafficLight>();
47 assert(trafficLightRegelems.size() == 1);
49 assert(tlRegelem->constData() == trafficLightRegelem->constData());
54 assert(theLight == trafficLight);
58 assert(!!tlRegelem->stopLine());
79 assert(!pts.empty() && pts.front() == point);
92 static constexpr
char RuleName[] =
"lights_on";
111 #if __cplusplus < 201703L
135 lanelet.addRegulatoryElement(regelem);
std::shared_ptr< RegulatoryElement > RegulatoryElementPtr
RuleParameterMap & parameters()
std::pair< iterator, bool > insert(const value_type &v)
std::shared_ptr< RegulatoryElementData > RegulatoryElementDataPtr
AttributeMap & attributes() noexcept
static constexpr const char TrafficLight[]
static constexpr char RuleName[]
ConstRuleParameterMap getParameters() const
std::shared_ptr< TrafficLight > Ptr
void part3AddingNewRegulatoryElements()
void part2HandlingRegulatoryElements()
std::vector< Point3d > Points3d
void addParameter(const std::string &role, const PrimitiveT &primitive)
LineString3d getLineStringAtY(double y)
lanelet::ConstLineString3d fromWhere() const
const ConstPointType & front() const noexcept
static constexpr const char RefLine[]
LightsOn(lanelet::Id id, lanelet::LineString3d fromWhere)
RegulatoryElementDataPtr data()
static RegulatoryElementPtr create(const std::string &ruleName, Id id, const RuleParameterMap &map, const AttributeMap &attributes=AttributeMap())
LineString3d getLineStringAtX(double x)
void part1BasicRegulatoryElements()
LightsOn(const lanelet::RegulatoryElementDataPtr &data)
static Ptr make(Id id, const AttributeMap &attributes, const LineStringsOrPolygons3d &trafficLights, const Optional< LineString3d > &stopLine={})
lanelet2_examples
Author(s): Fabian Poggenhans
autogenerated on Thu Mar 6 2025 03:26:15