operation_mode_setup_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 OPERATION_MODE_SETUP_EXECUTOR_NODE_SERVICE_CALLS_H
19 #define OPERATION_MODE_SETUP_EXECUTOR_NODE_SERVICE_CALLS_H
20 
21 #include <ros/ros.h>
22 
23 #include <std_srvs/SetBool.h>
24 
25 namespace prbt_hardware_support
26 {
27 template <class T>
28 static bool monitorCartesianSpeedSrv(T& srv_client, const bool active)
29 {
30  std_srvs::SetBool srv_msg;
31  srv_msg.request.data = active;
32  bool call_success = srv_client.call(srv_msg);
33  if (!call_success)
34  {
35  ROS_ERROR_STREAM("No success calling service: " << srv_client.getService());
36  }
37  return call_success;
38 }
39 
40 } // namespace prbt_hardware_support
41 
42 #endif // OPERATION_MODE_SETUP_EXECUTOR_NODE_SERVICE_CALLS_H
#define ROS_ERROR_STREAM(args)
static bool monitorCartesianSpeedSrv(T &srv_client, const bool active)


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