brake_test_executor_node_service_calls.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2019 Pilz GmbH & Co. KG
3  *
4  * This program is free software: you can redistribute it and/or modify
5  * it under the terms of the GNU Lesser General Public License as published by
6  * the Free Software Foundation, either version 3 of the License, or
7  * (at your option) any later version.
8 
9  * This program is distributed in the hope that it will be useful,
10  * but WITHOUT ANY WARRANTY; without even the implied warranty of
11  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12  * GNU Lesser General Public License for more details.
13 
14  * You should have received a copy of the GNU Lesser General Public License
15  * along with this program. If not, see <http://www.gnu.org/licenses/>.
16  */
17 
18 #ifndef BRAKE_TEST_EXECUTOR_NODE_SERVICE_CALLS_H
19 #define BRAKE_TEST_EXECUTOR_NODE_SERVICE_CALLS_H
20 
21 #include <ros/ros.h>
22 #include <std_srvs/Trigger.h>
23 
24 #include <prbt_hardware_support/BrakeTest.h>
25 #include <prbt_hardware_support/SendBrakeTestResult.h>
26 
27 namespace prbt_hardware_support
28 {
29 template <class T>
30 static void triggerServiceCall(T& client)
31 {
32  ROS_DEBUG_STREAM("Calling service: " << client.getService() << ")");
33  std_srvs::Trigger srv;
34  if (!client.call(srv))
35  {
36  ROS_WARN_STREAM("Calling service " << client.getService() << " failed.");
37  return;
38  }
39 
40  if (!srv.response.success)
41  {
42  ROS_WARN_STREAM("Execution of service " << client.getService()
43  << " failed with error message\n:" << srv.response.message);
44  }
45 }
46 
47 template <class T>
48 static BrakeTest::Response executeBrakeTestCall(T& client)
49 {
50  ROS_DEBUG_STREAM("Calling service: " << client.getService() << ")");
51  BrakeTest srv;
52  if (!client.call(srv))
53  {
54  ROS_WARN_STREAM("Calling service " << client.getService() << " failed.");
55  BrakeTest::Response res;
56  res.success = false;
57  res.error_msg = "Failed to trigger brake test via service " + client.getService();
58  res.error_code.value = BrakeTestErrorCodes::TRIGGER_BRAKETEST_SERVICE_FAILURE;
59  return res;
60  }
61  return srv.response;
62 }
63 
64 template <class T>
65 static bool sendBrakeTestResultCall(T& client, const bool brake_test_result)
66 {
67  ROS_DEBUG_STREAM("Calling service: " << client.getService());
68  SendBrakeTestResult srv;
69  srv.request.result = brake_test_result;
70  return client.call(srv);
71 }
72 
73 } // namespace prbt_hardware_support
74 
75 #endif // BRAKE_TEST_EXECUTOR_NODE_SERVICE_CALLS_H
static bool sendBrakeTestResultCall(T &client, const bool brake_test_result)
#define ROS_WARN_STREAM(args)
#define ROS_DEBUG_STREAM(args)
static BrakeTest::Response executeBrakeTestCall(T &client)


prbt_hardware_support
Author(s):
autogenerated on Mon Feb 28 2022 23:14:34