psen_scan_driver.cpp
Go to the documentation of this file.
1 // Copyright (c) 2019-2020 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 "psen_scan/scanner.h"
23 
24 using namespace psen_scan;
25 typedef std::unique_ptr<PSENscanUDPInterface> PSENscanUDPptr;
26 
27 int main(int argc, char** argv)
28 {
29  ros::init(argc, argv, "psen_scan_node");
30  ros::NodeHandle pnh("~");
31 
32  ROS_WARN("You are using an outdated version of psen_scan. Please update your scanner firmware and use the new "
33  "psen_scan_v2 package. See https://github.com/PilzDE/psen_scan_v2/#migration for detailed instruction.");
34 
35  try
36  {
37  psen_scan::RosParameterHandler param_handler(pnh);
38  PSENscanUDPptr udp_interface =
39  PSENscanUDPptr(new PSENscanUDPInterface(param_handler.getSensorIP(), param_handler.getHostUDPPort()));
40 
41  std::unique_ptr<Scanner> scanner = std::unique_ptr<Scanner>(new Scanner(param_handler.getSensorIP(),
42  param_handler.getHostIP(),
43  param_handler.getHostUDPPort(),
44  param_handler.getPassword(),
45  param_handler.getAngleStart(),
46  param_handler.getAngleEnd(),
47  std::move(udp_interface)));
48  ROSScannerNode ros_scanner_node(pnh,
50  param_handler.getFrameID(),
51  param_handler.getSkip(),
52  param_handler.getXAxisRotation(),
53  std::move(scanner));
54  ros_scanner_node.processingLoop();
55  }
56  catch (PSENScanFatalException& e)
57  {
58  std::cerr << e.what() << std::endl;
59  }
60  catch (std::exception& e)
61  {
62  std::cerr << e.what() << std::endl;
63  }
64 
65  return 0;
66 }
PSENscanInternalAngle getAngleEnd() const
Getter Method for angle_end_.
Class implements a ROS-Node for the PSENscan safety laser scanner.
static const std::string DEFAULT_PUBLISH_TOPIC
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
Degree getXAxisRotation() const
Getter Method for x_axis_rotation_.
#define ROS_WARN(...)
Class for getting ROS-Parameters from the parameter-server.
std::unique_ptr< PSENscanUDPInterface > PSENscanUDPptr
PSENscanInternalAngle getAngleStart() const
Getter Method for angle_start_.
std::string getSensorIP() const
Getter Method for sensor_ip_.
uint16_t getSkip() const
Getter method for skip_.
Class for Modeling a PSENscan safety laser scanner.
Definition: scanner.h:42
uint32_t getHostUDPPort() const
Getter method for host_udp_port_.
uint32_t getHostIP() const
Getter method for host_ip_.
std::string getPassword() const
Getter method for password_.
std::string getFrameID() const
Getter method for frame_id_.
void processingLoop()
endless loop for processing incoming UDP data from the laser scanner
int main(int argc, char **argv)
Class for the UDP communication with the scanner.


psen_scan
Author(s):
autogenerated on Mon Feb 28 2022 23:16:20