sick_ldmrs_node.hpp
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2015, DFKI GmbH
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of DFKI GmbH nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  *
29  * Created on: 23.11.2015
30  *
31  * Authors:
32  * Martin Günther <martin.guenther@dfki.de>
33  * Jochen Sprickerhof <jochen@sprickerhof.de>
34  *
35  */
36 
37 #ifndef SICK_LDMRS800001S01_H_
38 #define SICK_LDMRS800001S01_H_
39 
40 #include <stdio.h>
41 #include <stdlib.h>
42 #include <string.h>
43 #include <vector>
44 
45 #include <ros/ros.h>
46 #include <sensor_msgs/PointCloud2.h>
48 
51 
52 #include <dynamic_reconfigure/server.h>
53 #include <sick_ldmrs_driver/SickLDMRSDriverConfig.h>
54 
55 #include <sick_ldmrs/manager.hpp>
56 #include <sick_ldmrs/application/BasicApplication.hpp>
57 #include <sick_ldmrs/datatypes/Object.hpp>
58 
59 
61 {
62 
63 typedef pcl::PointCloud<sick_ldmrs_msgs::SICK_LDMRS_Point> PointCloud;
64 
65 class SickLDMRS : public application::BasicApplication
66 {
67 public:
68  SickLDMRS(Manager* manager, boost::shared_ptr<diagnostic_updater::Updater> diagnostics);
69  virtual ~SickLDMRS();
70  void init();
72  void validate_config(SickLDMRSDriverConfig &conf);
73  void update_config(SickLDMRSDriverConfig &new_config, uint32_t level = 0);
74  void pubObjects(datatypes::ObjectList &objects);
75 
76 protected:
78  void setData(BasicData& data); // Callback for new data from the manager (scans etc.)
79  void validate_flexres_resolution(int &res);
80  void validate_flexres_start_angle(double &angle1, double &angle2);
81  bool isUpsideDown();
82  void printFlexResError();
83  std::string flexres_err_to_string(const UINT32 code) const;
84 
85 private:
86  // ROS
90  // Diagnostics
92 
93  // Dynamic Reconfigure
94  SickLDMRSDriverConfig config_;
95  dynamic_reconfigure::Server<SickLDMRSDriverConfig> dynamic_reconfigure_server_;
96 
97  // sick_ldmrs library objects
98  Manager* manager_;
99 
100  // Expected scan frequency. Must be a member variable for access by diagnostics.
102 
104 };
105 
106 } /* namespace sick_ldmrs_driver */
107 #endif /* SICK_LDMRS800001S01_H_ */
diagnostic_updater::DiagnosedPublisher< sensor_msgs::PointCloud2 > * diagnosticPub_
SickLDMRS(Manager *manager, boost::shared_ptr< diagnostic_updater::Updater > diagnostics)
dynamic_reconfigure::Server< SickLDMRSDriverConfig > dynamic_reconfigure_server_
void setData(BasicData &data)
void produce_diagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat)
void validate_flexres_resolution(int &res)
void validate_config(SickLDMRSDriverConfig &conf)
boost::shared_ptr< diagnostic_updater::Updater > diagnostics_
std::string flexres_err_to_string(const UINT32 code) const
void update_config(SickLDMRSDriverConfig &new_config, uint32_t level=0)
void validate_flexres_start_angle(double &angle1, double &angle2)
void pubObjects(datatypes::ObjectList &objects)
pcl::PointCloud< sick_ldmrs_msgs::SICK_LDMRS_Point > PointCloud
SickLDMRSDriverConfig config_


sick_ldmrs_driver
Author(s): Martin Günther , Jochen Sprickerhof
autogenerated on Sun Oct 25 2020 03:33:55