alb_services_test.cpp
Go to the documentation of this file.
1 // Standard headers
2 #include <memory>
3 #include <thread>
4 
5 // GTest headers
6 #include <gtest/gtest.h>
7 
8 // ROS headers
9 #include "ros/ros.h"
10 #include "std_srvs/Trigger.h"
11 
12 // Local headers
13 #include "alb_common.h"
14 #include "alb_requester.h"
15 #include "outsight_alb_driver/AlbConfig.h"
16 #include "outsight_alb_driver/AlbFile.h"
17 
18 // Constant testing definition.
19 constexpr const char *k_invalid_service = "invalid_service";
20 
22 class AlbServicesTest : public ::testing::Test {
23  protected:
24  void SetUp() override
25  {
26  requester = std::make_unique<AlbRequester>(node);
27  }
28 
29  void TearDown() override
30  {
31  // Sleep to correctly delete the ROS services.
32  ros::Duration(0.5).sleep();
33  }
34 
36  void testServiceCall(const std::string &service_name)
37  {
38  // Check that the callback is called.
39  ASSERT_TRUE(ros::service::waitForService(service_name, ros::Duration(1)));
40  ASSERT_TRUE(ros::service::call(service_name, request, response));
41  }
42 
43  protected:
45  std::unique_ptr<AlbRequester> requester;
46  std_srvs::Trigger::Request request;
47  std_srvs::Trigger::Response response;
48 };
49 
51 TEST_F(AlbServicesTest, invalidService)
52 {
53  ASSERT_FALSE(ros::service::exists(k_invalid_service, true));
55  ASSERT_FALSE(ros::service::call(k_invalid_service, request, response));
56 }
57 
59 TEST_F(AlbServicesTest, processingServicesDefined)
60 {
65 }
66 
68 TEST_F(AlbServicesTest, processingServicesCalled)
69 {
70  testServiceCall(ALBCommon::k_alb_processing_restart);
71  testServiceCall(ALBCommon::k_alb_processing_stop);
72 }
73 
75 TEST_F(AlbServicesTest, processingConfigServicesCalled)
76 {
77  outsight_alb_driver::AlbConfig srv;
80 
83 }
84 
86 TEST_F(AlbServicesTest, storageServicesDefined)
87 {
91 }
92 
94 TEST_F(AlbServicesTest, storageServicesCalled)
95 {
96  outsight_alb_driver::AlbFile srv;
99 
102 
105 }
106 
107 int main(int argc, char **argv)
108 {
109  testing::InitGoogleTest(&argc, argv);
110  ros::init(argc, argv, "alb_services_test");
111 
112  std::thread t([] {
113  while (ros::ok()) {
114  ros::spin();
115  }
116  });
117 
118  auto res = RUN_ALL_TESTS();
119  ros::shutdown();
120 
121  return res;
122 }
response
const std::string response
ALBCommon::k_alb_processing_put_config
constexpr const char * k_alb_processing_put_config
Definition: alb_common.h:44
AlbServicesTest::request
std_srvs::Trigger::Request request
Definition: alb_services_test.cpp:46
ALBCommon::k_alb_storage_download
constexpr const char * k_alb_storage_download
Definition: alb_common.h:46
ros::service::exists
ROSCPP_DECL bool exists(const std::string &service_name, bool print_failure_reason)
ros::service::call
bool call(const std::string &service_name, MReq &req, MRes &res)
alb_requester.h
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
k_invalid_service
constexpr const char * k_invalid_service
Definition: alb_services_test.cpp:19
ALBCommon::k_alb_processing_restart
constexpr const char * k_alb_processing_restart
Definition: alb_common.h:41
ros.h
ros::shutdown
ROSCPP_DECL void shutdown()
ros::ok
ROSCPP_DECL bool ok()
TEST_F
TEST_F(AlbServicesTest, invalidService)
Test to check that invalid service call should fail.
Definition: alb_services_test.cpp:51
alb_common.h
AlbServicesTest::requester
std::unique_ptr< AlbRequester > requester
Definition: alb_services_test.cpp:45
ALBCommon::k_alb_storage_list
constexpr const char * k_alb_storage_list
Definition: alb_common.h:48
AlbServicesTest::TearDown
void TearDown() override
Definition: alb_services_test.cpp:29
AlbServicesTest::testServiceCall
void testServiceCall(const std::string &service_name)
Function to check if a service can be called.
Definition: alb_services_test.cpp:36
ALBCommon::k_alb_storage_upload
constexpr const char * k_alb_storage_upload
Definition: alb_common.h:47
ALBCommon::k_alb_processing_get_config
constexpr const char * k_alb_processing_get_config
Definition: alb_common.h:43
AlbServicesTest::response
std_srvs::Trigger::Response response
Definition: alb_services_test.cpp:47
ros::service::waitForService
ROSCPP_DECL bool waitForService(const std::string &service_name, int32_t timeout)
ALBCommon::k_alb_processing_stop
constexpr const char * k_alb_processing_stop
Definition: alb_common.h:42
ros::spin
ROSCPP_DECL void spin()
ros::Duration::sleep
bool sleep() const
AlbServicesTest
Class to test the ALB services.
Definition: alb_services_test.cpp:22
ros::Duration
main
int main(int argc, char **argv)
Definition: alb_services_test.cpp:107
AlbServicesTest::node
ros::NodeHandle node
Definition: alb_services_test.cpp:44
t
geometry_msgs::TransformStamped t
AlbServicesTest::SetUp
void SetUp() override
Definition: alb_services_test.cpp:24
ros::NodeHandle


outsight_alb_driver
Author(s): Outsight
autogenerated on Thu Oct 13 2022 02:21:45