operation_mode_setup_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 <string>
19 
20 #include <ros/ros.h>
21 
22 #include <std_srvs/SetBool.h>
23 
24 #include <pilz_msgs/GetOperationMode.h>
25 
26 #include <pilz_utils/get_param.h>
28 
33 
34 static const std::string MONITOR_CARTESIAN_SPEED_SERVICE{ "manipulator_joint_trajectory_controller/"
35  "monitor_cartesian_speed" };
36 static const std::string OPERATION_MODE_TOPIC{ "operation_mode" };
37 static const std::string GET_SPEED_OVERRIDE_SERVICE{ "get_speed_override" };
38 
39 static constexpr uint32_t DEFAULT_QUEUE_SIZE{ 10 };
40 
41 using namespace prbt_hardware_support;
42 
47 // LCOV_EXCL_START
48 int main(int argc, char** argv)
49 {
50  ros::init(argc, argv, "operation_mode_setup_executor");
51  ros::NodeHandle nh;
52 
53  using std::placeholders::_1;
55  ros::ServiceClient monitor_cartesian_speed_srv = nh.serviceClient<std_srvs::SetBool>(MONITOR_CARTESIAN_SPEED_SERVICE);
56  MonitorCartesianSpeedFunc monitor_cartesian_speed_func =
57  std::bind(monitorCartesianSpeedSrv<ros::ServiceClient>, monitor_cartesian_speed_srv, _1);
58 
59  OperationModeSetupExecutor op_mode_executor(monitor_cartesian_speed_func);
60 
61  ros::Subscriber operation_mode_sub = nh.subscribe(
63 
64  ros::ServiceServer speed_override_srv =
66  ros::spin();
67 
68  return EXIT_FAILURE;
69 }
70 // LCOV_EXCL_STOP
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
bool getSpeedOverride(pilz_msgs::GetSpeedOverride::Request &, pilz_msgs::GetSpeedOverride::Response &response)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void updateOperationMode(const pilz_msgs::OperationModes &operation_mode)
Function to be called whenever a new operation mode is set.
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
int main(int argc, char **argv)
Read necessary parameters, start and initialize the prbt_hardware_support::OperationModeSetupExecutor...
static constexpr uint32_t DEFAULT_QUEUE_SIZE
static const std::string MONITOR_CARTESIAN_SPEED_SERVICE
static const std::string MONITOR_CARTESIAN_SPEED_SERVICE
Activates speed monitoring and sets the speed override based on the current operation mode...
static const std::string GET_SPEED_OVERRIDE_SERVICE
static void waitForService(const std::string service_name, const double retry_timeout=DEFAULT_RETRY_TIMEOUT, const double msg_output_period=DEFAULT_MSG_OUTPUT_PERIOD)
std::function< bool(const bool)> MonitorCartesianSpeedFunc
ROSCPP_DECL void spin()
static const std::string GET_SPEED_OVERRIDE_SERVICE
static const std::string OPERATION_MODE_TOPIC
static constexpr int DEFAULT_QUEUE_SIZE


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