sick_ldmrs_driver.hpp
Go to the documentation of this file.
1 #include "sick_scan/sick_scan_base.h" /* Base definitions included in all header files, added by add_sick_scan_base_header.py. Do not edit this line. */
2 /*
3  * Copyright (C) 2015, DFKI GmbH
4  * All rights reserved.
5  *
6  * Redistribution and use in source and binary forms, with or without
7  * modification, are permitted provided that the following conditions are met:
8  *
9  * * Redistributions of source code must retain the above copyright
10  * notice, this list of conditions and the following disclaimer.
11  * * Redistributions in binary form must reproduce the above copyright
12  * notice, this list of conditions and the following disclaimer in the
13  * documentation and/or other materials provided with the distribution.
14  * * Neither the name of DFKI GmbH nor the names of its
15  * contributors may be used to endorse or promote products derived from
16  * this software without specific prior written permission.
17  *
18  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
21  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
22  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
23  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
24  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
25  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
26  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
27  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
28  * POSSIBILITY OF SUCH DAMAGE.
29  *
30  * Created on: 23.11.2015
31  *
32  * Authors:
33  * Martin Günther <martin.guenther@dfki.de>
34  * Jochen Sprickerhof <jochen@sprickerhof.de>
35  *
36  * Modified and ported to ROS2: 02.10.2020 by Ing.-Buero Dr. Michael Lehning, Hildesheim
37  */
38 
39 #ifndef SICK_LDMRS800001S01_H_
40 #define SICK_LDMRS800001S01_H_
41 
42 #include <stdio.h>
43 #include <stdlib.h>
44 #include <string.h>
45 #include <vector>
46 
47 #include <cfloat>
48 #include <chrono>
49 #include <future>
50 #include <memory>
51 
52 // #include <dynamic_reconfigure/server.h>
53 // #include <sick_ldmrs_driver/SickLDMRSDriverConfig.h>
57 
58 #include <sick_ldmrs/manager.hpp>
59 #include <sick_ldmrs/application/BasicApplication.hpp>
60 #include <sick_ldmrs/datatypes/Object.hpp>
61 
62 #if __ROS_VERSION == 2 // ROS-2 (Linux or Windows)
63 #include <sick_scan_xd/msg/sick_ldmrs_object_array.hpp>
64 #include <diagnostic_updater/diagnostic_updater.hpp> // part of diagnostic_msgs of ROS2, not available on ROS2-Windows until foxy patch 4
65 #include <diagnostic_updater/publisher.hpp>
66 #else
68 #endif
69 
70 namespace sick_ldmrs_driver
71 {
72 
73 // Adapter to combine publisher for sensor_msgs::msg::PointCloud2 and diagnostic_msgs::msg::DiagnosticArray.
74 // see https://github.com/ros/diagnostics/blob/eloquent/diagnostic_updater/include/diagnostic_updater/publisher.hpp
75 // and https://github.com/ros/diagnostics/issues/164
76 template <class DiagnosedPublisherT> class DiagnosedPublishAdapter : public diagnostic_updater::TopicDiagnostic
77 {
78 public:
79  template <typename PublisherType> DiagnosedPublishAdapter(PublisherType publisher, diagnostic_updater::Updater & diag,
81  : diagnostic_updater::TopicDiagnostic(rosTopicName(publisher), diag, freq, stamp), publisher_(publisher)
82  {
83  }
85  {
86  }
87  template <typename MessageType> void publish(const std::shared_ptr<MessageType> & message)
88  {
89  if(message)
90  publish(*message);
91  }
92  template <typename MessageType> void publish(const MessageType & message)
93  {
94  tick(message.header.stamp);
95  rosPublish(publisher_, message); // publisher_->publish(message);
96  }
97 protected:
98  DiagnosedPublisherT publisher_;
99 };
100 
101 class SickLDMRS : public application::BasicApplication
102 {
103 public:
104  SickLDMRS(rosNodePtr nh, Manager* manager, std::shared_ptr<diagnostic_updater::Updater> diagnostics);
105  virtual ~SickLDMRS();
106  void init();
109  void update_config(SickLDMRSDriverConfig &new_config, uint32_t level = 0);
110 #if defined USE_DYNAMIC_RECONFIGURE && __ROS_VERSION == 1
111  void update_config_cb(sick_scan_xd::SickLDMRSDriverConfig &new_config, uint32_t level = 0);
112 #endif
113 #if defined USE_DYNAMIC_RECONFIGURE && __ROS_VERSION == 2
114  rcl_interfaces::msg::SetParametersResult update_config_cb(const std::vector<rclcpp::Parameter> &parameters);
115 #endif
116  void pubObjects(datatypes::ObjectList &objects);
117 
118 protected:
119  std::shared_ptr<diagnostic_updater::Updater> diagnostics_;
120  void setData(BasicData& data); // Callback for new data from the manager (scans etc.)
121  void validate_flexres_resolution(int &res);
122  void validate_flexres_start_angle(double &angle1, double &angle2);
123  bool isUpsideDown();
124  void printFlexResError();
125  std::string flexres_err_to_string(const UINT32 code) const;
126 
127 private:
128 
129  // ROS
131  std::string cloud_topic_val = "cloud";
134  // Diagnostics
136  // Dynamic Reconfigure
138 #if defined USE_DYNAMIC_RECONFIGURE && __ROS_VERSION == 1
140 #endif
141 
142  // sick_ldmrs library objects
143  Manager* manager_;
144 
145  // Expected scan frequency. Must be a member variable for access by diagnostics.
147 
149  sick_scan_xd::SickCloudTransform m_add_transform_xyz_rpy; // Apply an additional transform to the cartesian pointcloud, default: "0,0,0,0,0,0" (i.e. no transform)
151 };
152 
153 } /* namespace sick_ldmrs_driver */
154 
155 #endif /* SICK_LDMRS800001S01_H_ */
sick_ldmrs_driver::SickLDMRS::produce_diagnostics
void produce_diagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat)
Definition: sick_ldmrs_driver.cpp:131
sick_cloud_transform.h
sick_ldmrs_driver::SickLDMRS::m_add_transform_xyz_rpy
sick_scan_xd::SickCloudTransform m_add_transform_xyz_rpy
Definition: sick_ldmrs_driver.hpp:149
sick_ldmrs_driver::SickLDMRS::printFlexResError
void printFlexResError()
Definition: sick_ldmrs_driver.cpp:359
sick_ldmrs_driver::SickLDMRS::diagnosticPub_
DiagnosedPublishAdapter< rosPublisher< ros_sensor_msgs::PointCloud2 > > * diagnosticPub_
Definition: sick_ldmrs_driver.hpp:135
sick_ldmrs_driver::SickLDMRS::diagnostics_
std::shared_ptr< diagnostic_updater::Updater > diagnostics_
Definition: sick_ldmrs_driver.hpp:119
diagnostic_updater::TimeStampStatusParam
A structure that holds the constructor parameters for the TimeStampStatus class.
Definition: eloquent/include/diagnostic_updater/update_functions.hpp:218
sick_ldmrs_driver::DiagnosedPublishAdapter::publish
void publish(const std::shared_ptr< MessageType > &message)
Definition: sick_ldmrs_driver.hpp:87
sick_ldmrs_driver::SickLDMRS::SickLDMRS
SickLDMRS(rosNodePtr nh, Manager *manager, std::shared_ptr< diagnostic_updater::Updater > diagnostics)
Definition: sick_ldmrs_driver.cpp:63
sick_scan_xd::SickCloudTransform
Definition: sick_cloud_transform.h:85
sick_ldmrs_driver::SickLDMRS::init
void init()
Definition: sick_ldmrs_driver.cpp:111
SickLdmrsObjectArray.h
sick_ldmrs_driver::SickLDMRS::validate_flexres_resolution
void validate_flexres_resolution(int &res)
Definition: sick_ldmrs_driver.cpp:253
rosTopicName
std::string rosTopicName(rosPublisher< T > &publisher)
Definition: sick_ros_wrapper.h:204
diagnostic_updater::Updater
Manages a list of diagnostic tasks, and calls them in a rate-limited manner.
Definition: eloquent/include/diagnostic_updater/diagnostic_updater.hpp:353
diagnostic_updater::TopicDiagnostic::TopicDiagnostic
TopicDiagnostic(std::string name, diagnostic_updater::Updater &diag, const diagnostic_updater::FrequencyStatusParam &freq, const diagnostic_updater::TimeStampStatusParam &stamp)
sick_ldmrs_driver::SickLDMRS::m_range_filter
sick_scan_xd::SickRangeFilter m_range_filter
Definition: sick_ldmrs_driver.hpp:150
sick_ldmrs_driver::SickLDMRS::pubObjects
void pubObjects(datatypes::ObjectList &objects)
Definition: sick_ldmrs_driver.cpp:283
sick_range_filter.h
sick_ldmrs_driver::SickLDMRS::manager_
Manager * manager_
Definition: sick_ldmrs_driver.hpp:143
sick_ldmrs_driver::SickLDMRS::update_config
void update_config(SickLDMRSDriverConfig &new_config, uint32_t level=0)
Definition: sick_ldmrs_driver.cpp:444
message
def message(msg, *args, **kwargs)
diagnostic_updater::TopicDiagnostic::tick
virtual void tick()
sick_ldmrs_driver::DiagnosedPublishAdapter
Definition: sick_ldmrs_driver.hpp:76
rosPublisher< ros_sensor_msgs::PointCloud2 >
diagnostic_updater
Author: Blaise Gassend.
sick_ldmrs_driver::SickLDMRS::setData
void setData(BasicData &data)
Definition: sick_ldmrs_driver.cpp:149
sick_ldmrs_config.hpp
sick_ldmrs_driver::SickLDMRS::object_pub_
rosPublisher< sick_scan_msg::SickLdmrsObjectArray > object_pub_
Definition: sick_ldmrs_driver.hpp:133
rosPublish
void rosPublish(rosPublisher< T > &publisher, const T &msg)
Definition: sick_ros_wrapper.h:203
ros::NodeHandle
sick_ldmrs_driver::DiagnosedPublishAdapter::publish
void publish(const MessageType &message)
Definition: sick_ldmrs_driver.hpp:92
diagnostic_updater::TopicDiagnostic
A class to facilitate making diagnostics for a topic using a FrequencyStatus and TimeStampStatus.
Definition: eloquent/include/diagnostic_updater/publisher.hpp:107
sick_ldmrs_driver::DiagnosedPublishAdapter::DiagnosedPublishAdapter
DiagnosedPublishAdapter(PublisherType publisher, diagnostic_updater::Updater &diag, const diagnostic_updater::FrequencyStatusParam &freq, const diagnostic_updater::TimeStampStatusParam &stamp)
Definition: sick_ldmrs_driver.hpp:79
sick_ldmrs_driver
Definition: sick_ldmrs_driver.cpp:60
sick_ldmrs_driver::SickLDMRS::expected_frequency_
double expected_frequency_
Definition: sick_ldmrs_driver.hpp:146
sick_ldmrs_driver::SickLDMRS::validate_config
void validate_config(SickLDMRSDriverConfig &conf)
Definition: sick_ldmrs_driver.cpp:215
sick_ldmrs_driver::SickLDMRS::pub_
rosPublisher< ros_sensor_msgs::PointCloud2 > pub_
Definition: sick_ldmrs_driver.hpp:132
dynamic_reconfigure::Server
Definition: server.h:65
sick_scan_base.h
diagnostic_updater::DiagnosticStatusWrapper
Wrapper for the diagnostic_msgs::msg::DiagnosticStatus message that makes it easier to update.
Definition: eloquent/include/diagnostic_updater/diagnostic_status_wrapper.hpp:68
sick_ldmrs_driver::SickLDMRS::isUpsideDown
bool isUpsideDown()
Definition: sick_ldmrs_driver.cpp:344
sick_ldmrs_driver::SickLDMRS::initialized_
bool initialized_
Definition: sick_ldmrs_driver.hpp:148
UINT32
uint32_t UINT32
Definition: BasicDatatypes.hpp:72
sick_ldmrs_driver::SickLDMRSDriverConfig
Definition: sick_ldmrs_config.hpp:98
sick_ldmrs_driver::DiagnosedPublishAdapter::~DiagnosedPublishAdapter
virtual ~DiagnosedPublishAdapter()
Definition: sick_ldmrs_driver.hpp:84
sick_ldmrs_driver::SickLDMRS::cloud_topic_val
std::string cloud_topic_val
Definition: sick_ldmrs_driver.hpp:131
sick_ldmrs_driver::SickLDMRS::config_
SickLDMRSDriverConfig config_
Definition: sick_ldmrs_driver.hpp:137
sick_ldmrs_driver::SickLDMRS::flexres_err_to_string
std::string flexres_err_to_string(const UINT32 code) const
Definition: sick_ldmrs_driver.cpp:584
sick_ldmrs_driver::SickLDMRS::validate_flexres_start_angle
void validate_flexres_start_angle(double &angle1, double &angle2)
Definition: sick_ldmrs_driver.cpp:274
sick_ldmrs_driver::SickLDMRS::nh_
rosNodePtr nh_
Definition: sick_ldmrs_driver.hpp:130
sick_ldmrs_driver::SickLDMRS
Definition: sick_ldmrs_driver.hpp:101
sick_ldmrs_driver::SickLDMRS::~SickLDMRS
virtual ~SickLDMRS()
Definition: sick_ldmrs_driver.cpp:106
sick_ldmrs_driver::DiagnosedPublishAdapter::publisher_
DiagnosedPublisherT publisher_
Definition: sick_ldmrs_driver.hpp:98
sick_scan_xd::SickRangeFilter
Definition: sick_range_filter.h:85
diagnostic_updater::FrequencyStatusParam
A structure that holds the constructor parameters for the FrequencyStatus class.
Definition: eloquent/include/diagnostic_updater/update_functions.hpp:53


sick_scan_xd
Author(s): Michael Lehning , Jochen Sprickerhof , Martin Günther
autogenerated on Fri Oct 25 2024 02:47:10