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 <pilz_utils/get_param.h>
24 
26 #include <prbt_hardware_support/SetSpeedLimit.h>
28 #include <prbt_hardware_support/GetOperationMode.h>
31 
32 static const std::string SET_SPEED_LIMIT_SERVICE{"set_speed_limit"};
33 static const std::string OPERATION_MODE_TOPIC{"operation_mode"};
34 static const std::string GET_SPEED_OVERRIDE_SERVICE{"get_speed_override"};
35 
36 static const std::string PARAM_SPEED_LIMIT_T1_STR {"speed_limit_t1"};
37 static const std::string PARAM_SPEED_LIMIT_AUTO_STR {"speed_limit_automatic"};
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 speed_limit_srv = nh.serviceClient<SetSpeedLimit>(SET_SPEED_LIMIT_SERVICE);
56  SetSpeedLimitFunc set_speed_limit_func = std::bind(setSpeedLimitSrv<ros::ServiceClient>,
57  speed_limit_srv, _1);
58 
59  double speed_limit_t1 {0};
60  double speed_limit_auto {0};
61  ros::NodeHandle pnh{"~"};
62  try
63  {
64  speed_limit_t1 = pilz_utils::getParam<double>(pnh, PARAM_SPEED_LIMIT_T1_STR);
65  speed_limit_auto = pilz_utils::getParam<double>(pnh, PARAM_SPEED_LIMIT_AUTO_STR);
66  }
67  catch (const std::runtime_error &ex)
68  {
69  ROS_ERROR_STREAM(ex.what());
70  return EXIT_FAILURE;
71  }
72 
73  OperationModeSetupExecutor op_mode_executor(speed_limit_t1, speed_limit_auto,
74  set_speed_limit_func);
75 
78  &op_mode_executor);
79 
82  &op_mode_executor);
83  ros::spin();
84 
85  return EXIT_FAILURE;
86 }
87 // LCOV_EXCL_STOP
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
static const std::string PARAM_SPEED_LIMIT_AUTO_STR
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
static const std::string SET_SPEED_LIMIT_SERVICE
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool getSpeedOverride(GetSpeedOverride::Request &, GetSpeedOverride::Response &response)
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
ROSCPP_DECL void spin(Spinner &spinner)
Sets the allowed speed limit for each frame based on the current operation mode.
static const std::string PARAM_SPEED_LIMIT_T1_STR
static void waitForService(const std::string service_name, const double retry_timeout=DEFAULT_RETRY_TIMEOUT, const double msg_output_period=DEFAULT_MSG_OUTPUT_PERIOD)
static const std::string GET_SPEED_OVERRIDE_SERVICE
std::function< bool(const double &)> SetSpeedLimitFunc
static const std::string OPERATION_MODE_TOPIC
static constexpr int DEFAULT_QUEUE_SIZE
#define ROS_ERROR_STREAM(args)
void updateOperationMode(const OperationModes &operation_mode)
Function to be called whenever a new operation mode is set.


prbt_hardware_support
Author(s):
autogenerated on Tue Feb 2 2021 03:50:17