Class implements a ROS-Node for the PSENscan safety laser scanner. More...
#include <ros_scanner_node.h>
Public Member Functions | |
sensor_msgs::LaserScan | buildRosMessage (const LaserScan &laserscan) |
Creates a ROS message from an LaserScan, which contains one scanning round. More... | |
void | processingLoop () |
endless loop for processing incoming UDP data from the laser scanner More... | |
ROSScannerNode (ros::NodeHandle &nh, const std::string &topic, const std::string &frame_id, const uint16_t &skip, const Degree &x_axis_rotation, std::unique_ptr< vScanner > scanner) | |
Construct a new ROSScannerNode::ROSScannerNode object. More... | |
Private Attributes | |
std::string | frame_id_ |
ros::NodeHandle | nh_ |
ros::Publisher | pub_ |
std::unique_ptr< vScanner > | scanner_ |
uint16_t | skip_ |
Degree | x_axis_rotation_ |
Class implements a ROS-Node for the PSENscan safety laser scanner.
Definition at line 30 of file ros_scanner_node.h.
psen_scan::ROSScannerNode::ROSScannerNode | ( | ros::NodeHandle & | nh, |
const std::string & | topic, | ||
const std::string & | frame_id, | ||
const uint16_t & | skip, | ||
const Degree & | x_axis_rotation, | ||
std::unique_ptr< vScanner > | scanner | ||
) |
Construct a new ROSScannerNode::ROSScannerNode object.
nh | node handle for the ROS node |
topic | name of the ROS topic |
frame_id | name of the frame id |
skip | skip certain number of frames, reduces publish rate |
scanner | pointer ot an instance of the class Scanner |
Definition at line 35 of file ros_scanner_node.cpp.
sensor_msgs::LaserScan psen_scan::ROSScannerNode::buildRosMessage | ( | const LaserScan & | laserscan | ) |
Creates a ROS message from an LaserScan, which contains one scanning round.
laserscan |
BuildROSMessageException |
Definition at line 73 of file ros_scanner_node.cpp.
void psen_scan::ROSScannerNode::processingLoop | ( | ) |
endless loop for processing incoming UDP data from the laser scanner
Definition at line 113 of file ros_scanner_node.cpp.
|
private |
Defines the name of the frame_id. Default is scanner.
Definition at line 45 of file ros_scanner_node.h.
|
private |
ROS Node handler
Definition at line 43 of file ros_scanner_node.h.
|
private |
ROS message publisher
Definition at line 44 of file ros_scanner_node.h.
|
private |
Points to an instance of the Scanner class.
Definition at line 47 of file ros_scanner_node.h.
|
private |
Skip certain number of frames. Reduces publish rate.
Definition at line 46 of file ros_scanner_node.h.
|
private |
X-axis rotation.
Definition at line 48 of file ros_scanner_node.h.