sick_generic_monitoring.h
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) 2021, Ing.-Buero Dr. Michael Lehning, Hildesheim
4  * Copyright (C) 2021, SICK AG, Waldkirch
5  * All rights reserved.
6  *
7 * Licensed under the Apache License, Version 2.0 (the "License");
8 * you may not use this file except in compliance with the License.
9 * You may obtain a copy of the License at
10 *
11 * http://www.apache.org/licenses/LICENSE-2.0
12 *
13 * Unless required by applicable law or agreed to in writing, software
14 * distributed under the License is distributed on an "AS IS" BASIS,
15 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
16 * See the License for the specific language governing permissions and
17 * limitations under the License.
18 *
19 *
20 * All rights reserved.
21 *
22 * Redistribution and use in source and binary forms, with or without
23 * modification, are permitted provided that the following conditions are met:
24 *
25 * * Redistributions of source code must retain the above copyright
26 * notice, this list of conditions and the following disclaimer.
27 * * Redistributions in binary form must reproduce the above copyright
28 * notice, this list of conditions and the following disclaimer in the
29 * documentation and/or other materials provided with the distribution.
30 * * Neither the name of Osnabrueck University nor the names of its
31 * contributors may be used to endorse or promote products derived from
32 * this software without specific prior written permission.
33 * * Neither the name of SICK AG nor the names of its
34 * contributors may be used to endorse or promote products derived from
35 * this software without specific prior written permission
36 * * Neither the name of Ing.-Buero Dr. Michael Lehning nor the names of its
37 * contributors may be used to endorse or promote products derived from
38 * this software without specific prior written permission
39 *
40 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
41 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
42 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
43 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
44 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
45 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
46 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
47 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
48 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
49 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
50 * POSSIBILITY OF SUCH DAMAGE.
51  *
52  * Created on: 22nd november 2021
53  *
54  * Authors:
55  * Michael Lehning <michael.lehning@lehning.de>
56  *
57  */
58 
59 #ifndef SICK_GENERIC_MONITORING_H_
60 #define SICK_GENERIC_MONITORING_H_
61 
67 
68 namespace sick_scan_xd
69 {
70 
71  /*
72  * @brief class SickScanMonitor monitors incoming scanner messages.
73  * After a read timeout, the tcp connection is closed
74  * and the scanner is re-initialized.
75  */
77  {
78  public:
79 
81  SickScanMonitor(int read_timeout_millisec = READ_TIMEOUT_MILLISEC_DEFAULT);
82 
85 
86  /*
87  * @brief Monitors incoming scanner messages.
88  * In case of read timeouts, checkState returns ExitError, otherwise ExitSuccess.
89  */
91 
92  /*
93  * @brief Monitors incoming scanner messages.
94  * In case of read timeouts, checkStateReinitOnError closes the tcp connection, re-initializes the scanner.
95  * Returns ExitSuccess (no timeout or successful re-init), or ExitError otherwise.
96  */
98 
99  protected:
100 
101  int m_read_timeout_millisec; // read timeout in milliseconds, messages are expected after max <read_timeout_millisec> delay (otherwise timeout and scanner re-init)
102  NodeRunState m_lastRunState; // runState of last check: scanner_init, scanner_run or scanner_finalize
103 
104  };
105 
106  /*
107  * @brief class PointCloudMonitor monitors point cloud messages.
108  * The ros node will be killed, if no point cloud is published within a given amount of time.
109  */
111  {
112  public:
113 
116 
119 
120  /*
121  * @brief Starts a thread to monitor point cloud messages.
122  * The ros node will be killed, if no point cloud is published within a given amount of time.
123  */
124  bool startPointCloudMonitoring(rosNodePtr nh, int timeout_millisec = READ_TIMEOUT_MILLISEC_KILL_NODE, const std::string& ros_cloud_topic = "cloud");
125 
126  /*
127  * @brief Stops the thread to monitor point cloud messages.
128  */
129  void stopPointCloudMonitoring(void);
130 
131  protected:
132 
135 
137  void messageCbPointCloudROS2(const std::shared_ptr<ros_sensor_msgs::PointCloud2> msg);
138 
139  /*
140  * @brief Thread callback, runs the point cloud monitoring.
141  * If no point cloud is published within the timeout (150 sec. by default),
142  * the process is killed (and the node is restarted by ros)
143  */
144  void runMonitoringThreadCb(void);
145 
146 
149  std::string m_ros_cloud_topic;
150  uint64_t m_last_msg_timestamp_nanosec; // timestamp of last received point cloud message in nanoseconds
152  std::thread* m_monitoring_thread;
153 
154  };
155 
156 } /* namespace sick_scan_xd */
157 #endif // SICK_GENERIC_MONITORING_H_
sick_scan_xd::PointCloudMonitor::m_ros_cloud_topic
std::string m_ros_cloud_topic
Definition: sick_generic_monitoring.h:149
sick_scan_xd::PointCloudMonitor::stopPointCloudMonitoring
void stopPointCloudMonitoring(void)
Definition: sick_generic_monitoring.cpp:186
sick_scan_xd::PointCloudMonitor
Definition: sick_generic_monitoring.h:110
msg
msg
sick_generic_laser.h
sick_scan_xd::SickScanServices
Definition: sick_scan_services.h:76
sick_scan_xd::PointCloudMonitor::m_monitoring_thread
std::thread * m_monitoring_thread
Definition: sick_generic_monitoring.h:152
sensor_msgs::PointCloud2
::sensor_msgs::PointCloud2_< std::allocator< void > > PointCloud2
Definition: PointCloud2.h:90
sick_scan_xd::PointCloudMonitor::m_nh
rosNodePtr m_nh
Definition: sick_generic_monitoring.h:147
sick_scan_xd::SickScanMonitor::SickScanMonitor
SickScanMonitor(int read_timeout_millisec=READ_TIMEOUT_MILLISEC_DEFAULT)
Definition: sick_generic_monitoring.cpp:61
sick_scan_xd::SickGenericParser
Definition: sick_generic_parser.h:239
sick_scan_xd::SickScanMonitor::m_lastRunState
NodeRunState m_lastRunState
Definition: sick_generic_monitoring.h:102
sick_scan_xd
Definition: abstract_parser.cpp:65
sick_scan_common.h
sick_ros_wrapper.h
sick_scan_xd::PointCloudMonitor::messageCbPointCloudROS2
void messageCbPointCloudROS2(const std::shared_ptr< ros_sensor_msgs::PointCloud2 > msg)
Definition: sick_generic_monitoring.cpp:206
sick_scan_xd::SickScanMonitor::checkStateReinitOnError
sick_scan_xd::ExitCode checkStateReinitOnError(rosNodePtr nh, NodeRunState runState, SickScanCommonTcp *scanner, sick_scan_xd::SickGenericParser *parser, sick_scan_xd::SickScanServices *services)
Definition: sick_generic_monitoring.cpp:121
READ_TIMEOUT_MILLISEC_DEFAULT
#define READ_TIMEOUT_MILLISEC_DEFAULT
Definition: sick_scan_common.h:94
sick_generic_parser.h
sick_scan_xd::PointCloudMonitor::m_timeout_millisec
int m_timeout_millisec
Definition: sick_generic_monitoring.h:148
NodeRunState
NodeRunState
Definition: sick_generic_laser.h:12
imu_delay_tester.parser
parser
Definition: imu_delay_tester.py:116
sick_scan_xd::PointCloudMonitor::m_last_msg_timestamp_nanosec
uint64_t m_last_msg_timestamp_nanosec
Definition: sick_generic_monitoring.h:150
sick_scan_xd::PointCloudMonitor::m_monitoring_thread_running
bool m_monitoring_thread_running
Definition: sick_generic_monitoring.h:151
sick_scan_xd::SickScanMonitor
Definition: sick_generic_monitoring.h:76
ros::NodeHandle
sick_scan_xd::SickScanMonitor::m_read_timeout_millisec
int m_read_timeout_millisec
Definition: sick_generic_monitoring.h:101
sick_scan_xd::SickScanMonitor::~SickScanMonitor
~SickScanMonitor()
Definition: sick_generic_monitoring.cpp:68
sick_scan_services.h
sick_scan_xd::PointCloudMonitor::~PointCloudMonitor
~PointCloudMonitor()
Definition: sick_generic_monitoring.cpp:159
sick_scan_xd::SickScanCommonTcp
Definition: sick_scan_common_tcp.h:91
sick_scan_xd::PointCloudMonitor::runMonitoringThreadCb
void runMonitoringThreadCb(void)
Definition: sick_generic_monitoring.cpp:216
sick_scan_xd::ExitCode
ExitCode
Definition: abstract_parser.h:44
sick_scan_base.h
sick_scan_xd::PointCloudMonitor::startPointCloudMonitoring
bool startPointCloudMonitoring(rosNodePtr nh, int timeout_millisec=READ_TIMEOUT_MILLISEC_KILL_NODE, const std::string &ros_cloud_topic="cloud")
Definition: sick_generic_monitoring.cpp:168
sick_scan_xd::SickScanMonitor::checkState
sick_scan_xd::ExitCode checkState(NodeRunState runState, SickScanCommonTcp *scanner, sick_scan_xd::SickGenericParser *parser, sick_scan_xd::SickScanServices *services)
Definition: sick_generic_monitoring.cpp:76
sick_scan_xd::PointCloudMonitor::PointCloudMonitor
PointCloudMonitor()
Definition: sick_generic_monitoring.cpp:153
sick_scan_xd::PointCloudMonitor::messageCbPointCloud
void messageCbPointCloud(const ros_sensor_msgs::PointCloud2 &msg)
Definition: sick_generic_monitoring.cpp:199
READ_TIMEOUT_MILLISEC_KILL_NODE
#define READ_TIMEOUT_MILLISEC_KILL_NODE
Definition: sick_scan_common.h:95


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