TraveSim Adapters  0.1
Protobuf adapters for TraveSim project
multicast_receiver_reset_example.cpp
Go to the documentation of this file.
1 /**
2  * @file multicast_receiver_example.cpp
3  *
4  * @author Lucas Haug <lucas.haug@thuneratz.org>
5  * @author Lucas Schneider <lucas.schneider@thuneratz.org>
6  *
7  * @brief Example on how to use the MulticastReceiver
8  *
9  * @date 04/2021
10  *
11  * @note This example depends on ROS
12  *
13  * @copyright MIT License - Copyright (c) 2021 ThundeRatz
14  */
15 
16 #include <ros/ros.h>
17 
18 #include <iostream>
19 #include <string>
20 #include <boost/asio.hpp>
21 #include "boost/bind.hpp"
22 
24 
25 /*****************************************
26  * Private Constants
27  *****************************************/
28 
29 #define BUFFER_SIZE 1024U
30 
31 /*****************************************
32  * Main Function
33  *****************************************/
34 
35 int main(int argc, char* argv[]) {
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 }
void reset(void)
Reset the receiver.
Definition: receiver.cpp:117
Receiver class using UDP in multicast mode.
size_t receive(char *buffer, const size_t buffer_size)
Receive data using UDP.
Definition: receiver.cpp:44
void force_specific_source(bool specific_source)
Set wheter to enable any source or source specific. True for specific source, false for any source,...
Definition: receiver.cpp:108
Receiver data using UDP in multicast mode.
int main(int argc, char *argv[])