ThreadedStream.cc
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2017 Roboception GmbH
3  * All rights reserved
4  *
5  * Author: Christian Emmerich
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions are met:
9  *
10  * 1. Redistributions of source code must retain the above copyright notice,
11  * this list of conditions and the following disclaimer.
12  *
13  * 2. Redistributions in binary form must reproduce the above copyright notice,
14  * this list of conditions and the following disclaimer in the documentation
15  * and/or other materials provided with the distribution.
16  *
17  * 3. Neither the name of the copyright holder nor the names of its contributors
18  * may be used to endorse or promote products derived from this software without
19  * specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
22  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
23  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
24  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
25  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
26  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
27  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
28  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
29  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
30  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31  * POSSIBILITY OF SUCH DAMAGE.
32  */
33 
34 #include "ThreadedStream.h"
35 
36 using namespace std;
37 
38 namespace rc
39 {
40 namespace rcd = dynamics;
41 
42 ThreadedStream::ThreadedStream(rc::dynamics::RemoteInterface::Ptr rcdIface, const std::string& stream,
43  ros::NodeHandle& nh)
44  : _stop(false), _requested(false), _success(false), _rcdyn(rcdIface), _stream(stream), _nh(nh)
45 {
46 }
47 
49 {
50  _stop = false;
51  _requested = true;
52  _success = false;
53  _thread = std::thread(&ThreadedStream::work, this);
54 }
55 
57 {
58  _stop = true;
59 }
60 
62 {
63  if (_thread.joinable())
64  _thread.join();
65 }
66 
68 {
70  {
71  _success = false;
72  if (_manager)
73  _manager->_any_failed = true;
74  ROS_ERROR_STREAM("rc_visard_driver: rc-dynamics streaming failed: " << _stream);
75  }
76 }
77 
79 {
80  return Ptr(new Manager());
81 }
82 
83 ThreadedStream::Manager::Manager() : _any_failed(false)
84 {
85 }
86 
88 {
89  stream->_manager = shared_from_this();
90  _streams.push_back(stream);
91 }
92 
93 const std::list<ThreadedStream::Ptr>& ThreadedStream::Manager::get()
94 {
95  return _streams;
96 }
97 
99 {
100  for (auto& s : _streams)
101  s->start();
102 }
103 
105 {
106  for (auto& s : _streams)
107  s->stop();
108 }
109 
111 {
112  for (auto& s : _streams)
113  s->join();
114 }
115 
117 {
118  if (_streams.empty())
119  return true;
120 
121  for (const auto& s : _streams)
122  if (s->requested() && !s->succeeded())
123  return false;
124 
125  return true;
126 }
127 }
std::shared_ptr< RemoteInterface > Ptr
void add(ThreadedStream::Ptr stream)
XmlRpcServer s
std::shared_ptr< ThreadedStream > Ptr
std::atomic_bool _requested
std::shared_ptr< Manager > Ptr
std::list< ThreadedStream::Ptr > _streams
Manager::Ptr _manager
#define ROS_ERROR_STREAM(args)
virtual void work()
std::atomic_bool _stop
std::atomic_bool _success
const std::list< ThreadedStream::Ptr > & get()
virtual bool startReceivingAndPublishingAsRos()=0


rc_visard_driver
Author(s): Heiko Hirschmueller , Christian Emmerich , Felix Ruess
autogenerated on Sat Feb 13 2021 03:42:55