SickSafetyscannersRos.h
Go to the documentation of this file.
1 // this is for emacs file handling -*- mode: c++; indent-tabs-mode: nil -*-
2 
3 // -- BEGIN LICENSE BLOCK ----------------------------------------------
4 
24 // -- END LICENSE BLOCK ------------------------------------------------
25 
26 //----------------------------------------------------------------------
33 //----------------------------------------------------------------------
34 
35 #ifndef SICK_SAFETYSCANNERS_SICKSAFETYSCANNERSROS_H
36 #define SICK_SAFETYSCANNERS_SICKSAFETYSCANNERSROS_H
37 
38 
39 // ROS
40 #include <ros/ros.h>
41 #include <sensor_msgs/JointState.h>
42 #include <sensor_msgs/LaserScan.h>
43 
44 // STD
45 #include <string>
46 #include <vector>
47 
48 // Package
49 #include <sick_safetyscanners/ExtendedLaserScanMsg.h>
50 #include <sick_safetyscanners/FieldData.h>
51 #include <sick_safetyscanners/OutputPathsMsg.h>
52 #include <sick_safetyscanners/RawMicroScanDataMsg.h>
54 #include <sick_safetyscanners/SickSafetyscannersConfigurationConfig.h>
57 
58 #include <dynamic_reconfigure/server.h>
59 
60 #include <cmath>
61 
62 namespace sick {
63 
69 inline float degToRad(float deg)
70 {
71  return deg * M_PI / 180.0f;
72 }
73 
79 inline float radToDeg(float rad)
80 {
81  return rad * 180.0f / M_PI;
82 }
83 
91 inline uint16_t skipToPublishFrequency(int skip)
92 {
93  return skip + 1;
94 }
95 
102 {
103 public:
112 
117  virtual ~SickSafetyscannersRos();
118 
119 private:
122 
125 
131 
133 
135 
136  std::shared_ptr<sick::SickSafetyscanners> m_device;
137 
139 
140  dynamic_reconfigure::Server<sick_safetyscanners::SickSafetyscannersConfigurationConfig>
142 
143  std::string m_frame_id;
145  double m_range_min;
146  double m_range_max;
147 
151 
156  bool readParameters();
157 
162  void receivedUDPPacket(const datastructure::Data& data);
163 
169  void
170  reconfigure_callback(const sick_safetyscanners::SickSafetyscannersConfigurationConfig& config,
171  const uint32_t& level);
172 
173  bool isInitialised();
174 
175  sensor_msgs::LaserScan createLaserScanMessage(const sick::datastructure::Data& data);
176  sick_safetyscanners::ExtendedLaserScanMsg
178  std::vector<bool>
179  getMedianReflectors(const std::vector<sick::datastructure::ScanPoint> scan_points);
180  sick_safetyscanners::OutputPathsMsg
182  sick_safetyscanners::RawMicroScanDataMsg
184  sick_safetyscanners::DataHeaderMsg createDataHeaderMessage(const sick::datastructure::Data& data);
185  sick_safetyscanners::DerivedValuesMsg
187  sick_safetyscanners::GeneralSystemStateMsg
189  sick_safetyscanners::MeasurementDataMsg
191  std::vector<sick_safetyscanners::ScanPointMsg>
193  sick_safetyscanners::IntrusionDataMsg
195  std::vector<sick_safetyscanners::IntrusionDatumMsg>
197  sick_safetyscanners::ApplicationDataMsg
199  sick_safetyscanners::ApplicationInputsMsg
201  sick_safetyscanners::ApplicationOutputsMsg
203  void readTypeCodeSettings();
204  void readPersistentConfig();
205 
206  bool getFieldData(sick_safetyscanners::FieldData::Request& req,
207  sick_safetyscanners::FieldData::Response& res);
208 };
209 
210 } // namespace sick
211 
212 #endif // SICK_SAFETYSCANNERS_SICKSAFETYSCANNERSROS_H
sick_safetyscanners::ApplicationOutputsMsg createApplicationOutputsMessage(const sick::datastructure::Data &data)
sick_safetyscanners::MeasurementDataMsg createMeasurementDataMessage(const sick::datastructure::Data &data)
sick_safetyscanners::DataHeaderMsg createDataHeaderMessage(const sick::datastructure::Data &data)
ros::NodeHandle m_nh
ROS node handle.
sick_safetyscanners::GeneralSystemStateMsg createGeneralSystemStateMessage(const sick::datastructure::Data &data)
uint16_t skipToPublishFrequency(int skip)
Converts a skip value into a "publish frequency" value.
std::vector< sick_safetyscanners::IntrusionDatumMsg > createIntrusionDatumMessageVector(const sick::datastructure::Data &data)
ros::ServiceServer m_field_service_server
sick_safetyscanners::RawMicroScanDataMsg createRawDataMessage(const sick::datastructure::Data &data)
Containing the communication settings for the sensor which can be changed on runtime.
Definition: CommSettings.h:48
void reconfigure_callback(const sick_safetyscanners::SickSafetyscannersConfigurationConfig &config, const uint32_t &level)
Function which is triggered when a dynamic reconfiguration is performed.
sick_safetyscanners::ApplicationDataMsg createApplicationDataMessage(const sick::datastructure::Data &data)
The data class containing all data blocks of a measurement.
Definition: Data.h:55
dynamic_reconfigure::Server< sick_safetyscanners::SickSafetyscannersConfigurationConfig > m_dynamic_reconfiguration_server
sick_safetyscanners::ExtendedLaserScanMsg createExtendedLaserScanMessage(const sick::datastructure::Data &data)
sick_safetyscanners::DerivedValuesMsg createDerivedValuesMessage(const sick::datastructure::Data &data)
bool getFieldData(sick_safetyscanners::FieldData::Request &req, sick_safetyscanners::FieldData::Response &res)
void receivedUDPPacket(const datastructure::Data &data)
Function which is called when a new complete UDP Packet is received.
float degToRad(float deg)
Converts degrees to radians.
ros::Publisher m_laser_scan_publisher
ROS topic publisher.
The SickSafetyscannersRos class.
sick_safetyscanners::IntrusionDataMsg createIntrusionDataMessage(const sick::datastructure::Data &data)
ros::NodeHandle m_private_nh
ROS private node handle.
std::vector< bool > getMedianReflectors(const std::vector< sick::datastructure::ScanPoint > scan_points)
sick_safetyscanners::ApplicationInputsMsg createApplicationInputsMessage(const sick::datastructure::Data &data)
sick_safetyscanners::OutputPathsMsg createOutputPathsMessage(const sick::datastructure::Data &data)
std::shared_ptr< sick::SickSafetyscanners > m_device
sick::datastructure::CommSettings m_communication_settings
sensor_msgs::LaserScan createLaserScanMessage(const sick::datastructure::Data &data)
float radToDeg(float rad)
Converts radians to degrees.
virtual ~SickSafetyscannersRos()
~SickSafetyscannersRos Destructor if the SickSafetyscanners ROS
bool readParameters()
Reads and verifies the ROS parameters.
ros::Publisher m_extended_laser_scan_publisher
std::vector< sick_safetyscanners::ScanPointMsg > createScanPointMessageVector(const sick::datastructure::Data &data)
SickSafetyscannersRos()
Constructor of the SickSafetyscannersRos.


sick_safetyscanners
Author(s): Lennart Puck
autogenerated on Thu May 9 2019 02:41:08