47 #include <boost/asio.hpp>
48 #include <boost/thread.hpp>
55 #include <udp_com/UdpPacket.h>
56 #include <udp_com/UdpSend.h>
57 #include <udp_com/UdpSocket.h>
59 using boost::asio::ip::udp;
80 UdpCom(std::string computer_address, std::string sensor_address,
81 uint16_t port,
bool is_multicast, ros::Publisher publisher);
109 size_t send(
const std::vector<u_char> &data,
const std::string &ip_address,
110 const uint16_t udp_port);
Implements the UDP methods for recieving and sending within the ROS ecosystem.
Definition: udp_com.h:69
size_t send(const std::vector< u_char > &data, const std::string &ip_address, const uint16_t udp_port)
Definition: udp_com.cpp:112
std::string computer_address_
Source (computer) IP Address.
Definition: udp_com.h:141
udp::endpoint sender_endpoint_
UDP endpoint sender.
Definition: udp_com.h:123
std::string getIp()
Returns the src IP for the created socket.
Definition: udp_com.h:113
~UdpCom()
Definition: udp_com.cpp:83
udp::endpoint receiver_endpoint_
UDP endpoint receiver.
Definition: udp_com.h:120
UdpPacket udp_packet_
UDP packet to be sent.
Definition: udp_com.h:129
ros::Publisher udp_packet_publisher_
ROS publisher.
Definition: udp_com.h:126
udp::socket socket_
UDP socket.
Definition: udp_com.h:135
boost::asio::io_service io_service_
UDP IO service.
Definition: udp_com.h:132
UdpCom(std::string computer_address, std::string sensor_address, uint16_t port, bool is_multicast, ros::Publisher publisher)
Definition: udp_com.cpp:18
boost::thread thread_
Thread for service.
Definition: udp_com.h:138
void doReceive()
Definition: udp_com.cpp:89