udp_com  1.1.1
Provides a flexible ROS driver for working with UDP interfaces
udp_com_nodelet.h
Go to the documentation of this file.
1 /*
8  * Copyright (c) 2015, Hunter Laux
9  * All rights reserved.
10  */
11 
12 #ifndef UDP_COM_NODELET_H
13 #define UDP_COM_NODELET_H
14 
15 #include <udp_com.h>
16 #include <map>
17 #include <memory>
18 #include <nodelet/nodelet.h>
19 #include <ros/console.h>
20 #include <ros/ros.h>
21 #include <udp_com/UdpPacket.h>
22 #include <udp_com/UdpSend.h>
23 #include <udp_com/UdpSocket.h>
24 
25 namespace udp_com
26 {
30 class UdpComNodelet : public nodelet::Nodelet
31 {
32 public:
37 
42 
48  void onInit();
49 
50 private:
52  ros::ServiceServer send_service_;
53 
55  ros::ServiceServer create_socket_service_;
56 
58  ros::NodeHandle node_handler_;
59 
61  std::map<uint16_t, std::shared_ptr<UdpCom>> udp_sockets_;
62 
71  bool send(UdpSend::Request &request, UdpSend::Response &);
72 
81  bool createSocket(UdpSocket::Request &request, UdpSocket::Response &response);
82 };
83 
84 } // namespace udp_com
85 
86 #endif // UDP_COM_NODELET_H
Implements the udp_com create_socket and send services.
Definition: udp_com_nodelet.h:31
ros::ServiceServer send_service_
ROS send service.
Definition: udp_com_nodelet.h:52
~UdpComNodelet()
Definition: udp_com_nodelet.h:41
bool createSocket(UdpSocket::Request &request, UdpSocket::Response &response)
Definition: udp_com_nodelet.cpp:40
bool send(UdpSend::Request &request, UdpSend::Response &)
Definition: udp_com_nodelet.cpp:79
ros::NodeHandle node_handler_
ROS node handle.
Definition: udp_com_nodelet.h:58
void onInit()
Definition: udp_com_nodelet.cpp:20
ros::ServiceServer create_socket_service_
ROS socket creation service.
Definition: udp_com_nodelet.h:55
UdpComNodelet()
Definition: udp_com_nodelet.h:36
std::map< uint16_t, std::shared_ptr< UdpCom > > udp_sockets_
Map of all the created UDP Sockets.
Definition: udp_com_nodelet.h:61
Implements the UDP methods for recieving and sending within the ROS ecosystem.