Skip to content

Commit

Permalink
Merge branch 'master' into remove-gcc-version-check
Browse files Browse the repository at this point in the history
  • Loading branch information
meyerj authored Oct 15, 2017
2 parents 1b7e8cb + e297928 commit 3bb9d08
Show file tree
Hide file tree
Showing 50 changed files with 351 additions and 272 deletions.
10 changes: 2 additions & 8 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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} )
Expand All @@ -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:
Expand Down
2 changes: 1 addition & 1 deletion rtt/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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"
Expand Down
20 changes: 5 additions & 15 deletions rtt/ExecutionEngine.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,12 +48,6 @@
#include "extras/SlaveActivity.hpp"

#include <boost/bind.hpp>
#include <boost/ref.hpp>
#ifndef USE_CPP11
#include <boost/lambda/lambda.hpp>
#include <boost/lambda/bind.hpp>
#endif
#include <functional>
#include <algorithm>

#define ORONUM_EE_MQUEUE_SIZE 100
Expand Down Expand Up @@ -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 )
Expand All @@ -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;
}
Expand Down Expand Up @@ -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,
Expand Down Expand Up @@ -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,
Expand Down
6 changes: 1 addition & 5 deletions rtt/InputPort.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
}

Expand Down
13 changes: 12 additions & 1 deletion rtt/Logger.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -363,8 +363,9 @@ namespace RTT
}

void Logger::allowRealTime() {
*this << Logger::Warning << "Enabling Real-Time Logging !" <<Logger::endl;
// re-enable and then log, otherwise you might not get the log event!
d->allowRT = true;
*this << Logger::Warning << "Enabling Real-Time Logging !" <<Logger::endl;
}
void Logger::disallowRealTime() {
*this << Logger::Warning << "Disabling Real-Time Logging !" <<Logger::endl;
Expand Down Expand Up @@ -420,19 +421,25 @@ namespace RTT

Logger& Logger::in(const std::string& modname)
{
if ( !d->maylog() )
return *this;
os::MutexLock lock( d->inpguard );
d->moduleptr = modname.c_str();
return *this;
}

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;
Expand Down Expand Up @@ -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;
Expand Down
16 changes: 2 additions & 14 deletions rtt/OutputPort.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -233,15 +233,9 @@ namespace RTT
has_initial_sample = true;
has_last_written_value = false;

#ifdef USE_CPP11
cmanager.delete_if( bind(
&OutputPort<T>::do_init, this, boost::ref(sample), _1)
);
#else
cmanager.delete_if( boost::bind(
&OutputPort<T>::do_init, this, boost::ref(sample), _1)
&OutputPort<T>::do_init, this, boost::ref(sample), _1 )
);
#endif
}

/**
Expand All @@ -258,15 +252,9 @@ namespace RTT
}
has_last_written_value = keeps_last_written_value;

#ifdef USE_CPP11
cmanager.delete_if( bind(
&OutputPort<T>::do_write, this, boost::ref(sample), _1)
);
#else
cmanager.delete_if( boost::bind(
&OutputPort<T>::do_write, this, boost::ref(sample), boost::lambda::_1)
&OutputPort<T>::do_write, this, boost::ref(sample), _1 )
);
#endif
}

void write(base::DataSourceBase::shared_ptr source)
Expand Down
17 changes: 12 additions & 5 deletions rtt/Property.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<DataSourceType>::shared_ptr datasource )
const typename internal::AssignableDataSource<DataSourceType>::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.
Expand Down Expand Up @@ -373,14 +373,21 @@ namespace RTT
return new Property<T>(*this);
}

virtual Property<T>* copy() const
virtual Property<T>* create() const
{
return new Property<T>( _name, _description, _value );
return new Property<T>( _name, _description, T() );
}

virtual Property<T>* create() const
virtual Property<T>* create( const base::DataSourceBase::shared_ptr& datasource ) const
{
return new Property<T>( _name, _description, T() );
typename internal::AssignableDataSource<DataSourceType>::shared_ptr value
= internal::AssignableDataSource<DataSourceType>::narrow( datasource.get() );
Property<T>* prop = new Property<T>( _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 {
Expand Down
4 changes: 2 additions & 2 deletions rtt/PropertyBag.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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 );
Expand Down Expand Up @@ -615,7 +615,7 @@ namespace RTT
temp->update( (*sit) );
}
// step 3 : add result to target bag.
target.add( temp );
target.ownProperty( temp );
}
}
++it;
Expand Down
7 changes: 4 additions & 3 deletions rtt/Service.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,8 +40,6 @@
#include "TaskContext.hpp"
#include <algorithm>
#include "internal/mystd.hpp"
#include <boost/lambda/lambda.hpp>
#include <boost/lambda/construct.hpp>
#include <algorithm>

namespace RTT {
Expand Down Expand Up @@ -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();
Expand Down
12 changes: 6 additions & 6 deletions rtt/base/PropertyBase.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
2 changes: 1 addition & 1 deletion rtt/base/TaskCore.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -182,7 +182,7 @@ namespace RTT {
mTargetState = mTaskState = mInitialState;
return true;
}
if (mTaskState == RunTimeError ) {
if (mTaskState == RunTimeError && mTargetState >= Running) {
mTargetState = mTaskState = Running;
return true;
}
Expand Down
9 changes: 7 additions & 2 deletions rtt/extras/TimerThread.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,7 @@
#include "../Logger.hpp"
#include <algorithm>
#include "../os/MutexLock.hpp"
#include "../os/MainThread.hpp"

namespace RTT {
using namespace extras;
Expand All @@ -60,14 +61,15 @@ 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)
{
// 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();
Expand All @@ -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;
Expand Down
18 changes: 11 additions & 7 deletions rtt/internal/ConnectionManager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -60,6 +60,7 @@ namespace RTT

ConnectionManager::ConnectionManager(PortInterface* port)
: mport(port)
, cur_channel(NULL)
{
}

Expand Down Expand Up @@ -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)
Expand All @@ -116,7 +117,7 @@ namespace RTT
std::list<ChannelDescriptor> 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));
Expand All @@ -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)
Expand All @@ -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
Expand Down
Loading

0 comments on commit 3bb9d08

Please sign in to comment.