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

Example to read data published from vision adapter. More...

#include <iostream>
#include <string>
#include <google/protobuf/util/json_util.h>
#include <google/protobuf/text_format.h>
#include "packet.pb.h"
#include "travesim_adapters/udp/multicast_receiver.hpp"
Include dependency graph for vision_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 to read data published from vision adapter.

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
Felipe Gomes de Melo felip.nosp@m.e.go.nosp@m.mes@t.nosp@m.hune.nosp@m.ratz..nosp@m.org
Date
04/2021

Definition in file vision_receiver_example.cpp.

Macro Definition Documentation

◆ BUFFER_SIZE

#define BUFFER_SIZE   1024U

Definition at line 27 of file vision_receiver_example.cpp.

Function Documentation

◆ main()

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

Definition at line 33 of file vision_receiver_example.cpp.

33  {
34  const std::string listen_address_str = "0.0.0.0";
35  const std::string multicast_address_str = "224.0.0.1";
36  const short multicast_port = 10002;
37 
38  char data_buff[BUFFER_SIZE];
39 
40  try {
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  fira_message::sim_to_ref::Environment env_data;
50  env_data.ParseFromString(data_buff);
51 
52  std::string parsed_msg;
53 
54  google::protobuf::util::JsonPrintOptions options;
55  options.add_whitespace = true;
56  options.always_print_primitive_fields = true;
57 
58  google::protobuf::util::MessageToJsonString(env_data, &parsed_msg, options);
59 
60  std::cout << parsed_msg << std::endl;
61  }
62 
63  if (i % 100000 == 0) {
64  std::cout << "Loop count: " << i << std::endl;
65  }
66  }
67  } catch (std::exception& e) {
68  std::cerr << "Exception: " << e.what() << "\n";
69  }
70 
71  return 0;
72 }
#define BUFFER_SIZE
Receiver class using UDP in multicast mode.

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

Here is the call graph for this function: