Public Member Functions | Private Attributes | List of all members
psen_scan::ROSScannerNode Class Reference

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< vScannerscanner_
 
uint16_t skip_
 
Degree x_axis_rotation_
 

Detailed Description

Class implements a ROS-Node for the PSENscan safety laser scanner.

Definition at line 30 of file ros_scanner_node.h.

Constructor & Destructor Documentation

◆ ROSScannerNode()

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.

Parameters
nhnode handle for the ROS node
topicname of the ROS topic
frame_idname of the frame id
skipskip certain number of frames, reduces publish rate
scannerpointer ot an instance of the class Scanner

Definition at line 35 of file ros_scanner_node.cpp.

Member Function Documentation

◆ buildRosMessage()

sensor_msgs::LaserScan psen_scan::ROSScannerNode::buildRosMessage ( const LaserScan laserscan)

Creates a ROS message from an LaserScan, which contains one scanning round.

Parameters
laserscan
Returns
sensor_msgs::LaserScan, ROS message, ready to be published
Exceptions
BuildROSMessageException

Definition at line 73 of file ros_scanner_node.cpp.

◆ processingLoop()

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.

Member Data Documentation

◆ frame_id_

std::string psen_scan::ROSScannerNode::frame_id_
private

Defines the name of the frame_id. Default is scanner.

Definition at line 45 of file ros_scanner_node.h.

◆ nh_

ros::NodeHandle psen_scan::ROSScannerNode::nh_
private

ROS Node handler

Definition at line 43 of file ros_scanner_node.h.

◆ pub_

ros::Publisher psen_scan::ROSScannerNode::pub_
private

ROS message publisher

Definition at line 44 of file ros_scanner_node.h.

◆ scanner_

std::unique_ptr<vScanner> psen_scan::ROSScannerNode::scanner_
private

Points to an instance of the Scanner class.

Definition at line 47 of file ros_scanner_node.h.

◆ skip_

uint16_t psen_scan::ROSScannerNode::skip_
private

Skip certain number of frames. Reduces publish rate.

Definition at line 46 of file ros_scanner_node.h.

◆ x_axis_rotation_

Degree psen_scan::ROSScannerNode::x_axis_rotation_
private

X-axis rotation.

Definition at line 48 of file ros_scanner_node.h.


The documentation for this class was generated from the following files:


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