config_server_node_main.cpp
Go to the documentation of this file.
1 // Copyright (c) 2021 Pilz GmbH & Co. KG
2 //
3 // This program is free software: you can redistribute it and/or modify
4 // it under the terms of the GNU Lesser General Public License as published by
5 // the Free Software Foundation, either version 3 of the License, or
6 // (at your option) any later version.
7 //
8 // This program is distributed in the hope that it will be useful,
9 // but WITHOUT ANY WARRANTY; without even the implied warranty of
10 // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
11 // GNU Lesser General Public License for more details.
12 //
13 // You should have received a copy of the GNU Lesser General Public License
14 // along with this program. If not, see <https://www.gnu.org/licenses/>.
15 
16 #include <ros/ros.h>
17 
20 
21 const std::string CONFIG_FILE{ "config_file" };
22 const std::string FRAME_ID{ "frame_id" };
23 
24 using namespace psen_scan_v2;
25 
26 int main(int argc, char** argv)
27 {
28  ros::init(argc, argv, "config_server_node");
29  ros::NodeHandle nh;
30  ros::NodeHandle pnh{ "~" };
31 
32  try
33  {
34  psen_scan_v2::ConfigServerNode config_server_node(nh,
35  getRequiredParamFromServer<std::string>(pnh, CONFIG_FILE).c_str(),
36  getRequiredParamFromServer<std::string>(pnh, FRAME_ID));
37 
38  ros::spin();
39  }
40  // LCOV_EXCL_START
41  catch (std::exception& e)
42  {
43  ROS_ERROR_STREAM(e.what());
44  }
45  // LCOV_EXCL_STOP
46 
47  return 0;
48 }
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
FRAME_ID
const std::string FRAME_ID
Definition: config_server_node_main.cpp:22
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros.h
config_server_node.h
ros_parameter_handler.h
psen_scan_v2::ConfigServerNode
ROS Node that publishes a latched topic containing the configured zonesets.
Definition: config_server_node.h:39
psen_scan_v2
Root namespace for the ROS part.
Definition: active_zoneset_node.h:29
CONFIG_FILE
const std::string CONFIG_FILE
Definition: config_server_node_main.cpp:21
main
int main(int argc, char **argv)
Definition: config_server_node_main.cpp:26
ros::spin
ROSCPP_DECL void spin()
psen_scan_v2_standalone::protocol_layer::scanner_events
Contains the events needed to define and implement the scanner protocol.
Definition: scanner_events.h:30
ros::NodeHandle


psen_scan_v2
Author(s): Pilz GmbH + Co. KG
autogenerated on Sat Jun 22 2024 02:46:11