canopen_braketest_adapter.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 PRBT_HARDWARE_SUPPORT_CANOPEN_BRAKETEST_ADAPTER_H
19 #define PRBT_HARDWARE_SUPPORT_CANOPEN_BRAKETEST_ADAPTER_H
20 
21 #include <ros/ros.h>
22 
23 #include <string>
24 #include <utility>
25 
26 #include <canopen_chain_node/GetObject.h>
27 #include <canopen_chain_node/SetObject.h>
28 
29 #include <prbt_hardware_support/BrakeTest.h>
30 
31 namespace prbt_hardware_support
32 {
38 {
39 public:
41 
42 private:
43  using BrakeTestStatus = std::pair<int8_t, std::string>;
44 
45 private:
46  bool triggerBrakeTests(BrakeTest::Request& req, BrakeTest::Response& response);
47  void triggerBrakeTestForNode(const std::string& node_name);
48  BrakeTestStatus getBrakeTestStatusForNode(const std::string& node_name);
49  ros::Duration getBrakeTestDuration(const std::string& node_name);
50  void checkBrakeTestResultForNode(const std::string& node_name);
51  std::vector<std::string> getNodeNames();
52  ros::Duration getMaximumBrakeTestDuration(const std::vector<std::string>& node_names);
53 
54 private:
58 
61 };
62 
63 } // namespace prbt_hardware_support
64 #endif // PRBT_HARDWARE_SUPPORT_CANOPEN_BRAKETEST_ADAPTER_H
void checkBrakeTestResultForNode(const std::string &node_name)
BrakeTestStatus getBrakeTestStatusForNode(const std::string &node_name)
ros::Duration getMaximumBrakeTestDuration(const std::vector< std::string > &node_names)
ros::ServiceServer brake_test_srv_
Service which triggers brake tests for all joints.
bool triggerBrakeTests(BrakeTest::Request &req, BrakeTest::Response &response)
Executes the brake test for all joints. A brake test is triggered via service call.
void triggerBrakeTestForNode(const std::string &node_name)
ros::Duration getBrakeTestDuration(const std::string &node_name)


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