TraveSim Adapters  0.1
Protobuf adapters for TraveSim project
vision_adapter.test.cpp File Reference
#include <iostream>
#include <string>
#include <google/protobuf/util/json_util.h>
#include <google/protobuf/text_format.h>
#include <ros/ros.h>
#include <ros/console.h>
#include <gazebo_msgs/ModelStates.h>
#include <gtest/gtest.h>
#include "travesim_adapters/udp/multicast_receiver.hpp"
#include "packet.pb.h"
Include dependency graph for vision_adapter.test.cpp:

Go to the source code of this file.

Macros

#define BUFFER_SIZE   1024U
 
#define MAX_RETRIES   5
 

Functions

 TEST (vision_adapter, relay_messages)
 
int main (int argc, char **argv)
 

Detailed Description

Author
Felipe Gomes de Melo felip.nosp@m.e.go.nosp@m.mes@t.nosp@m.hund.nosp@m.eratz.nosp@m..org
Date
04/2021

Definition in file vision_adapter.test.cpp.

Macro Definition Documentation

◆ BUFFER_SIZE

#define BUFFER_SIZE   1024U

Definition at line 24 of file vision_adapter.test.cpp.

◆ MAX_RETRIES

#define MAX_RETRIES   5

Definition at line 25 of file vision_adapter.test.cpp.

Function Documentation

◆ main()

int main ( int  argc,
char **  argv 
)

Definition at line 74 of file vision_adapter.test.cpp.

74  {
75  testing::InitGoogleTest(&argc, argv);
76  ros::init(argc, argv, "tester_vision_adapter");
77  ros::NodeHandle nh;
78  return RUN_ALL_TESTS();
79 }

◆ TEST()

TEST ( vision_adapter  ,
relay_messages   
)

Definition at line 27 of file vision_adapter.test.cpp.

28 {
29  std::string listen_address_str = "0.0.0.0";
30 
31  char data_buff[BUFFER_SIZE];
32 
33  uint16_t multicast_port = 10002;
34  std::string multicast_address_str = "224.0.0.1";
35 
36  travesim::udp::MulticastReceiver my_receiver(multicast_address_str, multicast_port);
37 
38  size_t data_size = -1;
39  size_t retries = 0;
40 
41  bool success = false;
42 
43  while (!success && retries < MAX_RETRIES) {
44  while (retries < MAX_RETRIES && data_size <= 0) {
45  EXPECT_NO_THROW(data_size = my_receiver.receive(data_buff, BUFFER_SIZE));
46  retries++;
47  ros::Duration(0.5).sleep();
48  }
49 
50  EXPECT_LT(retries, MAX_RETRIES);
51  EXPECT_GT(data_size, 0);
52 
53  fira_message::sim_to_ref::Environment env_data;
54  env_data.ParseFromString(data_buff);
55 
56  std::string parsed_msg;
57 
58  google::protobuf::util::JsonPrintOptions options;
59  options.add_whitespace = true;
60  options.always_print_primitive_fields = true;
61 
62  google::protobuf::util::MessageToJsonString(env_data, &parsed_msg, options);
63 
64  ROS_INFO_STREAM(parsed_msg);
65 
66  success = env_data.has_frame();
67  data_size = 0;
68  }
69 
70  EXPECT_EQ(success, true);
71 }
Receiver class using UDP in multicast mode.
#define MAX_RETRIES
#define BUFFER_SIZE

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

Here is the call graph for this function: