Public Member Functions | Private Member Functions | Private Attributes | Friends | List of all members
psen_scan_v2::ROSScannerNodeT< S > Class Template Reference

ROS Node that continuously publishes scan data of a single PSENscan laser scanner. More...

#include <ros_scanner_node.h>

Public Member Functions

 ROSScannerNodeT (ros::NodeHandle &nh, const std::string &topic, const std::string &tf_prefix, const double &x_axis_rotation, const ScannerConfiguration &scanner_config)
 Constructor. More...
 
void run ()
 Continuously fetches data from the scanner and publishes the data into the ROS network. More...
 
void terminate ()
 Terminates the fetching and publishing of scanner data. More...
 

Private Member Functions

 FRIEND_TEST (RosScannerNodeTests, shouldLogChangedIOStates)
 
 FRIEND_TEST (RosScannerNodeTests, shouldProvideActiveZonesetTopic)
 
 FRIEND_TEST (RosScannerNodeTests, shouldProvideScanTopic)
 
 FRIEND_TEST (RosScannerNodeTests, shouldPublishActiveZonesetWhenLaserScanCallbackIsInvoked)
 
 FRIEND_TEST (RosScannerNodeTests, shouldPublishChangedIOStatesEqualToConversionOfSuppliedStandaloneIOStates)
 
 FRIEND_TEST (RosScannerNodeTests, shouldPublishLatchedOnIOStatesTopic)
 
 FRIEND_TEST (RosScannerNodeTests, shouldPublishScanEqualToConversionOfSuppliedLaserScan)
 
 FRIEND_TEST (RosScannerNodeTests, shouldPublishScansWhenLaserScanCallbackIsInvoked)
 
 FRIEND_TEST (RosScannerNodeTests, shouldStartAndStopSuccessfullyIfScannerRespondsToRequests)
 
 FRIEND_TEST (RosScannerNodeTests, shouldThrowExceptionSetInScannerStartFuture)
 
 FRIEND_TEST (RosScannerNodeTests, shouldThrowExceptionSetInScannerStopFuture)
 
 FRIEND_TEST (RosScannerNodeTests, shouldWaitWhenStopRequestResponseIsMissing)
 
void laserScanCallback (const LaserScan &scan)
 
void publishChangedIOStates (const std::vector< psen_scan_v2_standalone::IOState > &io_states)
 

Private Attributes

psen_scan_v2_standalone::IOState last_io_state_ {}
 
ros::NodeHandle nh_
 
ros::Publisher pub_io_
 
ros::Publisher pub_scan_
 
ros::Publisher pub_zone_
 
scanner_
 
std::atomic_bool terminate_ { false }
 
std::string tf_prefix_
 
double x_axis_rotation_
 

Friends

class RosScannerNodeTests
 

Detailed Description

template<typename S = ScannerV2>
class psen_scan_v2::ROSScannerNodeT< S >

ROS Node that continuously publishes scan data of a single PSENscan laser scanner.

Definition at line 54 of file ros_scanner_node.h.

Constructor & Destructor Documentation

◆ ROSScannerNodeT()

template<typename S >
psen_scan_v2::ROSScannerNodeT< S >::ROSScannerNodeT ( ros::NodeHandle nh,
const std::string &  topic,
const std::string &  tf_prefix,
const double &  x_axis_rotation,
const ScannerConfiguration scanner_config 
)

Constructor.

Parameters
nhNode handle for the ROS node on which the scanner topic is advertised.
topicName of the ROS topic under which the scanner data are published.
tf_prefixPrefix for the frame ids.
x_axis_rotationRotation of 2D scan around the z-axis.
scanner_configScanner configuration.

Definition at line 114 of file ros_scanner_node.h.

Member Function Documentation

◆ FRIEND_TEST() [1/12]

template<typename S = ScannerV2>
psen_scan_v2::ROSScannerNodeT< S >::FRIEND_TEST ( RosScannerNodeTests  ,
shouldLogChangedIOStates   
)
private

◆ FRIEND_TEST() [2/12]

template<typename S = ScannerV2>
psen_scan_v2::ROSScannerNodeT< S >::FRIEND_TEST ( RosScannerNodeTests  ,
shouldProvideActiveZonesetTopic   
)
private

◆ FRIEND_TEST() [3/12]

template<typename S = ScannerV2>
psen_scan_v2::ROSScannerNodeT< S >::FRIEND_TEST ( RosScannerNodeTests  ,
shouldProvideScanTopic   
)
private

◆ FRIEND_TEST() [4/12]

template<typename S = ScannerV2>
psen_scan_v2::ROSScannerNodeT< S >::FRIEND_TEST ( RosScannerNodeTests  ,
shouldPublishActiveZonesetWhenLaserScanCallbackIsInvoked   
)
private

◆ FRIEND_TEST() [5/12]

template<typename S = ScannerV2>
psen_scan_v2::ROSScannerNodeT< S >::FRIEND_TEST ( RosScannerNodeTests  ,
shouldPublishChangedIOStatesEqualToConversionOfSuppliedStandaloneIOStates   
)
private

◆ FRIEND_TEST() [6/12]

template<typename S = ScannerV2>
psen_scan_v2::ROSScannerNodeT< S >::FRIEND_TEST ( RosScannerNodeTests  ,
shouldPublishLatchedOnIOStatesTopic   
)
private

◆ FRIEND_TEST() [7/12]

template<typename S = ScannerV2>
psen_scan_v2::ROSScannerNodeT< S >::FRIEND_TEST ( RosScannerNodeTests  ,
shouldPublishScanEqualToConversionOfSuppliedLaserScan   
)
private

◆ FRIEND_TEST() [8/12]

template<typename S = ScannerV2>
psen_scan_v2::ROSScannerNodeT< S >::FRIEND_TEST ( RosScannerNodeTests  ,
shouldPublishScansWhenLaserScanCallbackIsInvoked   
)
private

◆ FRIEND_TEST() [9/12]

template<typename S = ScannerV2>
psen_scan_v2::ROSScannerNodeT< S >::FRIEND_TEST ( RosScannerNodeTests  ,
shouldStartAndStopSuccessfullyIfScannerRespondsToRequests   
)
private

◆ FRIEND_TEST() [10/12]

template<typename S = ScannerV2>
psen_scan_v2::ROSScannerNodeT< S >::FRIEND_TEST ( RosScannerNodeTests  ,
shouldThrowExceptionSetInScannerStartFuture   
)
private

◆ FRIEND_TEST() [11/12]

template<typename S = ScannerV2>
psen_scan_v2::ROSScannerNodeT< S >::FRIEND_TEST ( RosScannerNodeTests  ,
shouldThrowExceptionSetInScannerStopFuture   
)
private

◆ FRIEND_TEST() [12/12]

template<typename S = ScannerV2>
psen_scan_v2::ROSScannerNodeT< S >::FRIEND_TEST ( RosScannerNodeTests  ,
shouldWaitWhenStopRequestResponseIsMissing   
)
private

◆ laserScanCallback()

template<typename S >
void psen_scan_v2::ROSScannerNodeT< S >::laserScanCallback ( const LaserScan scan)
private

Definition at line 130 of file ros_scanner_node.h.

◆ publishChangedIOStates()

template<typename S >
void psen_scan_v2::ROSScannerNodeT< S >::publishChangedIOStates ( const std::vector< psen_scan_v2_standalone::IOState > &  io_states)
private

Definition at line 159 of file ros_scanner_node.h.

◆ run()

template<typename S >
void psen_scan_v2::ROSScannerNodeT< S >::run

Continuously fetches data from the scanner and publishes the data into the ROS network.

Exceptions
std::runtime_errorif starting the scanner was not successful.

Definition at line 183 of file ros_scanner_node.h.

◆ terminate()

template<typename S >
void psen_scan_v2::ROSScannerNodeT< S >::terminate

Terminates the fetching and publishing of scanner data.

Definition at line 177 of file ros_scanner_node.h.

Friends And Related Function Documentation

◆ RosScannerNodeTests

template<typename S = ScannerV2>
friend class RosScannerNodeTests
friend

Definition at line 96 of file ros_scanner_node.h.

Member Data Documentation

◆ last_io_state_

template<typename S = ScannerV2>
psen_scan_v2_standalone::IOState psen_scan_v2::ROSScannerNodeT< S >::last_io_state_ {}
private

Definition at line 94 of file ros_scanner_node.h.

◆ nh_

template<typename S = ScannerV2>
ros::NodeHandle psen_scan_v2::ROSScannerNodeT< S >::nh_
private

Definition at line 85 of file ros_scanner_node.h.

◆ pub_io_

template<typename S = ScannerV2>
ros::Publisher psen_scan_v2::ROSScannerNodeT< S >::pub_io_
private

Definition at line 88 of file ros_scanner_node.h.

◆ pub_scan_

template<typename S = ScannerV2>
ros::Publisher psen_scan_v2::ROSScannerNodeT< S >::pub_scan_
private

Definition at line 86 of file ros_scanner_node.h.

◆ pub_zone_

template<typename S = ScannerV2>
ros::Publisher psen_scan_v2::ROSScannerNodeT< S >::pub_zone_
private

Definition at line 87 of file ros_scanner_node.h.

◆ scanner_

template<typename S = ScannerV2>
S psen_scan_v2::ROSScannerNodeT< S >::scanner_
private

Definition at line 91 of file ros_scanner_node.h.

◆ terminate_

template<typename S = ScannerV2>
std::atomic_bool psen_scan_v2::ROSScannerNodeT< S >::terminate_ { false }
private

Definition at line 92 of file ros_scanner_node.h.

◆ tf_prefix_

template<typename S = ScannerV2>
std::string psen_scan_v2::ROSScannerNodeT< S >::tf_prefix_
private

Definition at line 89 of file ros_scanner_node.h.

◆ x_axis_rotation_

template<typename S = ScannerV2>
double psen_scan_v2::ROSScannerNodeT< S >::x_axis_rotation_
private

Definition at line 90 of file ros_scanner_node.h.


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


psen_scan_v2
Author(s): Pilz GmbH + Co. KG
autogenerated on Sat Nov 25 2023 03:46:26