TraveSim Adapters  0.1
Protobuf adapters for TraveSim project
multicast_receiver_reset_example.cpp File Reference
#include <ros/ros.h>
#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_reset_example.cpp:

Go to the source code of this file.

Macros

#define BUFFER_SIZE   1024U
 

Functions

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

Macro Definition Documentation

◆ BUFFER_SIZE

#define BUFFER_SIZE   1024U

Definition at line 29 of file multicast_receiver_reset_example.cpp.

Function Documentation

◆ main()

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

Definition at line 35 of file multicast_receiver_reset_example.cpp.

35  {
36  const std::string listen_address_str = "0.0.0.0";
37  const std::string multicast_address_str = "239.255.0.1";
38  const short multicast_port = 30001;
39 
40  char data_buff[BUFFER_SIZE];
41 
42  ros::init(argc, argv, "reset_example_node", ros::init_options::AnonymousName);
43  ros::NodeHandle nh;
44 
45  bool reset = false;
46 
47  ros::param::set("reset", reset);
48 
49  try {
50  travesim::udp::MulticastReceiver my_receiver(multicast_address_str, multicast_port);
51 
52  my_receiver.force_specific_source(true);
53 
54  size_t data_size = 0;
55 
56  int counter = 0;
57 
58  ros::Rate loop_rate(60);
59 
60  while (ros::ok()) {
61  data_size = my_receiver.receive(data_buff, BUFFER_SIZE);
62 
63  if (data_size > 0) {
64  std::string received_msg(data_buff, data_size);
65  ROS_INFO_STREAM(received_msg << std::endl);
66  }
67 
68  if (counter % 100 == 0) {
69  ROS_INFO_STREAM("Loop count: " << counter << std::endl);
70  }
71 
72  ros::param::get("reset", reset);
73 
74  if (reset) {
75  ROS_INFO_STREAM("Receiver reseted!" << std::endl);
76  reset = false;
77  ros::param::set("reset", reset);
78  my_receiver.reset();
79  }
80 
81  counter++;
82 
83  ros::spinOnce();
84  loop_rate.sleep();
85  }
86  } catch (std::exception& e) {
87  std::cerr << "Exception: " << e.what() << "\n";
88  }
89 
90  return 0;
91 }
Receiver class using UDP in multicast mode.

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

Here is the call graph for this function: