12 #ifndef UDP_COM_NODELET_H 13 #define UDP_COM_NODELET_H 21 #include <udp_com/UdpPacket.h> 22 #include <udp_com/UdpSend.h> 23 #include <udp_com/UdpSocket.h> 71 bool send(UdpSend::Request &request, UdpSend::Response &);
81 bool createSocket(UdpSocket::Request &request, UdpSocket::Response &response);
86 #endif // UDP_COM_NODELET_H Implements the udp_com create_socket and send services.
bool send(UdpSend::Request &request, UdpSend::Response &)
ros::ServiceServer send_service_
ROS send service.
Implements the UDP methods for recieving and sending within the ROS ecosystem.
ros::NodeHandle node_handler_
ROS node handle.
ros::ServiceServer create_socket_service_
ROS socket creation service.
bool createSocket(UdpSocket::Request &request, UdpSocket::Response &response)
std::map< uint16_t, std::shared_ptr< UdpCom > > udp_sockets_
Map of all the created UDP Sockets.