src
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
48
void
ThreadedStream::start
()
49
{
50
_stop
=
false
;
51
_requested
=
true
;
52
_success
=
false
;
53
_thread
= std::thread(&
ThreadedStream::work
,
this
);
54
}
55
56
void
ThreadedStream::stop
()
57
{
58
_stop
=
true
;
59
}
60
61
void
ThreadedStream::join
()
62
{
63
if
(
_thread
.joinable())
64
_thread
.join();
65
}
66
67
void
ThreadedStream::work
()
68
{
69
if
(!this->
startReceivingAndPublishingAsRos
())
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
78
ThreadedStream::Manager::Ptr
ThreadedStream::Manager::create
()
79
{
80
return
Ptr
(
new
Manager
());
81
}
82
83
ThreadedStream::Manager::Manager
() : _any_failed(false)
84
{
85
}
86
87
void
ThreadedStream::Manager::add
(
ThreadedStream::Ptr
stream)
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
98
void
ThreadedStream::Manager::start_all
()
99
{
100
for
(
auto
&
s
: _streams)
101
s
->start();
102
}
103
104
void
ThreadedStream::Manager::stop_all
()
105
{
106
for
(
auto
&
s
: _streams)
107
s
->stop();
108
}
109
110
void
ThreadedStream::Manager::join_all
()
111
{
112
for
(
auto
&
s
: _streams)
113
s
->join();
114
}
115
116
bool
ThreadedStream::Manager::all_succeeded
()
const
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
}
rc::ThreadedStream::startReceivingAndPublishingAsRos
virtual bool startReceivingAndPublishingAsRos()=0
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
rc::ThreadedStream::Manager::all_succeeded
bool all_succeeded() const
Definition:
ThreadedStream.cc:116
rc::ThreadedStream::Manager::Manager
Manager()
Definition:
ThreadedStream.cc:83
rc::ThreadedStream::_manager
Manager::Ptr _manager
Definition:
ThreadedStream.h:123
rc::ThreadedStream::start
void start()
Definition:
ThreadedStream.cc:48
s
XmlRpcServer s
rc::ThreadedStream::_thread
std::thread _thread
Definition:
ThreadedStream.h:122
rc::ThreadedStream::Ptr
std::shared_ptr< ThreadedStream > Ptr
Definition:
ThreadedStream.h:62
rc::dynamics::RemoteInterface::Ptr
std::shared_ptr< RemoteInterface > Ptr
ThreadedStream.h
rc
rc::ThreadedStream::Manager::stop_all
void stop_all()
Definition:
ThreadedStream.cc:104
rc::ThreadedStream::Manager::add
void add(ThreadedStream::Ptr stream)
Definition:
ThreadedStream.cc:87
rc::ThreadedStream::_requested
std::atomic_bool _requested
Definition:
ThreadedStream.h:120
rc::ThreadedStream::stop
void stop()
Definition:
ThreadedStream.cc:56
rc::ThreadedStream::Manager::get
const std::list< ThreadedStream::Ptr > & get()
Definition:
ThreadedStream.cc:93
rc::ThreadedStream::_stop
std::atomic_bool _stop
Definition:
ThreadedStream.h:120
rc::ThreadedStream::_success
std::atomic_bool _success
Definition:
ThreadedStream.h:120
std
rc::ThreadedStream::Manager::Ptr
std::shared_ptr< Manager > Ptr
Definition:
ThreadedStream.h:67
rc::ThreadedStream::work
virtual void work()
Definition:
ThreadedStream.cc:67
rc::ThreadedStream::Manager::join_all
void join_all()
Definition:
ThreadedStream.cc:110
rc::ThreadedStream::Manager::start_all
void start_all()
Definition:
ThreadedStream.cc:98
rc::ThreadedStream::join
void join()
Definition:
ThreadedStream.cc:61
ros::NodeHandle
rc::ThreadedStream::_stream
std::string _stream
Definition:
ThreadedStream.h:126
rc::ThreadedStream::Manager::create
static Ptr create()
Definition:
ThreadedStream.cc:78
rc_visard_driver
Author(s): Heiko Hirschmueller
, Christian Emmerich
, Felix Ruess
autogenerated on Sun May 15 2022 02:25:43