udp_com-test.cpp
Go to the documentation of this file.
1 /*
2  Unit Test for the udp_com
3 
4 * Copyright (c) 2019, Evan Flynn
5 * All rights reserved.
6 */
7 
8 #include <gtest/gtest.h>
9 #include <vector>
10 // Example of calling a header file from the driver
11 #include "nodelet/nodelet.h"
12 #include "ros/ros.h"
13 #include "udp_com/UdpPacket.h"
14 #include "udp_com/UdpSend.h"
15 #include "udp_com/UdpSocket.h"
16 
20 auto createPacket = [](double length, uint8_t initialValue)
21 {
22  std::vector<uint8_t> packet(length, initialValue);
23  return packet;
24 };
25 
31 
32 TEST(UdpTestSuite, doesCreateSocketServiceExist)
33 {
34  ros::NodeHandle nh;
35  // TODO(uia75303): the path /eno1/udp/create_socket is dependent on the
36  // udp_com.test file if the udp_com node in that test file is launched in a
37  // different namespace this test will fail
38  ros::ServiceClient create_socket_client_ =
39  nh.serviceClient<udp_com::UdpSocket>("udp/create_socket");
40  // waits for 3 secs for service to exist
41  ASSERT_EQ(create_socket_client_.waitForExistence(ros::Duration(3)), true);
42 }
43 
44 TEST(UdpTestSuite, doesSendServiceExist)
45 {
46  ros::NodeHandle nh;
47  // TODO(uia75303): the path /eno1/udp/send is dependent on the udp_com.test
48  // file if the udp_com node in that test file is launched in a different
49  // namespace this test will fail
50  ros::ServiceClient send_service_client_ =
51  nh.serviceClient<udp_com::UdpSend>("udp/send");
52 
53  ASSERT_EQ(send_service_client_.waitForExistence(ros::Duration(3)), true);
54 }
55 
56 TEST(UdpTestSuite, testCreateSocketService)
57 {
58  ros::NodeHandle nh;
59  // TODO(uia75303): the path /eno1/udp/send is dependent on the udp_com.test
60  // file if the udp_com node in that test file is launched in a different
61  // namespace this test will fail
62  ros::ServiceClient create_socket_client_ =
63  nh.serviceClient<udp_com::UdpSocket>("/eno1/udp/create_socket");
64  udp_com::UdpSocket socket_request;
65 
66  // NOTE: this assumes the workstations IPv4 address is set to 127.0.0.1
67  // and that port 6000 is available
68  socket_request.request.srcAddress = "127.0.0.1";
69  socket_request.request.destAddress = "127.0.0.2";
70  socket_request.request.port = 54786;
71  socket_request.request.isMulticast = false;
72 
73  if (create_socket_client_.waitForExistence(ros::Duration(3)) == true)
74  {
75  ASSERT_EQ(create_socket_client_.call(socket_request), true);
76  }
77 }
78 
79 TEST(UdpTestSuite, testSendService)
80 {
81  ros::NodeHandle nh;
82  // TODO(uia75303): the path /eno1/udp/send is dependent on the udp_com.test
83  // file if the udp_com node in that test file is launched in a different
84  // namespace this test will fail
85  ros::ServiceClient send_service_client_ =
86  nh.serviceClient<udp_com::UdpSend>("/eno1/udp/send");
87  udp_com::UdpSend send_request;
88 
89  send_request.request.address = "127.0.0.2";
90  send_request.request.srcPort = 54786;
91  send_request.request.dstPort = 54786;
92  send_request.request.data = createPacket(10, 1);
93 
94  if (send_service_client_.waitForExistence(ros::Duration(3)) == true)
95  {
96  ASSERT_EQ(send_service_client_.call(send_request), true);
97  }
98 }
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
bool call(MReq &req, MRes &res)
auto createPacket
bool waitForExistence(ros::Duration timeout=ros::Duration(-1))
TEST(UdpTestSuite, doesCreateSocketServiceExist)


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