Vanetza
 
Loading...
Searching...
No Matches
router.cpp
1#include <vanetza/btp/data_indication.hpp>
2#include <vanetza/btp/data_request.hpp>
3#include <vanetza/common/its_aid.hpp>
4#include <vanetza/common/position_fix.hpp>
5#include <vanetza/common/runtime.hpp>
6#include <vanetza/dcc/data_request.hpp>
7#include <vanetza/dcc/interface.hpp>
8#include <vanetza/dcc/profile.hpp>
9#include <vanetza/net/mac_address.hpp>
10#include <vanetza/net/osi_layer.hpp>
11#include <vanetza/units/frequency.hpp>
12#include <vanetza/units/length.hpp>
13#include <vanetza/units/time.hpp>
14#include <vanetza/geonet/router.hpp>
15#include <vanetza/geonet/cbf_counter.hpp>
16#include <vanetza/geonet/data_confirm.hpp>
17#include <vanetza/geonet/dcc_field_generator.hpp>
18#include <vanetza/geonet/duplicate_packet_list.hpp>
19#include <vanetza/geonet/indication_context.hpp>
20#include <vanetza/geonet/loctex_g5.hpp>
21#include <vanetza/geonet/next_hop.hpp>
22#include <vanetza/geonet/pdu_conversion.hpp>
23#include <vanetza/geonet/repetition_dispatcher.hpp>
24#include <vanetza/geonet/transport_interface.hpp>
25#include <vanetza/geonet/extended_pdu.hpp>
26#include <vanetza/geonet/secured_pdu.hpp>
27#include <boost/units/cmath.hpp>
28#include <functional>
29#include <stdexcept>
30#include <tuple>
31#include <type_traits>
32
33namespace vanetza
34{
35namespace geonet
36{
37namespace
38{
39
40struct ControlInfo
41{
42 ControlInfo(const DataRequest request) :
43 communication_profile(request.communication_profile),
44 its_aid(request.its_aid) {}
45
46 const CommunicationProfile communication_profile;
47 const ItsAid its_aid;
48};
49
50template<typename PDU>
51class PendingPacketBufferData : public packet_buffer::Data
52{
53public:
54 PendingPacketBufferData(PendingPacket<PDU>&& packet) : m_packet(std::move(packet)) {}
55
56 std::size_t length() const override
57 {
58 return m_packet.length();
59 }
60
61 Clock::duration reduce_lifetime(Clock::duration d) override
62 {
63 return m_packet.reduce_lifetime(d);
64 }
65
66 void flush() override
67 {
68 m_packet.process();
69 }
70
71protected:
72 PendingPacket<PDU> m_packet;
73};
74
75dcc::RequestInterface* get_default_request_interface()
76{
77 static dcc::NullRequestInterface null;
78 return &null;
79}
80
81DccFieldGenerator* get_default_dcc_field_generator()
82{
83 static NullDccFieldGenerator null;
84 return &null;
85}
86
87template<typename PDU>
88auto create_forwarding_duplicate(const PDU& pdu, const UpPacket& packet) ->
89std::tuple<std::unique_ptr<ExtendedPdu<typename PDU::ExtendedHeader>>, std::unique_ptr<DownPacket>>
90{
91 using pdu_type = ExtendedPdu<typename PDU::ExtendedHeader>;
92 std::unique_ptr<pdu_type> pdu_dup { new pdu_type { pdu }};
93 std::unique_ptr<DownPacket> packet_dup;
94 if (pdu.secured()) {
95 packet_dup.reset(new DownPacket());
96 } else {
97 packet_dup = duplicate(packet);
98 }
99 return std::make_tuple(std::move(pdu_dup), std::move(packet_dup));
100}
101
102template<typename PDU>
103PDU& get_pdu(const std::tuple<std::unique_ptr<PDU>, std::unique_ptr<DownPacket>>& packet)
104{
105 PDU* pdu = std::get<0>(packet).get();
106 assert(pdu);
107 return *pdu;
108}
109
110std::unique_ptr<CbfCounter> create_cbf_counter(Runtime& rt, const MIB& mib)
111{
112 std::unique_ptr<CbfCounter> counter;
113 if (mib.vanetzaFadingCbfCounter) {
114 counter.reset(new CbfCounterFading(rt, units::clock_cast(mib.vanetzaFadingCbfCounterLifetime)));
115 } else {
116 counter.reset(new CbfCounterContending());
117 }
118 assert(counter);
119 return counter;
120}
121
122} // namespace
123
124using units::clock_cast;
125using PendingPacketGbc = PendingPacket<GbcPdu>;
126
127const access::EtherType ether_type = access::ethertype::GeoNetworking;
128
129Router::Router(Runtime& rt, const MIB& mib) :
130 m_mib(mib),
131 m_runtime(rt),
132 m_request_interface(get_default_request_interface()),
133 m_dcc_field_generator(get_default_dcc_field_generator()),
134 m_security_entity(nullptr),
135 m_location_table(mib, m_runtime),
136 m_bc_forward_buffer(mib.itsGnBcForwardingPacketBufferSize * 1024),
137 m_uc_forward_buffer(mib.itsGnUcForwardingPacketBufferSize * 1024),
138 m_cbf_buffer(m_runtime,
139 [](PendingPacketGbc&& packet) { packet.process(); },
140 create_cbf_counter(rt, mib),
141 mib.itsGnCbfPacketBufferSize * 1024),
142 m_local_sequence_number(0),
143 m_repeater(m_runtime,
144 std::bind(&Router::dispatch_repetition, this, std::placeholders::_1, std::placeholders::_2)),
145 m_random_gen(mib.vanetzaDefaultSeed)
146{
147 if (!m_mib.vanetzaDisableBeaconing) {
148 if (!m_mib.vanetzaDeferInitialBeacon) {
149 // send Beacon immediately after start-up at next runtime trigger invocation
150 reset_beacon_timer(Clock::duration::zero());
151 } else {
152 // defer initial Beacon transmission slightly
153 std::uniform_real_distribution<double> dist(0.0, 1.0);
154 const auto first_beacon = dist(m_random_gen) * m_mib.itsGnBeaconServiceRetransmitTimer;
155 reset_beacon_timer(clock_cast(first_beacon));
156 }
157 }
158
159 m_gbc_memory.capacity(m_mib.vanetzaGbcMemoryCapacity);
160}
161
162Router::~Router()
163{
164 m_runtime.cancel(this);
165}
166
167void Router::update_position(const PositionFix& position_fix)
168{
169 // EN 302 636-4-1 v1.3.1 is a little bit fuzzy regarding the time stamp:
170 // "Expresses the time (...) at which the latitude and longitude (...) were acquired by the GeoAdhoc router."
171 // My reading: use the current time stamp (now) when update_position is called (not the position fix time stamp)
172 m_local_position_vector.timestamp = m_runtime.now();
173 m_local_position_vector.latitude = static_cast<geo_angle_i32t>(position_fix.latitude);
174 m_local_position_vector.longitude = static_cast<geo_angle_i32t>(position_fix.longitude);
175 if (m_mib.itsGnIsMobile) {
176 m_local_position_vector.speed = static_cast<LongPositionVector::speed_u15t>(position_fix.speed.value());
177 m_local_position_vector.heading = static_cast<heading_u16t>(position_fix.course.value() - units::TrueNorth::from_value(0.0));
178 } else {
179 m_local_position_vector.speed = static_cast<LongPositionVector::speed_u15t>(0);
180 m_local_position_vector.heading = static_cast<heading_u16t>(0);
181 }
182 // see field 5 (PAI) in table 2 (long position vector)
183 m_local_position_vector.position_accuracy_indicator =
184 position_fix.confidence.semi_major * 2.0 < m_mib.itsGnPaiInterval;
185}
186
187void Router::set_transport_handler(UpperProtocol proto, TransportInterface* ifc)
188{
189 m_transport_ifcs[proto] = ifc;
190}
191
192void Router::set_security_entity(security::SecurityEntity* entity)
193{
194 m_security_entity = entity;
195}
196
197void Router::set_access_interface(dcc::RequestInterface* ifc)
198{
199 m_request_interface = (ifc == nullptr ? get_default_request_interface() : ifc);
200 assert(m_request_interface != nullptr);
201}
202
203void Router::set_dcc_field_generator(DccFieldGenerator* dcc)
204{
205 m_dcc_field_generator = (dcc == nullptr) ? get_default_dcc_field_generator() : dcc;
206 assert(m_dcc_field_generator != nullptr);
207}
208
209void Router::set_address(const Address& addr)
210{
211 m_local_position_vector.gn_addr = addr;
212}
213
214void Router::set_random_seed(std::uint_fast32_t seed)
215{
216 m_random_gen.seed(seed);
217}
218
219DataConfirm Router::request(const ShbDataRequest& request, DownPacketPtr payload)
220{
221 DataConfirm result;
222 result ^= validate_data_request(request, m_mib);
223 result ^= validate_payload(payload, m_mib);
224
225 if (result.accepted()) {
227
228 // step 4: set up packet repetition (NOTE 4 on page 57 requires re-execution of source operations)
229 if (request.repetition) {
230 // plaintext payload needs to get passed
231 m_repeater.add(request, *payload);
232 }
233
234 // step 1: create PDU
235 auto pdu = create_shb_pdu(request);
236 pdu->common().payload = payload->size();
237
238 ControlInfo ctrl(request);
239 auto transmit = [this, ctrl](PendingPacket::Packet&& packet) {
240 std::unique_ptr<ShbPdu> pdu;
241 std::unique_ptr<DownPacket> payload;
242 std::tie(pdu, payload) = std::move(packet);
243
244 // update SO PV before actual transmission
245 pdu->extended().source_position = m_local_position_vector;
246
247 // step 2: encapsulate packet by security
248 if (m_mib.itsGnSecurity) {
249 payload = encap_packet(ctrl.its_aid, *pdu, std::move(payload));
250 }
251
252 // step 5: execute media-dependent procedures
253 execute_media_procedures(ctrl.communication_profile);
254
255 // step 6: pass packet down to link layer with broadcast destination
256 pass_down(cBroadcastMacAddress, std::move(pdu), std::move(payload));
257
258 // step 7: reset beacon timer
259 reset_beacon_timer();
260 };
261
262 PendingPacket packet(std::make_tuple(std::move(pdu), std::move(payload)), transmit);
263
264 // step 3: store & carry forwarding
265 if (request.traffic_class.store_carry_forward() && !m_location_table.has_neighbours()) {
266 PacketBuffer::data_ptr data { new PendingPacketBufferData<ShbPdu>(std::move(packet)) };
267 m_bc_forward_buffer.push(std::move(data), m_runtime.now());
268 } else {
269 // tranmsit immediately
270 packet.process();
271 }
272 }
273
274 return result;
275}
276
277DataConfirm Router::request(const GbcDataRequest& request, DownPacketPtr payload)
278{
279 DataConfirm result;
280 result ^= validate_data_request(request, m_mib);
281 result ^= validate_payload(payload, m_mib);
282
283 if (!result.accepted())
284 return result;
285
286 // step 6: set up packet repetition
287 // packet repetition is done first because of "NOTE 2" on page 60:
288 // "For every retransmission, the source operations need to be re-executed".
289 // Hence, all routing decisions and security encapsulation have to be performed again.
290 // Assumption: "omit execution of further steps" does not cancel the repetition procedure.
291 if (request.repetition) {
292 m_repeater.add(request, *payload);
293 }
294
296 using Packet = PendingPacket::Packet;
297
298 // step 1: create PDU and set header fields
299 auto pdu = create_gbc_pdu(request);
300 pdu->common().payload = payload->size();
301
302 ControlInfo ctrl(request);
303 auto transmit = [this, ctrl](Packet&& packet, const MacAddress& mac) {
304 std::unique_ptr<GbcPdu> pdu;
305 std::unique_ptr<DownPacket> payload;
306 std::tie(pdu, payload) = std::move(packet);
307
308 // update SO PV before actual transmission
309 pdu->extended().source_position = m_local_position_vector;
310
311 // step 5: apply security
312 if (m_mib.itsGnSecurity) {
313 assert(pdu->basic().next_header == NextHeaderBasic::Secured);
314 payload = encap_packet(ctrl.its_aid, *pdu, std::move(payload));
315 }
316
317 // step 6: repetition is already set-up before
318
319 // step 7: execute media-dependent procedures
320 execute_media_procedures(ctrl.communication_profile);
321
322 // step 8: pass PDU to link layer
323 pass_down(mac, std::move(pdu), std::move(payload));
324 };
325
326 auto forwarding = [this, transmit](Packet&& packet) {
327 // step 3: forwarding algorithm selection procedure
328 NextHop nh = forwarding_algorithm_selection(PendingPacketForwarding(std::move(packet), transmit), nullptr);
329
330 // step 4: omit execution of further steps when packet if buffered or discarded
331 std::move(nh).process();
332 };
333
334 PendingPacket packet(std::make_tuple(std::move(pdu), std::move(payload)), forwarding);
335
336 // step 2: check if neighbours are present
337 const bool scf = request.traffic_class.store_carry_forward();
338 if (scf && !m_location_table.has_neighbours()) {
339 PacketBuffer::data_ptr data { new PendingPacketBufferData<GbcPdu>(std::move(packet)) };
340 m_bc_forward_buffer.push(std::move(data), m_runtime.now());
341 } else {
342 packet.process();
343 }
344
345 return result;
346}
347
348DataConfirm Router::request(const GacDataRequest&, DownPacketPtr)
349{
350 return DataConfirm(DataConfirm::ResultCode::Rejected_Unspecified);
351}
352
353DataConfirm Router::request(const GucDataRequest&, DownPacketPtr)
354{
355 return DataConfirm(DataConfirm::ResultCode::Rejected_Unspecified);
356}
357
358DataConfirm Router::request(const TsbDataRequest&, DownPacketPtr)
359{
360 return DataConfirm(DataConfirm::ResultCode::Rejected_Unspecified);
361}
362
363void Router::indicate(UpPacketPtr packet, const MacAddress& sender, const MacAddress& destination)
364{
365 assert(packet);
366
367 struct indication_visitor : public boost::static_visitor<>
368 {
369 indication_visitor(Router& router, const IndicationContext::LinkLayer& link_layer, UpPacketPtr packet) :
370 m_router(router), m_link_layer(link_layer), m_packet(std::move(packet))
371 {
372 }
373
374 void operator()(CohesivePacket& packet)
375 {
376 IndicationContextDeserialize ctx(std::move(m_packet), packet, m_link_layer);
377 m_router.indicate_basic(ctx);
378 }
379
380 void operator()(ChunkPacket& packet)
381 {
382 IndicationContextCast ctx(std::move(m_packet), packet, m_link_layer);
383 m_router.indicate_basic(ctx);
384 }
385
386 Router& m_router;
387 const IndicationContext::LinkLayer& m_link_layer;
388 UpPacketPtr m_packet;
389 };
390
392 link_layer.sender = sender;
393 link_layer.destination = destination;
394
395 UpPacket* packet_ptr = packet.get();
396 indication_visitor visitor(*this, link_layer, std::move(packet));
397 boost::apply_visitor(visitor, *packet_ptr);
398}
399
400void Router::indicate_basic(IndicationContextBasic& ctx)
401{
402 const BasicHeader* basic = ctx.parse_basic();
403 if (!basic) {
404 packet_dropped(PacketDropReason::Parse_Basic_Header);
405 } else if (basic->version.raw() != m_mib.itsGnProtocolVersion) {
406 packet_dropped(PacketDropReason::ITS_Protocol_Version);
407 } else {
408 DataIndication& indication = ctx.service_primitive();
409 indication.remaining_packet_lifetime = basic->lifetime;
410 indication.remaining_hop_limit = basic->hop_limit;
411
412 if (basic->next_header == NextHeaderBasic::Secured) {
413 indication.security_report = security::DecapReport::Incompatible_Protocol;
414 indicate_secured(ctx, *basic);
415 } else if (basic->next_header == NextHeaderBasic::Common) {
416 if (!m_mib.itsGnSecurity || SecurityDecapHandling::Non_Strict == m_mib.itsGnSnDecapResultHandling) {
417 indication.security_report = security::DecapReport::Unsigned_Message,
418 indicate_common(ctx, *basic);
419 } else {
420 packet_dropped(PacketDropReason::Decap_Unsuccessful_Strict);
421 }
422 }
423 }
424}
425
426void Router::indicate_common(IndicationContext& ctx, const BasicHeader& basic)
427{
428 const CommonHeader* common = ctx.parse_common();
429 if (!common) {
430 packet_dropped(PacketDropReason::Parse_Common_Header);
431 } else if (common->maximum_hop_limit < basic.hop_limit) {
432 // step 1) check the MHL field
433 packet_dropped(PacketDropReason::Hop_Limit);
434 } else {
435 DataIndication& indication = ctx.service_primitive();
436 indication.traffic_class = common->traffic_class;
437 switch (common->next_header)
438 {
439 case NextHeaderCommon::BTP_A:
440 indication.upper_protocol = UpperProtocol::BTP_A;
441 break;
442 case NextHeaderCommon::BTP_B:
443 indication.upper_protocol = UpperProtocol::BTP_B;
444 break;
445 case NextHeaderCommon::IPv6:
446 indication.upper_protocol = UpperProtocol::IPv6;
447 break;
448 default:
449 indication.upper_protocol = UpperProtocol::Unknown;
450 break;
451 }
452
453 // clean up location table at packet indication (nothing else creates entries)
454 m_location_table.drop_expired();
455
456 // step 2) process BC forwarding packet buffer
457 flush_broadcast_forwarding_buffer();
458
459 // step 3) execute steps depending on extended header type
460 indicate_extended(ctx, *common);
461
462 // NOTE: There is a good chance that processing of extended header updated the location table.
463 // Thus, a routing decision may be possible for some packets in the BC packet forwarding buffer now, e.g.
464 // those buffered due to greedy forwarding's SCF behaviour. However, flushing twice would induce additional
465 // processing overhead. For now, we stick quite conservatively to the standard.
466 }
467}
468
469void Router::indicate_secured(IndicationContextBasic& ctx, const BasicHeader& basic)
470{
471 struct secured_payload_visitor : public boost::static_visitor<>
472 {
473 secured_payload_visitor(Router& router, IndicationContextBasic& ctx, const BasicHeader& basic) :
474 m_router(router), m_context(ctx), m_basic(basic)
475 {
476 }
477
478 void operator()(ChunkPacket& packet)
479 {
480 IndicationContextSecuredCast ctx(m_context, packet);
481 m_router.indicate_common(ctx, m_basic);
482 }
483
484 void operator()(CohesivePacket& packet)
485 {
486 IndicationContextSecuredDeserialize ctx(m_context, packet);
487 m_router.indicate_common(ctx, m_basic);
488 }
489
490 Router& m_router;
491 IndicationContextBasic& m_context;
492 const BasicHeader& m_basic;
493 };
494
495 auto secured_message = ctx.parse_secured();
496 if (!secured_message) {
497 packet_dropped(PacketDropReason::Parse_Secured_Header);
498 } else if (m_security_entity) {
499 // Decap packet
500 using namespace vanetza::security;
501 DecapConfirm decap_confirm = m_security_entity->decapsulate_packet(DecapRequest(*secured_message));
502 ctx.service_primitive().security_report = decap_confirm.report;
503 ctx.service_primitive().its_aid = decap_confirm.its_aid;
504 ctx.service_primitive().permissions = decap_confirm.permissions;
505 secured_payload_visitor visitor(*this, ctx, basic);
506
507 // check whether the received packet is valid
508 if (DecapReport::Success == decap_confirm.report) {
509 boost::apply_visitor(visitor, decap_confirm.plaintext_payload);
510 } else if (SecurityDecapHandling::Non_Strict == m_mib.itsGnSnDecapResultHandling) {
511 // according to ETSI EN 302 636-4-1 v1.2.1 section 9.3.3 Note 2
512 // handle the packet anyway, when itsGnDecapResultHandling is set to NON-Strict (1)
513 switch (decap_confirm.report) {
514 case DecapReport::False_Signature:
515 case DecapReport::Invalid_Certificate:
516 case DecapReport::Revoked_Certificate:
517 case DecapReport::Inconsistant_Chain:
518 case DecapReport::Invalid_Timestamp:
519 case DecapReport::Invalid_Mobility_Data:
520 case DecapReport::Unsigned_Message:
521 case DecapReport::Signer_Certificate_Not_Found:
522 case DecapReport::Unsupported_Signer_Identifier_Type:
523 case DecapReport::Unencrypted_Message:
524 // ok, continue
525 boost::apply_visitor(visitor, decap_confirm.plaintext_payload);
526 break;
527 case DecapReport::Duplicate_Message:
528 case DecapReport::Incompatible_Protocol:
529 case DecapReport::Decryption_Error:
530 default:
531 packet_dropped(PacketDropReason::Decap_Unsuccessful_Non_Strict);
532 break;
533 }
534 } else {
535 // discard packet
536 packet_dropped(PacketDropReason::Decap_Unsuccessful_Strict);
537 }
538 } else {
539 packet_dropped(PacketDropReason::Security_Entity_Missing);
540 }
541}
542
543void Router::indicate_extended(IndicationContext& ctx, const CommonHeader& common)
544{
545 struct extended_header_visitor : public boost::static_visitor<bool>
546 {
547 extended_header_visitor(Router& router, IndicationContext& ctx, const UpPacket& packet) :
548 m_router(router), m_context(ctx), m_packet(packet)
549 {
550 }
551
552 bool operator()(const ShbHeader& shb)
553 {
554 DataIndication& indication = m_context.service_primitive();
555 indication.transport_type = TransportType::SHB;
556 indication.source_position = static_cast<ShortPositionVector>(shb.source_position);
557
558 auto& pdu = m_context.pdu();
559 ExtendedPduConstRefs<ShbHeader> shb_pdu(pdu.basic(), pdu.common(), shb, pdu.secured());
560
561 return m_router.process_extended(shb_pdu, m_packet, m_context.link_layer());
562 }
563
564 bool operator()(const GeoBroadcastHeader& gbc)
565 {
566 DataIndication& indication = m_context.service_primitive();
567 indication.transport_type = TransportType::GBC;
568 indication.source_position = static_cast<ShortPositionVector>(gbc.source_position);
569 indication.destination = gbc.destination(m_context.pdu().common().header_type);
570
571 auto& pdu = m_context.pdu();
572 ExtendedPduConstRefs<GeoBroadcastHeader> gbc_pdu(pdu.basic(), pdu.common(), gbc, pdu.secured());
573 return m_router.process_extended(gbc_pdu, m_packet, m_context.link_layer());
574 }
575
576 bool operator()(const BeaconHeader& beacon)
577 {
578 auto& pdu = m_context.pdu();
579 ExtendedPduConstRefs<BeaconHeader> beacon_pdu(pdu.basic(), pdu.common(), beacon, pdu.secured());
580 return m_router.process_extended(beacon_pdu, m_packet, m_context.link_layer());
581 }
582
583 Router& m_router;
584 IndicationContext& m_context;
585 const UpPacket& m_packet;
586 };
587
588 auto extended = ctx.parse_extended(common.header_type);
589 UpPacketPtr packet = ctx.finish();
590 assert(packet);
591
592 if (!extended) {
593 packet_dropped(PacketDropReason::Parse_Extended_Header);
594 } else if (common.payload != size(*packet, OsiLayer::Transport, max_osi_layer())) {
595 packet_dropped(PacketDropReason::Payload_Size);
596 } else {
597 extended_header_visitor visitor(*this, ctx, *packet);
598 if (boost::apply_visitor(visitor, *extended)) {
599 pass_up(ctx.service_primitive(), std::move(packet));
600 }
601 }
602}
603
604NextHop Router::forwarding_algorithm_selection(PendingPacketForwarding&& packet, const LinkLayer* ll)
605{
606 NextHop nh;
607 const Area& destination = packet.pdu().extended().destination(packet.pdu().common().header_type);
608 if (inside_or_at_border(destination, m_local_position_vector.position())) {
609 switch (m_mib.itsGnAreaForwardingAlgorithm) {
610 case BroadcastForwarding::Unspecified:
611 // do simple forwarding
612 case BroadcastForwarding::SIMPLE:
613 // Simple always returns link-layer broadcast address (see Annex F.2)
614 nh.transmit(std::move(packet), cBroadcastMacAddress);
615 break;
616 case BroadcastForwarding::CBF:
617 nh = area_contention_based_forwarding(std::move(packet), ll ? &ll->sender : nullptr);
618 break;
619 case BroadcastForwarding::Advanced:
620 nh = area_advanced_forwarding(std::move(packet), ll);
621 break;
622 default:
623 throw std::runtime_error("unhandled area forwarding algorithm");
624 break;
625 };
626 } else {
627 // packets received from senders located inside destination area are not meant for non-area forwarding
628 const LongPositionVector* pv_se = ll ? m_location_table.get_position(ll->sender) : nullptr;
629 if (pv_se && pv_se->position_accuracy_indicator && inside_or_at_border(destination, pv_se->position())) {
630 nh.discard();
631 forwarding_stopped(ForwardingStopReason::Outside_Destination_Area);
632 } else {
633 switch (m_mib.itsGnNonAreaForwardingAlgorithm) {
634 case UnicastForwarding::Unspecified:
635 // fall through to greedy forwarding
636 case UnicastForwarding::Greedy:
637 nh = greedy_forwarding(std::move(packet));
638 break;
639 case UnicastForwarding::CBF:
640 nh = non_area_contention_based_forwarding(std::move(packet), ll ? &ll->sender : nullptr);
641 break;
642 default:
643 throw std::runtime_error("unhandled non-area forwarding algorithm");
644 break;
645 };
646 }
647 }
648
649 return nh;
650}
651
652void Router::execute_media_procedures(CommunicationProfile com_profile)
653{
654 switch (com_profile) {
655 case CommunicationProfile::ITS_G5:
656 execute_itsg5_procedures();
657 break;
658 case CommunicationProfile::Unspecified:
659 // do nothing
660 break;
661 default:
662 throw std::runtime_error("Unhandled communication profile");
663 break;
664 }
665}
666
667void Router::execute_itsg5_procedures()
668{
669 // TODO: implement ITS_G5A procedures, see EN 302636-4-2
670}
671
672void Router::pass_down(const dcc::DataRequest& request, PduPtr pdu, DownPacketPtr payload)
673{
674 assert(pdu);
675 assert(payload);
676 if (pdu->secured()) {
677 if (pdu->basic().next_header != NextHeaderBasic::Secured) {
678 throw std::runtime_error("PDU with secured message but Secured not set in basic header");
679 }
680 if (payload->size(OsiLayer::Transport, max_osi_layer()) > 0) {
681 throw std::runtime_error("PDU with secured message and illegal upper layer payload");
682 }
683 } else {
684 if (pdu->basic().next_header == NextHeaderBasic::Secured) {
685 throw std::runtime_error("PDU without secured message but Secured set in basic header");
686 }
687 }
688
689 (*payload)[OsiLayer::Network] = ByteBufferConvertible(std::move(pdu));
690 assert(m_request_interface);
691 m_request_interface->request(request, std::move(payload));
692}
693
694void Router::pass_down(const MacAddress& addr, PduPtr pdu, DownPacketPtr payload)
695{
696 assert(pdu);
697
698 dcc::DataRequest request;
699 request.destination = addr;
700 request.source = m_local_position_vector.gn_addr.mid();
701 request.dcc_profile = map_tc_onto_profile(pdu->common().traffic_class);
702 request.ether_type = geonet::ether_type;
703 request.lifetime = clock_cast(pdu->basic().lifetime.decode());
704
705 pass_down(request, std::move(pdu), std::move(payload));
706}
707
708void Router::pass_up(const DataIndication& ind, UpPacketPtr packet)
709{
710 TransportInterface* transport = m_transport_ifcs[ind.upper_protocol];
711 if (transport != nullptr) {
712 transport->indicate(ind, std::move(packet));
713 }
714}
715
716void Router::on_beacon_timer_expired()
717{
718 if (m_mib.vanetzaDisableBeaconing) {
719 // bail out immediately if beaconing has been disabled
720 return;
721 }
722
723 // Beacons originate in GeoNet layer, therefore no upper layer payload
724 DownPacketPtr payload { new DownPacket() };
725 auto pdu = create_beacon_pdu();
726
727 if (m_mib.itsGnSecurity) {
728 pdu->basic().next_header = NextHeaderBasic::Secured;
729 payload = encap_packet(aid::GN_MGMT, *pdu, std::move(payload));
730 } else {
731 pdu->basic().next_header = NextHeaderBasic::Common;
732 }
733
734 execute_media_procedures(m_mib.itsGnIfType);
735 pass_down(cBroadcastMacAddress, std::move(pdu), std::move(payload));
736 reset_beacon_timer();
737}
738
739void Router::reset_beacon_timer()
740{
741 using duration_t = decltype(m_mib.itsGnBeaconServiceRetransmitTimer);
742 using real_t = duration_t::value_type;
743 static_assert(std::is_floating_point<real_t>::value, "floating point type expected");
744
745 std::uniform_real_distribution<real_t> dist_jitter(0.0, 1.0);
746 const auto jitter = dist_jitter(m_random_gen);
747 const duration_t next_beacon = m_mib.itsGnBeaconServiceRetransmitTimer +
748 jitter * m_mib.itsGnBeaconServiceMaxJitter;
749 reset_beacon_timer(clock_cast(next_beacon));
750}
751
752void Router::reset_beacon_timer(Clock::duration next_beacon)
753{
754 m_runtime.cancel(this);
755 m_runtime.schedule(next_beacon, [this](Clock::time_point) {
756 on_beacon_timer_expired();
757 }, this);
758}
759
760void Router::dispatch_repetition(const DataRequestVariant& request, std::unique_ptr<DownPacket> payload)
761{
762 RepetitionDispatcher dispatcher(*this, std::move(payload));
763 boost::apply_visitor(dispatcher, request);
764}
765
766NextHop Router::greedy_forwarding(PendingPacketForwarding&& packet)
767{
768 NextHop nh;
769 GeodeticPosition dest = packet.pdu().extended().position();
770 const units::Length own = distance(dest, m_local_position_vector.position());
771 units::Length mfr_dist = own;
772
773 MacAddress mfr_addr;
774 for (const LocationTableEntry& neighbour : m_location_table.neighbours()) {
775 if (neighbour.has_position_vector()) {
776 const units::Length dist = distance(dest, neighbour.get_position_vector().position());
777 if (dist < mfr_dist) {
778 mfr_addr = neighbour.link_layer_address();
779 mfr_dist = dist;
780 }
781 }
782 }
783
784 if (mfr_dist < own) {
785 nh.transmit(std::move(packet), mfr_addr);
786 } else {
787 const bool scf = packet.pdu().common().traffic_class.store_carry_forward();
788 if (scf) {
789 std::function<void(PendingPacketForwarding&&)> greedy_fwd = [this](PendingPacketForwarding&& packet) {
790 NextHop nh = greedy_forwarding(std::move(packet));
791 std::move(nh).process();
792 };
793 PendingPacket<GbcPdu> greedy_packet(std::move(packet), greedy_fwd);
794 PacketBuffer::data_ptr data { new PendingPacketBufferData<GbcPdu>(std::move(greedy_packet)) };
795 m_bc_forward_buffer.push(std::move(data), m_runtime.now());
796 nh.buffer();
797 } else {
798 nh.transmit(std::move(packet), cBroadcastMacAddress);
799 }
800 }
801
802 return nh;
803}
804
805NextHop Router::non_area_contention_based_forwarding(PendingPacketForwarding&& packet, const MacAddress* sender)
806{
807 NextHop nh;
808 const GeoBroadcastHeader& gbc = packet.pdu().extended();
809 const auto cbf_id = identifier(gbc.source_position.gn_addr, gbc.sequence_number);
810
811 // immediately broadcast packet if it is originating from local router
812 if (!sender) {
813 nh.transmit(std::move(packet), cBroadcastMacAddress);
814 } else if (m_cbf_buffer.remove(cbf_id)) {
815 // packet has been in CBF buffer (and is now dropped)
816 nh.discard();
817 } else {
818 const HeaderType ht = packet.pdu().common().header_type;
819 const Area destination = gbc.destination(ht);
820 const auto& epv = m_local_position_vector;
821 const LongPositionVector* pv_se = sender ? m_location_table.get_position(*sender) : nullptr;
822 // condition "PV_SE = EPV" is omitted here
823 if (pv_se && pv_se->position_accuracy_indicator) {
824 const auto& pv_p = destination.position;
825 const units::Length dist_sender = distance(pv_p, pv_se->position());
826 const units::Length dist_local = distance(pv_p, epv.position());
827 if (dist_sender > dist_local) {
828 CbfPacket cbf { std::move(packet), *sender };
829 const auto progress = dist_sender - dist_local;
830 m_cbf_buffer.add(std::move(cbf), clock_cast(timeout_cbf(progress)));
831 nh.buffer();
832
833 } else {
834 nh.discard();
835 }
836 } else {
837 CbfPacket cbf { std::move(packet), *sender };
838 const auto to_cbf_max = m_mib.itsGnCbfMaxTime;
839 m_cbf_buffer.add(std::move(cbf), clock_cast(to_cbf_max));
840 nh.buffer();
841 }
842 }
843 return nh;
844}
845
846NextHop Router::area_contention_based_forwarding(PendingPacketForwarding&& packet, const MacAddress* sender)
847{
848 NextHop nh;
849 const GeoBroadcastHeader& gbc = packet.pdu().extended();
850 const auto cbf_id = identifier(gbc.source_position.gn_addr, gbc.sequence_number);
851
852 if (!sender) {
853 nh.transmit(std::move(packet), cBroadcastMacAddress);
854 } else if (m_cbf_buffer.remove(cbf_id) || m_cbf_buffer.counter(cbf_id) >= m_mib.vanetzaCbfMaxCounter) {
855 nh.discard();
856 } else {
857 const units::Duration timeout = timeout_cbf(*sender);
858 m_cbf_buffer.add(CbfPacket { std::move(packet), *sender }, clock_cast(timeout));
859 nh.buffer();
860 }
861 return nh;
862}
863
864units::Duration Router::timeout_cbf(units::Length prog) const
865{
866 // TODO: media-dependent maximum communication range
867 const auto dist_max = m_mib.itsGnDefaultMaxCommunicationRange;
868 const auto to_cbf_min = m_mib.itsGnCbfMinTime;
869 const auto to_cbf_max = m_mib.itsGnCbfMaxTime;
870
871 if (prog > dist_max) {
872 return to_cbf_min;
873 } else if (prog > 0.0 * units::si::meter) {
874 return to_cbf_max + (to_cbf_min - to_cbf_max) / dist_max * prog;
875 } else {
876 return to_cbf_max;
877 }
878}
879
880units::Duration Router::timeout_cbf(const MacAddress& sender) const
881{
882 // use maximum CBF time as fallback value
883 units::Duration timeout = m_mib.itsGnCbfMaxTime;
884 const LongPositionVector* pv_se = m_location_table.get_position(sender);
885 if (pv_se && pv_se->position_accuracy_indicator) {
886 units::Length dist = distance(pv_se->position(), m_local_position_vector.position());
887 timeout = timeout_cbf(dist);
888 }
889 return timeout;
890}
891
892NextHop Router::area_advanced_forwarding(PendingPacketForwarding&& packet, const LinkLayer* ll)
893{
894 NextHop nh;
895 if (!ll) {
896 // packet is from local node (source operations)
897 nh.transmit(std::move(packet), cBroadcastMacAddress);
898 } else {
899 const GeoBroadcastHeader& gbc = packet.pdu().extended();
900 const HeaderType ht = packet.pdu().common().header_type;
901 const Area destination_area = gbc.destination(ht);
902 const std::size_t max_counter = m_mib.vanetzaCbfMaxCounter;
903 const auto cbf_id = identifier(gbc.source_position.gn_addr, gbc.sequence_number);
904 const CbfPacket* cbf_packet = m_cbf_buffer.find(cbf_id);
905
906 if (cbf_packet) {
907 // packet is already buffered
908 if (m_cbf_buffer.counter(cbf_id) >= max_counter) {
909 // stop contending if counter is exceeded
910 m_cbf_buffer.remove(cbf_id);
911 nh.discard();
912 } else if (!outside_sectorial_contention_area(cbf_packet->sender(), ll->sender)) {
913 // within sectorial area
914 // - sender S = sender of buffered packet
915 // - forwarder F = sender of now received packet
916 m_cbf_buffer.remove(cbf_id);
917 nh.discard();
918 } else {
919 m_cbf_buffer.update(cbf_id, clock_cast(timeout_cbf(ll->sender)));
920 nh.buffer();
921 }
922 } else {
923 if (ll->destination == m_local_position_vector.gn_addr.mid()) {
924 // continue with greedy forwarding
925 nh = greedy_forwarding(packet.duplicate());
926 // optimization: avoid "double broadcast"
927 if (nh.valid() && nh.mac() == cBroadcastMacAddress) {
928 // contending without further broadcasting
929 static const PendingPacketForwarding::Function noop_fn =
930 [](PendingPacketForwarding::Packet&&, const MacAddress&) {};
931 PendingPacketForwarding noop { std::move(packet).packet(), noop_fn };
932 CbfPacket cbf { std::move(noop), ll->sender };
933 m_cbf_buffer.add(std::move(cbf), clock_cast(m_mib.itsGnCbfMaxTime));
934 } else {
935 // no immediate broadcast by greedy forwarding
936 CbfPacket cbf { std::move(packet), ll->sender };
937 m_cbf_buffer.add(std::move(cbf), clock_cast(m_mib.itsGnCbfMaxTime));
938 }
939 // next hop (nh) conveys result of greedy forwarding algorithm
940 } else {
941 // classical CBF (timeout_cbf_gbc looks up sender's position)
942 nh.buffer();
943 CbfPacket cbf { std::move(packet), ll->sender };
944 m_cbf_buffer.add(std::move(cbf), clock_cast(timeout_cbf(ll->sender)));
945 }
946 }
947 }
948
949 return nh;
950}
951
952bool Router::outside_sectorial_contention_area(const MacAddress& sender, const MacAddress& forwarder) const
953{
954 using units::si::meter;
955 auto position_sender = m_location_table.get_position(sender);
956 auto position_forwarder = m_location_table.get_position(forwarder);
957
958 // Assumption: if any position is missing, then sectorial area becomes infinite small
959 // As a result of this assumption, everything lays outside then
960 if (position_sender && position_forwarder) {
961 auto dist_r = distance(position_sender->position(), m_local_position_vector.position());
962 auto dist_f = distance(position_forwarder->position(), position_sender->position());
963 const auto dist_max = m_mib.itsGnDefaultMaxCommunicationRange;
964
965 auto dist_rf = distance(position_forwarder->position(), m_local_position_vector.position());
966 auto angle_fsr = 0.0 * units::si::radians;
967 if (dist_r > 0.0 * meter && dist_f > 0.0 * meter) {
968 auto cos_fsr = (dist_rf * dist_rf - dist_r * dist_r - dist_f * dist_f) /
969 (-2.0 * dist_r * dist_f);
970 angle_fsr = boost::units::acos(cos_fsr);
971 }
972 const auto angle_th = m_mib.itsGnBroadcastCBFDefSectorAngle;
973
974 return !(dist_r < dist_f && dist_f < dist_max && angle_fsr < angle_th);
975 } else {
976 return true;
977 }
978}
979
980bool Router::process_extended(const ExtendedPduConstRefs<ShbHeader>& pdu, const UpPacket& packet, const LinkLayer& ll)
981{
982 const ShbHeader& shb = pdu.extended();
983 const Address& source_addr = shb.source_position.gn_addr;
984
985 // step 3: execute duplicate address detection (see 9.2.1.5)
986 detect_duplicate_address(source_addr, ll.sender);
987
988 // step 4: update location table with SO.PV (see C.2)
989 auto& source_entry = m_location_table.update(shb.source_position);
990 // NOTE: position vector (PV) may still be missing in location table when received PV has been invalid
991 assert(source_entry.has_position_vector() || !is_valid(shb.source_position));
992
993 // step 5: update SO.PDR in location table (see B.2)
994 const std::size_t packet_size = size(packet, OsiLayer::Network, OsiLayer::Application);
995 source_entry.update_pdr(packet_size, m_mib.itsGnMaxPacketDataRateEmaBeta);
996
997 // step 6: set SO LocTE to neighbour
998 source_entry.set_neighbour(true, m_mib.vanetzaNeighbourFlagExpiry);
999
1000 // media-dependent update of LocTEX_G5 (see TS 102 636-4-2 V1.1.1, section 6.1.2)
1001 if (m_mib.itsGnIfType == InterfaceType::ITS_G5) {
1002 boost::optional<DccMcoField> dcc_mco = get_dcc_mco(shb.dcc);
1003 if (dcc_mco) {
1004 auto& loctex = source_entry.extensions.get<LocTEX_G5>();
1005 loctex.local_update = m_runtime.now();
1006 loctex.source_update = shb.source_position.timestamp;
1007 loctex.dcc_mco = *dcc_mco;
1008 }
1009 }
1010
1011 // step 7: pass up SHB packet anyways
1012 return true;
1013}
1014
1015bool Router::process_extended(const ExtendedPduConstRefs<BeaconHeader>& pdu, const UpPacket& packet, const LinkLayer& ll)
1016{
1017 const BeaconHeader& beacon = pdu.extended();
1018 const Address& source_addr = beacon.source_position.gn_addr;
1019
1020 // step 3: execute duplicate address detection (see 9.2.1.5)
1021 detect_duplicate_address(source_addr, ll.sender);
1022
1023 // step 4: update location table with SO.PV (see C.2)
1024 auto& source_entry = m_location_table.update(beacon.source_position);
1025
1026 // step 5: update SO.PDR in location table (see B.2)
1027 const std::size_t packet_size = size(packet, OsiLayer::Network, OsiLayer::Application);
1028 source_entry.update_pdr(packet_size, m_mib.itsGnMaxPacketDataRateEmaBeta);
1029
1030 // step 6: set SO LocTE to neighbour
1031 source_entry.set_neighbour(true, m_mib.vanetzaNeighbourFlagExpiry);
1032
1033 // step 7: never pass up Beacons
1034 return false;
1035}
1036
1037bool Router::process_extended(const ExtendedPduConstRefs<GeoBroadcastHeader>& pdu, const UpPacket& packet, const LinkLayer& ll)
1038{
1039 // GBC forwarder and receiver operations (section 9.3.11.3 in EN 302 636-4-1 V1.2.1)
1040 const GeoBroadcastHeader& gbc = pdu.extended();
1041 const Address& source_addr = gbc.source_position.gn_addr;
1042 const Area dest_area = gbc.destination(pdu.common().header_type);
1043
1044 // remember if LocTE(SO) exists (5) before duplicate packet detection might (3) silently create an entry
1045 const bool locte_exists = m_location_table.has_entry(source_addr);
1046
1047 // step 3: determine position relative to destination area
1048 const bool within_destination = inside_or_at_border(dest_area, m_local_position_vector.position());
1049 // step 3a
1050 bool duplicate_packet = false;
1051 if (!within_destination) {
1052 if (m_mib.itsGnNonAreaForwardingAlgorithm == UnicastForwarding::Unspecified ||
1053 m_mib.itsGnNonAreaForwardingAlgorithm == UnicastForwarding::Greedy) {
1054 duplicate_packet = detect_duplicate_packet(source_addr, gbc.sequence_number);
1055 }
1056 // step 3b
1057 } else {
1058 if (m_mib.itsGnAreaForwardingAlgorithm == BroadcastForwarding::Unspecified ||
1059 m_mib.itsGnAreaForwardingAlgorithm == BroadcastForwarding::SIMPLE) {
1060 duplicate_packet = detect_duplicate_packet(source_addr, gbc.sequence_number);
1061 }
1062 }
1063 // step 3a & 3b
1064 if (duplicate_packet) {
1065 // omit execution of further steps
1066 return false;
1067 }
1068
1069 // step 4: execute DAD
1070 if (m_mib.vanetzaMultiHopDuplicateAddressDetection) {
1071 // Be careful, DAD is broken with address mode AUTO for multi-hop communication
1072 detect_duplicate_address(source_addr, ll.sender);
1073 }
1074
1075 // step 5 & step 6 (make sure IS_NEIGHBOUR is false for new location table entry)
1076 const std::size_t packet_size = size(packet, OsiLayer::Network, OsiLayer::Application);
1077 auto& source_entry = m_location_table.update(gbc.source_position);
1078 source_entry.update_pdr(packet_size, m_mib.itsGnMaxPacketDataRateEmaBeta);
1079 if (!locte_exists) {
1080 // step 5b only
1081 source_entry.set_neighbour(false);
1082 }
1083
1084 // step 7: pass packet to upper layer if router is within destination area, return value
1085
1086 // step 8a: TODO: flush SO LS packet buffer if LS_pending, reset LS_pending
1087 // step 8b: flush UC forwarding packet buffer
1088 flush_unicast_forwarding_buffer(source_addr);
1089
1090 // step 9: discard packet (no forwarding) if hop limit is reached
1091 if (pdu.basic().hop_limit <= 1) {
1092 forwarding_stopped(ForwardingStopReason::Hop_Limit);
1093 return decide_pass_up(within_destination, gbc); // discard packet (step 9a)
1094 } else if (m_mib.itsGnMaxPacketDataRate < std::numeric_limits<decltype(m_mib.itsGnMaxPacketDataRate)>::max()) {
1095 // do packet data rate checks (annex B.2) if set maximum rate is not "infinity" (i.e. max unsigned value)
1096 if (source_entry.get_pdr() > m_mib.itsGnMaxPacketDataRate * 1000.0) {
1097 forwarding_stopped(ForwardingStopReason::Source_PDR);
1098 return decide_pass_up(within_destination, gbc); // omit forwarding, source exceeds PDR limit
1099 } else if (const auto* sender_entry = m_location_table.get_entry(ll.sender)) {
1100 if (sender_entry->get_pdr() > m_mib.itsGnMaxPacketDataRate * 1000.0) {
1101 forwarding_stopped(ForwardingStopReason::Sender_PDR);
1102 return decide_pass_up(within_destination, gbc); // omit forwarding, sender exceeds PDR limit
1103 }
1104 }
1105 }
1106
1107 // step 9b: update hop limit in basic header
1108 auto fwd_dup = create_forwarding_duplicate(pdu, packet);
1109 GbcPdu& fwd_pdu = get_pdu(fwd_dup);
1110 --fwd_pdu.basic().hop_limit;
1111 assert(fwd_pdu.basic().hop_limit + 1 == pdu.basic().hop_limit);
1112
1113 using Packet = PendingPacketGbc::Packet;
1114
1115 auto transmit = [this](Packet&& packet, const MacAddress& mac) {
1116 // step 13: execute media-dependent procedures
1117 execute_media_procedures(m_mib.itsGnIfType);
1118
1119 // step 14: pass down to link-layer
1120 std::unique_ptr<Pdu> pdu;
1121 std::unique_ptr<DownPacket> payload;
1122 std::tie(pdu, payload) = std::move(packet);
1123
1124 dcc::DataRequest request;
1125 request.destination = mac;
1126 request.source = m_local_position_vector.gn_addr.mid();
1127 request.dcc_profile = dcc::Profile::DP3;
1128 request.ether_type = geonet::ether_type;
1129 request.lifetime = clock_cast(pdu->basic().lifetime.decode());
1130
1131 pass_down(request, std::move(pdu), std::move(payload));
1132 };
1133
1134 auto forwarding = [this, transmit, ll](Packet&& packet) {
1135 // step 11: execute forwarding algorithm
1136 PendingPacket<GbcPdu, const MacAddress&> tmp(std::move(packet), transmit);
1137 NextHop forwarding = forwarding_algorithm_selection(std::move(tmp), &ll);
1138
1139 // step 12: transmit immediately if not buffered or discarded
1140 std::move(forwarding).process();
1141 };
1142
1143 PendingPacketGbc fwd_packet(std::move(fwd_dup), forwarding);
1144
1145 // step 10: store & carry forwarding procedure
1146 const bool scf = pdu.common().traffic_class.store_carry_forward();
1147 if (scf && !m_location_table.has_neighbours()) {
1148 PacketBuffer::data_ptr data { new PendingPacketBufferData<GbcPdu>(std::move(fwd_packet)) };
1149 m_bc_forward_buffer.push(std::move(data), m_runtime.now());
1150 } else {
1151 fwd_packet.process();
1152 }
1153
1154 // step 7: pass up decision
1155 return decide_pass_up(within_destination, gbc);
1156}
1157
1158bool Router::decide_pass_up(bool within_destination, const GeoBroadcastHeader& gbc)
1159{
1160 if (m_mib.vanetzaGbcMemoryCapacity == 0) {
1161 // classic pass up: suppress only GBCs outside of destination area
1162 return within_destination;
1163 } else if (within_destination) {
1164 // modified pass up: suppress passing up duplicate GBC packets
1165 return !m_gbc_memory.remember(std::make_tuple(gbc.source_position.gn_addr, gbc.sequence_number));
1166 } else {
1167 return false;
1168 }
1169}
1170
1171void Router::flush_broadcast_forwarding_buffer()
1172{
1173 m_bc_forward_buffer.flush(m_runtime.now());
1174}
1175
1176void Router::flush_unicast_forwarding_buffer(const Address& source)
1177{
1178 // TODO flush only packets for given source address (required for GUC packets)
1179 m_uc_forward_buffer.flush(m_runtime.now());
1180}
1181
1182void Router::detect_duplicate_address(const Address& source, const MacAddress& sender)
1183{
1184 // EN 302 636-4-1 V1.3.1 10.2.1.5: DAD is only applied for Auto
1185 if (m_mib.itsGnLocalAddrConfMethod == AddrConfMethod::Auto) {
1186 const Address& local = m_local_position_vector.gn_addr;
1187 if (source == local || sender == local.mid()) {
1188 MacAddress random_mac_addr;
1189 std::uniform_int_distribution<unsigned> octet_dist;
1190 for (auto& octet : random_mac_addr.octets) {
1191 octet = octet_dist(m_random_gen);
1192 }
1193
1194 m_local_position_vector.gn_addr.mid(random_mac_addr);
1195 }
1196 }
1197}
1198
1199bool Router::detect_duplicate_packet(const Address& addr_so, SequenceNumber sn)
1200{
1201 bool is_duplicate = false;
1202 ObjectContainer& so_ext = m_location_table.get_or_create_entry(addr_so).extensions;
1203 DuplicatePacketList* dpl = so_ext.find<DuplicatePacketList>();
1204 if (dpl) {
1205 is_duplicate = dpl->check(sn);
1206 } else {
1207 std::unique_ptr<DuplicatePacketList> dpl { new DuplicatePacketList(m_mib.itsGnDPLLength) };
1208 is_duplicate = dpl->check(sn);
1209 so_ext.insert(std::move(dpl));
1210 }
1211 return is_duplicate;
1212}
1213
1214std::unique_ptr<ShbPdu> Router::create_shb_pdu(const ShbDataRequest& request)
1215{
1216 std::unique_ptr<ShbPdu> pdu { new ShbPdu(request, m_mib) };
1217 pdu->basic().hop_limit = 1;
1218 pdu->common().header_type = HeaderType::TSB_Single_Hop;
1219 pdu->common().maximum_hop_limit = 1;
1220 pdu->extended().source_position = m_local_position_vector;
1221 pdu->extended().dcc = m_dcc_field_generator->generate_dcc_field();
1222 return pdu;
1223}
1224
1225std::unique_ptr<BeaconPdu> Router::create_beacon_pdu()
1226{
1227 std::unique_ptr<BeaconPdu> pdu { new BeaconPdu(m_mib) };
1228 pdu->basic().hop_limit = 1;
1229 pdu->common().next_header = NextHeaderCommon::Any;
1230 pdu->common().header_type = HeaderType::Beacon;
1231 pdu->common().maximum_hop_limit = 1;
1232 // TODO: Beacons are sent with itsGnDefaultTrafficClass (DP0) at the moment, but DP3 may be more appropriate?
1233 pdu->extended().source_position = m_local_position_vector;
1234 return pdu;
1235}
1236
1237std::unique_ptr<GbcPdu> Router::create_gbc_pdu(const GbcDataRequest& request)
1238{
1239 std::unique_ptr<GbcPdu> pdu { new GbcPdu(request, m_mib) };
1240 pdu->common().header_type = gbc_header_type(request.destination);
1241 pdu->extended().sequence_number = m_local_sequence_number++;
1242 pdu->extended().source_position = m_local_position_vector;
1243 pdu->extended().destination(request.destination);
1244 return pdu;
1245}
1246
1247Router::DownPacketPtr Router::encap_packet(ItsAid its_aid, Pdu& pdu, DownPacketPtr packet)
1248{
1249 security::EncapRequest encap_request;
1250
1251 DownPacket sec_payload;
1252 sec_payload[OsiLayer::Network] = SecuredPdu(pdu);
1253 sec_payload.merge(*packet, OsiLayer::Transport, max_osi_layer());
1254 encap_request.plaintext_payload = std::move(sec_payload);
1255 encap_request.its_aid = its_aid;
1256
1257 if (m_security_entity) {
1258 security::EncapConfirm confirm = m_security_entity->encapsulate_packet(std::move(encap_request));
1259 pdu.secured(std::move(confirm.sec_packet));
1260 } else {
1261 throw std::runtime_error("security entity unavailable");
1262 }
1263
1264 assert(size(*packet, OsiLayer::Transport, max_osi_layer()) == 0);
1265 assert(pdu.basic().next_header == NextHeaderBasic::Secured);
1266 return packet;
1267}
1268
1269std::string stringify(Router::PacketDropReason pdr)
1270{
1271 std::string reason_string;
1272
1273 // TODO replace this by something more elegant, e.g. https://github.com/aantron/better-enums
1274 switch (pdr) {
1275 case Router::PacketDropReason::Parse_Basic_Header:
1276 reason_string = "Parse_Basic_Header";
1277 break;
1278 case Router::PacketDropReason::Parse_Common_Header:
1279 reason_string = "Parse_Common_Header";
1280 break;
1281 case Router::PacketDropReason::Parse_Secured_Header:
1282 reason_string = "Parse_Secured_Header";
1283 break;
1284 case Router::PacketDropReason::Parse_Extended_Header:
1285 reason_string = "Parse_Extended_Header";
1286 break;
1287 case Router::PacketDropReason::ITS_Protocol_Version:
1288 reason_string = "ITS_Protocol_Version";
1289 break;
1290 case Router::PacketDropReason::Decap_Unsuccessful_Non_Strict:
1291 reason_string = "Decap_Unsuccessful_Non_Strict";
1292 break;
1293 case Router::PacketDropReason::Decap_Unsuccessful_Strict:
1294 reason_string = "Decap_Unsuccessful_Strict";
1295 break;
1296 case Router::PacketDropReason::Hop_Limit:
1297 reason_string = "Hop_Limit";
1298 break;
1299 case Router::PacketDropReason::Payload_Size:
1300 reason_string = "Payload_Size";
1301 break;
1302 case Router::PacketDropReason::Security_Entity_Missing:
1303 reason_string = "Security_Entity_Missing";
1304 break;
1305 default:
1306 reason_string = "UNKNOWN";
1307 break;
1308 }
1309
1310 return reason_string;
1311}
1312
1313} // namespace geonet
1314} // namespace vanetza
ChunckPacket is a packet consisting of several memory chunks.
ChunkPacket & merge(ChunkPacket &packet, OsiLayer from, OsiLayer to)
const MacAddress & sender() const
virtual UpPacketPtr finish()=0
const MacAddress & mac() const
Definition: next_hop.cpp:27
void transmit(Packet &&packet, const MacAddress &destination)
Definition: next_hop.cpp:43
PacketDropReason
Reason for packet drop used by drop hook.
Definition: router.hpp:85
STL namespace.
BasicHeader specified in ETSI EN 302 636-4-1 v1.2.1, section 8.6.
contains output of the verify process described in TS 102 723-8 v1.0.0 (2013-07) TS 102 636-4-1 v1....
contains input for verify process described in TS 102 723-8 v1.0.0 (2013-07) TS 102 636-4-1 v1....
contains output of the signing process described in TS 102 636-4-1 v1.2.3 (2015-01)