udp_com.cpp
Go to the documentation of this file.
1 /*
8  * Copyright (c) 2015, Hunter Laux
9  * All rights reserved.
10  */
11 #include <string>
12 #include <udp_com.h>
13 #include <vector>
14 
15 namespace udp_com
16 {
17 
18 UdpCom::UdpCom(std::string computer_address, std::string sensor_address,
19  uint16_t port, bool isMulticast, ros::Publisher publisher)
20  : io_service_(), socket_(io_service_), udp_packet_publisher_(publisher)
21 {
22  // Store Computer IP Address to compare to requested sockets
23  computer_address_ = computer_address;
24  // convert addresses & ports
25  const boost::asio::ip::address &multicast_addr = boost::asio::ip::address::from_string(sensor_address);
26  const boost::asio::ip::address &receiver_addr = boost::asio::ip::address::from_string(computer_address);
27  uint16_t multicast_port = boost::lexical_cast<uint16_t>(port);
28 
29  // Initialize endpoint
30  udp::endpoint receiver_endpoint_(receiver_addr, multicast_port);
31 
32  // Open Socket
33  socket_.open(receiver_endpoint_.protocol());
34 
35  // Allow other processes to reuse the address
36  socket_.set_option(boost::asio::ip::udp::socket::reuse_address(true));
37 
38  // Set socket buffer size
39  boost::asio::socket_base::receive_buffer_size r_option(16000000);
40  socket_.set_option(r_option);
41 
42  // try to bind socket to endpoint
43  try
44  {
45  socket_.bind(receiver_endpoint_);
46  }
47  catch (std::exception &e)
48  {
49  ROS_ERROR("COULD NOT BIND SOCKET TO ENDPOINT");
50  ROS_ERROR(
51  "Please Make sure your Computer's IPv4 Settings are set correctly.");
52  }
53 
54  // Try to join the multicast group if there is one
55  if (isMulticast)
56  {
57  try
58  {
59  // join multicast group
60  boost::asio::ip::multicast::join_group option(receiver_addr.to_v4(),
61  multicast_addr.to_v4());
62  socket_.set_option(option);
63  ROS_INFO("*****JOINED MULTICAST GROUP*****");
64  }
65  catch (std::exception &e)
66  {
67  ROS_ERROR("No multicast group to join...");
68  // Now that we have isMulticast set, if the group is not joined we should
69  // do something about the error
70  }
71  }
72 
73  // Calls doReceive() function
74  doReceive();
75 
76  // Initialize thread
77  thread_ = boost::thread(boost::bind(&boost::asio::io_service::run, &io_service_));
78 
79  // Initialize header message
80  udp_packet_.header.seq = 0;
81 }
82 
84 {
85  io_service_.stop();
86  thread_.interrupt();
87 }
88 
90 {
91  // Receive UDP socket data
92  udp_packet_.data.resize(1500);
93  socket_.async_receive_from(
94  boost::asio::buffer(udp_packet_.data), sender_endpoint_,
95  [this](boost::system::error_code ec, std::size_t bytes_received)
96  {
97  // Populate UDP packet ROS message
98  udp_packet_.header.stamp = ros::Time::now();
99  udp_packet_.header.seq++;
100  udp_packet_.data.resize(bytes_received);
101  udp_packet_.address = sender_endpoint_.address().to_string();
102  udp_packet_.srcPort = sender_endpoint_.port();
103 
104  // Publilshes UDP packet ROS message
105  udp_packet_publisher_.publish(udp_packet_);
106  doReceive();
107  }
108 );
109  boost::this_thread::interruption_point();
110 }
111 
112 size_t UdpCom::send(const std::vector<u_char> &data,
113  const std::string &ip_address, const uint16_t port)
114 {
115  // Create the remote endpoint so send data too
116  udp::endpoint remote(boost::asio::ip::address::from_string(ip_address), port);
117  return socket_.send_to(boost::asio::buffer(data), remote);
118 }
119 } // namespace udp_com
std::string computer_address_
Source (computer) IP Address.
Definition: udp_com.h:141
boost::asio::io_service io_service_
UDP IO service.
Definition: udp_com.h:132
UdpPacket udp_packet_
UDP packet to be sent.
Definition: udp_com.h:129
UdpCom(std::string computer_address, std::string sensor_address, uint16_t port, bool is_multicast, ros::Publisher publisher)
Definition: udp_com.cpp:18
#define ROS_INFO(...)
Implements the UDP methods for recieving and sending within the ROS ecosystem.
udp::endpoint receiver_endpoint_
UDP endpoint receiver.
Definition: udp_com.h:120
size_t send(const std::vector< u_char > &data, const std::string &ip_address, const uint16_t udp_port)
Definition: udp_com.cpp:112
void doReceive()
Definition: udp_com.cpp:89
udp::socket socket_
UDP socket.
Definition: udp_com.h:135
udp::endpoint sender_endpoint_
UDP endpoint sender.
Definition: udp_com.h:123
boost::thread thread_
Thread for service.
Definition: udp_com.h:138
#define ROS_ERROR(...)


udp_com
Author(s): Hunter Laux , Max Ginier , Evan Flynn , Gerardo Bravo , Moises Diaz
autogenerated on Sat Dec 5 2020 04:01:00