scansegment_threads.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  * @brief scansegement_threads runs all threads to receive, convert and publish scan data for the sick 3D lidar multiScan136.
4  *
5  * Copyright (C) 2022 Ing.-Buero Dr. Michael Lehning, Hildesheim
6  * Copyright (C) 2022 SICK AG, Waldkirch
7  *
8  * Licensed under the Apache License, Version 2.0 (the "License");
9  * you may not use this file except in compliance with the License.
10  * You may obtain a copy of the License at
11  *
12  * http://www.apache.org/licenses/LICENSE-2.0
13  *
14  * Unless required by applicable law or agreed to in writing, software
15  * distributed under the License is distributed on an "AS IS" BASIS,
16  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
17  * See the License for the specific language governing permissions and
18  * limitations under the License.
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 SICK AG 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 Ing.-Buero Dr. Michael Lehning 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  *
37  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
38  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
39  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
40  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
41  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
42  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
43  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
44  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
45  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
46  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
47  * POSSIBILITY OF SUCH DAMAGE.
48  *
49  * Authors:
50  * Michael Lehning <michael.lehning@lehning.de>
51  *
52  * Copyright 2022 SICK AG
53  * Copyright 2022 Ing.-Buero Dr. Michael Lehning
54  *
55  */
56 #ifndef __SICK_SCANSEGEMENT_THREADS_H
57 #define __SICK_SCANSEGEMENT_THREADS_H
58 
59 namespace sick_scan_xd
60 {
61  class SickScanServices;
62 }
63 
65 
66 namespace sick_scansegment_xd
67 {
68  /*
69  * @brief Initializes and runs all threads to receive, convert and publish scan data for the sick 3D lidar multiScan136.
70  */
71  int run(rosNodePtr node, const std::string& scannerName);
72 
73  /*
74  * @brief class MsgPackThreads runs all threads to receive, convert and publish scan data for the sick 3D lidar multiScan136.
75  */
77  {
78  public:
79 
80  /*
81  * @brief MsgPackThreads constructor
82  */
84 
85  /*
86  * @brief MsgPackThreads destructor
87  */
89 
90  /*
91  * @brief Initializes msgpack receiver, converter and publisher and starts msgpack handling and publishing in a background thread.
92  */
94 
95  /*
96  * @brief Stops running threads and closes msgpack receiver, converter and publisher.
97  */
98  bool stop(bool do_join);
99 
100  /*
101  * @brief Joins running threads and returns after they finished.
102  */
103  void join(void);
104 
105  protected:
106 
107  /*
108  * @brief Thread callback, initializes and runs msgpack receiver, converter and publisher.
109  */
110  bool runThreadCb(void);
111 
112  sick_scansegment_xd::Config m_config; // sick_scansegment_xd configuration
113  std::thread* m_scansegment_thread; // background thread to convert msgpack to ScanSegmentParserOutput data
114  bool m_run_scansegment_thread; // flag to start and stop the udp converter thread
115  };
116 
118 
119 } // namespace sick_scansegment_xd
120 #endif // __SICK_SCANSEGEMENT_THREADS_H
sick_scansegment_xd::MsgPackThreads::stop
bool stop(bool do_join)
Definition: scansegment_threads.cpp:143
sick_scan_xd::SickScanServices
Definition: sick_scan_services.h:76
sick_scansegment_xd
Definition: include/sick_scansegment_xd/common.h:138
sick_scan_xd
Definition: abstract_parser.cpp:65
sick_scansegment_xd::sopasService
sick_scan_xd::SickScanServices * sopasService()
Definition: scansegment_threads.cpp:69
sick_scansegment_xd::MsgPackThreads::join
void join(void)
Definition: scansegment_threads.cpp:159
sick_scansegment_xd::MsgPackThreads::m_scansegment_thread
std::thread * m_scansegment_thread
Definition: scansegment_threads.h:113
polar_to_cartesian_pointcloud_ros1.node
node
Definition: polar_to_cartesian_pointcloud_ros1.py:81
sick_scansegment_xd::MsgPackThreads::start
bool start(const sick_scansegment_xd::Config &config)
Definition: scansegment_threads.cpp:132
sick_scansegment_xd::MsgPackThreads::MsgPackThreads
MsgPackThreads()
Definition: scansegment_threads.cpp:116
sick_scansegment_xd::MsgPackThreads::~MsgPackThreads
~MsgPackThreads()
Definition: scansegment_threads.cpp:124
sick_scansegment_xd::MsgPackThreads::runThreadCb
bool runThreadCb(void)
Definition: scansegment_threads.cpp:171
ros::NodeHandle
sick_scansegment_xd::Config
Definition: config.h:84
sick_scansegment_xd::MsgPackThreads::m_run_scansegment_thread
bool m_run_scansegment_thread
Definition: scansegment_threads.h:114
sick_scansegment_xd::MsgPackThreads::m_config
sick_scansegment_xd::Config m_config
Definition: scansegment_threads.h:112
sick_scansegment_xd::MsgPackThreads
Definition: scansegment_threads.h:76
sick_scan_base.h
config.h
config
config
sick_scansegment_xd::run
int run(rosNodePtr node, const std::string &scannerName)
Definition: scansegment_threads.cpp:74


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