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 Types | |
using | ScannerId = psen_scan_v2_standalone::configuration::ScannerId |
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_zone_ |
std::unordered_map< ScannerId, ros::Publisher > | pubs_scan_ |
S | scanner_ |
std::atomic_bool | terminate_ { false } |
std::unordered_map< ScannerId, std::string > | tf_prefixes_ |
double | x_axis_rotation_ |
Friends | |
class | RosScannerNodeTests |
ROS Node that continuously publishes scan data of a single PSENscan laser scanner.
Definition at line 55 of file ros_scanner_node.h.
|
private |
Definition at line 87 of file ros_scanner_node.h.
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.
nh | Node handle for the ROS node on which the scanner topic is advertised. |
topic | Name of the ROS topic under which the scanner data are published. |
tf_prefix | Prefix for the frame ids. |
x_axis_rotation | Rotation of 2D scan around the z-axis. |
scanner_config | Scanner configuration. |
Definition at line 116 of file ros_scanner_node.h.
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
Definition at line 141 of file ros_scanner_node.h.
|
private |
Definition at line 171 of file ros_scanner_node.h.
void psen_scan_v2::ROSScannerNodeT< S >::run |
Continuously fetches data from the scanner and publishes the data into the ROS network.
std::runtime_error | if starting the scanner was not successful. |
Definition at line 196 of file ros_scanner_node.h.
void psen_scan_v2::ROSScannerNodeT< S >::terminate |
Terminates the fetching and publishing of scanner data.
Definition at line 190 of file ros_scanner_node.h.
|
friend |
Definition at line 98 of file ros_scanner_node.h.
|
private |
Definition at line 96 of file ros_scanner_node.h.
|
private |
Definition at line 86 of file ros_scanner_node.h.
|
private |
Definition at line 90 of file ros_scanner_node.h.
|
private |
Definition at line 89 of file ros_scanner_node.h.
|
private |
Definition at line 88 of file ros_scanner_node.h.
|
private |
Definition at line 93 of file ros_scanner_node.h.
|
private |
Definition at line 94 of file ros_scanner_node.h.
|
private |
Definition at line 91 of file ros_scanner_node.h.
|
private |
Definition at line 92 of file ros_scanner_node.h.