Public Member Functions | Private Member Functions | Private Attributes | List of all members
sick::SickSafetyscannersRos Class Reference

The SickSafetyscannersRos class. More...

#include <SickSafetyscannersRos.h>

Public Member Functions

 SickSafetyscannersRos ()
 Constructor of the SickSafetyscannersRos. More...
 
virtual ~SickSafetyscannersRos ()
 ~SickSafetyscannersRos Destructor if the SickSafetyscanners ROS More...
 

Private Member Functions

sick_safetyscanners::ApplicationDataMsg createApplicationDataMessage (const sick::datastructure::Data &data)
 
sick_safetyscanners::ApplicationInputsMsg createApplicationInputsMessage (const sick::datastructure::Data &data)
 
sick_safetyscanners::ApplicationOutputsMsg createApplicationOutputsMessage (const sick::datastructure::Data &data)
 
sick_safetyscanners::DataHeaderMsg createDataHeaderMessage (const sick::datastructure::Data &data)
 
sick_safetyscanners::DerivedValuesMsg createDerivedValuesMessage (const sick::datastructure::Data &data)
 
sick_safetyscanners::ExtendedLaserScanMsg createExtendedLaserScanMessage (const sick::datastructure::Data &data)
 
sick_safetyscanners::GeneralSystemStateMsg createGeneralSystemStateMessage (const sick::datastructure::Data &data)
 
sick_safetyscanners::IntrusionDataMsg createIntrusionDataMessage (const sick::datastructure::Data &data)
 
std::vector< sick_safetyscanners::IntrusionDatumMsg > createIntrusionDatumMessageVector (const sick::datastructure::Data &data)
 
sensor_msgs::LaserScan createLaserScanMessage (const sick::datastructure::Data &data)
 
sick_safetyscanners::MeasurementDataMsg createMeasurementDataMessage (const sick::datastructure::Data &data)
 
sick_safetyscanners::OutputPathsMsg createOutputPathsMessage (const sick::datastructure::Data &data)
 
sick_safetyscanners::RawMicroScanDataMsg createRawDataMessage (const sick::datastructure::Data &data)
 
std::vector< sick_safetyscanners::ScanPointMsg > createScanPointMessageVector (const sick::datastructure::Data &data)
 
bool getFieldData (sick_safetyscanners::FieldData::Request &req, sick_safetyscanners::FieldData::Response &res)
 
std::vector< bool > getMedianReflectors (const std::vector< sick::datastructure::ScanPoint > scan_points)
 
bool isInitialised ()
 
bool readParameters ()
 Reads and verifies the ROS parameters. More...
 
void readPersistentConfig ()
 
void readTypeCodeSettings ()
 
void receivedUDPPacket (const datastructure::Data &data)
 Function which is called when a new complete UDP Packet is received. More...
 
void reconfigureCallback (const sick_safetyscanners::SickSafetyscannersConfigurationConfig &config, const uint32_t &level)
 Function which is triggered when a dynamic reconfiguration is performed. More...
 
void sensorDiagnostics (diagnostic_updater::DiagnosticStatusWrapper &diagnostic_status)
 

Private Attributes

float m_angle_offset
 
sick::datastructure::CommSettings m_communication_settings
 
std::shared_ptr< sick::SickSafetyscannersm_device
 
std::shared_ptr< DiagnosedLaserScanPublisherm_diagnosed_laser_scan_publisher
 
diagnostic_updater::Updater m_diagnostic_updater
 
dynamic_reconfigure::Server< sick_safetyscanners::SickSafetyscannersConfigurationConfig > m_dynamic_reconfiguration_server
 
double m_expected_frequency = 20.0
 
ros::Publisher m_extended_laser_scan_publisher
 
ros::ServiceServer m_field_service_server
 
std::string m_frame_id
 
double m_frequency_tolerance = 0.1
 
bool m_initialised
 
boost::asio::ip::address_v4 m_interface_ip
 
ros::Publisher m_laser_scan_publisher
 ROS topic publisher. More...
 
sick_safetyscanners::RawMicroScanDataMsg m_last_raw_data
 
double m_min_intensities = 0.0
 
ros::NodeHandle m_nh
 ROS node handle. More...
 
ros::Publisher m_output_path_publisher
 
ros::NodeHandle m_private_nh
 ROS private node handle. More...
 
double m_range_max
 
double m_range_min
 
ros::Publisher m_raw_data_publisher
 
double m_time_offset
 
double m_timestamp_max_acceptable = 1.0
 
double m_timestamp_min_acceptable = -1.0
 
bool m_use_pers_conf
 
bool m_use_sick_angles
 

Detailed Description

The SickSafetyscannersRos class.

Main class for the node to handle the ROS interfacing.

Definition at line 105 of file SickSafetyscannersRos.h.

Constructor & Destructor Documentation

sick::SickSafetyscannersRos::SickSafetyscannersRos ( )

Constructor of the SickSafetyscannersRos.

Constructor of the SickSafetyscannersRos, loads all parameters from the parameter server, initialises the dynamic reconfiguration server. Furthermore initialises the ROS Publishers for the different laserscan outputs.

Definition at line 41 of file SickSafetyscannersRos.cpp.

sick::SickSafetyscannersRos::~SickSafetyscannersRos ( )
virtual

~SickSafetyscannersRos Destructor if the SickSafetyscanners ROS

Definition at line 157 of file SickSafetyscannersRos.cpp.

Member Function Documentation

sick_safetyscanners::ApplicationDataMsg sick::SickSafetyscannersRos::createApplicationDataMessage ( const sick::datastructure::Data data)
private

Definition at line 677 of file SickSafetyscannersRos.cpp.

sick_safetyscanners::ApplicationInputsMsg sick::SickSafetyscannersRos::createApplicationInputsMessage ( const sick::datastructure::Data data)
private

Definition at line 690 of file SickSafetyscannersRos.cpp.

sick_safetyscanners::ApplicationOutputsMsg sick::SickSafetyscannersRos::createApplicationOutputsMessage ( const sick::datastructure::Data data)
private

Definition at line 723 of file SickSafetyscannersRos.cpp.

sick_safetyscanners::DataHeaderMsg sick::SickSafetyscannersRos::createDataHeaderMessage ( const sick::datastructure::Data data)
private

Definition at line 501 of file SickSafetyscannersRos.cpp.

sick_safetyscanners::DerivedValuesMsg sick::SickSafetyscannersRos::createDerivedValuesMessage ( const sick::datastructure::Data data)
private

Definition at line 529 of file SickSafetyscannersRos.cpp.

sick_safetyscanners::ExtendedLaserScanMsg sick::SickSafetyscannersRos::createExtendedLaserScanMessage ( const sick::datastructure::Data data)
private

Definition at line 343 of file SickSafetyscannersRos.cpp.

sick_safetyscanners::GeneralSystemStateMsg sick::SickSafetyscannersRos::createGeneralSystemStateMessage ( const sick::datastructure::Data data)
private

Definition at line 548 of file SickSafetyscannersRos.cpp.

sick_safetyscanners::IntrusionDataMsg sick::SickSafetyscannersRos::createIntrusionDataMessage ( const sick::datastructure::Data data)
private

Definition at line 641 of file SickSafetyscannersRos.cpp.

std::vector< sick_safetyscanners::IntrusionDatumMsg > sick::SickSafetyscannersRos::createIntrusionDatumMessageVector ( const sick::datastructure::Data data)
private

Definition at line 653 of file SickSafetyscannersRos.cpp.

sensor_msgs::LaserScan sick::SickSafetyscannersRos::createLaserScanMessage ( const sick::datastructure::Data data)
private

Definition at line 394 of file SickSafetyscannersRos.cpp.

sick_safetyscanners::MeasurementDataMsg sick::SickSafetyscannersRos::createMeasurementDataMessage ( const sick::datastructure::Data data)
private

Definition at line 599 of file SickSafetyscannersRos.cpp.

sick_safetyscanners::OutputPathsMsg sick::SickSafetyscannersRos::createOutputPathsMessage ( const sick::datastructure::Data data)
private

Definition at line 452 of file SickSafetyscannersRos.cpp.

sick_safetyscanners::RawMicroScanDataMsg sick::SickSafetyscannersRos::createRawDataMessage ( const sick::datastructure::Data data)
private

Definition at line 486 of file SickSafetyscannersRos.cpp.

std::vector< sick_safetyscanners::ScanPointMsg > sick::SickSafetyscannersRos::createScanPointMessageVector ( const sick::datastructure::Data data)
private

Definition at line 612 of file SickSafetyscannersRos.cpp.

bool sick::SickSafetyscannersRos::getFieldData ( sick_safetyscanners::FieldData::Request &  req,
sick_safetyscanners::FieldData::Response &  res 
)
private

Definition at line 781 of file SickSafetyscannersRos.cpp.

std::vector< bool > sick::SickSafetyscannersRos::getMedianReflectors ( const std::vector< sick::datastructure::ScanPoint scan_points)
private

Definition at line 368 of file SickSafetyscannersRos.cpp.

bool sick::SickSafetyscannersRos::isInitialised ( )
private

Definition at line 151 of file SickSafetyscannersRos.cpp.

bool sick::SickSafetyscannersRos::readParameters ( )
private

Reads and verifies the ROS parameters.

Returns
True if successful.

Definition at line 159 of file SickSafetyscannersRos.cpp.

void sick::SickSafetyscannersRos::readPersistentConfig ( )
private

Definition at line 108 of file SickSafetyscannersRos.cpp.

void sick::SickSafetyscannersRos::readTypeCodeSettings ( )
private

Definition at line 98 of file SickSafetyscannersRos.cpp.

void sick::SickSafetyscannersRos::receivedUDPPacket ( const datastructure::Data data)
private

Function which is called when a new complete UDP Packet is received.

Parameters
data,theassortment of all data from the sensor

Definition at line 259 of file SickSafetyscannersRos.cpp.

void sick::SickSafetyscannersRos::reconfigureCallback ( const sick_safetyscanners::SickSafetyscannersConfigurationConfig &  config,
const uint32_t &  level 
)
private

Function which is triggered when a dynamic reconfiguration is performed.

Parameters
configThe new configuration to set
levelLevel of the new configuration

Definition at line 117 of file SickSafetyscannersRos.cpp.

void sick::SickSafetyscannersRos::sensorDiagnostics ( diagnostic_updater::DiagnosticStatusWrapper diagnostic_status)
private

Definition at line 290 of file SickSafetyscannersRos.cpp.

Member Data Documentation

float sick::SickSafetyscannersRos::m_angle_offset
private

Definition at line 165 of file SickSafetyscannersRos.h.

sick::datastructure::CommSettings sick::SickSafetyscannersRos::m_communication_settings
private

Definition at line 148 of file SickSafetyscannersRos.h.

std::shared_ptr<sick::SickSafetyscanners> sick::SickSafetyscannersRos::m_device
private

Definition at line 146 of file SickSafetyscannersRos.h.

std::shared_ptr<DiagnosedLaserScanPublisher> sick::SickSafetyscannersRos::m_diagnosed_laser_scan_publisher
private

Definition at line 138 of file SickSafetyscannersRos.h.

diagnostic_updater::Updater sick::SickSafetyscannersRos::m_diagnostic_updater
private

Definition at line 137 of file SickSafetyscannersRos.h.

dynamic_reconfigure::Server<sick_safetyscanners::SickSafetyscannersConfigurationConfig> sick::SickSafetyscannersRos::m_dynamic_reconfiguration_server
private

Definition at line 152 of file SickSafetyscannersRos.h.

double sick::SickSafetyscannersRos::m_expected_frequency = 20.0
private

Definition at line 159 of file SickSafetyscannersRos.h.

ros::Publisher sick::SickSafetyscannersRos::m_extended_laser_scan_publisher
private

Definition at line 132 of file SickSafetyscannersRos.h.

ros::ServiceServer sick::SickSafetyscannersRos::m_field_service_server
private

Definition at line 142 of file SickSafetyscannersRos.h.

std::string sick::SickSafetyscannersRos::m_frame_id
private

Definition at line 154 of file SickSafetyscannersRos.h.

double sick::SickSafetyscannersRos::m_frequency_tolerance = 0.1
private

Definition at line 158 of file SickSafetyscannersRos.h.

bool sick::SickSafetyscannersRos::m_initialised
private

Definition at line 144 of file SickSafetyscannersRos.h.

boost::asio::ip::address_v4 sick::SickSafetyscannersRos::m_interface_ip
private

Definition at line 149 of file SickSafetyscannersRos.h.

ros::Publisher sick::SickSafetyscannersRos::m_laser_scan_publisher
private

ROS topic publisher.

Definition at line 131 of file SickSafetyscannersRos.h.

sick_safetyscanners::RawMicroScanDataMsg sick::SickSafetyscannersRos::m_last_raw_data
private

Definition at line 139 of file SickSafetyscannersRos.h.

double sick::SickSafetyscannersRos::m_min_intensities = 0.0
private

min intensities for laser points

Definition at line 162 of file SickSafetyscannersRos.h.

ros::NodeHandle sick::SickSafetyscannersRos::m_nh
private

ROS node handle.

Definition at line 125 of file SickSafetyscannersRos.h.

ros::Publisher sick::SickSafetyscannersRos::m_output_path_publisher
private

Definition at line 134 of file SickSafetyscannersRos.h.

ros::NodeHandle sick::SickSafetyscannersRos::m_private_nh
private

ROS private node handle.

Definition at line 128 of file SickSafetyscannersRos.h.

double sick::SickSafetyscannersRos::m_range_max
private

Definition at line 157 of file SickSafetyscannersRos.h.

double sick::SickSafetyscannersRos::m_range_min
private

Definition at line 156 of file SickSafetyscannersRos.h.

ros::Publisher sick::SickSafetyscannersRos::m_raw_data_publisher
private

Definition at line 133 of file SickSafetyscannersRos.h.

double sick::SickSafetyscannersRos::m_time_offset
private

Definition at line 155 of file SickSafetyscannersRos.h.

double sick::SickSafetyscannersRos::m_timestamp_max_acceptable = 1.0
private

Definition at line 161 of file SickSafetyscannersRos.h.

double sick::SickSafetyscannersRos::m_timestamp_min_acceptable = -1.0
private

Definition at line 160 of file SickSafetyscannersRos.h.

bool sick::SickSafetyscannersRos::m_use_pers_conf
private

Definition at line 166 of file SickSafetyscannersRos.h.

bool sick::SickSafetyscannersRos::m_use_sick_angles
private

Definition at line 164 of file SickSafetyscannersRos.h.


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


sick_safetyscanners
Author(s): Lennart Puck
autogenerated on Fri Apr 2 2021 02:45:42