udp_com_nodelet.cpp
Go to the documentation of this file.
1 /*
8  * Copyright (c) 2015, Hunter Laux
9  * All rights reserved.
10  */
11 
12 #include <memory>
13 #include <udp_com_nodelet.h>
15 
16 namespace udp_com
17 {
18 
19 
21 {
22  // Get private node handler
24 
25  // Advertize "send" service
27  "create_socket", &UdpComNodelet::createSocket, this);
30 }
31 
40 bool UdpComNodelet::createSocket(UdpSocket::Request &request,
41  UdpSocket::Response &)
42 {
43  ROS_INFO("Creating a UDP Socket for port: %i", request.port);
44  if (udp_sockets_.find(request.port) != udp_sockets_.end())
45  {
46  ROS_ERROR("Socket with port: %i already exists.. ", request.port);
47  if (udp_sockets_[request.port]->getIp() == request.srcAddress)
48  {
49  return true; // return true since socket exists
50  }
51  else
52  {
53  ROS_ERROR(
54  "Sockets with the same port but different source IP Addresses are "
55  "currently not supported. ");
56  }
57  }
58  try
59  {
60  ros::Publisher temp_pub = node_handler_.advertise<udp_com::UdpPacket>(
61  "p" + std::to_string(request.port), 1000);
62 
63  // Create the Socket
64  udp_sockets_[request.port] =
65  std::make_shared<UdpCom>(request.srcAddress, request.destAddress,
66  request.port, request.isMulticast, temp_pub);
67  return true;
68  }
69  catch (std::exception e)
70  {
71  return false;
72  }
73  catch (...)
74  {
75  return false;
76  }
77 }
78 
79 bool UdpComNodelet::send(UdpSend::Request &request,
80  UdpSend::Response &response)
81 {
82  ROS_DEBUG("sending data...");
83  size_t bytes_sent;
84  try
85  {
86  bytes_sent = udp_sockets_.at(request.srcPort)
87  ->send(request.data, request.address, request.dstPort);
88  }
89  catch (std::out_of_range e)
90  {
91  ROS_ERROR("Socket Requested was not found.");
92  response.socketCreated = false;
93  return false;
94  }
95  // No out of range error. Socket created
96  response.socketCreated = true;
97 
98  // Return true if data sent
99  if (bytes_sent > 0)
100  return true;
101  else
102  return false;
103 }
104 } // namespace udp_com
Implements the udp_com create_socket and send services.
PLUGINLIB_EXPORT_CLASS(udp_com::UdpComNodelet, nodelet::Nodelet)
bool send(UdpSend::Request &request, UdpSend::Response &)
ros::ServiceServer send_service_
ROS send service.
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
ros::NodeHandle & getPrivateNodeHandle() const
#define ROS_INFO(...)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::NodeHandle node_handler_
ROS node handle.
ros::ServiceServer create_socket_service_
ROS socket creation service.
Implements the create_socket and send ROS services.
bool createSocket(UdpSocket::Request &request, UdpSocket::Response &response)
#define ROS_ERROR(...)
#define ROS_DEBUG(...)
std::map< uint16_t, std::shared_ptr< UdpCom > > udp_sockets_
Map of all the created UDP Sockets.


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