diff --git a/CMakeLists.txt b/CMakeLists.txt index b092328ba..ba36b0116 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -21,14 +21,13 @@ endif() PROJECT(orocos-rtt) - SET( RTT_VERSION 2.8.3 ) STRING( REGEX MATCHALL "[0-9]+" RTT_VERSIONS ${RTT_VERSION} ) LIST( GET RTT_VERSIONS 0 RTT_VERSION_MAJOR) LIST( GET RTT_VERSIONS 1 RTT_VERSION_MINOR) LIST( GET RTT_VERSIONS 2 RTT_VERSION_PATCH) - -MESSAGE( "Orocos RTT version ${VERSION} (${RTT_VERSION_MAJOR}.${RTT_VERSION_MINOR}.${RTT_VERSION_PATCH})" ) +SET( RTT_SOVERSION ${RTT_VERSION_MAJOR}.${RTT_VERSION_MINOR} ) +MESSAGE( "Orocos RTT version ${RTT_VERSION}" ) SET( PROJ_SOURCE_DIR ${orocos-rtt_SOURCE_DIR} ) SET( PROJ_BINARY_DIR ${orocos-rtt_BINARY_DIR} ) @@ -43,11 +42,6 @@ if (NOT EXISTS ${PROJ_SOURCE_DIR}/orocos-rtt.cmake) INCLUDE(${PROJ_SOURCE_DIR}/orocos-rtt.default.cmake) endif () -OPTION(USE_CPP11 "Turn on to replace boost::bind with cpp11 bind." OFF) -if(USE_CPP11) - ADD_DEFINITIONS(-DUSE_CPP11) -endif(USE_CPP11) - # On Windows, the default CMAKE_INSTALL_PREFIX is either: # C:\Program Files\orocos-rtt or C:\Program Files (x86)\orocos-rtt # However, we want it to be either: diff --git a/rtt/CMakeLists.txt b/rtt/CMakeLists.txt index feebcc7ba..2100f3471 100644 --- a/rtt/CMakeLists.txt +++ b/rtt/CMakeLists.txt @@ -194,8 +194,8 @@ ENDIF ( BUILD_STATIC ) ADD_LIBRARY(orocos-rtt-${OROCOS_TARGET}_dynamic SHARED $ENV{GLOBAL_LIBRARY_SRCS}) SET_TARGET_PROPERTIES( orocos-rtt-${OROCOS_TARGET}_dynamic PROPERTIES DEFINE_SYMBOL "RTT_DLL_EXPORT" - SOVERSION "${RTT_VERSION_MAJOR}.${RTT_VERSION_MINOR}" VERSION "${RTT_VERSION}" + SOVERSION "${RTT_SOVERSION}" OUTPUT_NAME orocos-rtt-${OROCOS_TARGET} COMPILE_DEFINITIONS OROCOS_TARGET=${OROCOS_TARGET} INSTALL_NAME_DIR "${CMAKE_INSTALL_PREFIX}/lib" diff --git a/rtt/ExecutionEngine.cpp b/rtt/ExecutionEngine.cpp index 61eb3f463..88cb97fe6 100644 --- a/rtt/ExecutionEngine.cpp +++ b/rtt/ExecutionEngine.cpp @@ -48,12 +48,6 @@ #include "extras/SlaveActivity.hpp" #include -#include -#ifndef USE_CPP11 -#include -#include -#endif -#include #include #define ORONUM_EE_MQUEUE_SIZE 100 @@ -161,8 +155,8 @@ namespace RTT found = true; // always true in order to be able to quit waitForMessages. } virtual void dispose() {} - virtual bool isError() const { return false;} - + virtual bool isError() const { return false; } + bool done() const { return !mf->isLoaded() || found; } }; bool ExecutionEngine::removeFunction( ExecutableInterface* f ) @@ -182,11 +176,7 @@ namespace RTT // Running: create message on stack. RemoveMsg rmsg(f,this); if ( this->process(&rmsg) ) -#ifdef USE_CPP11 - this->waitForMessages( ! bind(&ExecutableInterface::isLoaded, f) || bind(&RemoveMsg::found,boost::ref(rmsg)) ); -#else - this->waitForMessages( ! lambda::bind(&ExecutableInterface::isLoaded, f) || lambda::bind(&RemoveMsg::found,boost::ref(rmsg)) ); -#endif + this->waitForMessages( boost::bind(&RemoveMsg::done, &rmsg) ); if (!rmsg.found) return false; } @@ -378,7 +368,7 @@ namespace RTT ) } // in case start() or updateHook() called error(), this will be called: - if ( taskc->mTaskState == TaskCore::RunTimeError ) { + if (taskc->mTaskState == TaskCore::RunTimeError && taskc->mTargetState >= TaskCore::Running) { TRY ( taskc->errorHook(); ) CATCH(std::exception const& e, @@ -408,7 +398,7 @@ namespace RTT (*it)->exception(); // calls stopHook,cleanupHook ) } - if ( (*it)->mTaskState == TaskCore::RunTimeError ){ + if ((*it)->mTaskState == TaskCore::RunTimeError && (*it)->mTargetState == TaskCore::RunTimeError){ TRY ( (*it)->errorHook(); ) CATCH(std::exception const& e, diff --git a/rtt/InputPort.hpp b/rtt/InputPort.hpp index 5ce3fd15a..1dece6655 100644 --- a/rtt/InputPort.hpp +++ b/rtt/InputPort.hpp @@ -152,11 +152,7 @@ namespace RTT { FlowStatus result = NoData; // read and iterate if necessary. -#ifdef USE_CPP11 - cmanager.select_reader_channel( bind( &InputPort::do_read, this, boost::ref(sample), boost::ref(result), _1, _2), copy_old_data ); -#else - cmanager.select_reader_channel( boost::bind( &InputPort::do_read, this, boost::ref(sample), boost::ref(result), boost::lambda::_1, boost::lambda::_2), copy_old_data ); -#endif + cmanager.select_reader_channel( boost::bind( &InputPort::do_read, this, boost::ref(sample), boost::ref(result), _1, _2 ), copy_old_data ); return result; } diff --git a/rtt/Logger.cpp b/rtt/Logger.cpp index 8b867deb8..339d90f45 100644 --- a/rtt/Logger.cpp +++ b/rtt/Logger.cpp @@ -363,8 +363,9 @@ namespace RTT } void Logger::allowRealTime() { - *this << Logger::Warning << "Enabling Real-Time Logging !" <allowRT = true; + *this << Logger::Warning << "Enabling Real-Time Logging !" <maylog() ) + return *this; os::MutexLock lock( d->inpguard ); d->moduleptr = modname.c_str(); return *this; @@ -427,12 +430,16 @@ namespace RTT Logger& Logger::out(const std::string& oldmod) { + if ( !d->maylog() ) + return *this; os::MutexLock lock( d->inpguard ); d->moduleptr = oldmod.c_str(); return *this; } std::string Logger::getLogModule() const { + if ( !d->maylog() ) + return ""; os::MutexLock lock( d->inpguard ); std::string ret = d->moduleptr.c_str(); return ret; @@ -509,7 +516,11 @@ namespace RTT os::MutexLock lock( d->inpguard ); getline( d->remotestream, line ); if ( !d->remotestream ) + { + d->remotestream.str(""); d->remotestream.clear(); + d->messagecnt = 0; + } } if ( !line.empty() ) --d->messagecnt; diff --git a/rtt/OutputPort.hpp b/rtt/OutputPort.hpp index e41af8733..615d95825 100644 --- a/rtt/OutputPort.hpp +++ b/rtt/OutputPort.hpp @@ -233,15 +233,9 @@ namespace RTT has_initial_sample = true; has_last_written_value = false; -#ifdef USE_CPP11 - cmanager.delete_if( bind( - &OutputPort::do_init, this, boost::ref(sample), _1) - ); -#else cmanager.delete_if( boost::bind( - &OutputPort::do_init, this, boost::ref(sample), _1) + &OutputPort::do_init, this, boost::ref(sample), _1 ) ); -#endif } /** @@ -258,15 +252,9 @@ namespace RTT } has_last_written_value = keeps_last_written_value; -#ifdef USE_CPP11 - cmanager.delete_if( bind( - &OutputPort::do_write, this, boost::ref(sample), _1) - ); -#else cmanager.delete_if( boost::bind( - &OutputPort::do_write, this, boost::ref(sample), boost::lambda::_1) + &OutputPort::do_write, this, boost::ref(sample), _1 ) ); -#endif } void write(base::DataSourceBase::shared_ptr source) diff --git a/rtt/Property.hpp b/rtt/Property.hpp index 1bafa7169..9c7a3f410 100644 --- a/rtt/Property.hpp +++ b/rtt/Property.hpp @@ -165,7 +165,7 @@ namespace RTT * @post ready() will be true if datasource is a valid pointer. */ Property(const std::string& name, const std::string& description, - typename internal::AssignableDataSource::shared_ptr datasource ) + const typename internal::AssignableDataSource::shared_ptr& datasource ) : base::PropertyBase(name, description), _value( datasource ) { // need to do this on the datasource in order to have access to set()/rvalue() of the data source. @@ -373,14 +373,21 @@ namespace RTT return new Property(*this); } - virtual Property* copy() const + virtual Property* create() const { - return new Property( _name, _description, _value ); + return new Property( _name, _description, T() ); } - virtual Property* create() const + virtual Property* create( const base::DataSourceBase::shared_ptr& datasource ) const { - return new Property( _name, _description, T() ); + typename internal::AssignableDataSource::shared_ptr value + = internal::AssignableDataSource::narrow( datasource.get() ); + Property* prop = new Property( _name, _description, value ); + if ( datasource && !prop->ready() ) { + log(Error) << "Cannot initialize Property: " + << "incompatible type ( destination type: " << getType() << ", source type: " << datasource->getTypeName() << ")." << endlog(); + } + return prop; } virtual base::DataSourceBase::shared_ptr getDataSource() const { diff --git a/rtt/PropertyBag.cpp b/rtt/PropertyBag.cpp index 6bf27465d..f9f27d23e 100644 --- a/rtt/PropertyBag.cpp +++ b/rtt/PropertyBag.cpp @@ -233,7 +233,7 @@ namespace RTT for( const_iterator i = orig.mproperties.begin(); i != orig.mproperties.end(); ++i) { if ( orig.ownsProperty( *i ) ) { - PropertyBase* copy = (*i)->copy(); + PropertyBase* copy = (*i)->create( (*i)->getDataSource() ); this->ownProperty( copy ); } else { this->add( *i ); @@ -615,7 +615,7 @@ namespace RTT temp->update( (*sit) ); } // step 3 : add result to target bag. - target.add( temp ); + target.ownProperty( temp ); } } ++it; diff --git a/rtt/Service.cpp b/rtt/Service.cpp index 875701f36..498b74b3c 100644 --- a/rtt/Service.cpp +++ b/rtt/Service.cpp @@ -40,8 +40,6 @@ #include "TaskContext.hpp" #include #include "internal/mystd.hpp" -#include -#include #include namespace RTT { @@ -223,7 +221,10 @@ namespace RTT { simpleoperations.erase(simpleoperations.begin() ); } - for_each(ownedoperations.begin(),ownedoperations.end(), lambda::delete_ptr() ); + for( OperationList::const_iterator it = ownedoperations.begin(); it != ownedoperations.end(); ++it ) + { + delete *it; + } ownedoperations.clear(); OperationInterface::clear(); diff --git a/rtt/base/PropertyBase.hpp b/rtt/base/PropertyBase.hpp index 52af0e0d1..86b85f4f6 100644 --- a/rtt/base/PropertyBase.hpp +++ b/rtt/base/PropertyBase.hpp @@ -179,18 +179,18 @@ namespace RTT virtual PropertyBase* clone() const = 0; /** - * Deliver a shallow copy of this PropertyBase with a shared - * DataSource. The original may be deleted and the clone can be - * transparantly used in its place or vice versa. + * Create a new default instance of the PropertyBase. + * This is a factory method to 'make something of the same type'. + * The new PropertyBase has the same name and description as this. */ - virtual PropertyBase* copy() const = 0; + virtual PropertyBase* create() const = 0; /** - * Create a new default instance of the PropertyBase. + * Create a new instance of the PropertyBase with a custom data source. * This is a factory method to 'make something of the same type'. * The new PropertyBase has the same name and description as this. */ - virtual PropertyBase* create() const = 0; + virtual PropertyBase* create( const base::DataSourceBase::shared_ptr& datasource ) const = 0; /** * Get an assignable base::DataSource through which this PropertyBase diff --git a/rtt/base/TaskCore.cpp b/rtt/base/TaskCore.cpp index 9217deb3d..08a0e3daf 100644 --- a/rtt/base/TaskCore.cpp +++ b/rtt/base/TaskCore.cpp @@ -182,7 +182,7 @@ namespace RTT { mTargetState = mTaskState = mInitialState; return true; } - if (mTaskState == RunTimeError ) { + if (mTaskState == RunTimeError && mTargetState >= Running) { mTargetState = mTaskState = Running; return true; } diff --git a/rtt/extras/TimerThread.cpp b/rtt/extras/TimerThread.cpp index cbd7ff17a..22b417801 100644 --- a/rtt/extras/TimerThread.cpp +++ b/rtt/extras/TimerThread.cpp @@ -44,6 +44,7 @@ #include "../Logger.hpp" #include #include "../os/MutexLock.hpp" +#include "../os/MainThread.hpp" namespace RTT { using namespace extras; @@ -60,7 +61,7 @@ namespace RTT { TimerThreadPtr TimerThread::Instance(int scheduler, int pri, double per) { - return Instance(scheduler, pri, per, ~0); + return Instance(scheduler, pri, per, 0); } TimerThreadPtr TimerThread::Instance(int scheduler, int pri, double per, unsigned cpu_affinity) @@ -68,6 +69,7 @@ namespace RTT { // Since the period is stored as nsecs, we convert per to NS in order // to get a match. os::CheckPriority(scheduler, pri); + if (cpu_affinity == 0) cpu_affinity = os::MainThread::Instance()->getCpuAffinity(); TimerThreadList::iterator it = TimerThreads.begin(); while ( it != TimerThreads.end() ) { TimerThreadPtr tptr = it->lock(); @@ -77,7 +79,10 @@ namespace RTT { it = TimerThreads.begin(); continue; } - if ( tptr->getScheduler() == scheduler && tptr->getPriority() == pri && tptr->getPeriodNS() == Seconds_to_nsecs(per) ) { + if ( tptr->getScheduler() == scheduler && + tptr->getPriority() == pri && + tptr->getPeriodNS() == Seconds_to_nsecs(per) && + tptr->getCpuAffinity() == cpu_affinity ) { return tptr; } ++it; diff --git a/rtt/internal/ConnectionManager.cpp b/rtt/internal/ConnectionManager.cpp index 227fc28b1..58240a3dc 100644 --- a/rtt/internal/ConnectionManager.cpp +++ b/rtt/internal/ConnectionManager.cpp @@ -60,6 +60,7 @@ namespace RTT ConnectionManager::ConnectionManager(PortInterface* port) : mport(port) + , cur_channel(NULL) { } @@ -89,9 +90,9 @@ namespace RTT void ConnectionManager::updateCurrentChannel(bool reset_current) { if (connections.empty()) - cur_channel = ChannelDescriptor(); + cur_channel = NULL; else if (reset_current) - cur_channel = connections.front(); + cur_channel = &(connections.front()); } bool ConnectionManager::disconnect(PortInterface* port) @@ -116,7 +117,7 @@ namespace RTT std::list all_connections; { RTT::os::MutexLock lock(connection_lock); all_connections.splice(all_connections.end(), connections); - cur_channel = ChannelDescriptor(); + cur_channel = NULL; } std::for_each(all_connections.begin(), all_connections.end(), boost::bind(&ConnectionManager::eraseConnection, this, _1)); @@ -130,9 +131,9 @@ namespace RTT { RTT::os::MutexLock lock(connection_lock); assert(conn_id); ChannelDescriptor descriptor = boost::make_tuple(conn_id, channel, policy); - if (connections.empty()) - cur_channel = descriptor; - connections.push_back(descriptor); + connections.insert(connections.end(), descriptor); + if (connections.size() == 1) + cur_channel = &(connections.front()); } bool ConnectionManager::removeConnection(ConnID* conn_id) @@ -144,8 +145,11 @@ namespace RTT if (conn_it == connections.end()) return false; descriptor = *conn_it; + // Verify whether cur_channel is conn_it before we erase, as + // cur_channel is a pointer to an element in connections + bool reset_current = cur_channel && (cur_channel->get<1>() == descriptor.get<1>()); connections.erase(conn_it); - updateCurrentChannel( cur_channel.get<1>() == descriptor.get<1>() ); + updateCurrentChannel(reset_current); } // disconnect needs to know if we're from Out->In (forward) or from In->Out diff --git a/rtt/internal/ConnectionManager.hpp b/rtt/internal/ConnectionManager.hpp index 23f5363fb..6639f7f25 100644 --- a/rtt/internal/ConnectionManager.hpp +++ b/rtt/internal/ConnectionManager.hpp @@ -56,9 +56,6 @@ #include #include #include -#ifndef USE_CPP11 -#include -#endif #include #include @@ -145,34 +142,34 @@ namespace RTT template void select_reader_channel(Pred pred, bool copy_old_data) { RTT::os::MutexLock lock(connection_lock); - std::pair new_channel = + ChannelDescriptor *new_channel = find_if(pred, copy_old_data); - if (new_channel.first) + if (new_channel) { // We don't clear the current channel (to get it to NoData state), because there is a race // between find_if and this line. We have to accept (in other parts of the code) that eventually, // all channels return 'OldData'. - cur_channel = new_channel.second; + cur_channel = new_channel; } } template - std::pair find_if(Pred pred, bool copy_old_data) { + ChannelDescriptor *find_if(Pred pred, bool copy_old_data) { // We only copy OldData in the initial read of the current channel. // if it has no new data, the search over the other channels starts, // but no old data is needed. - ChannelDescriptor channel = cur_channel; - if ( channel.get<1>() ) - if ( pred( copy_old_data, channel ) ) - return std::make_pair(true, channel); + ChannelDescriptor *channel = cur_channel; + if ( channel ) + if ( pred( copy_old_data, *channel ) ) + return channel; std::list::iterator result; for (result = connections.begin(); result != connections.end(); ++result) { - if (result->get<1>() == cur_channel.get<1>()) continue; + if (cur_channel && (result->get<1>() == cur_channel->get<1>())) continue; if ( pred(false, *result) == true) - return std::make_pair(true, *result); + return &(*result); } - return std::make_pair(false, ChannelDescriptor()); + return NULL; } /** @@ -187,7 +184,7 @@ namespace RTT * @return */ base::ChannelElementBase* getCurrentChannel() const { - return cur_channel.get<1>().get(); + return cur_channel ? cur_channel->get<1>().get() : NULL; } /** @@ -254,7 +251,7 @@ namespace RTT /** * Optimisation in case only one channel is to be managed. */ - ChannelDescriptor cur_channel; + ChannelDescriptor *cur_channel; /** * Lock that should be taken before the list of connections is diff --git a/rtt/internal/FusedFunctorDataSource.hpp b/rtt/internal/FusedFunctorDataSource.hpp index 7f8478ded..4e7a1b5fc 100644 --- a/rtt/internal/FusedFunctorDataSource.hpp +++ b/rtt/internal/FusedFunctorDataSource.hpp @@ -507,7 +507,7 @@ namespace RTT * puts them into the assignable data sources and * executes the associated action. */ - result_type invoke(typename SequenceFactory::data_type seq) { + result_type invoke(const typename SequenceFactory::data_type& seq) const { if ( subscriber ) { // asynchronous shared_ptr sg = this->cloneRT(); diff --git a/rtt/internal/ListLocked.hpp b/rtt/internal/ListLocked.hpp index a3004741a..601be3913 100644 --- a/rtt/internal/ListLocked.hpp +++ b/rtt/internal/ListLocked.hpp @@ -254,7 +254,7 @@ namespace RTT { if(pred(cur->data)) { - cur = mlist.erase_and_dispose(cur, boost::bind(&ListLocked::give_back, this, ::_1) ); + cur = mlist.erase_and_dispose(cur, boost::bind(&ListLocked::give_back, this, _1) ); deleted = true; } else diff --git a/rtt/internal/OperationCallerBinder.hpp b/rtt/internal/OperationCallerBinder.hpp index 289768a3f..3e4db2082 100644 --- a/rtt/internal/OperationCallerBinder.hpp +++ b/rtt/internal/OperationCallerBinder.hpp @@ -65,7 +65,7 @@ namespace RTT { template boost::function operator()(M m, O o) { - return boost::bind( boost::mem_fn(m), o, ::_1 ); + return boost::bind( boost::mem_fn(m), o, _1 ); } }; @@ -74,7 +74,7 @@ namespace RTT { template boost::function operator()(M m, O o) { - return boost::bind( boost::mem_fn(m), o, ::_1, ::_2 ); + return boost::bind( boost::mem_fn(m), o, _1, _2 ); } }; @@ -83,7 +83,7 @@ namespace RTT { template boost::function operator()(M m, O o) { - return boost::bind( boost::mem_fn(m), o, ::_1, ::_2, ::_3 ); + return boost::bind( boost::mem_fn(m), o, _1, _2, _3 ); } }; @@ -92,7 +92,7 @@ namespace RTT { template boost::function operator()(M m, O o) { - return boost::bind( boost::mem_fn(m), o, ::_1, ::_2, ::_3, ::_4 ); + return boost::bind( boost::mem_fn(m), o, _1, _2, _3, _4 ); } }; @@ -101,7 +101,7 @@ namespace RTT { template boost::function operator()(M m, O o) { - return boost::bind( boost::mem_fn(m), o, ::_1, ::_2, ::_3, ::_4, ::_5 ); + return boost::bind( boost::mem_fn(m), o, _1, _2, _3, _4, _5 ); } }; @@ -110,7 +110,7 @@ namespace RTT { template boost::function operator()(M m, O o) { - return boost::bind( boost::mem_fn(m), o, ::_1, ::_2, ::_3, ::_4, ::_5, ::_6 ); + return boost::bind( boost::mem_fn(m), o, _1, _2, _3, _4, _5, _6 ); } }; @@ -119,7 +119,7 @@ namespace RTT { template boost::function operator()(M m, O o) { - return boost::bind( boost::mem_fn(m), o, ::_1, ::_2, ::_3, ::_4, ::_5, ::_6, ::_7 ); + return boost::bind( boost::mem_fn(m), o, _1, _2, _3, _4, _5, _6, _7 ); } }; @@ -128,7 +128,7 @@ namespace RTT { template boost::function operator()(M m, O o) { - return boost::bind( boost::mem_fn(m), o, ::_1, ::_2, ::_3, ::_4, ::_5, ::_6, ::_7, ::_8 ); + return boost::bind( boost::mem_fn(m), o, _1, _2, _3, _4, _5, _6, _7, _8 ); } }; @@ -137,7 +137,7 @@ namespace RTT { template boost::function operator()(M m, O o) { - return boost::bind( boost::mem_fn(m), o, ::_1, ::_2, ::_3, ::_4, ::_5, ::_6, ::_7, ::_8, ::_9 ); + return boost::bind( boost::mem_fn(m), o, _1, _2, _3, _4, _5, _6, _7, _8, _9 ); } }; diff --git a/rtt/internal/OperationInterfacePartFused.hpp b/rtt/internal/OperationInterfacePartFused.hpp index b9c561183..8dfbc4d56 100644 --- a/rtt/internal/OperationInterfacePartFused.hpp +++ b/rtt/internal/OperationInterfacePartFused.hpp @@ -50,6 +50,7 @@ #ifndef BOOST_FUSION_UNFUSED_MAX_ARITY #define BOOST_FUSION_UNFUSED_MAX_ARITY 7 #endif +#include #include #else // our code goes up to 7 FUSION_MAX_VECTOR_SIZE defaults to 10 @@ -59,10 +60,6 @@ #include #endif -#ifndef USE_CPP11 -#include -#endif - #include #include @@ -171,7 +168,7 @@ namespace RTT assert( carity == collectArity() + 1 ); // check for arity functions. (this is actually a compile time assert). if ( args.size() != carity ) throw wrong_number_of_args_exception(carity, args.size() ); // we need to ask FusedMCollectDataSource what the arg types are, based on the collect signature. - return new FusedMCollectDataSource( create_sequence::handle_and_arg_types >::sources(args.begin()), blocking ); + return new FusedMCollectDataSource( create_sequence::handle_and_arg_types >::assignable(args.begin()), blocking ); } #ifdef ORO_SIGNALLING_OPERATIONS @@ -216,32 +213,34 @@ namespace RTT if ( args.size() != OperationInterfacePartFused::arity() ) throw wrong_number_of_args_exception(OperationInterfacePartFused::arity(), args.size() ); // note: in boost 1.41.0+ the function make_unfused() is available. #if BOOST_VERSION >= 104100 -#ifdef USE_CPP11 - return this->op->signals( boost::fusion::make_unfused(boost::bind(&FusedMSignal::invoke, - boost::make_shared >(func, SequenceFactory::assignable(args.begin()), subscriber), - _1 - ) - ) - ); -#else - return this->op->signals( boost::fusion::make_unfused(boost::bind(&FusedMSignal::invoke, - boost::make_shared >(func, SequenceFactory::assignable(args.begin()), subscriber), - boost::lambda::_1 - ) - ) - ); -#endif -#else - return this->op->signals( boost::fusion::make_unfused_generic(boost::bind(&FusedMSignal::invoke, - boost::make_shared >(func, SequenceFactory::assignable(args.begin()),subscriber), - boost::lambda::_1 - ) - ) - ); -#endif +#if __cplusplus > 199711L + auto invoke_fused = boost::bind(&FusedMSignal::invoke, + boost::make_shared >(func, SequenceFactory::assignable(args.begin()), subscriber), + _1 + ); + typedef typename boost::fusion::result_of::make_unfused< decltype(invoke_fused) >::type unfused_type; + return this->op->signals(boost::forward_adapter(boost::fusion::make_unfused(invoke_fused))); +#else // __cplusplus > 199711L + return this->op->signals( + boost::fusion::make_unfused(boost::bind(&FusedMSignal::invoke, + boost::make_shared >(func, SequenceFactory::assignable(args.begin()), subscriber), + _1 + ) + ) + ); +#endif // __cplusplus > 199711L +#else // BOOST_VERSION >= 104100 + return this->op->signals( + boost::fusion::make_unfused_generic(boost::bind(&FusedMSignal::invoke, + boost::make_shared >(func, SequenceFactory::assignable(args.begin()), subscriber), + _1 + ) + ) + ); +#endif // BOOST_VERSION >= 104100 } }; -#endif +#endif // ORO_SIGNALLING_OPERATIONS /** * OperationInterfacePart implementation that only provides synchronous @@ -421,7 +420,7 @@ namespace RTT assert( carity == collectArity() + 1 ); // check for arity functions. (this is actually a compile time assert). if ( args.size() != carity ) throw wrong_number_of_args_exception(carity, args.size() ); // we need to ask FusedMCollectDataSource what the arg types are, based on the collect signature. - return new FusedMCollectDataSource( create_sequence::handle_and_arg_types >::sources(args.begin()), blocking ); + return new FusedMCollectDataSource( create_sequence::handle_and_arg_types >::assignable(args.begin()), blocking ); } #ifdef ORO_SIGNALLING_OPERATIONS virtual Handle produceSignal( base::ActionInterface* func, const std::vector& args, ExecutionEngine* subscriber) const { @@ -435,23 +434,35 @@ namespace RTT a2.push_back(mwp); a2.insert(a2.end(), args.begin(), args.end()); // note: in boost 1.41.0+ the function make_unfused() is available. - #if BOOST_VERSION >= 104100 - return this->op->signals( boost::fusion::make_unfused(boost::bind(&FusedMSignal::invoke, - boost::make_shared >(func, SequenceFactory::assignable(args.begin()),subscriber), - _1 - ) - ) - ); - #else - return this->op->signals( boost::fusion::make_unfused_generic(boost::bind(&FusedMSignal::invoke, - boost::make_shared >(func, SequenceFactory::assignable(args.begin()),subscriber), - _1 - ) - ) - ); - #endif +#if BOOST_VERSION >= 104100 +#if __cplusplus > 199711L + auto invoke_fused = boost::bind(&FusedMSignal::invoke, + boost::make_shared >(func, SequenceFactory::assignable(args.begin()), subscriber), + _1 + ); + typedef typename boost::fusion::result_of::make_unfused< decltype(invoke_fused) >::type unfused_type; + return this->op->signals(boost::forward_adapter(boost::fusion::make_unfused(invoke_fused))); +#else // __cplusplus > 199711L + return this->op->signals( + boost::fusion::make_unfused(boost::bind(&FusedMSignal::invoke, + boost::make_shared >(func, SequenceFactory::assignable(args.begin()), subscriber), + _1 + ) + ) + ); +#endif // __cplusplus > 199711L +#else // BOOST_VERSION >= 104100 + return this->op->signals( + boost::fusion::make_unfused_generic(boost::bind(&FusedMSignal::invoke, + boost::make_shared >(func, SequenceFactory::assignable(args.begin()), subscriber), + _1 + ) + ) + ); +#endif // BOOST_VERSION >= 104100 } -#endif +#endif // ORO_SIGNALLING_OPERATIONS + boost::shared_ptr getLocalOperation() const { return this->op->getImplementation(); } diff --git a/rtt/internal/SignalBase.cpp b/rtt/internal/SignalBase.cpp index b9e62faa2..fbf374f96 100644 --- a/rtt/internal/SignalBase.cpp +++ b/rtt/internal/SignalBase.cpp @@ -37,7 +37,7 @@ #include "SignalBase.hpp" -#include +#include #ifdef ORO_SIGNAL_USE_LIST_LOCK_FREE #else @@ -232,15 +232,14 @@ namespace RTT { } #ifdef ORO_SIGNAL_USE_LIST_LOCK_FREE - // required for GCC 4.0.2 - ConnectionBase* getPointer( ConnectionBase::shared_ptr c ) { - return c.get(); + static void disconnectImpl( const ConnectionBase::shared_ptr& c ) { + c->disconnect(); } #endif void SignalBase::disconnect() { #ifdef ORO_SIGNAL_USE_LIST_LOCK_FREE - mconnections.apply( boost::lambda::bind(&ConnectionBase::disconnect, boost::lambda::bind( &getPointer, boost::lambda::_1) ) ); // works for any compiler + mconnections.apply( boost::bind(&disconnectImpl, _1 ) ); #else // avoid invalidating iterator os::MutexLock lock(m); diff --git a/rtt/internal/signal_template.hpp b/rtt/internal/signal_template.hpp index 88f6c9be2..60d90a9a3 100644 --- a/rtt/internal/signal_template.hpp +++ b/rtt/internal/signal_template.hpp @@ -43,11 +43,7 @@ #include "NA.hpp" #ifdef ORO_SIGNAL_USE_LIST_LOCK_FREE -#ifndef USE_CPP11 -#include #include -#include -#endif #else #include "../os/MutexLock.hpp" #endif @@ -105,14 +101,7 @@ namespace RTT { typedef arg1_type first_argument_type; typedef arg2_type second_argument_type; #endif - private: -#ifdef ORO_SIGNAL_USE_LIST_LOCK_FREE - // required for GCC 4.0.2 - static connection_impl* applyEmit( connection_t c ) { - return static_cast (c.get() ); - } -#endif - public: + OROCOS_SIGNAL_N() { } @@ -132,6 +121,17 @@ namespace RTT { return Handle(conn); } + private: + static void emitImpl(const connection_t& c +#if OROCOS_SIGNATURE_NUM_ARGS != 0 + , OROCOS_SIGNATURE_PARMS +#endif + ) + { + static_cast(c.get())->emit(OROCOS_SIGNATURE_ARGS); + } + + public: R emit(OROCOS_SIGNATURE_PARMS) { #ifdef ORO_SIGNAL_USE_LIST_LOCK_FREE @@ -140,14 +140,8 @@ namespace RTT { // this code did initially not work under gcc 4.0/ubuntu breezy. // connection_t::get() const becomes an undefined symbol. // works under gcc 3.4 -#ifdef USE_CPP11 - mconnections.apply( bind(&connection_impl::emit, - bind( &applyEmit, _1) // works for any compiler -#else - mconnections.apply( boost::lambda::bind(&connection_impl::emit, - boost::lambda::bind( &applyEmit, boost::lambda::_1) // works for any compiler - //not in gcc 4.0.2: boost::lambda::ll_static_cast(boost::lambda::bind(&connection_t::get, boost::lambda::_1)) -#endif + mconnections.apply( boost::bind(&OROCOS_SIGNAL_N::emitImpl, + _1 #if OROCOS_SIGNATURE_NUM_ARGS != 0 ,OROCOS_SIGNATURE_ARGS #endif diff --git a/rtt/marsh/CPFDemarshaller.cpp b/rtt/marsh/CPFDemarshaller.cpp index 268fc4186..f3c11472b 100644 --- a/rtt/marsh/CPFDemarshaller.cpp +++ b/rtt/marsh/CPFDemarshaller.cpp @@ -143,10 +143,10 @@ namespace RTT if ( type == "boolean" ) { if ( value_string == "1" || value_string == "true") - bag_stack.top().first->add + bag_stack.top().first->ownProperty ( new Property( name, description, true ) ); else if ( value_string == "0" || value_string == "false" ) - bag_stack.top().first->add + bag_stack.top().first->ownProperty ( new Property( name, description, false ) ); else throw SAXException(std::string("Wrong value for property '"+type+"'." \ @@ -154,27 +154,27 @@ namespace RTT } else if ( type == "char" ) { if ( value_string.empty() ) - bag_stack.top().first->add( new Property( name, description, '\0' ) ); + bag_stack.top().first->ownProperty( new Property( name, description, '\0' ) ); else if ( value_string.length() != 1 ) throw SAXException(std::string("Wrong value for property '"+type+"'." \ " Value should contain a single character, got '"+ value_string +"'.").c_str()); else - bag_stack.top().first->add( new Property( name, description, value_string[0] ) ); + bag_stack.top().first->ownProperty( new Property( name, description, value_string[0] ) ); } else if ( type == "uchar" || type == "octet" ) { if ( value_string.length() != 1 ) throw SAXException(std::string("Wrong value for property '"+type+"'." \ " Value should contain a single unsigned character, got '"+ value_string +"'.").c_str()); else - bag_stack.top().first->add + bag_stack.top().first->ownProperty ( new Property( name, description, value_string[0] ) ); } else if ( type == "long" || type == "short") { int v; if ( sscanf(value_string.c_str(), "%d", &v) == 1) - bag_stack.top().first->add( new Property( name, description, v ) ); + bag_stack.top().first->ownProperty( new Property( name, description, v ) ); else throw SAXException(std::string("Wrong value for property '"+type+"'." \ " Value should contain an integer value, got '"+ value_string +"'.").c_str()); @@ -183,7 +183,7 @@ namespace RTT { unsigned int v; if ( sscanf(value_string.c_str(), "%u", &v) == 1) - bag_stack.top().first->add( new Property( name, description, v ) ); + bag_stack.top().first->ownProperty( new Property( name, description, v ) ); else throw SAXException(std::string("Wrong value for property '"+type+"'." \ " Value should contain an integer value, got '"+ value_string +"'.").c_str()); @@ -192,7 +192,7 @@ namespace RTT { double v; if ( sscanf(value_string.c_str(), "%lf", &v) == 1 ) - bag_stack.top().first->add + bag_stack.top().first->ownProperty ( new Property( name, description, v ) ); else throw SAXException(std::string("Wrong value for property '"+type+"'." \ @@ -202,14 +202,14 @@ namespace RTT { float v; if ( sscanf(value_string.c_str(), "%f", &v) == 1 ) - bag_stack.top().first->add + bag_stack.top().first->ownProperty ( new Property( name, description, v ) ); else throw SAXException(std::string("Wrong value for property '"+type+"'." \ " Value should contain a float value, got '"+ value_string +"'.").c_str()); } else if ( type == "string") - bag_stack.top().first->add + bag_stack.top().first->ownProperty ( new Property( name, description, value_string ) ); tag_stack.pop(); value_string.clear(); // cleanup @@ -222,7 +222,7 @@ namespace RTT { Property* prop = bag_stack.top().second; bag_stack.pop(); - bag_stack.top().first->add( prop ); + bag_stack.top().first->ownProperty( prop ); //( new Property( pn, description, *pb ) ); //delete pb; tag_stack.pop(); diff --git a/rtt/os/Atomic.hpp b/rtt/os/Atomic.hpp index 858f2745b..ba3fcd27b 100644 --- a/rtt/os/Atomic.hpp +++ b/rtt/os/Atomic.hpp @@ -85,14 +85,29 @@ namespace RTT void sub(int i) { oro_atomic_sub( &_val, i ); } + /** Subtract a value and test if the result is zero + * + * @return true if the atomic is zero after the decrement, and false + * otherwise + */ bool sub_and_test(int i) { return oro_atomic_sub_and_test( &_val, i) != 0; } void inc() { oro_atomic_inc( &_val ); } void dec() { oro_atomic_dec( &_val ); } + /** Decrement and test if the result is zero + * + * @return true if the atomic is zero after the decrement, and false + * otherwise + */ bool dec_and_test() { return oro_atomic_dec_and_test( &_val ) != 0; } + /** Increment and test if the result is zero + * + * @return true if the atomic is zero after the increment, and false + * otherwise + */ bool inc_and_test() { return oro_atomic_inc_and_test( &_val ) != 0; } }; diff --git a/rtt/os/MainThread.cpp b/rtt/os/MainThread.cpp index bcd8f2c5a..9b1015e41 100644 --- a/rtt/os/MainThread.cpp +++ b/rtt/os/MainThread.cpp @@ -111,6 +111,11 @@ namespace RTT return rtos_task_get_pid(&main_task); } + unsigned MainThread::getCpuAffinity() const + { + return rtos_task_get_cpu_affinity(&main_task); + } + bool MainThread::setPeriod(Seconds period) { return false; diff --git a/rtt/os/MainThread.hpp b/rtt/os/MainThread.hpp index 0ebb8bf04..25dff6e3b 100644 --- a/rtt/os/MainThread.hpp +++ b/rtt/os/MainThread.hpp @@ -128,6 +128,8 @@ namespace RTT virtual unsigned int getPid() const; + virtual unsigned getCpuAffinity() const; + virtual void setMaxOverrun(int m); virtual int getMaxOverrun() const; diff --git a/rtt/os/Thread.cpp b/rtt/os/Thread.cpp index b078aae1c..5deb44c45 100644 --- a/rtt/os/Thread.cpp +++ b/rtt/os/Thread.cpp @@ -41,6 +41,7 @@ #include "threads.hpp" #include "../Logger.hpp" #include "MutexLock.hpp" +#include "MainThread.hpp" #include "../rtt-config.h" #include "../internal/CatchConfig.hpp" diff --git a/rtt/os/Thread.hpp b/rtt/os/Thread.hpp index ff06ea9c7..0640d9931 100644 --- a/rtt/os/Thread.hpp +++ b/rtt/os/Thread.hpp @@ -119,6 +119,7 @@ namespace RTT * @param priority The priority of the thread, this is interpreted by your RTOS. * @param period The period in seconds (eg 0.001) of the thread, or zero if not periodic. * @param cpu_affinity The cpu affinity of the thread, this is interpreted by your RTOS. + * If 0, the new thread inherits the affinity of its creator (the default). * @param name The name of the Thread. May be used by your OS to identify the thread. * the thread's own virtual functions are executed. */ @@ -220,9 +221,10 @@ namespace RTT virtual int getPriority() const; virtual unsigned int getPid() const; + /** * Set cpu affinity for this thread - * @cpu_affinity The cpu affinity of the thread (@see rtos_task_set_cpu_affinity). + * @param cpu_affinity The cpu affinity of the thread (@see rtos_task_set_cpu_affinity). * @return true if the mask has been applied */ virtual bool setCpuAffinity(unsigned cpu_affinity); diff --git a/rtt/os/ThreadInterface.hpp b/rtt/os/ThreadInterface.hpp index 702d65f88..69717667c 100644 --- a/rtt/os/ThreadInterface.hpp +++ b/rtt/os/ThreadInterface.hpp @@ -190,6 +190,11 @@ namespace RTT */ virtual unsigned int getPid() const = 0; + /** + * @return the cpu affinity + */ + virtual unsigned getCpuAffinity() const = 0; + virtual void setMaxOverrun(int m) = 0; virtual int getMaxOverrun() const = 0; diff --git a/rtt/os/gnulinux/fosi_internal.cpp b/rtt/os/gnulinux/fosi_internal.cpp index 069d20e8b..2916ebfc8 100644 --- a/rtt/os/gnulinux/fosi_internal.cpp +++ b/rtt/os/gnulinux/fosi_internal.cpp @@ -173,12 +173,12 @@ namespace RTT } int result = pthread_setname_np(task->thread, thread_name); if (result != 0) { - log(Error) << "Failed to set thread name for " << task->name << ": " - << strerror(result) << endlog(); + log(Warning) << "Failed to set thread name for " << task->name << ": " + << strerror(result) << endlog(); } } - if ( cpu_affinity != (unsigned)~0 ) { + if ( cpu_affinity != 0 ) { log(Debug) << "Setting CPU affinity to " << cpu_affinity << endlog(); int result = rtos_task_set_cpu_affinity(task, cpu_affinity); if (result != 0) { diff --git a/rtt/os/xenomai/fosi_internal.cpp b/rtt/os/xenomai/fosi_internal.cpp index 9d10a76ad..573b59bfe 100644 --- a/rtt/os/xenomai/fosi_internal.cpp +++ b/rtt/os/xenomai/fosi_internal.cpp @@ -424,7 +424,7 @@ namespace RTT INTERNAL_QUAL unsigned rtos_task_get_cpu_affinity(const RTOS_TASK *task) { - return 0; + return ~0; } INTERNAL_QUAL const char* rtos_task_get_name(const RTOS_TASK* mytask) { diff --git a/rtt/plugin/PluginLoader.cpp b/rtt/plugin/PluginLoader.cpp index fc718140e..754db10ea 100644 --- a/rtt/plugin/PluginLoader.cpp +++ b/rtt/plugin/PluginLoader.cpp @@ -318,8 +318,8 @@ namespace { static boost::shared_ptr instance2; -PluginLoader::PluginLoader() { log(Debug) <<"PluginLoader Created" < PluginLoader::Instance() { diff --git a/rtt/transports/corba/CMakeLists.txt b/rtt/transports/corba/CMakeLists.txt index 1c0e91db7..82694fe56 100644 --- a/rtt/transports/corba/CMakeLists.txt +++ b/rtt/transports/corba/CMakeLists.txt @@ -67,8 +67,8 @@ ENDIF( BUILD_STATIC ) OUTPUT_NAME orocos-rtt-corba-${OROCOS_TARGET} CLEAN_DIRECT_OUTPUT 1 COMPILE_DEFINITIONS "${OROCOS-RTT_DEFINITIONS}" - SOVERSION "${RTT_VERSION_MAJOR}.${RTT_VERSION_MINOR}" VERSION "${RTT_VERSION}" + SOVERSION "${RTT_SOVERSION}" INSTALL_NAME_DIR "${CMAKE_INSTALL_PREFIX}/lib") create_pc_flags( "${CORBA_DEFINITIONS}" "${CORBA_INCLUDE_DIRS}" "${CORBA_LIBRARIES}" RTT_CORBA_DEFINES RTT_CORBA_CFLAGS RTT_CORBA_LINKFLAGS) diff --git a/rtt/transports/corba/CorbaConversion.hpp b/rtt/transports/corba/CorbaConversion.hpp index fa81cbb12..a3f2942b5 100644 --- a/rtt/transports/corba/CorbaConversion.hpp +++ b/rtt/transports/corba/CorbaConversion.hpp @@ -213,13 +213,13 @@ namespace RTT { * to a Corba sequence, given the conversion between * the C++ type and the Corba type */ - template - struct AnyConversion< std::vector > + template + struct AnyConversion< std::vector > { typedef RTT::corba::CAnySequence sequence; typedef typename AnyConversion::sequence CorbaType; - typedef std::vector StdType; + typedef std::vector StdType; static bool toStdType(StdType& tp, const CorbaType& cb) { bool res = true; @@ -331,12 +331,12 @@ namespace RTT { * to a two Corba sequences, given the conversions between * the C++ types and the Corba types */ - template - struct AnyConversion > { + template + struct AnyConversion > { typedef RTT::corba::CAnySequence sequence; typedef RTT::corba::PairSeq CorbaType; - typedef std::map StdType; + typedef std::map StdType; static bool toStdType(StdType& tp, const CorbaType& cb) { bool res = true; diff --git a/rtt/transports/corba/CorbaTemplateProtocol.hpp b/rtt/transports/corba/CorbaTemplateProtocol.hpp index 60a2f1cd6..62b5820ce 100644 --- a/rtt/transports/corba/CorbaTemplateProtocol.hpp +++ b/rtt/transports/corba/CorbaTemplateProtocol.hpp @@ -77,13 +77,11 @@ namespace RTT */ virtual CORBA::Any* createAny( base::DataSourceBase::shared_ptr source) const { - typename internal::LateReferenceDataSource::shared_ptr d_ref = boost::dynamic_pointer_cast< internal::LateReferenceDataSource >( source ); - if ( d_ref ) - return AnyConversion::createAny( d_ref->set()); - - typename internal::DataSource::shared_ptr d = boost::dynamic_pointer_cast< internal::DataSource >( source ); - if ( d ) - return AnyConversion::createAny( d->get()); + typename internal::DataSource::shared_ptr d = internal::DataSource::narrow( source.get() ); + if ( d ) { + if ( !d->evaluate() ) return 0; + return AnyConversion::createAny( d->rvalue()); + } return 0; } @@ -93,13 +91,11 @@ namespace RTT */ virtual bool updateAny( base::DataSourceBase::shared_ptr source, CORBA::Any& any) const { - typename internal::LateConstReferenceDataSource::shared_ptr d_ref = boost::dynamic_pointer_cast< internal::LateConstReferenceDataSource >( source ); - if ( d_ref ) - return AnyConversion::updateAny( d_ref->rvalue(), any); - - typename internal::DataSource::shared_ptr d = boost::dynamic_pointer_cast< internal::DataSource >( source ); - if ( d ) - return AnyConversion::updateAny( d->get(), any); + typename internal::DataSource::shared_ptr d = internal::DataSource::narrow( source.get() ); + if ( d ) { + if ( !d->evaluate() ) return false; + return AnyConversion::updateAny( d->rvalue(), any); + } return false; } @@ -117,22 +113,12 @@ namespace RTT */ virtual bool updateFromAny(const CORBA::Any* any, base::DataSourceBase::shared_ptr target) const { - typename internal::LateReferenceDataSource::shared_ptr ad_ref = boost::dynamic_pointer_cast< internal::LateReferenceDataSource >( target ); - if ( ad_ref ) { - if (AnyConversion::update(*any, ad_ref->set() ) ) { - return true; - } - return false; - } - typename internal::AssignableDataSource::shared_ptr ad = internal::AssignableDataSource::narrow( target.get() ); if ( ad ) { - PropertyType value = PropertyType(); - if (AnyConversion::update(*any, value ) ) { - ad->set( value ); - return true; + if ( AnyConversion::update(*any, ad->set() ) ) { + ad->updated(); + return true; } - return false; } return false; diff --git a/rtt/transports/corba/RemotePorts.hpp b/rtt/transports/corba/RemotePorts.hpp index 74bb61cef..68f42ee6f 100644 --- a/rtt/transports/corba/RemotePorts.hpp +++ b/rtt/transports/corba/RemotePorts.hpp @@ -84,7 +84,8 @@ namespace RTT { bool connected() const; bool createStream( const ConnPolicy& policy ); virtual bool addConnection(internal::ConnID* port_id, base::ChannelElementBase::shared_ptr channel_input, ConnPolicy const& policy); - void disconnect(); + virtual void disconnect(); + using PortClass::disconnect; }; /** @@ -104,9 +105,11 @@ namespace RTT { bool keepsLastWrittenValue() const; void keepLastWrittenValue(bool new_flag); - using base::OutputPortInterface::createConnection; virtual bool disconnect(PortInterface* port); + using RemotePort::disconnect; + bool createConnection( base::InputPortInterface& sink, ConnPolicy const& policy ); + using base::OutputPortInterface::createConnection; virtual base::DataSourceBase::shared_ptr getDataSource() const; @@ -162,6 +165,7 @@ namespace RTT { base::PortInterface* antiClone() const; virtual bool disconnect(PortInterface* port); + using RemotePort::disconnect; base::DataSourceBase* getDataSource(); diff --git a/rtt/transports/mqueue/CMakeLists.txt b/rtt/transports/mqueue/CMakeLists.txt index dd0b2148c..b6856c205 100644 --- a/rtt/transports/mqueue/CMakeLists.txt +++ b/rtt/transports/mqueue/CMakeLists.txt @@ -45,8 +45,8 @@ ENDIF( BUILD_STATIC ) CLEAN_DIRECT_OUTPUT 1 LINK_FLAGS "${MQ_LDFLAGS} ${CMAKE_LD_FLAGS}" COMPILE_DEFINITIONS "${OROCOS-RTT_DEFINITIONS}" - SOVERSION "${RTT_VERSION_MAJOR}.${RTT_VERSION_MINOR}" VERSION "${RTT_VERSION}" + SOVERSION "${RTT_SOVERSION}" INSTALL_NAME_DIR "${CMAKE_INSTALL_PREFIX}/lib") create_pc_flags( "${MQ_DEFINITIONS}" "${MQ_INCLUDE_DIRS}" "${MQ_LIBRARIES}" RTT_MQ_DEFINES RTT_MQ_CFLAGS RTT_MQ_LINKFLAGS) diff --git a/rtt/transports/mqueue/Dispatcher.hpp b/rtt/transports/mqueue/Dispatcher.hpp index 7660b8b3a..7276f6e25 100644 --- a/rtt/transports/mqueue/Dispatcher.hpp +++ b/rtt/transports/mqueue/Dispatcher.hpp @@ -192,10 +192,13 @@ namespace RTT { contains file descriptor 4 in it. */ if (readsocks < 0) { - log(Error) <<"Dispatcher failed to select on message queues. Stopped thread."< 0 read_socks(); diff --git a/tests/CMakeLists.txt b/tests/CMakeLists.txt index d7e53deb2..4e3a222a6 100644 --- a/tests/CMakeLists.txt +++ b/tests/CMakeLists.txt @@ -43,8 +43,8 @@ IF (BUILD_TESTING) LIST(APPEND TEST_LIBRARIES fixtures rtt-typekit-${OROCOS_TARGET}_plugin ${OROCOS-RTT_USER_LINK_LIBS} ) SET_TARGET_PROPERTIES( fixtures PROPERTIES DEFINE_SYMBOL "RTT_UNIT_DLL_EXPORT" - SOVERSION "${RTT_VERSION_MAJOR}.${RTT_VERSION_MINOR}" VERSION "${RTT_VERSION}" + SOVERSION "${RTT_SOVERSION}" COMPILE_DEFINITIONS OROCOS_TARGET=${OROCOS_TARGET} ) IF (UNIX AND NOT APPLE) diff --git a/tests/datasource_test.cpp b/tests/datasource_test.cpp index 1dc1de51a..b0a6b3563 100644 --- a/tests/datasource_test.cpp +++ b/tests/datasource_test.cpp @@ -32,11 +32,8 @@ #include #include -#include #include "datasource_fixture.hpp" -using namespace boost::lambda; - class DataSourceTest { public: diff --git a/tests/dev_test.cpp b/tests/dev_test.cpp index 55ddae1c6..59fd596ce 100644 --- a/tests/dev_test.cpp +++ b/tests/dev_test.cpp @@ -47,7 +47,8 @@ BOOST_FIXTURE_TEST_SUITE( DevTestSuite, DevTest ) BOOST_AUTO_TEST_CASE( testClasses) { - DigitalInput din(true, false); // init, invert + bool din_state = true; + DigitalInput din(din_state, false); // init, invert DigitalOutput dout(false); // init. AnalogInput ain(0,0); AnalogOutput aout(0,0); diff --git a/tests/enum_string_type_test.cpp b/tests/enum_string_type_test.cpp index 3c423588c..44ef895ae 100644 --- a/tests/enum_string_type_test.cpp +++ b/tests/enum_string_type_test.cpp @@ -21,7 +21,6 @@ #include #include #include -#include #include "datasource_fixture.hpp" #include "marsh/PropertyBagIntrospector.hpp" @@ -29,8 +28,6 @@ #include "marsh/PropertyLoader.hpp" #include "TaskContext.hpp" -using namespace boost::lambda; - typedef enum { A, B, C @@ -74,7 +71,6 @@ class EnumTypeTest // Registers the fixture into the 'registry' BOOST_FIXTURE_TEST_SUITE( EnumTypeTestSuite, EnumTypeTest ) - // Tests enum to string conversions BOOST_AUTO_TEST_CASE( testEnumStringConversion ) { diff --git a/tests/enum_type_test.cpp b/tests/enum_type_test.cpp index acbc1e238..735336af3 100644 --- a/tests/enum_type_test.cpp +++ b/tests/enum_type_test.cpp @@ -21,7 +21,6 @@ #include #include #include -#include #include "datasource_fixture.hpp" #include "marsh/PropertyBagIntrospector.hpp" @@ -29,8 +28,6 @@ #include "marsh/PropertyLoader.hpp" #include "TaskContext.hpp" -using namespace boost::lambda; - typedef enum { A, B, C diff --git a/tests/taskstates_test.cpp b/tests/taskstates_test.cpp index dde2d4cd6..8b4b657e6 100644 --- a/tests/taskstates_test.cpp +++ b/tests/taskstates_test.cpp @@ -637,5 +637,89 @@ BOOST_AUTO_TEST_CASE( testExecutionEngine) tsim->run(0); } +class calling_error_does_not_override_a_stop_transition_Task : public RTT::TaskContext +{ +public: + calling_error_does_not_override_a_stop_transition_Task() + : TaskContext("test") {} + void updateHook() { error(); } + void errorHook() { + while(getTargetState() != Stopped); + error(); + trigger(); + } +}; +BOOST_AUTO_TEST_CASE(calling_error_does_not_override_a_stop_transition) +{ + for (int i = 0; i < 100; ++i) + { + calling_error_does_not_override_a_stop_transition_Task task; + task.start(); + usleep(100); + task.stop(); + BOOST_REQUIRE_EQUAL(RTT::TaskContext::Stopped, task.getTaskState()); + BOOST_REQUIRE_EQUAL(RTT::TaskContext::Stopped, task.getTargetState()); + } +} + +class calling_recover_does_not_override_a_stop_transition_Task : public RTT::TaskContext +{ +public: + bool mRecovered; + TaskState mTargetState; + calling_recover_does_not_override_a_stop_transition_Task() + : TaskContext("test"), mRecovered(true) {} // true is an error + void updateHook() { error(); } + void errorHook() { + while(getTargetState() != Stopped); + mRecovered = recover(); + trigger(); + } +}; +BOOST_AUTO_TEST_CASE(calling_recover_does_not_override_a_stop_transition) +{ + for (int i = 0; i < 100; ++i) + { + calling_recover_does_not_override_a_stop_transition_Task task; + task.start(); + usleep(100); + task.stop(); + BOOST_REQUIRE_EQUAL(RTT::TaskContext::Stopped, task.getTaskState()); + BOOST_REQUIRE_EQUAL(RTT::TaskContext::Stopped, task.getTargetState()); + BOOST_REQUIRE(!task.mRecovered); + } +} + +class errorHook_is_not_called_after_an_exit_transition_Task : public RTT::TaskContext +{ +public: + TimeService::ticks lastErrorHook; + TimeService::ticks lastStopHook; + + errorHook_is_not_called_after_an_exit_transition_Task() + : TaskContext("test") {} + void updateHook() { error(); } + void errorHook() { + usleep(100); + lastErrorHook = TimeService::Instance()->getTicks(); + trigger(); + } + void stopHook() { + lastStopHook = TimeService::Instance()->getTicks(); + usleep(100); + } +}; +BOOST_AUTO_TEST_CASE(testErrorHook_is_not_called_during_stop) +{ + for (int i = 0; i < 100; ++i) + { + errorHook_is_not_called_after_an_exit_transition_Task task; + task.start(); + usleep(100); + task.stop(); + BOOST_REQUIRE(task.lastErrorHook < task.lastStopHook); + } +} + BOOST_AUTO_TEST_SUITE_END() diff --git a/tests/taskthread_fd_test.cpp b/tests/taskthread_fd_test.cpp index d2f38971d..cac4fe45d 100644 --- a/tests/taskthread_fd_test.cpp +++ b/tests/taskthread_fd_test.cpp @@ -259,9 +259,9 @@ BOOST_AUTO_TEST_CASE(testFileDescriptor_Timeout ) BOOST_CHECK( mcomp.start() == true ); // no activity - usleep(1000000/4); + usleep(1000000 / RATE * 4.5); // ~4.5 timeout periods BOOST_CHECK_EQUAL( 0, mcomp.countError ); - BOOST_CHECK_CLOSE_FRACTION( 4., (double)mcomp.countTimeout, 2. ); + BOOST_CHECK_EQUAL( 4, mcomp.countTimeout ); BOOST_CHECK_EQUAL( 0, mcomp.countRead ); BOOST_CHECK_LE( 0, mcomp.countUpdate ); @@ -269,16 +269,16 @@ BOOST_AUTO_TEST_CASE(testFileDescriptor_Timeout ) rc = write(mcomp.fd[1], &ch, sizeof(ch)); if (1 != rc) std::cerr << "rc=" << rc << " errno=" << errno << ":" << strerror(errno) << std::endl; BOOST_CHECK_EQUAL( 1, rc ); - usleep(1000000/RATE); // ~1 timeout period + usleep(1000000 / RATE * 1.5); // ~1.5 timeout periods BOOST_CHECK_EQUAL( 0, mcomp.countError ); - BOOST_CHECK_CLOSE_FRACTION( 4. , (double)mcomp.countTimeout, 1. ); + BOOST_CHECK_EQUAL( 5, mcomp.countTimeout ); BOOST_CHECK_EQUAL( 1, mcomp.countRead ); BOOST_CHECK_LE( 0, mcomp.countUpdate ); // no activity - usleep(1000000/3); + usleep(1000000 / RATE * 3); // ~3 timeout periods BOOST_CHECK_EQUAL( 0, mcomp.countError ); - BOOST_CHECK_CLOSE_FRACTION( 4. + 3., (double)mcomp.countTimeout, 2. ); + BOOST_CHECK_EQUAL( 5 + 3, mcomp.countTimeout ); BOOST_CHECK_EQUAL( 1, mcomp.countRead ); BOOST_CHECK_LE( 0, mcomp.countUpdate ); } diff --git a/tests/taskthread_test.cpp b/tests/taskthread_test.cpp index 3619ac40a..17706ea25 100644 --- a/tests/taskthread_test.cpp +++ b/tests/taskthread_test.cpp @@ -205,6 +205,14 @@ BOOST_AUTO_TEST_CASE(testPeriodic ) } } + // Different CPU affinity + unsigned cpu_affinity = 1; // first CPU only + if ( mtask.thread()->getCpuAffinity() != cpu_affinity ) { + PeriodicActivity m4task(ORO_SCHED_OTHER, 15, 0.01, cpu_affinity); + BOOST_CHECK( mtask.thread() != m4task.thread() ); + BOOST_CHECK_EQUAL( cpu_affinity, m4task.thread()->getCpuAffinity() ); + } + // Starting thread if thread not running BOOST_CHECK( mtask.thread()->stop() ); BOOST_CHECK( mtask.thread()->isRunning() == false ); diff --git a/tests/testproject/plugins/CMakeLists.txt b/tests/testproject/plugins/CMakeLists.txt index 933b8e3c3..624ac50c9 100644 --- a/tests/testproject/plugins/CMakeLists.txt +++ b/tests/testproject/plugins/CMakeLists.txt @@ -7,8 +7,8 @@ endif (MSVC) SET_TARGET_PROPERTIES( service_plugin PROPERTIES - SOVERSION "${RTT_VERSION_MAJOR}.${RTT_VERSION_MINOR}" VERSION "${RTT_VERSION}" + SOVERSION "${RTT_SOVERSION}" OUTPUT_NAME service_plugin-${OROCOS_TARGET} COMPILE_DEFINITIONS "${OROCOS-RTT_DEFINITIONS}" ${PREFIX_HACK} @@ -23,8 +23,8 @@ ADD_LIBRARY(global_service_plugin SHARED plugins_test_global_services.cpp) SET_TARGET_PROPERTIES( global_service_plugin PROPERTIES - SOVERSION "${RTT_VERSION_MAJOR}.${RTT_VERSION_MINOR}" VERSION "${RTT_VERSION}" + SOVERSION "${RTT_SOVERSION}" OUTPUT_NAME global_service_plugin-${OROCOS_TARGET} COMPILE_DEFINITIONS "${OROCOS-RTT_DEFINITIONS}" ${PREFIX_HACK} diff --git a/tests/testproject/types/CMakeLists.txt b/tests/testproject/types/CMakeLists.txt index 7237d35c2..10e5ed62d 100644 --- a/tests/testproject/types/CMakeLists.txt +++ b/tests/testproject/types/CMakeLists.txt @@ -7,8 +7,8 @@ endif (MSVC) SET_TARGET_PROPERTIES( typekit_plugin PROPERTIES - SOVERSION "${RTT_VERSION_MAJOR}.${RTT_VERSION_MINOR}" VERSION "${RTT_VERSION}" + SOVERSION "${RTT_SOVERSION}" OUTPUT_NAME typekit_plugin-${OROCOS_TARGET} COMPILE_DEFINITIONS "${OROCOS-RTT_DEFINITIONS}" ${PREFIX_HACK} diff --git a/tests/testtypes/types/CMakeLists.txt b/tests/testtypes/types/CMakeLists.txt index b8ef74f38..78e404b5d 100644 --- a/tests/testtypes/types/CMakeLists.txt +++ b/tests/testtypes/types/CMakeLists.txt @@ -7,8 +7,8 @@ endif (MSVC) SET_TARGET_PROPERTIES( testtypes_plugin PROPERTIES - SOVERSION "${RTT_VERSION_MAJOR}.${RTT_VERSION_MINOR}" VERSION "${RTT_VERSION}" + SOVERSION "${RTT_SOVERSION}" OUTPUT_NAME typekit_plugin-${OROCOS_TARGET} COMPILE_DEFINITIONS "${OROCOS-RTT_DEFINITIONS}" ${PREFIX_HACK} diff --git a/tests/type_discovery_container_test.cpp b/tests/type_discovery_container_test.cpp index eb5511628..1fde1b43b 100644 --- a/tests/type_discovery_container_test.cpp +++ b/tests/type_discovery_container_test.cpp @@ -26,7 +26,6 @@ #include #include #include -#include #include "datasource_fixture.hpp" #include "types/StructTypeInfo.hpp" @@ -34,7 +33,6 @@ #include "types/SequenceTypeInfo.hpp" #include "types/BoostArrayTypeInfo.hpp" -using namespace boost::lambda; using namespace boost::archive; using namespace boost::serialization; @@ -62,9 +60,6 @@ BOOST_AUTO_TEST_CASE( testCTypeArray ) vector names = atype->getMemberNames(); BOOST_CHECK_EQUAL( atype->getMemberNames().size(), 2 ); // capacity,size -// for_each( names.begin(), names.end(), cout << lambda::_1 <<", " ); -// cout <getMember("0") ); @@ -110,9 +105,6 @@ BOOST_AUTO_TEST_CASE( testContainerType ) vector names = atype->getMemberNames(); BOOST_CHECK_EQUAL( atype->getMemberNames().size(), 2 ); // capacity,size -// for_each( names.begin(), names.end(), cout << lambda::_1 <<", " ); -// cout <getMember("0") ); @@ -168,9 +160,6 @@ BOOST_AUTO_TEST_CASE( testStringContainerType ) vector names = atype->getMemberNames(); BOOST_CHECK_EQUAL( atype->getMemberNames().size(), 2 ); // capacity,size -// for_each( names.begin(), names.end(), cout << lambda::_1 <<", " ); -// cout <getMember("0") ); diff --git a/tests/type_discovery_struct_test.cpp b/tests/type_discovery_struct_test.cpp index 4502fc720..e5fd584fc 100644 --- a/tests/type_discovery_struct_test.cpp +++ b/tests/type_discovery_struct_test.cpp @@ -26,7 +26,6 @@ #include #include #include -#include #include "datasource_fixture.hpp" #include "types/StructTypeInfo.hpp" @@ -34,7 +33,6 @@ #include "types/SequenceTypeInfo.hpp" #include "types/BoostArrayTypeInfo.hpp" -using namespace boost::lambda; using namespace boost::archive; using namespace boost::serialization; @@ -62,9 +60,6 @@ BOOST_AUTO_TEST_CASE( testATypeStruct ) vector names = atype->getMemberNames(); BOOST_CHECK_EQUAL( atype->getMemberNames().size(), 5 ); -// for_each( names.begin(), names.end(), cout << lambda::_1 <<", " ); -// cout <getMember("a") ); diff --git a/tests/type_discovery_test.cpp b/tests/type_discovery_test.cpp index 1ab9c49ce..a44561db8 100644 --- a/tests/type_discovery_test.cpp +++ b/tests/type_discovery_test.cpp @@ -26,7 +26,6 @@ #include #include #include -#include #include "datasource_fixture.hpp" #include "types/StructTypeInfo.hpp" @@ -34,7 +33,6 @@ #include "types/SequenceTypeInfo.hpp" #include "types/BoostArrayTypeInfo.hpp" -using namespace boost::lambda; using namespace boost::archive; using namespace boost::serialization; @@ -61,9 +59,6 @@ BOOST_AUTO_TEST_CASE( testATypeDiscovery ) BOOST_CHECK_EQUAL( out.mparts.size(), 5 ); BOOST_CHECK_EQUAL( out.mparent, atype); -// for_each( out.mnames.begin(), out.mnames.end(), cout << lambda::_1 <<", " ); -// cout <::shared_ptr a = AssignableDataSource::narrow( out.mparts[0].get() ); @@ -111,9 +106,6 @@ BOOST_AUTO_TEST_CASE( testBTypeDiscovery ) BOOST_CHECK_EQUAL( out.mparts.size(), 5 ); BOOST_CHECK_EQUAL( out.mparent, atype); -// for_each( out.mnames.begin(), out.mnames.end(), cout << lambda::_1 <<", " ); -// cout <::shared_ptr a = AssignableDataSource::narrow( out.mparts[0].get() );