00001 /* 00002 * Copyright (c) 2017 Roboception GmbH 00003 * All rights reserved 00004 * 00005 * Author: Christian Emmerich 00006 * 00007 * Redistribution and use in source and binary forms, with or without 00008 * modification, are permitted provided that the following conditions are met: 00009 * 00010 * 1. Redistributions of source code must retain the above copyright notice, 00011 * this list of conditions and the following disclaimer. 00012 * 00013 * 2. Redistributions in binary form must reproduce the above copyright notice, 00014 * this list of conditions and the following disclaimer in the documentation 00015 * and/or other materials provided with the distribution. 00016 * 00017 * 3. Neither the name of the copyright holder nor the names of its contributors 00018 * may be used to endorse or promote products derived from this software without 00019 * specific prior written permission. 00020 * 00021 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00022 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00023 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00024 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE 00025 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00026 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00027 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00028 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00029 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00030 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00031 * POSSIBILITY OF SUCH DAMAGE. 00032 */ 00033 00034 #include "ThreadedStream.h" 00035 00036 using namespace std; 00037 00038 namespace rc 00039 { 00040 00041 namespace rcd = dynamics; 00042 00043 ThreadedStream::ThreadedStream(rc::dynamics::RemoteInterface::Ptr rcdIface, 00044 const std::string &stream, ros::NodeHandle &nh) 00045 : _stop(false), _requested(false), _success(false), _rcdyn(rcdIface), 00046 _stream(stream), _nh(nh) 00047 {} 00048 00049 void ThreadedStream::start() 00050 { 00051 _stop = false; 00052 _requested = true; 00053 _success = false; 00054 _thread = std::thread(&ThreadedStream::work, this); 00055 } 00056 00057 void ThreadedStream::stop() 00058 { 00059 _stop = true; 00060 } 00061 00062 void ThreadedStream::join() 00063 { 00064 if (_thread.joinable()) 00065 _thread.join(); 00066 } 00067 00068 void ThreadedStream::work() 00069 { 00070 if (!this->startReceivingAndPublishingAsRos()) 00071 { 00072 _success = false; 00073 if (_manager) 00074 _manager->_any_failed = true; 00075 ROS_ERROR_STREAM("rc_visard_driver: rc-dynamics streaming failed: " << _stream); 00076 } 00077 } 00078 00079 00080 00081 00082 ThreadedStream::Manager::Ptr ThreadedStream::Manager::create() 00083 { 00084 return Ptr(new Manager()); 00085 } 00086 00087 ThreadedStream::Manager::Manager() : _any_failed(false) 00088 {} 00089 00090 void ThreadedStream::Manager::add(ThreadedStream::Ptr stream) 00091 { 00092 stream->_manager = shared_from_this(); 00093 _streams.push_back(stream); 00094 } 00095 00096 const std::list<ThreadedStream::Ptr>& ThreadedStream::Manager::get() 00097 { 00098 return _streams; 00099 } 00100 00101 void ThreadedStream::Manager::start_all() 00102 { 00103 for (auto &s : _streams) s->start(); 00104 } 00105 00106 void ThreadedStream::Manager::stop_all() 00107 { 00108 for (auto &s : _streams) s->stop(); 00109 } 00110 00111 void ThreadedStream::Manager::join_all() 00112 { 00113 for (auto &s : _streams) 00114 s->join(); 00115 } 00116 00117 bool ThreadedStream::Manager::all_succeeded() const 00118 { 00119 if (_streams.empty()) 00120 return true; 00121 00122 for (const auto &s : _streams) 00123 if (s->requested() && !s->succeeded()) 00124 return false; 00125 00126 return true; 00127 } 00128 00129 00130 }