psen_scan_driver.cpp
Go to the documentation of this file.
1 // Copyright (c) 2020-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 <functional>
17 #include <csignal>
18 #include <future>
19 #include <string>
20 
21 #include <ros/ros.h>
22 
28 
32 
35 
36 using namespace psen_scan_v2;
37 using namespace psen_scan_v2_standalone;
38 
39 std::function<void()> NODE_TERMINATE_CALLBACK;
40 
41 const std::string PARAM_HOST_IP{ "host_ip" };
42 const std::string PARAM_HOST_DATA_PORT{ "host_udp_port_data" };
43 const std::string PARAM_HOST_CONTROL_PORT{ "host_udp_port_control" };
44 const std::string PARAM_SCANNER_IP{ "sensor_ip" };
45 const std::string PARAM_TF_PREFIX{ "tf_prefix" };
46 const std::string PARAM_ANGLE_START{ "angle_start" };
47 const std::string PARAM_ANGLE_END{ "angle_end" };
48 const std::string PARAM_X_AXIS_ROTATION{ "x_axis_rotation" };
49 const std::string PARAM_FRAGMENTED_SCANS{ "fragmented_scans" };
50 const std::string PARAM_NR_SUBSCRIBERS{ "nr_subscribers" };
51 const std::string PARAM_INTENSITIES{ "intensities" };
52 const std::string PARAM_RESOLUTION{ "resolution" };
53 
54 static const std::string DEFAULT_TF_PREFIX = "laser_1";
55 
57 static const std::string DEFAULT_PUBLISH_TOPIC = "scan";
58 
60 {
62 
63  // Delay the shutdown() to get full debug output. Workaround for https://github.com/ros/ros_comm/issues/688
64  ros::Duration(0.2).sleep(); // TODO check if we can get rid of this sleep
65 
66  ros::shutdown();
67 }
68 
69 int main(int argc, char** argv)
70 {
71  ros::init(argc, argv, "psen_scan_v2_node");
72  ros::NodeHandle pnh("~");
73 
74  std::signal(SIGINT, delayed_shutdown_sig_handler);
75 
76  try
77  {
79  getOptionalParamFromServer<double>(
82  getOptionalParamFromServer<double>(
84 
85  ScannerConfiguration scanner_configuration{
86  ScannerConfigurationBuilder(getRequiredParamFromServer<std::string>(pnh, PARAM_SCANNER_IP))
87  .hostIP(getOptionalParamFromServer<std::string>(pnh, PARAM_HOST_IP, configuration::DEFAULT_HOST_IP_STRING))
88  .hostDataPort(
89  getOptionalParamFromServer<int>(pnh, PARAM_HOST_DATA_PORT, configuration::DATA_PORT_OF_HOST_DEVICE))
91  getOptionalParamFromServer<int>(pnh, PARAM_HOST_CONTROL_PORT, configuration::CONTROL_PORT_OF_HOST_DEVICE))
94  .scanRange(scan_range)
97  getOptionalParamFromServer<bool>(pnh, PARAM_FRAGMENTED_SCANS, configuration::FRAGMENTED_SCANS))
98  .nrSubscribers(getOptionalParamFromServer<int>(pnh, PARAM_NR_SUBSCRIBERS, configuration::NR_SUBSCRIBERS))
99  .enableIntensities(getOptionalParamFromServer<bool>(pnh, PARAM_INTENSITIES, configuration::INTENSITIES))
101  getOptionalParamFromServer<double>(pnh, PARAM_RESOLUTION, configuration::DEFAULT_SCAN_ANGLE_RESOLUTION)))
102  .build()
103  };
104 
105  if (scanner_configuration.fragmentedScansEnabled())
106  {
107  ROS_INFO("Using fragmented scans.");
108  }
109 
110  ROSScannerNode ros_scanner_node(pnh,
112  getOptionalParamFromServer<std::string>(pnh, PARAM_TF_PREFIX, DEFAULT_TF_PREFIX),
114  scanner_configuration);
115 
116  NODE_TERMINATE_CALLBACK = std::bind(&ROSScannerNode::terminate, &ros_scanner_node);
117 
118  ros_scanner_node.run();
119  }
120  catch (std::exception& e)
121  {
122  // The line below is needed since ROS_ERROR won't probably work during shutdown
123  std::cerr << "\x1B[91m" << e.what() << "\033[0m\n";
124  ROS_ERROR_STREAM(e.what());
125  return 1;
126  }
127 
128  return 0;
129 }
psen_scan_v2_standalone::configuration::DATA_PORT_OF_HOST_DEVICE
static constexpr unsigned short DATA_PORT_OF_HOST_DEVICE
Definition: default_parameters.h:32
function_pointers.h
scan_range.h
psen_scan_v2_standalone::ScannerConfigurationBuilder::hostIP
ScannerConfigurationBuilder & hostIP(const std::string &host_ip)
Definition: scanner_config_builder.h:82
PARAM_NR_SUBSCRIBERS
const std::string PARAM_NR_SUBSCRIBERS
Definition: psen_scan_driver.cpp:50
REGISTER_ROSCONSOLE_BRIDGE
REGISTER_ROSCONSOLE_BRIDGE
Definition: psen_scan_driver.cpp:34
psen_scan_v2_standalone::ScannerConfigurationBuilder::nrSubscribers
ScannerConfigurationBuilder & nrSubscribers(const uint8_t &nr_subscribers)
Definition: scanner_config_builder.h:156
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
psen_scan_v2::ROSScannerNodeT::terminate
void terminate()
Terminates the fetching and publishing of scanner data.
Definition: ros_scanner_node.h:190
psen_scan_v2::ROSScannerNodeT
ROS Node that continuously publishes scan data of a single PSENscan laser scanner.
Definition: ros_scanner_node.h:55
ros_scanner_node.h
ros.h
scanner_config_builder.h
psen_scan_v2_standalone::ScannerConfigurationBuilder::enableDiagnostics
ScannerConfigurationBuilder & enableDiagnostics(const bool &enable)
Definition: scanner_config_builder.h:138
psen_scan_v2_standalone::configuration::DEFAULT_SCAN_ANGLE_RESOLUTION
static constexpr double DEFAULT_SCAN_ANGLE_RESOLUTION(data_conversion_layer::degreeToRadian(0.1))
PARAM_SCANNER_IP
const std::string PARAM_SCANNER_IP
Definition: psen_scan_driver.cpp:44
psen_scan_v2_standalone::util::TenthOfDegree::fromRad
static TenthOfDegree fromRad(const double &angle_in_rad)
Definition: tenth_of_degree.h:37
scanner_configuration.h
ros::shutdown
ROSCPP_DECL void shutdown()
PARAM_INTENSITIES
const std::string PARAM_INTENSITIES
Definition: psen_scan_driver.cpp:51
delayed_shutdown_sig_handler
void delayed_shutdown_sig_handler(int sig)
Definition: psen_scan_driver.cpp:59
psen_scan_v2_standalone::configuration::DEFAULT_ANGLE_START
static constexpr double DEFAULT_ANGLE_START(-data_conversion_layer::degreeToRadian(137.4))
Start angle of measurement.
psen_scan_v2_standalone::ScannerConfigurationBuilder::scanRange
ScannerConfigurationBuilder & scanRange(const ScanRange &scan_range)
Definition: scanner_config_builder.h:121
psen_scan_v2_standalone::configuration::CONTROL_PORT_OF_HOST_DEVICE
static constexpr unsigned short CONTROL_PORT_OF_HOST_DEVICE
Definition: default_parameters.h:33
PARAM_HOST_CONTROL_PORT
const std::string PARAM_HOST_CONTROL_PORT
Definition: psen_scan_driver.cpp:43
ros_parameter_handler.h
psen_scan_v2_standalone::ScannerConfigurationBuilder::scanResolution
ScannerConfigurationBuilder & scanResolution(const util::TenthOfDegree &scan_resolution)
Definition: scanner_config_builder.h:128
psen_scan_v2_standalone::ScannerConfigurationBuilder::build
ScannerConfiguration build() const
Definition: scanner_config_builder.h:68
default_ros_parameters.h
psen_scan_v2_standalone::configuration::INTENSITIES
static constexpr bool INTENSITIES
Definition: default_parameters.h:36
PARAM_TF_PREFIX
const std::string PARAM_TF_PREFIX
Definition: psen_scan_driver.cpp:45
psen_scan_v2
Root namespace for the ROS part.
Definition: active_zoneset_node.h:29
psen_scan_v2_standalone::configuration::CONTROL_PORT_OF_SCANNER_DEVICE
static constexpr unsigned short CONTROL_PORT_OF_SCANNER_DEVICE
Definition: default_parameters.h:30
DEFAULT_PUBLISH_TOPIC
static const std::string DEFAULT_PUBLISH_TOPIC
Topic on which the LaserScan data are published.
Definition: psen_scan_driver.cpp:57
psen_scan_v2_standalone::ScannerConfigurationBuilder::scannerDataPort
ScannerConfigurationBuilder & scannerDataPort(const int &scanner_data_port)
Definition: scanner_config_builder.h:109
psen_scan_v2_standalone::configuration::DEFAULT_HOST_IP_STRING
static const std::string DEFAULT_HOST_IP_STRING
Definition: default_parameters.h:27
main
int main(int argc, char **argv)
Definition: psen_scan_driver.cpp:69
psen_scan_v2_standalone::ScannerConfigurationBuilder::enableIntensities
ScannerConfigurationBuilder & enableIntensities(const bool &enable)
Definition: scanner_config_builder.h:144
psen_scan_v2_standalone::ScannerConfigurationBuilder::scannerControlPort
ScannerConfigurationBuilder & scannerControlPort(const int &scanner_control_port)
Definition: scanner_config_builder.h:115
bridge.h
PARAM_HOST_IP
const std::string PARAM_HOST_IP
Definition: psen_scan_driver.cpp:41
psen_scan_v2_standalone::configuration::DEFAULT_ANGLE_END
static constexpr double DEFAULT_ANGLE_END(data_conversion_layer::degreeToRadian(137.4))
End angle of measurement.
psen_scan_v2::ROSScannerNodeT::run
void run()
Continuously fetches data from the scanner and publishes the data into the ROS network.
Definition: ros_scanner_node.h:196
default_parameters.h
PARAM_FRAGMENTED_SCANS
const std::string PARAM_FRAGMENTED_SCANS
Definition: psen_scan_driver.cpp:49
psen_scan_v2::DEFAULT_X_AXIS_ROTATION
static constexpr double DEFAULT_X_AXIS_ROTATION
The 2D scan will be rotated around the z-axis.
Definition: default_ros_parameters.h:24
psen_scan_v2_standalone::ScannerConfigurationBuilder
Helper class to simplify/improve the construction of the psen_scan_v2_standalone::ScannerConfiguratio...
Definition: scanner_config_builder.h:35
DEFAULT_TF_PREFIX
static const std::string DEFAULT_TF_PREFIX
Definition: psen_scan_driver.cpp:54
PARAM_RESOLUTION
const std::string PARAM_RESOLUTION
Definition: psen_scan_driver.cpp:52
PARAM_ANGLE_END
const std::string PARAM_ANGLE_END
Definition: psen_scan_driver.cpp:47
psen_scan_v2_standalone
Root namespace in which the software components to communicate with the scanner (firmware-version: 2)...
Definition: udp_client.h:41
NODE_TERMINATE_CALLBACK
std::function< void()> NODE_TERMINATE_CALLBACK
Definition: psen_scan_driver.cpp:39
PARAM_HOST_DATA_PORT
const std::string PARAM_HOST_DATA_PORT
Definition: psen_scan_driver.cpp:42
PARAM_X_AXIS_ROTATION
const std::string PARAM_X_AXIS_ROTATION
Definition: psen_scan_driver.cpp:48
psen_scan_v2_standalone::ScanRangeTemplated
Higher level data type storing the range in which the scanner takes measurements.
Definition: scan_range.h:31
psen_scan_v2_standalone::configuration::NR_SUBSCRIBERS
static constexpr unsigned short NR_SUBSCRIBERS
Definition: default_parameters.h:50
ros::Duration::sleep
bool sleep() const
psen_scan_v2_standalone::configuration::DATA_PORT_OF_SCANNER_DEVICE
static constexpr unsigned short DATA_PORT_OF_SCANNER_DEVICE
Definition: default_parameters.h:29
psen_scan_v2_standalone::ScannerConfigurationBuilder::enableFragmentedScans
ScannerConfigurationBuilder & enableFragmentedScans(const bool &enable)
Definition: scanner_config_builder.h:150
ROS_INFO
#define ROS_INFO(...)
psen_scan_v2_standalone::ScannerConfigurationBuilder::hostDataPort
ScannerConfigurationBuilder & hostDataPort(const int &host_data_port)
Definition: scanner_config_builder.h:91
psen_scan_v2_standalone::configuration::FRAGMENTED_SCANS
static constexpr bool FRAGMENTED_SCANS
Definition: default_parameters.h:35
ros::Duration
psen_scan_v2_standalone::protocol_layer::scanner_events
Contains the events needed to define and implement the scanner protocol.
Definition: scanner_events.h:30
PARAM_ANGLE_START
const std::string PARAM_ANGLE_START
Definition: psen_scan_driver.cpp:46
psen_scan_v2_standalone::ScannerConfigurationBuilder::hostControlPort
ScannerConfigurationBuilder & hostControlPort(const int &host_control_port)
Definition: scanner_config_builder.h:97
ros::NodeHandle
psen_scan_v2_standalone::ScannerConfiguration
Higher level data type storing the configuration details of the scanner like scanner IP,...
Definition: scanner_configuration.h:34


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