20 : io_service_(), socket_(io_service_), udp_packet_publisher_(publisher)
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);
33 socket_.open(receiver_endpoint_.protocol());
36 socket_.set_option(boost::asio::ip::udp::socket::reuse_address(
true));
39 boost::asio::socket_base::receive_buffer_size r_option(16000000);
45 socket_.bind(receiver_endpoint_);
47 catch (std::exception &e)
49 ROS_ERROR(
"COULD NOT BIND SOCKET TO ENDPOINT");
51 "Please Make sure your Computer's IPv4 Settings are set correctly.");
60 boost::asio::ip::multicast::join_group option(receiver_addr.to_v4(),
61 multicast_addr.to_v4());
63 ROS_INFO(
"*****JOINED MULTICAST GROUP*****");
65 catch (std::exception &e)
67 ROS_ERROR(
"No multicast group to join...");
95 [
this](boost::system::error_code ec, std::size_t bytes_received)
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();
105 udp_packet_publisher_.publish(udp_packet_);
109 boost::this_thread::interruption_point();
113 const std::string &ip_address,
const uint16_t port)
116 udp::endpoint remote(boost::asio::ip::address::from_string(ip_address), port);
117 return socket_.send_to(boost::asio::buffer(data), remote);
std::string computer_address_
Source (computer) IP Address.
boost::asio::io_service io_service_
UDP IO service.
UdpPacket udp_packet_
UDP packet to be sent.
UdpCom(std::string computer_address, std::string sensor_address, uint16_t port, bool is_multicast, ros::Publisher publisher)
Implements the UDP methods for recieving and sending within the ROS ecosystem.
udp::endpoint receiver_endpoint_
UDP endpoint receiver.
size_t send(const std::vector< u_char > &data, const std::string &ip_address, const uint16_t udp_port)
udp::socket socket_
UDP socket.
udp::endpoint sender_endpoint_
UDP endpoint sender.
boost::thread thread_
Thread for service.