TraveSim Adapters  0.1
Protobuf adapters for TraveSim project
multicast_receiver_example.cpp File Reference

Example on how to use the MulticastReceiver. More...

#include <iostream>
#include <string>
#include <boost/asio.hpp>
#include "boost/bind.hpp"
#include "travesim_adapters/udp/multicast_receiver.hpp"
Include dependency graph for multicast_receiver_example.cpp:

Go to the source code of this file.

Macros

#define BUFFER_SIZE   1024U
 

Functions

int main (int argc, char *argv[])
 

Detailed Description

Example on how to use the MulticastReceiver.

Author
Lucas Haug lucas.nosp@m..hau.nosp@m.g@thu.nosp@m.nera.nosp@m.tz.or.nosp@m.g
Lucas Schneider lucas.nosp@m..sch.nosp@m.neide.nosp@m.r@th.nosp@m.unera.nosp@m.tz.o.nosp@m.rg
Date
04/2021
Author
Lucas Haug lucas.nosp@m..hau.nosp@m.g@thu.nosp@m.nera.nosp@m.tz.or.nosp@m.g
Lucas Schneider lucas.nosp@m..sch.nosp@m.neide.nosp@m.r@th.nosp@m.unera.nosp@m.tz.o.nosp@m.rg
Date
04/2021
Note
This example depends on ROS

Definition in file multicast_receiver_example.cpp.

Macro Definition Documentation

◆ BUFFER_SIZE

#define BUFFER_SIZE   1024U

Definition at line 25 of file multicast_receiver_example.cpp.

Function Documentation

◆ main()

int main ( int  argc,
char *  argv[] 
)

Definition at line 31 of file multicast_receiver_example.cpp.

31  {
32  const std::string listen_address_str = "0.0.0.0";
33  const std::string multicast_address_str = "224.0.0.1";
34  const short multicast_port = 10002;
35 
36  char data_buff[BUFFER_SIZE];
37 
38  try {
39  boost::asio::io_context io_context;
40  boost::asio::steady_timer my_timer(io_context);
41  travesim::udp::MulticastReceiver my_receiver(multicast_address_str, multicast_port);
42 
43  size_t data_size = 0;
44 
45  for (long int i = 0;; i++) {
46  data_size = my_receiver.receive(data_buff, BUFFER_SIZE);
47 
48  if (data_size > 0) {
49  std::string received_msg(data_buff, data_size);
50  std::cout << received_msg << std::endl;
51  }
52 
53  if (i % 100000 == 0) {
54  std::cout << "Loop count: " << i << std::endl;
55  }
56 
57  my_timer.expires_after(std::chrono::milliseconds(200));
58  my_timer.wait();
59  }
60  } catch (std::exception& e) {
61  std::cerr << "Exception: " << e.what() << "\n";
62  }
63 
64  return 0;
65 }
Receiver class using UDP in multicast mode.
#define BUFFER_SIZE

References BUFFER_SIZE, and travesim::udp::Receiver::receive().

Here is the call graph for this function: