fake_speed_override_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 <atomic>
19 
20 #include <ros/ros.h>
21 
22 #include <dynamic_reconfigure/server.h>
23 #include <pilz_msgs/GetSpeedOverride.h>
24 #include <prbt_hardware_support/FakeSpeedOverrideConfig.h>
25 
26 std::atomic<double> SPEED_OVERRIDE{ 1.0 };
27 
28 void dynamic_set_speed_override(prbt_hardware_support::FakeSpeedOverrideConfig& config, uint32_t level)
29 {
30  ROS_INFO("Reconfigure Request: %f", config.speed_override);
31  SPEED_OVERRIDE = config.speed_override;
32 }
33 
34 bool getSpeedOverride(pilz_msgs::GetSpeedOverride::Request& /*req*/, pilz_msgs::GetSpeedOverride::Response& res)
35 {
36  res.speed_override = SPEED_OVERRIDE;
37  return true;
38 }
39 
40 int main(int argc, char** argv)
41 {
42  ros::init(argc, argv, "fake_speed_override");
44 
45  ros::ServiceServer service = n.advertiseService("/prbt/get_speed_override", getSpeedOverride);
46 
47  dynamic_reconfigure::Server<prbt_hardware_support::FakeSpeedOverrideConfig> server;
48  dynamic_reconfigure::Server<prbt_hardware_support::FakeSpeedOverrideConfig>::CallbackType f;
49 
50  f = boost::bind(&dynamic_set_speed_override, _1, _2);
51  server.setCallback(f);
52 
53  ros::spin();
54  return 0;
55 }
f
void dynamic_set_speed_override(prbt_hardware_support::FakeSpeedOverrideConfig &config, uint32_t level)
int main(int argc, char **argv)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool getSpeedOverride(pilz_msgs::GetSpeedOverride::Request &, pilz_msgs::GetSpeedOverride::Response &res)
std::atomic< double > SPEED_OVERRIDE
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
#define ROS_INFO(...)
ROSCPP_DECL void spin()


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