brake_test_executor_node.cpp
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 #include <functional>
19 
20 #include <ros/ros.h>
21 #include <std_srvs/Trigger.h>
22 
24 
26 #include <prbt_hardware_support/SendBrakeTestResult.h>
27 #include <prbt_hardware_support/BrakeTest.h>
30 
31 static const std::string EXECUTE_BRAKETEST_SERVICE_NAME{ "/prbt/execute_braketest" };
32 static const std::string BRAKETEST_ADAPTER_SERVICE_NAME{ "/prbt/braketest_adapter_node/trigger_braketest" };
33 
34 static const std::string CONTROLLER_HOLD_MODE_SERVICE_NAME{ "/prbt/manipulator_joint_trajectory_controller/hold" };
35 static const std::string CONTROLLER_UNHOLD_MODE_SERVICE_NAME{ "/prbt/manipulator_joint_trajectory_controller/unhold" };
36 static const std::string BRAKE_TEST_RESULT_SERVICE_NAME{ "/prbt/send_brake_test_result" };
37 
38 using namespace prbt_hardware_support;
39 
43 int main(int argc, char** argv)
44 {
45  ros::init(argc, argv, "brake_test_executor");
46  ros::NodeHandle nh{ "~" };
47 
49  ros::ServiceClient hold_client = nh.serviceClient<std_srvs::Trigger>(CONTROLLER_HOLD_MODE_SERVICE_NAME);
50 
52  ros::ServiceClient brake_test_execute_client = nh.serviceClient<BrakeTest>(BRAKETEST_ADAPTER_SERVICE_NAME);
53 
55  ros::ServiceClient unhold_client = nh.serviceClient<std_srvs::Trigger>(CONTROLLER_UNHOLD_MODE_SERVICE_NAME);
56 
58  ros::ServiceClient brake_test_result_client = nh.serviceClient<SendBrakeTestResult>(BRAKE_TEST_RESULT_SERVICE_NAME);
59 
60  using std::placeholders::_1;
61  prbt_hardware_support::BrakeTestExecutor brake_test_executor(
63  std::bind(triggerServiceCall<ros::ServiceClient>, hold_client),
64  std::bind(executeBrakeTestCall<ros::ServiceClient>, brake_test_execute_client),
65  std::bind(triggerServiceCall<ros::ServiceClient>, unhold_client),
66  std::bind(sendBrakeTestResultCall<ros::ServiceClient>, brake_test_result_client, _1));
67 
68  ros::ServiceServer brake_test_srv =
69  nh.advertiseService(EXECUTE_BRAKETEST_SERVICE_NAME, &BrakeTestExecutor::executeBrakeTest, &brake_test_executor);
70 
71  ros::spin();
72 
73  return EXIT_FAILURE;
74 }
bool executeBrakeTest(pilz_msgs::BrakeTest::Request &req, pilz_msgs::BrakeTest::Response &response)
static const std::string BRAKE_TEST_RESULT_SERVICE_NAME
static bool detectRobotMotion(double timeout_s=DEFAULT_ROBOT_MOTION_TIMEOUT_S)
return true if a robot motion was detected, false otherwise.
int main(int argc, char **argv)
Provides service to execute a braketest.
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
static const std::string EXECUTE_BRAKETEST_SERVICE_NAME
Triggers execution of brake tests only if the controller is not executing a trajectory.
static constexpr double DEFAULT_ROBOT_MOTION_TIMEOUT_S
static void waitForService(const std::string service_name, const double retry_timeout=DEFAULT_RETRY_TIMEOUT, const double msg_output_period=DEFAULT_MSG_OUTPUT_PERIOD)
ROSCPP_DECL void spin()
static const std::string BRAKETEST_ADAPTER_SERVICE_NAME
static const std::string CONTROLLER_HOLD_MODE_SERVICE_NAME
static const std::string CONTROLLER_UNHOLD_MODE_SERVICE_NAME


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