35 #ifndef SICK_SAFETYSCANNERS_SICKSAFETYSCANNERSROS_H 36 #define SICK_SAFETYSCANNERS_SICKSAFETYSCANNERSROS_H 41 #include <sensor_msgs/JointState.h> 42 #include <sensor_msgs/LaserScan.h> 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> 58 #include <dynamic_reconfigure/server.h> 71 return deg * M_PI / 180.0f;
81 return rad * 180.0f / M_PI;
136 std::shared_ptr<sick::SickSafetyscanners>
m_device;
140 dynamic_reconfigure::Server<sick_safetyscanners::SickSafetyscannersConfigurationConfig>
171 const uint32_t& level);
176 sick_safetyscanners::ExtendedLaserScanMsg
180 sick_safetyscanners::OutputPathsMsg
182 sick_safetyscanners::RawMicroScanDataMsg
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
206 bool getFieldData(sick_safetyscanners::FieldData::Request& req,
207 sick_safetyscanners::FieldData::Response& res);
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.
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.
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)
ros::Publisher m_output_path_publisher
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)
ros::Publisher m_raw_data_publisher
float radToDeg(float rad)
Converts radians to degrees.
virtual ~SickSafetyscannersRos()
~SickSafetyscannersRos Destructor if the SickSafetyscanners ROS
void readTypeCodeSettings()
bool readParameters()
Reads and verifies the ROS parameters.
ros::Publisher m_extended_laser_scan_publisher
void readPersistentConfig()
std::vector< sick_safetyscanners::ScanPointMsg > createScanPointMessageVector(const sick::datastructure::Data &data)
SickSafetyscannersRos()
Constructor of the SickSafetyscannersRos.