Skip to content
Snippets Groups Projects

Compare revisions

Changes are shown as if the source revision was being merged into the target revision. Learn more about comparing revisions.

Source

Select target project
No results found

Target

Select target project
  • cberge/dynamic-graph
  • ostasse/dynamic-graph
  • gsaurel/dynamic-graph
  • stack-of-tasks/dynamic-graph
4 results
Show changes
Showing
with 1904 additions and 1118 deletions
...@@ -5,23 +5,12 @@ ...@@ -5,23 +5,12 @@
* *
* CNRS/AIST * CNRS/AIST
* *
* This file is part of dynamic-graph.
* dynamic-graph is free software: you can redistribute it and/or
* modify it under the terms of the GNU Lesser General Public License
* as published by the Free Software Foundation, either version 3 of
* the License, or (at your option) any later version.
* dynamic-graph is distributed in the hope that it will be
* useful, but WITHOUT ANY WARRANTY; without even the implied warranty
* of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU Lesser General Public License for more details. You should
* have received a copy of the GNU Lesser General Public License along
* with dynamic-graph. If not, see <http://www.gnu.org/licenses/>.
*/ */
#include <dynamic-graph/exception-traces.h> #include <dynamic-graph/exception-traces.h>
#include <stdarg.h> #include <stdarg.h>
#include <cstdio>
#include <cstdio>
using namespace dynamicgraph; using namespace dynamicgraph;
/* --------------------------------------------------------------------- */ /* --------------------------------------------------------------------- */
...@@ -30,32 +19,26 @@ using namespace dynamicgraph; ...@@ -30,32 +19,26 @@ using namespace dynamicgraph;
const std::string ExceptionTraces::EXCEPTION_NAME = "Traces"; const std::string ExceptionTraces::EXCEPTION_NAME = "Traces";
ExceptionTraces:: ExceptionTraces::ExceptionTraces(const ExceptionTraces::ErrorCodeEnum &errcode,
ExceptionTraces ( const ExceptionTraces::ErrorCodeEnum& errcode, const std::string &msg)
const std::string & msg ) : ExceptionAbstract(errcode, msg) {}
:ExceptionAbstract(errcode,msg)
{
}
ExceptionTraces:: ExceptionTraces::ExceptionTraces(const ExceptionTraces::ErrorCodeEnum &errcode,
ExceptionTraces ( const ExceptionTraces::ErrorCodeEnum& errcode, const std::string &msg, const char *format,
const std::string & msg,const char* format, ... ) ...)
:ExceptionAbstract(errcode,msg) : ExceptionAbstract(errcode, msg) {
{
va_list args; va_list args;
va_start(args,format); va_start(args, format);
const unsigned int SIZE = 256; const unsigned int SIZE = 256;
char buffer[SIZE]; char buffer[SIZE];
vsnprintf(buffer,SIZE,format,args); vsnprintf(buffer, SIZE, format, args);
message += buffer; message += buffer;
va_end(args); va_end(args);
} }
/* /*
* Local variables: * Local variables:
* c-basic-offset: 2 * c-basic-offset: 2
......
/* Copyright LAAS, CNRS
* Author: O. Stasse, 2019
* See LICENSE file in the root directory of this repository.
*/
#include <dynamic-graph/process-list.hh>
#include <fstream>
#include <sstream>
#include <string>
using namespace dynamicgraph::CPU;
CPUData::CPUData()
: user_mode_time_(0),
nice_time_(0),
system_time_(0),
idle_time_(0),
iowait_time_(0),
irq_time_(0),
softirq_time_(0),
steal_time_(0),
guest_time_(0),
guest_nice_time_(0),
percent_(0.0) {}
void CPUData::ProcessLine(std::istringstream &aCPULine) {
unsigned long long int luser_mode_time = 0, lnice_time = 0, lsystem_time = 0,
lidle_time = 0, liowait_time = 0, lirq_time = 0,
lsoftirq_time = 0, lsteal_time = 0, lguest_time = 0,
lguest_nice_time;
aCPULine >> luser_mode_time;
aCPULine >> lnice_time;
aCPULine >> lsystem_time;
aCPULine >> lidle_time;
aCPULine >> liowait_time;
aCPULine >> lirq_time;
aCPULine >> lsoftirq_time;
aCPULine >> lsteal_time;
aCPULine >> lguest_time;
aCPULine >> lguest_nice_time;
// Remove guest time already in user_time:
luser_mode_time -= lguest_time;
lnice_time -= lguest_nice_time;
// Compute cumulative time
unsigned long long int lidle_all_time = 0, lsystem_all_time = 0,
lguest_all_time = 0, ltotal_time = 0;
lidle_all_time = lidle_time + liowait_time;
lsystem_all_time = lsystem_time + lirq_time + lsoftirq_time;
lguest_all_time = lguest_time + lguest_nice_time;
ltotal_time = luser_mode_time + lnice_time + lsystem_all_time +
lidle_all_time + lsteal_time + lguest_all_time;
// Update periodic computation.
user_mode_period_ = computePeriod(luser_mode_time, user_mode_time_);
nice_period_ = computePeriod(lnice_time, nice_time_);
system_period_ = computePeriod(lsystem_time, system_time_);
system_all_period_ = computePeriod(lsystem_all_time, system_all_time_);
idle_period_ = computePeriod(lidle_time, idle_time_);
idle_all_period_ = computePeriod(lidle_all_time, idle_all_time_);
iowait_period_ = computePeriod(liowait_time, idle_time_);
irq_period_ = computePeriod(lirq_time, irq_time_);
softirq_period_ = computePeriod(lsoftirq_time, softirq_time_);
steal_period_ = computePeriod(lsteal_time, steal_time_);
guest_period_ = computePeriod(lguest_all_time, guest_time_);
total_period_ = computePeriod(ltotal_time, total_time_);
/// Update time.
user_mode_time_ = luser_mode_time;
nice_time_ = lnice_time;
system_time_ = lsystem_time;
system_all_time_ = lsystem_all_time;
idle_time_ = lidle_time;
idle_all_time_ = lidle_all_time;
iowait_time_ = liowait_time;
irq_time_ = lirq_time;
softirq_time_ = lsoftirq_time;
steal_time_ = lsteal_time;
guest_time_ = lguest_all_time;
total_time_ = ltotal_time;
if (total_period_ != 0) {
percent_ = (double)(user_mode_period_) / (double)(total_period_)*100.0;
percent_ += (double)(nice_period_) / (double)(total_period_)*100.0;
percent_ += (double)(system_period_) / (double)(total_period_)*100.0;
percent_ += (double)(irq_period_) / (double)(total_period_)*100.0;
percent_ += (double)(softirq_period_) / (double)(total_period_)*100.0;
percent_ += (double)(steal_period_) / (double)(total_period_)*100.0;
percent_ += (double)(iowait_period_) / (double)(total_period_)*100.0;
}
}
System::System() {
vCPUData_.clear();
init();
}
void System::init() {
init_ = false;
readProcStat();
init_ = true;
}
void System::ProcessCPULine(unsigned int cpunb, std::istringstream &aCPULine) {
vCPUData_[cpunb].ProcessLine(aCPULine);
}
void System::readProcStat() {
std::ifstream aif;
cpuNb_ = 1;
aif.open("/proc/stat", std::ifstream::in);
std::string aline;
aline.clear();
while (std::getline(aif, aline)) {
// Read on line of the file
std::istringstream anISSLine(aline);
std::string line_hdr;
anISSLine >> line_hdr;
// Check if the line start with cpu
std::size_t pos = line_hdr.find("cpu");
std::string str_cpunbr = line_hdr.substr(pos + 3);
// Check if this is the first line
if (pos == 0 and str_cpunbr.empty()) {
gCPUData_.ProcessLine(anISSLine);
gCPUData_.cpu_id_ = -1;
} else {
// If not then check if there is a CPU number
if (pos == 0) {
std::istringstream iss(str_cpunbr);
unsigned int lcpunb;
iss >> lcpunb;
// If we did not initialize
if (!init_) {
// Count the number of CPU.
if (lcpunb > cpuNb_) cpuNb_ = lcpunb;
} else
// Otherwise process the line.
ProcessCPULine(lcpunb, anISSLine);
}
}
}
if (!init_) {
/// The number of CPU has been detected by going through /proc/stat.
vCPUData_.resize(cpuNb_ + 1);
for (unsigned long i = 0; i < (unsigned long)cpuNb_; i++)
vCPUData_[i].cpu_id_ = (int)i;
}
aif.close();
}
...@@ -5,21 +5,10 @@ ...@@ -5,21 +5,10 @@
* *
* CNRS/AIST * CNRS/AIST
* *
* This file is part of dynamic-graph.
* dynamic-graph is free software: you can redistribute it and/or
* modify it under the terms of the GNU Lesser General Public License
* as published by the Free Software Foundation, either version 3 of
* the License, or (at your option) any later version.
* dynamic-graph is distributed in the hope that it will be
* useful, but WITHOUT ANY WARRANTY; without even the implied warranty
* of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU Lesser General Public License for more details. You should
* have received a copy of the GNU Lesser General Public License along
* with dynamic-graph. If not, see <http://www.gnu.org/licenses/>.
*/ */
#include <dynamic-graph/signal-array.h> #include <dynamic-graph/signal-array.h>
namespace dynamicgraph { namespace dynamicgraph {
SignalArray<int> sotNOSIGNAL(0); SignalArray<int> sotNOSIGNAL(0);
} }
// -*- c++-mode -*-
// Copyright 2010 François Bleibel Thomas Moulard, Olivier Stasse, Nicolas Mansard
//
// This file is part of dynamic-graph.
// dynamic-graph is free software: you can redistribute it and/or modify
// it under the terms of the GNU Lesser General Public License as published by
// the Free Software Foundation, either version 3 of the License, or
// (at your option) any later version.
//
// dynamic-graph is distributed in the hope that it will be useful,
// but WITHOUT ANY WARRANTY; without even the implied warranty of
// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
// GNU Lesser General Public License for more details.
// You should have received a copy of the GNU Lesser General Public License
// along with dynamic-graph. If not, see <http://www.gnu.org/licenses/>.
#include <boost/date_time/posix_time/posix_time.hpp>
#include <dynamic-graph/signal-caster.h>
#include <dynamic-graph/signal-cast-helper.h>
#include <dynamic-graph/dynamic-graph-api.h>
#include <exception>
#include <boost/lambda/bind.hpp>
#include <string>
#include <sstream>
#include <algorithm>
#include <dynamic-graph/exception-signal.h>
#include <dynamic-graph/linear-algebra.h>
namespace dynamicgraph
{
// Define a custom implementation of the DefaultCastRegisterer
// to workaround the limitations of the stream based approach.
// When dealing with double: displaying a double on a stream
// is *NOT* the opposite of reading a double from a stream.
//
// In practice, it means that there is no way to read
// a NaN, +inf, -inf from a stream!
//
// To workaround this problem, parse special values manually
// (the strings used are the one produces by displaying special
// values on a stream).
template <>
inline boost::any
DefaultCastRegisterer<double>::cast (std::istringstream& iss)
{
std::string tmp;
iss >> tmp;
if (tmp == "nan")
return std::numeric_limits<double>::quiet_NaN ();
else if (tmp == "inf" || tmp == "+inf")
return std::numeric_limits<double>::infinity ();
else if (tmp == "-inf")
return -1. * std::numeric_limits<double>::infinity ();
try
{
return boost::lexical_cast<double> (tmp);
}
catch (boost::bad_lexical_cast&)
{
boost::format fmt ("failed to serialize %s (to double)");
fmt % tmp;
throw ExceptionSignal(ExceptionSignal::GENERIC, fmt.str ());
}
}
/* Specialize Matrix and Vector traces. */
template <>
void
DefaultCastRegisterer<dynamicgraph::Vector>::
trace(const boost::any& object, std::ostream& os)
{
const dynamicgraph::Vector & v = boost::any_cast<dynamicgraph::Vector> (object);
for( int i=0;i<v.size();++i )
{ os << "\t" << v(i); }
}
template <>
void
DefaultCastRegisterer<dynamicgraph::Matrix>::
trace(const boost::any& object, std::ostream& os)
{
const dynamicgraph::Matrix & m = boost::any_cast<dynamicgraph::Matrix> (object);
for(int i=0;i<m.rows();++i )
for(int j=0;j<m.cols();++j )
{ os << "\t" << m(i,j); }
}
/// Registers useful casts
namespace
{
DefaultCastRegisterer<double> double_reg;
DefaultCastRegisterer<int> int_reg;
DefaultCastRegisterer<unsigned int> uint_reg;
DefaultCastRegisterer<bool> bool_reg;
DefaultCastRegisterer<dynamicgraph::Vector> vectorCastRegisterer;
DefaultCastRegisterer<dynamicgraph::Matrix> matrixCastRegisterer;
DefaultCastRegisterer <boost::posix_time::ptime> ptimeCastRegisterer;
} // end of anonymous namespace.
} // namespace dynamicgraph
// -*- c++-mode -*-
// Copyright 2010 François Bleibel Thomas Moulard, Olivier Stasse
//
// This file is part of dynamic-graph.
// dynamic-graph is free software: you can redistribute it and/or modify
// it under the terms of the GNU Lesser General Public License as published by
// the Free Software Foundation, either version 3 of the License, or
// (at your option) any later version.
//
// dynamic-graph is distributed in the hope that it will be useful,
// but WITHOUT ANY WARRANTY; without even the implied warranty of
// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
// GNU Lesser General Public License for more details.
// You should have received a copy of the GNU Lesser General Public License
// along with dynamic-graph. If not, see <http://www.gnu.org/licenses/>.
#include <dynamic-graph/signal-caster.h>
#include <dynamic-graph/dynamic-graph-api.h>
#include <exception>
#include <boost/lambda/bind.hpp>
#include <string>
#include <sstream>
#include <algorithm>
#include <dynamic-graph/exception-signal.h>
#include <dynamic-graph/linear-algebra.h>
namespace dynamicgraph
{
SignalCaster::SignalCaster ()
{}
SignalCaster::~SignalCaster ()
{}
void SignalCaster::destroy()
{
delete instance_;
instance_ = 0;
}
void
SignalCaster::registerCast (const std::type_info& type,
SignalCaster::displayer_type displayer,
SignalCaster::caster_type caster,
SignalCaster::tracer_type tracer)
{
if (existsCast (type))
{
// If type name has already been registered for same type, do not throw.
if (type_info_[type.name()] != &type)
{
std::string typeName(type.name());
std::ostringstream os;
os << "cast already registered for typename " << typeName << "\n"
<< "and types differ: " << &type << " != "
<< type_info_[type.name()]
<< ".\n"
<< "A possible reason is that the dynamic"
<< " library defining this type\n"
<< "has been loaded several times, defining different symbols"
<< " for the same type.";
throw ExceptionSignal(ExceptionSignal::GENERIC,
os.str());
}
}
functions_[type.name()] = cast_functions_type(displayer,caster, tracer);
type_info_[type.name()] = &type;
}
void
SignalCaster::unregisterCast (const std::type_info& type)
{
size_t n = functions_.erase(type.name ());
if (0 == n) // erase did not find element
// TODO: throw Cast not registered exception
throw ExceptionSignal(ExceptionSignal::GENERIC);
}
bool
SignalCaster::existsCast (const std::type_info& type) const
{
return functions_.find (type.name ()) != functions_.end ();
}
SignalCaster::cast_functions_type&
SignalCaster::getCast (const std::string& type_name)
{
std::map<std::string, cast_functions_type>::iterator it =
functions_.find(type_name);
if (it == functions_.end ())
//TODO: throw "cast not registered" exception
throw ExceptionSignal(ExceptionSignal::BAD_CAST, "Cast not registered");
return it->second;
}
void SignalCaster::disp (const boost::any& object, std::ostream& os)
{
getCast(object.type ().name ()).get<0> () (object, os);
}
void
SignalCaster::trace(const boost::any& object, std::ostream& os)
{
getCast(object.type ().name ()).get<2> () (object, os);
}
std::vector<std::string>
SignalCaster::listTypenames() const
{
std::vector<std::string> typeList;
for (std::map<std::string, cast_functions_type>::const_iterator iter =
functions_.begin(); iter != functions_.end(); iter++)
typeList.push_back(iter->first);
return typeList;
}
boost::any
SignalCaster::cast (const std::type_info& type, std::istringstream& iss)
{
return getCast(type.name ()).get<1> () (iss);
}
/// Singleton on the library-wide instance of SignalCaster
SignalCaster* SignalCaster::getInstance(void)
{
if (instance_ == 0) {
instance_ = new SignalCaster;
}
return instance_;
}
SignalCaster* SignalCaster::instance_ = 0;
} // namespace dynamicgraph
...@@ -5,17 +5,6 @@ ...@@ -5,17 +5,6 @@
* *
* CNRS/AIST * CNRS/AIST
* *
* This file is part of dynamic-graph.
* dynamic-graph is free software: you can redistribute it and/or
* modify it under the terms of the GNU Lesser General Public License
* as published by the Free Software Foundation, either version 3 of
* the License, or (at your option) any later version.
* dynamic-graph is distributed in the hope that it will be
* useful, but WITHOUT ANY WARRANTY; without even the implied warranty
* of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU Lesser General Public License for more details. You should
* have received a copy of the GNU Lesser General Public License along
* with dynamic-graph. If not, see <http://www.gnu.org/licenses/>.
*/ */
/* --------------------------------------------------------------------- */ /* --------------------------------------------------------------------- */
...@@ -23,116 +12,98 @@ ...@@ -23,116 +12,98 @@
/* --------------------------------------------------------------------- */ /* --------------------------------------------------------------------- */
/* DG */ /* DG */
#include <iomanip> #include <dynamic-graph/all-commands.h>
#include <boost/bind.hpp>
#include <dynamic-graph/tracer-real-time.h>
#include <dynamic-graph/debug.h> #include <dynamic-graph/debug.h>
#include <dynamic-graph/pool.h>
#include <dynamic-graph/factory.h> #include <dynamic-graph/factory.h>
#include <dynamic-graph/all-commands.h> #include <dynamic-graph/pool.h>
#include <dynamic-graph/tracer-real-time.h>
#include <boost/bind.hpp>
#include <iomanip>
using namespace std; using namespace std;
using namespace dynamicgraph; using namespace dynamicgraph;
DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN(TracerRealTime,"TracerRealTime"); DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN(TracerRealTime, "TracerRealTime");
/* --------------------------------------------------------------------- */ /* --------------------------------------------------------------------- */
/* --- DGOUTSTRINGSTREAM ---------------------------------------------- */ /* --- DGOUTSTRINGSTREAM ---------------------------------------------- */
/* --------------------------------------------------------------------- */ /* --------------------------------------------------------------------- */
OutStringStream:: OutStringStream::OutStringStream()
OutStringStream () : std::ostringstream(), buffer(0), index(0), bufferSize(0), full(false) {
: std::ostringstream ()
,buffer( 0 ),index(0),bufferSize(0),full(false)
{
dgDEBUGINOUT(15); dgDEBUGINOUT(15);
} }
OutStringStream:: OutStringStream::~OutStringStream() {
~OutStringStream ()
{
dgDEBUGIN(15); dgDEBUGIN(15);
delete[] buffer; delete[] buffer;
dgDEBUGOUT(15); dgDEBUGOUT(15);
} }
void OutStringStream:: void OutStringStream::resize(const std::streamsize &size) {
resize (const std::streamsize& size)
{
dgDEBUGIN(15); dgDEBUGIN(15);
index=0; index = 0;
bufferSize = size; bufferSize = size;
full=false; full = false;
delete[] buffer; delete[] buffer;
buffer = new char[static_cast<size_t> (size)]; buffer = new char[static_cast<size_t>(size)];
dgDEBUGOUT(15); dgDEBUGOUT(15);
} }
bool OutStringStream:: bool OutStringStream::addData(const char *data, const std::streamoff &size) {
addData (const char * data, const std::streamoff& size)
{
dgDEBUGIN(15); dgDEBUGIN(15);
std::streamsize towrite = static_cast<std::streamsize> (size); std::streamsize towrite = static_cast<std::streamsize>(size);
if (index + towrite > bufferSize) if (index + towrite > bufferSize) {
{ dgDEBUGOUT(15);
dgDEBUGOUT(15); full = true;
full = true; return false;
return false; }
} memcpy(buffer + index, data, static_cast<size_t>(towrite));
memcpy (buffer + index, data, static_cast<size_t> (towrite));
index += towrite; index += towrite;
dgDEBUGOUT(15); dgDEBUGOUT(15);
return true; return true;
} }
void OutStringStream:: void OutStringStream::dump(std::ostream &os) {
dump( std::ostream& os )
{
dgDEBUGIN(15); dgDEBUGIN(15);
os.write( buffer,index ); os.write(buffer, index);
dgDEBUGOUT(15); dgDEBUGOUT(15);
} }
void OutStringStream:: void OutStringStream::empty() {
empty ()
{
dgDEBUGIN(15); dgDEBUGIN(15);
index=0; full=false; index = 0;
full = false;
dgDEBUGOUT(15); dgDEBUGOUT(15);
} }
/* --------------------------------------------------------------------- */ /* --------------------------------------------------------------------- */
/* --------------------------------------------------------------------- */ /* --------------------------------------------------------------------- */
/* --------------------------------------------------------------------- */ /* --------------------------------------------------------------------- */
TracerRealTime::TracerRealTime(const std::string &n)
TracerRealTime::TracerRealTime( const std::string & n ) : Tracer(n), bufferSize(BUFFER_SIZE_DEFAULT) {
:Tracer(n)
,bufferSize( BUFFER_SIZE_DEFAULT )
{
dgDEBUGINOUT(15); dgDEBUGINOUT(15);
/* --- Commands --- */ /* --- Commands --- */
{ {
using namespace dynamicgraph::command; using namespace dynamicgraph::command;
std::string doc std::string doc = docCommandVoid0(
= docCommandVoid0("Trash the current content of the buffers, without saving it."); "Trash the current content of the buffers, without saving it.");
addCommand("empty", addCommand("empty",
makeCommandVoid0(*this,&TracerRealTime::emptyBuffers,doc )); makeCommandVoid0(*this, &TracerRealTime::emptyBuffers, doc));
addCommand("getBufferSize", addCommand("getBufferSize",
makeDirectGetter(*this,&bufferSize, makeDirectGetter(*this, &bufferSize,
docDirectGetter("bufferSize","int"))); docDirectGetter("bufferSize", "int")));
addCommand("setBufferSize", addCommand("setBufferSize",
makeDirectSetter(*this,&bufferSize, makeDirectSetter(*this, &bufferSize,
docDirectSetter("bufferSize","int"))); docDirectSetter("bufferSize", "int")));
} // using namespace command } // using namespace command
dgDEBUGOUT(15); dgDEBUGOUT(15);
} }
...@@ -141,227 +112,194 @@ TracerRealTime::TracerRealTime( const std::string & n ) ...@@ -141,227 +112,194 @@ TracerRealTime::TracerRealTime( const std::string & n )
/* --------------------------------------------------------------------- */ /* --------------------------------------------------------------------- */
/* --------------------------------------------------------------------- */ /* --------------------------------------------------------------------- */
void TracerRealTime::openFile(const SignalBase<int> &sig,
void TracerRealTime:: const std::string &givenname) {
openFile( const SignalBase<int> & sig,
const std::string& givenname )
{
dgDEBUGIN(15); dgDEBUGIN(15);
string signame; string signame;
if( givenname.length () ) if (givenname.length()) {
{ signame = givenname; } else { signame = sig.shortName (); } signame = givenname;
} else {
signame = sig.shortName();
}
string filename = rootdir + basename + signame + suffix; string filename = rootdir + basename + signame + suffix;
dgDEBUG(5) << "Sig <"<<sig.getName () dgDEBUG(5) << "Sig <" << sig.getName() << ">: new file " << filename << endl;
<< ">: new file "<< filename << endl; std::ofstream *newfile = new std::ofstream(filename.c_str());
std::ofstream * newfile = new std::ofstream( filename.c_str () ); if (!newfile->good()) {
dgDEBUG(5) << "Newfile:" << (void*) newfile << endl; delete newfile;
hardFiles.push_back( newfile ); DG_THROW ExceptionTraces(
ExceptionTraces::NOT_OPEN,
"Could not open file " + filename + " for signal " + signame, "");
}
dgDEBUG(5) << "Newfile:" << (void *)newfile << endl;
hardFiles.push_back(newfile);
dgDEBUG(5) << "Creating Outstringstream" << endl; dgDEBUG(5) << "Creating Outstringstream" << endl;
//std::stringstream * newbuffer = new std::stringstream (); // std::stringstream * newbuffer = new std::stringstream ();
OutStringStream * newbuffer = new OutStringStream (); // std::stringstream (); OutStringStream *newbuffer = new OutStringStream(); // std::stringstream ();
newbuffer->resize( bufferSize ); newbuffer->resize(bufferSize);
newbuffer->givenname = givenname; newbuffer->givenname = givenname;
files.push_back( newbuffer ); files.push_back(newbuffer);
dgDEBUGOUT(15); dgDEBUGOUT(15);
} }
void TracerRealTime::closeFiles() {
void TracerRealTime::
closeFiles ()
{
dgDEBUGIN(15); dgDEBUGIN(15);
std::lock_guard<std::mutex> files_lock(files_mtx);
FileList::iterator iter = files.begin (); FileList::iterator iter = files.begin();
HardFileList::iterator hardIter = hardFiles.begin (); HardFileList::iterator hardIter = hardFiles.begin();
while( files.end ()!=iter ) while (files.end() != iter) {
{ dgDEBUG(25) << "Close the files." << endl;
dgDEBUG(25) << "Close the files." << endl;
std::stringstream * file = dynamic_cast< stringstream* >(*iter); std::stringstream *file = dynamic_cast<stringstream *>(*iter);
std::ofstream * hardFile = *hardIter; std::ofstream *hardFile = *hardIter;
(*hardFile) <<flush; hardFile->close (); (*hardFile) << flush;
delete file; hardFile->close();
delete hardFile; delete file;
delete hardFile;
++iter; ++hardIter; ++iter;
} ++hardIter;
}
dgDEBUG(25) << "Clear the lists." << endl; dgDEBUG(25) << "Clear the lists." << endl;
files.clear (); files.clear();
hardFiles.clear (); hardFiles.clear();
dgDEBUGOUT(15); dgDEBUGOUT(15);
} }
void TracerRealTime:: void TracerRealTime::trace() {
trace ()
{
dgDEBUGIN(15); dgDEBUGIN(15);
FileList::iterator iter = files.begin (); FileList::iterator iter = files.begin();
HardFileList::iterator hardIter = hardFiles.begin (); HardFileList::iterator hardIter = hardFiles.begin();
while( files.end ()!=iter ) while (files.end() != iter) {
{ dgDEBUG(35) << "Next" << endl;
dgDEBUG(35) << "Next" << endl; std::ostream *os = *iter;
std::ostream * os = *iter; if (NULL == os) {
if( NULL==os ) DG_THROW ExceptionTraces(ExceptionTraces::NOT_OPEN, "The buffer is null",
{ DG_THROW ExceptionTraces( ExceptionTraces::NOT_OPEN, "");
"The buffer is null",""); } }
//std::stringstream & file = * dynamic_cast< stringstream* >(os); // std::stringstream & file = * dynamic_cast< stringstream* >(os);
OutStringStream * file = dynamic_cast< OutStringStream* >(os); // segfault OutStringStream *file = dynamic_cast<OutStringStream *>(os); // segfault
if( NULL==file ) if (NULL == file) {
{ DG_THROW ExceptionTraces( ExceptionTraces::NOT_OPEN, DG_THROW ExceptionTraces(ExceptionTraces::NOT_OPEN,
"The buffer is not open",""); } "The buffer is not open", "");
}
std::ofstream & hardFile = **hardIter;
if(! hardFile.good () ) std::ofstream &hardFile = **hardIter;
{ DG_THROW ExceptionTraces( ExceptionTraces::NOT_OPEN, if (!hardFile.good()) {
"The file is not open",""); } DG_THROW ExceptionTraces(ExceptionTraces::NOT_OPEN,
"The file is not open", "");
if( (hardFile.good ())&&(NULL!=file) ) }
{
if ((hardFile.good()) && (NULL != file)) {
// const unsigned int SIZE = 1024*8; file->dump(hardFile);
// char buffer[SIZE]; file->empty();
// streambuf * pbuf = file.rdbuf (); hardFile.flush();
// pbuf->pubseekpos(0);
// const unsigned int NB_BYTE = pbuf->in_avail ();
// dgDEBUG(35) << "Bytes in buffer: " << NB_BYTE << endl;
// //dgDEBUG(35) << "Copie" <<endl<<file.str ()<< endl;
// for( unsigned int index=0;index<NB_BYTE;index+=SIZE )
// {
// pbuf->pubseekpos( index );
// int nget = pbuf->sgetn( buffer,SIZE );
// dgDEBUG(35) << "Copie ["<<nget<<"] " <<buffer<<endl;
// hardFile.write( buffer,nget );
// }
//hardFile << file.str () << flush;
//file.seekp(0);
file->dump( hardFile );
file->empty ();
hardFile.flush ();
//file.str("");
}
++iter; ++hardIter;
} }
++iter;
++hardIter;
}
dgDEBUGOUT(15); dgDEBUGOUT(15);
} }
void TracerRealTime:: void TracerRealTime::emptyBuffers() {
emptyBuffers ()
{
dgDEBUGIN(15); dgDEBUGIN(15);
for( FileList::iterator iter = files.begin ();files.end ()!=iter;++iter ) for (FileList::iterator iter = files.begin(); files.end() != iter; ++iter) {
{ // std::stringstream & file = * dynamic_cast< stringstream* >(*iter);
//std::stringstream & file = * dynamic_cast< stringstream* >(*iter); try {
try { OutStringStream &file = *dynamic_cast<OutStringStream *>(*iter);
OutStringStream & file = * dynamic_cast< OutStringStream* >(*iter); file.empty();
file.empty (); // file.str("");
//file.str(""); } catch (...) {
} DG_THROW ExceptionTraces(ExceptionTraces::NOT_OPEN,
catch( ... ) { DG_THROW ExceptionTraces( ExceptionTraces::NOT_OPEN, "The buffer is not open", "");
"The buffer is not open",""); }
} }
}
dgDEBUGOUT(15); dgDEBUGOUT(15);
} }
void TracerRealTime::recordSignal(std::ostream &os,
// void TracerRealTime:: const SignalBase<int> &sig) {
// emptyBuffer( std::stringstream & file )
// {
// streambuf * pbuf = file.rdbuf ();
// pbuf->file.rdbuf () ->pubsetbuf( fileBuffer,10 );
// }
void TracerRealTime::
recordSignal( std::ostream& os,
const SignalBase<int>& sig )
{
dgDEBUGIN(15); dgDEBUGIN(15);
try { try {
OutStringStream &file = dynamic_cast<OutStringStream &>(os);
OutStringStream & file = dynamic_cast< OutStringStream& >(os);
file.str(""); file.str("");
dgDEBUG(45) << "Empty file [" << file.tellp () dgDEBUG(45) << "Empty file [" << file.tellp() << "] <" << file.str().c_str()
<< "] <" << file.str ().c_str () <<"> " <<endl; << "> " << endl;
Tracer::recordSignal( file,sig ); Tracer::recordSignal(file, sig);
file.addData( file.str ().c_str (),file.tellp () ); file.addData(file.str().c_str(), file.tellp());
dgDEBUG(35) << "Write data [" << file.tellp () dgDEBUG(35) << "Write data [" << file.tellp() << "] <" << file.str().c_str()
<< "] <" << file.str ().c_str () <<"> " <<endl; << "> " << endl;
} catch( ExceptionAbstract & exc ) { throw exc; } } catch (ExceptionAbstract &exc) {
catch( ... ) { throw;
DG_THROW ExceptionTraces( ExceptionTraces::NOT_OPEN, } catch (...) {
"The buffer is not open",""); DG_THROW ExceptionTraces(ExceptionTraces::NOT_OPEN,
"The buffer is not open", "");
} }
dgDEBUGOUT(15); dgDEBUGOUT(15);
return ; return;
} }
/* --------------------------------------------------------------------- */ /* --------------------------------------------------------------------- */
/* --------------------------------------------------------------------- */ /* --------------------------------------------------------------------- */
/* --------------------------------------------------------------------- */ /* --------------------------------------------------------------------- */
void TracerRealTime:: void TracerRealTime::display(std::ostream &os) const {
display( std::ostream& os ) const os << CLASS_NAME << " " << name << " [mode=" << (play ? "play" : "pause")
{ << "] : " << endl
os << CLASS_NAME << " " << name << " [mode=" << (play?"play":"pause") << " - Dep list: " << endl;
<< "] : "<< endl
<< " - Dep list: "<<endl; FileList::const_iterator iterFile = files.begin();
for (SignalList::const_iterator iter = toTraceSignals.begin();
FileList::const_iterator iterFile = files.begin (); toTraceSignals.end() != iter; ++iter) {
for( SignalList::const_iterator iter = toTraceSignals.begin (); dgDEBUG(35) << "Next" << endl;
toTraceSignals.end ()!=iter;++iter ) const OutStringStream *file = dynamic_cast<OutStringStream *>(*iterFile);
{ os << " -> " << (*iter)->getName();
dgDEBUG(35) << "Next" << endl; if (file->givenname.length()) os << " (in " << file->givenname << ")";
const OutStringStream * file = dynamic_cast< OutStringStream* >(*iterFile); os << "\t";
os << " -> "<<(*iter)->getName (); if (file) {
if( file->givenname.length () ) os << " (in " << file->givenname << ")" ; const std::streamsize PRECISION = os.precision();
os << "\t"; const std::streamsize SIZE = file->index;
if( file ) const std::streamsize MSIZE = file->bufferSize;
{ unsigned int dec = 0;
const std::streamsize PRECISION = os.precision (); std::string unit = "";
const std::streamsize SIZE = file->index; if ((SIZE >> 30) || (MSIZE >> 30)) {
const std::streamsize MSIZE = file->bufferSize; dec = 30;
unsigned int dec=0; std::string unit =""; unit = "Go";
if( (SIZE>>30)||(MSIZE>>30) ) { dec = 30; unit="Go"; } } else if ((SIZE >> 20) || (MSIZE >> 20)) {
else if( (SIZE>>20)||(MSIZE>>20) ) { dec = 20; unit="Mo"; } dec = 20;
else if( (SIZE>>10)||(MSIZE>>10) ) { dec = 10; unit="Ko"; } unit = "Mo";
os << "[" << std::setw(1)<<std::setprecision(1) } else if ((SIZE >> 10) || (MSIZE >> 10)) {
<< (((double)SIZE+0.0)/(1<<dec)) << unit << "/" dec = 10;
<< std::setprecision(2)<<(((double)MSIZE+0.0)/(1<<dec)) unit = "Ko";
<< unit << "]\t"; }
if( file->full ) os << "(FULL)"; os << "[" << std::setw(1) << std::setprecision(1)
os.precision(PRECISION); << (((double)SIZE + 0.0) / (1 << dec)) << unit << "/"
} << std::setprecision(2) << (((double)MSIZE + 0.0) / (1 << dec)) << unit
os<<endl; << "]\t";
iterFile++; if (file->full) os << "(FULL)";
os.precision(PRECISION);
} }
os << endl;
++iterFile;
}
} }
std::ostream &operator<<(std::ostream &os, const TracerRealTime &t) {
std::ostream& operator<< ( std::ostream& os,const TracerRealTime& t )
{
t.display(os); t.display(os);
return os; return os;
} }
...@@ -5,17 +5,6 @@ ...@@ -5,17 +5,6 @@
* *
* CNRS/AIST * CNRS/AIST
* *
* This file is part of dynamic-graph.
* dynamic-graph is free software: you can redistribute it and/or
* modify it under the terms of the GNU Lesser General Public License
* as published by the Free Software Foundation, either version 3 of
* the License, or (at your option) any later version.
* dynamic-graph is distributed in the hope that it will be
* useful, but WITHOUT ANY WARRANTY; without even the implied warranty
* of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU Lesser General Public License for more details. You should
* have received a copy of the GNU Lesser General Public License along
* with dynamic-graph. If not, see <http://www.gnu.org/licenses/>.
*/ */
/* --------------------------------------------------------------------- */ /* --------------------------------------------------------------------- */
...@@ -23,115 +12,108 @@ ...@@ -23,115 +12,108 @@
/* --------------------------------------------------------------------- */ /* --------------------------------------------------------------------- */
/* DG */ /* DG */
#include <dynamic-graph/tracer.h> #include <dynamic-graph/all-commands.h>
#include <dynamic-graph/debug.h> #include <dynamic-graph/debug.h>
#include <dynamic-graph/value.h>
#include <dynamic-graph/pool.h>
#include <dynamic-graph/factory.h> #include <dynamic-graph/factory.h>
#include <dynamic-graph/all-commands.h> #include <dynamic-graph/pool.h>
#include <dynamic-graph/tracer.h>
#include <dynamic-graph/value.h>
#include <boost/bind.hpp> #include <boost/bind.hpp>
using namespace std; using namespace std;
using namespace dynamicgraph; using namespace dynamicgraph;
using namespace dynamicgraph::command; using namespace dynamicgraph::command;
DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN(Tracer,"Tracer"); DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN(Tracer, "Tracer");
/* --------------------------------------------------------------------- */ /* --------------------------------------------------------------------- */
/* --- CLASS ----------------------------------------------------------- */ /* --- CLASS ----------------------------------------------------------- */
/* --------------------------------------------------------------------- */ /* --------------------------------------------------------------------- */
Tracer::Tracer( const std::string n ) Tracer::Tracer(const std::string n)
:Entity(n) : Entity(n),
,toTraceSignals () toTraceSignals(),
,traceStyle(TRACE_STYLE_DEFAULT) traceStyle(TRACE_STYLE_DEFAULT),
,frequency(1) frequency(1),
,basename () basename(),
,suffix(".dat") suffix(".dat"),
,rootdir () rootdir(),
,namesSet( false ) namesSet(false),
,files () files(),
,names () names(),
,play(false) play(false),
,timeStart(0) timeStart(0),
,triger( boost::bind(&Tracer::recordTrigger,this,_1,_2), triger(boost::bind(&Tracer::recordTrigger, this, _1, _2), sotNOSIGNAL,
sotNOSIGNAL, "Tracer(" + n + ")::triger") {
"Tracer("+n+")::triger" ) signalRegistration(triger);
{
signalRegistration( triger );
/* --- Commands --- */ /* --- Commands --- */
{ {
using namespace dynamicgraph::command; using namespace dynamicgraph::command;
std::string doc; std::string doc;
doc = docCommandVoid2("Add a new signal to trace.", doc = docCommandVoid2("Add a new signal to trace.", "string (signal name)",
"string (signal name)","string (filename, empty for default"); "string (filename, empty for default");
addCommand("add", addCommand("add",
makeCommandVoid2(*this,&Tracer::addSignalToTraceByName,doc )); makeCommandVoid2(*this, &Tracer::addSignalToTraceByName, doc));
doc = docCommandVoid0("Remove all signals. If necessary, close open files."); doc =
docCommandVoid0("Remove all signals. If necessary, close open files.");
addCommand("clear", addCommand("clear",
makeCommandVoid0(*this,&Tracer::clearSignalToTrace,doc )); makeCommandVoid0(*this, &Tracer::clearSignalToTrace, doc));
doc = docCommandVoid3("Gives the args for file opening, and " doc = docCommandVoid3(
"if signals have been set, open the corresponding files.", "Gives the args for file opening, and "
"string (dirname)","string (prefix)","string (suffix)"); "if signals have been set, open the corresponding files.",
addCommand("open", "string (dirname)", "string (prefix)", "string (suffix)");
makeCommandVoid3(*this,&Tracer::openFiles,doc )); addCommand("open", makeCommandVoid3(*this, &Tracer::openFiles, doc));
doc = docCommandVoid0("Close all the open files."); doc = docCommandVoid0("Close all the open files.");
addCommand("close", addCommand("close", makeCommandVoid0(*this, &Tracer::closeFiles, doc));
makeCommandVoid0(*this,&Tracer::closeFiles,doc ));
doc = docCommandVoid0("If necessary, dump " doc = docCommandVoid0(
"(can be done automatically for some traces type)."); "If necessary, dump "
addCommand("dump", "(can be done automatically for some traces type).");
makeCommandVoid0(*this,&Tracer::trace,doc )); addCommand("dump", makeCommandVoid0(*this, &Tracer::trace, doc));
doc = docCommandVoid0("Start the tracing process."); doc = docCommandVoid0("Start the tracing process.");
addCommand("start", addCommand("start", makeCommandVoid0(*this, &Tracer::start, doc));
makeCommandVoid0(*this,&Tracer::start,doc ));
doc = docCommandVoid0("Stop temporarily the tracing process."); doc = docCommandVoid0("Stop temporarily the tracing process.");
addCommand("stop", addCommand("stop", makeCommandVoid0(*this, &Tracer::stop, doc));
makeCommandVoid0(*this,&Tracer::stop,doc ));
addCommand("getTimeStart", addCommand("getTimeStart",
makeDirectGetter(*this,&timeStart, makeDirectGetter(*this, &timeStart,
docDirectGetter("timeStart","int"))); docDirectGetter("timeStart", "int")));
addCommand("setTimeStart", addCommand("setTimeStart",
makeDirectSetter(*this,&timeStart, makeDirectSetter(*this, &timeStart,
docDirectSetter("timeStart","int"))); docDirectSetter("timeStart", "int")));
} // using namespace command } // using namespace command
} }
/* --------------------------------------------------------------------- */ /* --------------------------------------------------------------------- */
/* --------------------------------------------------------------------- */ /* --------------------------------------------------------------------- */
/* --------------------------------------------------------------------- */ /* --------------------------------------------------------------------- */
void Tracer::addSignalToTrace(const SignalBase<int> &sig,
void Tracer:: const string &filename) {
addSignalToTrace( const SignalBase<int>& sig,
const string& filename )
{
dgDEBUGIN(15); dgDEBUGIN(15);
toTraceSignals.push_back( &sig ); dgDEBUGF(15,"%p",&sig); // openFile may throw so it should be called first.
names.push_back( filename ); if (namesSet) openFile(sig, filename);
if( namesSet ) openFile( sig,filename ); toTraceSignals.push_back(&sig);
triger.addDependency( sig ); dgDEBUGF(15, "%p", &sig);
names.push_back(filename);
triger.addDependency(sig);
dgDEBUGOUT(15); dgDEBUGOUT(15);
} }
void Tracer:: void Tracer::addSignalToTraceByName(const string &signame,
addSignalToTraceByName( const string& signame, const string &filename) {
const string& filename )
{
dgDEBUGIN(15); dgDEBUGIN(15);
istringstream iss( signame ); istringstream iss(signame);
SignalBase<int> &sig = PoolStorage::getInstance()->getSignal(iss); SignalBase<int> &sig = PoolStorage::getInstance()->getSignal(iss);
addSignalToTrace(sig,filename); addSignalToTrace(sig, filename);
dgDEBUGOUT(15); dgDEBUGOUT(15);
} }
...@@ -139,12 +121,10 @@ addSignalToTraceByName( const string& signame, ...@@ -139,12 +121,10 @@ addSignalToTraceByName( const string& signame,
* does not modify the file list (it does not close * does not modify the file list (it does not close
* the files in particular. * the files in particular.
*/ */
void Tracer:: void Tracer::clearSignalToTrace() {
clearSignalToTrace () closeFiles();
{ toTraceSignals.clear();
closeFiles (); triger.clearDependencies();
toTraceSignals.clear ();
triger.clearDependencies ();
} }
// void Tracer:: // void Tracer::
...@@ -153,63 +133,59 @@ clearSignalToTrace () ...@@ -153,63 +133,59 @@ clearSignalToTrace ()
// triger.parasite(sig); // triger.parasite(sig);
// } // }
void Tracer:: void Tracer::openFiles(const std::string &rootdir_,
openFiles( const std::string& rootdir_, const std::string& basename_, const std::string &basename_,
const std::string& suffix_ ) const std::string &suffix_) {
{
dgDEBUGIN(15); dgDEBUGIN(15);
std::basic_string<char>::size_type n = rootdir_.length (); std::basic_string<char>::size_type n = rootdir_.length();
rootdir = rootdir_; rootdir = rootdir_;
if( (0<n)&('/'!=rootdir[n-1]) ) rootdir+='/'; if ((0 < n) & ('/' != rootdir[n - 1])) rootdir += '/';
basename=basename_; basename = basename_;
suffix=suffix_; suffix = suffix_;
if( files.size () ) closeFiles (); if (files.size()) closeFiles();
SignalList::const_iterator iter = toTraceSignals.begin (); SignalList::const_iterator iter = toTraceSignals.begin();
NameList::const_iterator iterName = names.begin (); NameList::const_iterator iterName = names.begin();
while( toTraceSignals.end ()!=iter ) while (toTraceSignals.end() != iter) {
{ dgDEBUG(15) << "Open <" << (*iter)->getName() << "> in <" << *iterName
dgDEBUG(15) << "Open <" << (*iter)->getName () << ">." << std::endl;
<< "> in <" << *iterName << ">." << std::endl; openFile(**iter, *iterName);
openFile( **iter,*iterName ); ++iter;
++iter; ++iterName; ++iterName;
} }
namesSet = true; namesSet = true;
dgDEBUGOUT(15); dgDEBUGOUT(15);
} }
void Tracer:: void Tracer::openFile(const SignalBase<int> &sig, const string &givenname) {
openFile( const SignalBase<int> & sig,
const string& givenname )
{
dgDEBUGIN(15); dgDEBUGIN(15);
string signame; string signame;
if( givenname.length () ) if (givenname.length()) {
{ signame = givenname; } else { signame = sig.shortName (); } signame = givenname;
} else {
signame = sig.shortName();
}
string filename = rootdir + basename + signame + suffix; string filename = rootdir + basename + signame + suffix;
dgDEBUG(5) << "Sig <"<< sig.getName () << ">: new file "<< filename << endl; dgDEBUG(5) << "Sig <" << sig.getName() << ">: new file " << filename << endl;
std::ofstream * newfile = new std::ofstream( filename.c_str () ); std::ofstream *newfile = new std::ofstream(filename.c_str());
files.push_back( newfile ); files.push_back(newfile);
dgDEBUGOUT(15); dgDEBUGOUT(15);
} }
void Tracer::closeFiles() {
void Tracer::
closeFiles ()
{
dgDEBUGIN(15); dgDEBUGIN(15);
std::lock_guard<std::mutex> files_lock(files_mtx);
for( FileList::iterator iter = files.begin ();files.end ()!=iter;++iter ) for (FileList::iterator iter = files.begin(); files.end() != iter; ++iter) {
{ std::ostream *filePtr = *iter;
std::ostream * filePtr = *iter; delete filePtr;
delete filePtr; }
} files.clear();
files.clear ();
dgDEBUGOUT(15); dgDEBUGOUT(15);
} }
...@@ -218,85 +194,83 @@ closeFiles () ...@@ -218,85 +194,83 @@ closeFiles ()
/* --------------------------------------------------------------------- */ /* --------------------------------------------------------------------- */
/* --------------------------------------------------------------------- */ /* --------------------------------------------------------------------- */
void Tracer:: void Tracer::record() {
record () if (!play) {
{ dgDEBUGINOUT(15);
if(! play) { dgDEBUGINOUT(15); return;} return;
}
dgDEBUGIN(15); dgDEBUGIN(15);
if( files.size ()!=toTraceSignals.size () ) // Ensure record() never hangs. If the attempt to acquire the lock fails,
{ DG_THROW ExceptionTraces( ExceptionTraces::NOT_OPEN, // then closeFiles() is active and we shouldn't write to files anyways.
"No files open for tracing"," (file=%d != %d=sig).", std::unique_lock<std::mutex> files_lock(files_mtx, std::try_to_lock);
files.size (),toTraceSignals.size ()); } if (!files_lock.owns_lock()) {
dgDEBUGOUT(15);
return;
}
if (files.size() != toTraceSignals.size()) {
DG_THROW
ExceptionTraces(ExceptionTraces::NOT_OPEN, "No files open for tracing",
" (file=%d != %d=sig).", files.size(),
toTraceSignals.size());
}
FileList::iterator iterFile = files.begin (); FileList::iterator iterFile = files.begin();
SignalList::iterator iterSig = toTraceSignals.begin (); SignalList::iterator iterSig = toTraceSignals.begin();
while( toTraceSignals.end ()!=iterSig ) while (toTraceSignals.end() != iterSig) {
{ dgDEBUG(45) << "Try..." << endl;
dgDEBUG(45) << "Try..." <<endl; recordSignal(**iterFile, **iterSig);
recordSignal( **iterFile,**iterSig ); ++iterSig;
++iterSig; ++iterFile; ++iterFile;
} }
dgDEBUGOUT(15); dgDEBUGOUT(15);
} }
void Tracer:: void Tracer::recordSignal(std::ostream &os, const SignalBase<int> &sig) {
recordSignal( std::ostream& os,
const SignalBase<int>& sig )
{
dgDEBUGIN(15); dgDEBUGIN(15);
try { try {
if( sig.getTime ()>timeStart ) if (sig.getTime() > timeStart) {
{ os << sig.getTime() << "\t";
os<< sig.getTime () << "\t"; sig.trace(os);
sig.trace(os); os<<endl; os << endl;
} }
} catch (ExceptionAbstract &exc) {
os << exc << std::endl;
} catch (...) {
os << "Unknown error occurred while reading signal." << std::endl;
} }
catch( ExceptionAbstract& exc ) { os << exc << std::endl; }
catch( ... ) { os << "Unknown error occurred while reading signal." << std::endl; }
dgDEBUGOUT(15);
dgDEBUGOUT(15);
} }
int &Tracer::recordTrigger(int &dummy, const int &time) {
int& Tracer:: dgDEBUGIN(15) << " time=" << time << endl;
recordTrigger( int& dummy, const int& time ) record();
{
dgDEBUGIN(15) << " time="<<time <<endl;
record ();
dgDEBUGOUT(15); dgDEBUGOUT(15);
return dummy; return dummy;
} }
void Tracer::trace() {}
void Tracer::
trace ()
{
}
/* --------------------------------------------------------------------- */ /* --------------------------------------------------------------------- */
/* --------------------------------------------------------------------- */ /* --------------------------------------------------------------------- */
/* --------------------------------------------------------------------- */ /* --------------------------------------------------------------------- */
void Tracer::display(std::ostream &os) const {
void Tracer:: os << CLASS_NAME << " " << name << " [mode=" << (play ? "play" : "pause")
display( std::ostream& os ) const << "] : " << endl
{ << " - Dep list: " << endl;
os << CLASS_NAME << " " << name << " [mode=" << (play?"play":"pause") for (SignalList::const_iterator iter = toTraceSignals.begin();
<< "] : "<< endl toTraceSignals.end() != iter; ++iter) {
<< " - Dep list: "<<endl; os << " -> " << (*iter)->getName() << endl;
for( SignalList::const_iterator iter = toTraceSignals.begin (); }
toTraceSignals.end ()!=iter;++iter )
{ os << " -> "<<(*iter)->getName ()<<endl; }
} }
std::ostream &operator<<(std::ostream &os, const Tracer &t) {
std::ostream& operator<< ( std::ostream& os,const Tracer& t )
{
t.display(os); t.display(os);
return os; return os;
} }
# Copyright 2010, Olivier Stasse, JRL, CNRS/AIST # Copyright 2010-2020, Olivier Stasse, Guilhem Saurel, JRL, CNRS/AIST, LAAS-CNRS
#
# This file is part of dynamic-graph.
# dynamic-graph is free software: you can redistribute it and/or
# modify it under the terms of the GNU Lesser General Public License
# as published by the Free Software Foundation, either version 3 of
# the License, or (at your option) any later version.
#
# dynamic-graph is distributed in the hope that it will be useful, but
# WITHOUT ANY WARRANTY; without even the implied warranty of
# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
# General Lesser Public License for more details. You should have
# received a copy of the GNU Lesser General Public License along with
# dynamic-graph. If not, see <http://www.gnu.org/licenses/>.
ADD_DEFINITIONS(-DDEBUG=2) add_definitions(-DBOOST_TEST_DYN_LINK -DBOOST_TEST_MAIN)
# Add Boost path to include directories. add_definitions(-DTESTS_DATADIR="${CMAKE_CURRENT_SOURCE_DIR}/data")
INCLUDE_DIRECTORIES(${Boost_INCLUDE_DIRS}) add_definitions(-DTESTS_PLUGINDIR="${LIBRARY_OUTPUT_PATH}")
add_definitions(-DTESTS_DYNLIBSUFFIX="${CMAKE_SHARED_LIBRARY_SUFFIX}")
# Make Boost.Test generates the main function in test cases.
ADD_DEFINITIONS(-DBOOST_TEST_DYN_LINK -DBOOST_TEST_MAIN)
ADD_DEFINITIONS(-DTESTS_DATADIR="${CMAKE_CURRENT_SOURCE_DIR}/data")
ADD_DEFINITIONS(-DTESTS_PLUGINDIR="${LIBRARY_OUTPUT_PATH}")
ADD_DEFINITIONS(-DTESTS_DYNLIBSUFFIX="${CMAKE_SHARED_LIBRARY_SUFFIX}")
# DYNAMIC_GRAPH_TEST(NAME)
# ------------------------
#
# Define a test named `NAME'.
#
# This macro will create a binary from `NAME.cpp', link it against
# Boost and add it to the test suite.
#
MACRO(DYNAMIC_GRAPH_TEST NAME)
ADD_EXECUTABLE(${NAME} ${NAME}.cpp)
ADD_TEST(${NAME} ${RUNTIME_OUTPUT_DIRECTORY}/${NAME})
TARGET_LINK_LIBRARIES(${NAME} ${PROJECT_NAME})
ADD_DEPENDENCIES(${NAME} ${PROJECT_NAME})
# Link against Boost.
TARGET_LINK_LIBRARIES(${NAME} ${Boost_LIBRARIES})
ENDMACRO(DYNAMIC_GRAPH_TEST)
macro(DYNAMIC_GRAPH_TEST NAME)
add_unit_test(${NAME} "${NAME}.cpp")
target_link_libraries(${NAME} PRIVATE ${PROJECT_NAME}
Boost::unit_test_framework)
endmacro(DYNAMIC_GRAPH_TEST)
# Signal cast test. # Signal cast test.
SET(signalcast_libs signal-cast-registerer-libA signal-cast-registerer-libB) set(signalcast_libs signal-cast-registerer-libA signal-cast-registerer-libB)
FOREACH(lib ${signalcast_libs}) foreach(lib ${signalcast_libs})
ADD_LIBRARY(${lib} SHARED ${lib}.cpp) add_library(${lib} SHARED "${lib}.cpp")
target_link_libraries(${lib} PRIVATE ${PROJECT_NAME})
endforeach()
TARGET_LINK_LIBRARIES(${lib} ${PROJECT_NAME}) dynamic_graph_test(signal-cast-registerer)
ADD_DEPENDENCIES(${lib} ${PROJECT_NAME})
ENDFOREACH()
DYNAMIC_GRAPH_TEST(signal-cast-registerer)
# Unit testing. # Unit testing.
IF(NOT APPLE) if(NOT APPLE)
DYNAMIC_GRAPH_TEST(entity) dynamic_graph_test(entity)
ENDIF(NOT APPLE) endif(NOT APPLE)
DYNAMIC_GRAPH_TEST(custom-entity) dynamic_graph_test(custom-entity)
DYNAMIC_GRAPH_TEST(factory) dynamic_graph_test(factory)
DYNAMIC_GRAPH_TEST(pool) dynamic_graph_test(pool)
DYNAMIC_GRAPH_TEST(signal-time-dependent) dynamic_graph_test(signal-time-dependent)
DYNAMIC_GRAPH_TEST(value) dynamic_graph_test(value)
DYNAMIC_GRAPH_TEST(signal-ptr) dynamic_graph_test(signal-ptr)
dynamic_graph_test(real-time-logger)
dynamic_graph_test(debug-trace)
dynamic_graph_test(debug-tracer)
target_link_libraries(debug-tracer PRIVATE tracer)
dynamic_graph_test(debug-real-time-tracer)
target_link_libraries(debug-real-time-tracer PRIVATE tracer-real-time tracer)
dynamic_graph_test(debug-logger)
dynamic_graph_test(debug-logger-winit)
dynamic_graph_test(signal-all)
dynamic_graph_test(command-test)
dynamic_graph_test(test-mt)
target_link_libraries(test-mt PRIVATE tracer)
dynamic_graph_test(exceptions)
/* Copyright 2019, LAAS-CNRS
*
* Olivier Stasse
*
* See LICENSE file
*
*/
#include <dynamic-graph/entity.h>
#include <dynamic-graph/exception-factory.h>
#include <iostream>
#include <sstream>
#include "dynamic-graph/command-bind.h"
#include "dynamic-graph/factory.h"
#include "dynamic-graph/pool.h"
#define ENABLE_RT_LOG
#include <dynamic-graph/logger.h>
#include <dynamic-graph/real-time-logger.h>
#define BOOST_TEST_MODULE debug - logger
#if BOOST_VERSION >= 105900
#include <boost/test/tools/output_test_stream.hpp>
#else
#include <boost/test/output_test_stream.hpp>
#endif
#include <boost/test/unit_test.hpp>
using boost::test_tools::output_test_stream;
using namespace dynamicgraph::command;
namespace dynamicgraph {
class CustomEntity : public Entity {
public:
static const std::string CLASS_NAME;
bool test_zero_arg_;
bool test_one_arg_;
bool test_two_args_;
bool test_three_args_;
bool test_four_args_;
bool test_one_arg_ret_;
bool test_two_args_ret_;
virtual const std::string &getClassName() const { return CLASS_NAME; }
explicit CustomEntity(const std::string &n) : Entity(n) {
test_zero_arg_ = false;
test_one_arg_ = false;
test_two_args_ = false;
test_three_args_ = false;
test_four_args_ = false;
test_one_arg_ret_ = false;
test_two_args_ret_ = false;
addCommand("0_arg", makeCommandVoid0(*this, &CustomEntity::zero_arg,
docCommandVoid0("zero arg")));
addCommand("1_arg", makeCommandVoid1(*this, &CustomEntity::one_arg,
docCommandVoid1("one arg", "int")));
addCommand("2_args",
makeCommandVoid2(*this, &CustomEntity::two_args,
docCommandVoid2("two args", "int", "int")));
addCommand("3_args", makeCommandVoid3(*this, &CustomEntity::three_args,
docCommandVoid3("three args", "int",
"int", "int")));
addCommand("4_args",
makeCommandVoid4(
*this, &CustomEntity::four_args,
docCommandVoid4("four args", "int", "int", "int", "int")));
addCommand("1_arg_r",
makeCommandReturnType1(*this, &CustomEntity::one_arg_ret,
docCommandVoid1("one arg", "int")));
addCommand("2_args_r", makeCommandReturnType2(
*this, &CustomEntity::two_args_ret,
docCommandVoid2("two args", "int", "int")));
addCommand(
"cmd_verbose",
makeCommandVerbose(*this, &CustomEntity::cmd_verbose,
docCommandVerbose("Display some information")));
/// Generating an exception by adding a command which already exist
bool res = false;
std::string e_1_arg("1_arg");
try {
addCommand(e_1_arg, getNewStyleCommand(e_1_arg));
} catch (dynamicgraph::ExceptionFactory &aef) {
res = (aef.getCode() == dynamicgraph::ExceptionFactory::OBJECT_CONFLICT);
}
BOOST_CHECK(res);
}
~CustomEntity() {}
void zero_arg() { test_zero_arg_ = true; }
void one_arg(const int &) { test_one_arg_ = true; }
void two_args(const int &, const int &) { test_two_args_ = true; }
void three_args(const int &, const int &, const int &) {
test_three_args_ = true;
}
void four_args(const int &, const int &, const int &, const int &) {
test_four_args_ = true;
}
int one_arg_ret(const int &) {
test_one_arg_ret_ = true;
return 2;
}
std::string two_args_ret(const int &, const int &) {
test_two_args_ret_ = true;
return std::string("return");
}
void cmd_verbose(std::ostream &oss) {
std::string as("print verbose");
oss << as;
}
};
DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN(CustomEntity, "CustomEntity");
} // namespace dynamicgraph
BOOST_AUTO_TEST_CASE(command_test) {
dynamicgraph::CustomEntity *ptr_entity =
(dynamic_cast<dynamicgraph::CustomEntity *>(
dynamicgraph::FactoryStorage::getInstance()->newEntity("CustomEntity",
"my-entity")));
dynamicgraph::CustomEntity &entity = *ptr_entity;
std::map<const std::string, Command *> aCommandMap =
entity.getNewStyleCommandMap();
std::map<const std::string, Command *>::iterator it_map;
it_map = aCommandMap.find("0_arg");
if (it_map == aCommandMap.end()) BOOST_CHECK(false);
it_map->second->execute();
BOOST_CHECK(entity.test_zero_arg_);
int first_arg = 1;
Value aValue(first_arg);
std::vector<std::string> vec_fname(4);
vec_fname[0] = "1_arg";
vec_fname[1] = "2_args";
vec_fname[2] = "3_args";
vec_fname[3] = "4_args";
std::vector<Value> values;
for (unsigned int i = 0; i < 4; i++) {
it_map = aCommandMap.find(vec_fname[i]);
if (it_map == aCommandMap.end()) BOOST_CHECK(false);
values.push_back(aValue);
it_map->second->setParameterValues(values);
it_map->second->execute();
it_map->second->owner();
it_map->second->getDocstring();
}
BOOST_CHECK(entity.test_one_arg_);
BOOST_CHECK(entity.test_two_args_);
BOOST_CHECK(entity.test_three_args_);
BOOST_CHECK(entity.test_four_args_);
// With return type.
vec_fname.clear();
vec_fname.push_back(std::string("1_arg_r"));
vec_fname.push_back(std::string("2_args_r"));
values.clear();
for (unsigned int i = 0; i < 2; i++) {
it_map = aCommandMap.find(vec_fname[i]);
if (it_map == aCommandMap.end()) {
BOOST_CHECK(false);
exit(-1);
}
values.push_back(aValue);
it_map->second->setParameterValues(values);
Value aValue = it_map->second->execute();
it_map->second->owner();
it_map->second->getDocstring();
}
BOOST_CHECK(entity.test_one_arg_ret_);
BOOST_CHECK(entity.test_two_args_ret_);
std::vector<Value> values_two;
values_two.push_back(aValue);
/// Wrong number of arguments
bool res = false;
it_map = aCommandMap.find(std::string("2_args"));
try {
it_map->second->setParameterValues(values_two);
} catch (const dynamicgraph::ExceptionAbstract &aea) {
res = (aea.getCode() == dynamicgraph::ExceptionAbstract::ABSTRACT);
}
BOOST_CHECK(res);
double snd_arg_db = 10.0;
Value aValue2(snd_arg_db);
values_two.push_back(aValue2);
/// Wrong types of arguments
res = false;
it_map = aCommandMap.find(std::string("2_args"));
try {
it_map->second->setParameterValues(values_two);
} catch (const dynamicgraph::ExceptionAbstract &aea) {
res = (aea.getCode() == dynamicgraph::ExceptionAbstract::TOOLS);
}
BOOST_CHECK(res);
/// Try to find the command 1_arg
res = false;
entity.getNewStyleCommand(vec_fname[0]);
BOOST_CHECK(true);
/// Generate an exception by searching a command with an empty name.w
std::string empty("");
try {
entity.getNewStyleCommand(empty);
} catch (dynamicgraph::ExceptionFactory &aef) {
res = (aef.getCode() == dynamicgraph::ExceptionFactory::UNREFERED_FUNCTION);
}
BOOST_CHECK(res);
/// delete the entity.
delete ptr_entity;
}
// Copyright 2010 Thomas Moulard. // Copyright 2010 Thomas Moulard.
// //
// This file is part of dynamic-graph.
// dynamic-graph is free software: you can redistribute it and/or modify
// it under the terms of the GNU Lesser General Public License as published by
// the Free Software Foundation, either version 3 of the License, or
// (at your option) any later version.
//
// dynamic-graph is distributed in the hope that it will be useful,
// but WITHOUT ANY WARRANTY; without even the implied warranty of
// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
// GNU Lesser General Public License for more details.
// You should have received a copy of the GNU Lesser General Public License
// along with dynamic-graph. If not, see <http://www.gnu.org/licenses/>.
#include <sstream>
#include <dynamic-graph/factory.h>
#include <dynamic-graph/pool.h>
#include <dynamic-graph/entity.h> #include <dynamic-graph/entity.h>
#include <dynamic-graph/exception-factory.h> #include <dynamic-graph/exception-factory.h>
#include <dynamic-graph/factory.h>
#include <dynamic-graph/pool.h>
#include <sstream>
#define BOOST_TEST_MODULE customEntity #define BOOST_TEST_MODULE customEntity
#include <boost/test/unit_test.hpp> #if BOOST_VERSION >= 105900
#include <boost/test/tools/output_test_stream.hpp>
#else
#include <boost/test/output_test_stream.hpp> #include <boost/test/output_test_stream.hpp>
#endif
#include <boost/test/unit_test.hpp>
using boost::test_tools::output_test_stream; using boost::test_tools::output_test_stream;
struct CustomEntity : public dynamicgraph::Entity struct CustomEntity : public dynamicgraph::Entity {
{
static const std::string CLASS_NAME; static const std::string CLASS_NAME;
virtual const std::string& getClassName () const virtual const std::string &getClassName() const { return CLASS_NAME; }
{
return CLASS_NAME;
}
CustomEntity (const std::string n) explicit CustomEntity(const std::string &n) : Entity(n) {}
: Entity (n)
{
}
virtual ~CustomEntity() virtual ~CustomEntity() {}
{
}
void display (std::ostream& os) const
{
os << "custom entity";
}
void display(std::ostream &os) const { os << "custom entity"; }
}; };
DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN (CustomEntity,"CustomEntity"); DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN(CustomEntity, "CustomEntity");
BOOST_AUTO_TEST_CASE (constructor) BOOST_AUTO_TEST_CASE(constructor) {
{ BOOST_CHECK_EQUAL(CustomEntity::CLASS_NAME, "CustomEntity");
BOOST_CHECK_EQUAL (CustomEntity::CLASS_NAME, "CustomEntity");
dynamicgraph::Entity* entity = dynamicgraph::Entity *entity =
dynamicgraph::FactoryStorage::getInstance()-> dynamicgraph::FactoryStorage::getInstance()->newEntity("CustomEntity",
newEntity("CustomEntity", "my-entity"); "my-entity");
BOOST_CHECK_EQUAL (entity->getName (), "my-entity"); BOOST_CHECK_EQUAL(entity->getName(), "my-entity");
BOOST_CHECK_EQUAL (entity->getClassName (), CustomEntity::CLASS_NAME); BOOST_CHECK_EQUAL(entity->Entity::getClassName(), "Entity");
BOOST_CHECK_EQUAL(entity->getClassName(), CustomEntity::CLASS_NAME);
//CustomEntity entity2 (""); // CustomEntity entity2 ("");
// Deregister entities before destroying them // Deregister entities before destroying them
dynamicgraph::PoolStorage::destroy(); dynamicgraph::PoolStorage::destroy();
} }
BOOST_AUTO_TEST_CASE (display) BOOST_AUTO_TEST_CASE(display) {
{ dynamicgraph::Entity *entity =
dynamicgraph::Entity* entity = dynamicgraph::FactoryStorage::getInstance()-> dynamicgraph::FactoryStorage::getInstance()->newEntity("CustomEntity",
newEntity("CustomEntity", "my-entity"); "my-entity");
output_test_stream output; output_test_stream output;
entity->display(output); entity->display(output);
BOOST_CHECK (output.is_equal ("custom entity")); BOOST_CHECK(output.is_equal("custom entity"));
// Deregister entities before destroying them // Deregister entities before destroying them
dynamicgraph::PoolStorage::destroy(); dynamicgraph::PoolStorage::destroy();
} }
/* Copyright 2019, LAAS-CNRS
*
* Olivier Stasse
*
* See LICENSE file
*
*/
#include <iostream>
#include <sstream>
#define ENABLE_RT_LOG
#include <dynamic-graph/entity.h>
#include <dynamic-graph/exception-factory.h>
#include <dynamic-graph/logger.h>
#include <dynamic-graph/real-time-logger.h>
#include "dynamic-graph/factory.h"
#include "dynamic-graph/pool.h"
#define BOOST_TEST_MODULE debug - logger
#if BOOST_VERSION >= 105900
#include <boost/test/tools/output_test_stream.hpp>
#else
#include <boost/test/output_test_stream.hpp>
#endif
#include <boost/date_time/posix_time/posix_time.hpp>
#include <boost/test/unit_test.hpp>
#include <boost/thread/thread.hpp>
using boost::test_tools::output_test_stream;
namespace dynamicgraph {
class CustomEntity : public Entity {
public:
static const std::string CLASS_NAME;
virtual const std::string &getClassName() const { return CLASS_NAME; }
explicit CustomEntity(const std::string &n) : Entity(n) {
logger_.setTimeSample(0.001);
logger_.setStreamPrintPeriod(0.005);
logger_.setVerbosity(VERBOSITY_ALL);
LoggerVerbosity alv = logger_.getVerbosity();
BOOST_CHECK(alv == VERBOSITY_ALL);
}
~CustomEntity() {}
void testDebugTrace() {
sendMsg("This is a message of level MSG_TYPE_DEBUG", MSG_TYPE_DEBUG);
sendMsg("This is a message of level MSG_TYPE_INFO", MSG_TYPE_INFO);
sendMsg("This is a message of level MSG_TYPE_WARNING", MSG_TYPE_WARNING);
sendMsg("This is a message of level MSG_TYPE_ERROR", MSG_TYPE_ERROR);
sendMsg("This is a message of level MSG_TYPE_DEBUG_STREAM",
MSG_TYPE_DEBUG_STREAM);
sendMsg("This is a message of level MSG_TYPE_INFO_STREAM",
MSG_TYPE_INFO_STREAM);
sendMsg("This is a message of level MSG_TYPE_WARNING_STREAM",
MSG_TYPE_WARNING_STREAM);
sendMsg("This is a message of level MSG_TYPE_ERROR_STREAM",
MSG_TYPE_ERROR_STREAM);
logger_.countdown();
}
};
DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN(CustomEntity, "CustomEntity");
} // namespace dynamicgraph
BOOST_AUTO_TEST_CASE(debug_logger_wrong_initialization) {
dynamicgraph::RealTimeLogger::instance();
BOOST_CHECK_EQUAL(dynamicgraph::CustomEntity::CLASS_NAME, "CustomEntity");
dynamicgraph::CustomEntity &entity =
*(dynamic_cast<dynamicgraph::CustomEntity *>(
dynamicgraph::FactoryStorage::getInstance()->newEntity(
"CustomEntity", "my-entity-2")));
for (unsigned int i = 0; i < 1000; i++) {
entity.testDebugTrace();
}
dynamicgraph::RealTimeLogger::destroy();
}
/* Copyright 2019, LAAS-CNRS
*
* Olivier Stasse
*
* See LICENSE file
*
*/
#include <dynamic-graph/entity.h>
#include <dynamic-graph/exception-factory.h>
#include <iostream>
#include <sstream>
#include "dynamic-graph/factory.h"
#include "dynamic-graph/pool.h"
#define ENABLE_RT_LOG
#include <dynamic-graph/logger.h>
#include <dynamic-graph/real-time-logger.h>
#define BOOST_TEST_MODULE debug - logger
#if BOOST_VERSION >= 105900
#include <boost/test/tools/output_test_stream.hpp>
#else
#include <boost/test/output_test_stream.hpp>
#endif
#include <boost/test/unit_test.hpp>
using boost::test_tools::output_test_stream;
namespace dynamicgraph {
class CustomEntity : public Entity {
public:
static const std::string CLASS_NAME;
virtual const std::string &getClassName() const { return CLASS_NAME; }
explicit CustomEntity(const std::string &n) : Entity(n) {
logger_.setTimeSample(0.001);
logger_.setStreamPrintPeriod(0.005);
logger_.setVerbosity(VERBOSITY_NONE);
BOOST_CHECK_EQUAL(logger_.getVerbosity(), VERBOSITY_NONE);
BOOST_CHECK(logger_.stream(MSG_TYPE_DEBUG).isNull());
BOOST_CHECK(logger_.stream(MSG_TYPE_INFO).isNull());
BOOST_CHECK(logger_.stream(MSG_TYPE_WARNING).isNull());
BOOST_CHECK(logger_.stream(MSG_TYPE_ERROR).isNull());
logger_.setVerbosity(VERBOSITY_ERROR);
BOOST_CHECK_EQUAL(logger_.getVerbosity(), VERBOSITY_ERROR);
BOOST_CHECK(logger_.stream(MSG_TYPE_DEBUG).isNull());
BOOST_CHECK(logger_.stream(MSG_TYPE_INFO).isNull());
BOOST_CHECK(logger_.stream(MSG_TYPE_WARNING).isNull());
BOOST_CHECK(!logger_.stream(MSG_TYPE_ERROR).isNull());
logger_.setVerbosity(VERBOSITY_WARNING_ERROR);
BOOST_CHECK_EQUAL(logger_.getVerbosity(), VERBOSITY_WARNING_ERROR);
BOOST_CHECK(logger_.stream(MSG_TYPE_DEBUG).isNull());
BOOST_CHECK(logger_.stream(MSG_TYPE_INFO).isNull());
BOOST_CHECK(!logger_.stream(MSG_TYPE_WARNING).isNull());
BOOST_CHECK(!logger_.stream(MSG_TYPE_ERROR).isNull());
logger_.setVerbosity(VERBOSITY_INFO_WARNING_ERROR);
BOOST_CHECK_EQUAL(logger_.getVerbosity(), VERBOSITY_INFO_WARNING_ERROR);
BOOST_CHECK(logger_.stream(MSG_TYPE_DEBUG).isNull());
BOOST_CHECK(!logger_.stream(MSG_TYPE_INFO).isNull());
BOOST_CHECK(!logger_.stream(MSG_TYPE_WARNING).isNull());
BOOST_CHECK(!logger_.stream(MSG_TYPE_ERROR).isNull());
logger_.setVerbosity(VERBOSITY_ALL);
BOOST_CHECK_EQUAL(logger_.getVerbosity(), VERBOSITY_ALL);
BOOST_CHECK(!logger_.stream(MSG_TYPE_DEBUG).isNull());
BOOST_CHECK(!logger_.stream(MSG_TYPE_INFO).isNull());
BOOST_CHECK(!logger_.stream(MSG_TYPE_WARNING).isNull());
BOOST_CHECK(!logger_.stream(MSG_TYPE_ERROR).isNull());
}
~CustomEntity() {}
void testDebugTrace() {
logger_.stream(MSG_TYPE_DEBUG)
<< "This is a message of level MSG_TYPE_DEBUG\n";
dynamicgraph::RealTimeLogger::instance().spinOnce();
logger_.stream(MSG_TYPE_INFO)
<< "This is a message of level MSG_TYPE_INFO\n";
dynamicgraph::RealTimeLogger::instance().spinOnce();
logger_.stream(MSG_TYPE_WARNING)
<< "This is a message of level MSG_TYPE_WARNING\n";
dynamicgraph::RealTimeLogger::instance().spinOnce();
logger_.stream(MSG_TYPE_ERROR)
<< "This is a message of level MSG_TYPE_ERROR\n";
dynamicgraph::RealTimeLogger::instance().spinOnce();
logger_.stream(MSG_TYPE_DEBUG_STREAM)
<< "This is a message of level MSG_TYPE_DEBUG_STREAM\n";
dynamicgraph::RealTimeLogger::instance().spinOnce();
logger_.stream(MSG_TYPE_INFO_STREAM)
<< "This is a message of level MSG_TYPE_INFO_STREAM\n";
dynamicgraph::RealTimeLogger::instance().spinOnce();
logger_.stream(MSG_TYPE_WARNING_STREAM)
<< "This is a message of level MSG_TYPE_WARNING_STREAM\n";
dynamicgraph::RealTimeLogger::instance().spinOnce();
logger_.stream(MSG_TYPE_ERROR_STREAM)
<< "This is a message of level MSG_TYPE_ERROR_STREAM\n";
/* Add test toString */
dynamicgraph::RealTimeLogger::instance().spinOnce();
double q = 1.0;
logger_.stream() << "Value to display: " + toString(q) << '\n';
dynamicgraph::RealTimeLogger::instance().spinOnce();
std::vector<double> vq;
vq.resize(3);
vq[0] = 1.0;
vq[1] = 2.0;
vq[2] = 3.0;
logger_.stream(MSG_TYPE_INFO)
<< "Value to display: " << toString(vq) << '\n';
dynamicgraph::RealTimeLogger::instance().spinOnce();
logger_.stream(MSG_TYPE_INFO)
<< "Value to display: " << toString(vq, 3, 10) << '\n';
dynamicgraph::RealTimeLogger::instance().spinOnce();
Eigen::Matrix<double, 3, 3> an_eig_m;
an_eig_m.setOnes();
logger_.stream(MSG_TYPE_INFO)
<< "Value to display: " << toString(an_eig_m) << '\n';
dynamicgraph::RealTimeLogger::instance().spinOnce();
logger_.countdown();
}
};
DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN(CustomEntity, "CustomEntity");
} // namespace dynamicgraph
BOOST_AUTO_TEST_CASE(debug_logger) {
std::ofstream of;
dynamicgraph::RealTimeLogger::instance();
of.open("/tmp/dg-LOGS.txt", std::ofstream::out | std::ofstream::app);
dgADD_OSTREAM_TO_RTLOG(of);
BOOST_CHECK_EQUAL(dynamicgraph::CustomEntity::CLASS_NAME, "CustomEntity");
dynamicgraph::CustomEntity &entity =
*(dynamic_cast<dynamicgraph::CustomEntity *>(
dynamicgraph::FactoryStorage::getInstance()->newEntity("CustomEntity",
"my-entity")));
entity.setTimeSample(0.002);
BOOST_CHECK_EQUAL(entity.getTimeSample(), 0.002);
entity.setStreamPrintPeriod(0.002);
BOOST_CHECK_EQUAL(entity.getStreamPrintPeriod(), 0.002);
for (unsigned int i = 0; i < 10000; i++) {
entity.testDebugTrace();
}
dynamicgraph::RealTimeLogger::destroy();
}
/* Copyright 2019, LAAS-CNRS
*
* Olivier Stasse
*
*/
#include <dynamic-graph/command.h>
#include <dynamic-graph/entity.h>
#include <dynamic-graph/exception-factory.h>
#include <dynamic-graph/factory.h>
#include <dynamic-graph/pool.h>
#include <dynamic-graph/signal-ptr.h>
#include <dynamic-graph/signal-time-dependent.h>
#include <dynamic-graph/tracer-real-time.h>
#include <iostream>
#define BOOST_TEST_MODULE debug - tracer
#if BOOST_VERSION >= 105900
#include <boost/test/tools/output_test_stream.hpp>
#else
#include <boost/test/output_test_stream.hpp>
#endif
#include <boost/test/unit_test.hpp>
using boost::test_tools::output_test_stream;
namespace dynamicgraph {
struct MyEntity : public dynamicgraph::Entity {
static const std::string CLASS_NAME;
dynamicgraph::Signal<double, int> m_sigdSIN;
dynamicgraph::SignalTimeDependent<double, int> m_sigdTimeDepSOUT;
dynamicgraph::SignalTimeDependent<double, int> m_sigdTwoTimeDepSOUT;
explicit MyEntity(const std::string &name)
: Entity(name),
m_sigdSIN("MyEntity(" + name + ")::input(double)::in_double"),
m_sigdTimeDepSOUT(boost::bind(&MyEntity::update, this, _1, _2),
m_sigdSIN,
"MyEntity(" + name + ")::input(double)::out_double"),
m_sigdTwoTimeDepSOUT(
boost::bind(&MyEntity::update, this, _1, _2), m_sigdSIN,
"MyEntity(" + name + ")::input(double)::out2double")
{
signalRegistration(m_sigdSIN << m_sigdTimeDepSOUT << m_sigdTwoTimeDepSOUT);
}
double &update(double &res, const int &inTime) {
const double &aDouble = m_sigdSIN(inTime);
res = aDouble;
return res;
}
};
DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN(MyEntity, "MyEntity");
} // namespace dynamicgraph
BOOST_AUTO_TEST_CASE(test_tracer) {
using namespace dynamicgraph;
// Creates a tracer.
TracerRealTime &atracer = *dynamic_cast<TracerRealTime *>(
FactoryStorage::getInstance()->newEntity("TracerRealTime", "my-tracer"));
MyEntity &entity = *dynamic_cast<MyEntity *>(
FactoryStorage::getInstance()->newEntity("MyEntity", "my-entity"));
std::string rootdir("/tmp");
std::string basename("my-tracer");
std::string suffix(".dat");
atracer.setBufferSize(1 << 14);
// Check that an exception is thrown if the filename is invalid.
atracer.openFiles(rootdir, "invalid/filename", suffix);
BOOST_CHECK_THROW(
atracer.addSignalToTraceByName("my-entity.out_double", "output"),
ExceptionTraces);
// Test openfiles
atracer.openFiles(rootdir, basename, suffix);
// Add trace by name
atracer.addSignalToTraceByName("my-entity.out_double", "output");
/// Add trace by name
SignalBase<int> &out_double = entity.getSignal("out_double");
SignalBase<int> &out_double_2 = entity.getSignal("out2double");
Signal<double, int> &in_double =
*(dynamic_cast<Signal<double, int> *>(&entity.getSignal("in_double")));
in_double.setConstant(1.5);
atracer.start();
std::string emptybuf_cmd_str("empty");
command::Command *acmd = atracer.getNewStyleCommand(emptybuf_cmd_str);
acmd->execute();
for (int i = 0; i < 1000; i++) {
in_double.setTime(i);
out_double.recompute(i);
out_double_2.recompute(i);
atracer.recordTrigger(i, i);
}
output_test_stream output;
atracer.display(output);
atracer.stop();
atracer.trace();
atracer.clearSignalToTrace();
atracer.closeFiles();
acmd->execute();
atracer.record();
BOOST_CHECK(output.is_equal(
"TracerRealTime my-tracer [mode=play] : \n"
" - Dep list: \n"
" -> MyEntity(my-entity)::input(double)::out_double (in output)"
" [8Ko/16Ko] \n"));
}
/* Copyright 2019, LAAS-CNRS
*
* Olivier Stasse
*
*/
#include <dynamic-graph/entity.h>
#include <dynamic-graph/exception-factory.h>
#include <iostream>
#include <sstream>
#include "dynamic-graph/factory.h"
#include "dynamic-graph/pool.h"
#define VP_DEBUG 1
#define VP_DEBUG_MODE 50
#define VP_TEMPLATE_DEBUG_MODE 50
#include <dynamic-graph/debug.h>
#define BOOST_TEST_MODULE debug - trace
#if BOOST_VERSION >= 105900
#include <boost/test/tools/output_test_stream.hpp>
#else
#include <boost/test/output_test_stream.hpp>
#endif
#include <boost/test/unit_test.hpp>
using boost::test_tools::output_test_stream;
namespace dynamicgraph {
class CustomEntity : public Entity {
public:
static const std::string CLASS_NAME;
virtual const std::string &getClassName() const { return CLASS_NAME; }
explicit CustomEntity(const std::string &n) : Entity(n) {
dynamicgraph::dgDEBUGFLOW.openFile("/tmp/dynamic-graph-traces.txt");
}
~CustomEntity() {
dynamicgraph::dgDEBUGFLOW.closeFile("/tmp/dynamic-graph-traces.txt");
}
void testDebugTrace() {
/// Test debugging information when entering the code.
dgDEBUGIN(5);
/// Intermediate test.
dgDEBUGINOUT(5);
dgDEBUG(5) << "Here is a test" << std::endl;
/// Test debugging information when going out of the code.
dgDEBUGOUT(5);
}
};
DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN(CustomEntity, "CustomEntity");
} // namespace dynamicgraph
BOOST_AUTO_TEST_CASE(testDebugTrace) {
BOOST_CHECK_EQUAL(dynamicgraph::CustomEntity::CLASS_NAME, "CustomEntity");
dynamicgraph::CustomEntity *ptr_entity =
(dynamic_cast<dynamicgraph::CustomEntity *>(
dynamicgraph::FactoryStorage::getInstance()->newEntity("CustomEntity",
"my-entity")));
dynamicgraph::CustomEntity &entity = *ptr_entity;
entity.testDebugTrace();
/// Copy the debug file into the oss_debug_file
output_test_stream output;
std::fstream the_debug_file;
the_debug_file.open(dynamicgraph::DebugTrace::DEBUG_FILENAME_DEFAULT,
std::ios::in);
// Extract the filename and this source file from the output
std::string astr;
std::ostringstream oss_debug_file;
while (std::getline(the_debug_file, astr)) {
std::size_t found = astr.find(":");
std::string asubstr = astr.substr(found + 1, astr.length());
found = asubstr.find(":");
std::string asubstr2 = asubstr.substr(found + 1, astr.length());
oss_debug_file << asubstr2;
}
the_debug_file.close();
// Compare with the strings put inside this source file
std::string str_to_test =
"# In {"
"# In/Out { }"
"Here is a test"
"# Out }";
bool two_sub_string_identical;
// Make comparisons.
two_sub_string_identical = str_to_test == oss_debug_file.str();
BOOST_CHECK(two_sub_string_identical);
delete ptr_entity;
}
/* Copyright 2019, LAAS-CNRS
*
* Olivier Stasse
*
*/
#include <dynamic-graph/entity.h>
#include <dynamic-graph/exception-factory.h>
#include <dynamic-graph/factory.h>
#include <dynamic-graph/pool.h>
#include <dynamic-graph/signal-ptr.h>
#include <dynamic-graph/signal-time-dependent.h>
#include <dynamic-graph/tracer.h>
#include <iostream>
#define BOOST_TEST_MODULE debug - tracer
#if BOOST_VERSION >= 105900
#include <boost/test/tools/output_test_stream.hpp>
#else
#include <boost/test/output_test_stream.hpp>
#endif
#include <boost/test/unit_test.hpp>
namespace dynamicgraph {
struct MyEntity : public dynamicgraph::Entity {
static const std::string CLASS_NAME;
dynamicgraph::Signal<double, int> m_sigdSIN;
dynamicgraph::SignalTimeDependent<double, int> m_sigdTimeDepSOUT;
dynamicgraph::SignalTimeDependent<Vector, int> m_sigVTimeDepSOUT;
dynamicgraph::SignalTimeDependent<double, int> m_sigdTwoTimeDepSOUT;
explicit MyEntity(const std::string &name)
: Entity(name),
m_sigdSIN("MyEntity(" + name + ")::input(double)::in_double"),
m_sigdTimeDepSOUT(boost::bind(&MyEntity::update, this, _1, _2),
m_sigdSIN,
"MyEntity(" + name + ")::input(double)::out_double"),
m_sigVTimeDepSOUT(boost::bind(&MyEntity::updateVector, this, _1, _2),
m_sigdSIN,
"MyEntity(" + name + ")::input(vector)::out_vector"),
m_sigdTwoTimeDepSOUT(
boost::bind(&MyEntity::update, this, _1, _2), m_sigdSIN,
"MyEntity(" + name + ")::input(double)::out2double")
{
signalRegistration(m_sigdSIN << m_sigdTimeDepSOUT << m_sigVTimeDepSOUT
<< m_sigdTwoTimeDepSOUT);
}
virtual void display(std::ostream &os) const {
os << "Hello! My name is " << getName() << " !" << std::endl;
}
virtual const std::string &getClassName() const { return CLASS_NAME; }
double &update(double &res, const int &inTime) {
const double &aDouble = m_sigdSIN(inTime);
res = aDouble;
return res;
}
Vector &updateVector(Vector &res, const int &inTime) {
const double &aDouble = m_sigdSIN(inTime);
res.resize(2);
res << aDouble, 2 * aDouble;
return res;
}
};
DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN(MyEntity, "MyEntity");
} // namespace dynamicgraph
BOOST_AUTO_TEST_CASE(test_tracer) {
using dynamicgraph::Vector;
// Creates a tracer.
dynamicgraph::Tracer &atracer = *dynamic_cast<dynamicgraph::Tracer *>(
dynamicgraph::FactoryStorage::getInstance()->newEntity("Tracer",
"my-tracer"));
dynamicgraph::Entity &entity =
*dynamicgraph::FactoryStorage::getInstance()->newEntity("MyEntity",
"my-entity");
std::string rootdir("/tmp");
std::string basename("my-tracer");
std::string suffix(".dat");
/// Test openfiles
atracer.openFiles(rootdir, basename, suffix);
/// Add trace by name
atracer.addSignalToTraceByName("my-entity.out_double", "output");
/// Add trace by name
atracer.addSignalToTraceByName("my-entity.out_vector", "output-vector");
dynamicgraph::SignalBase<int> &aSignal = entity.getSignal("out2double");
dynamicgraph::Signal<double, int> &aSignalInt =
*(dynamic_cast<dynamicgraph::Signal<double, int> *>(
&entity.getSignal("in_double")));
dynamicgraph::Signal<Vector, int> &aSignalVector =
*(dynamic_cast<dynamicgraph::Signal<Vector, int> *>(
&entity.getSignal("out_vector")));
/// Add trace by signal object
atracer.addSignalToTrace(aSignal, "output2");
aSignalInt.setConstant(1.5);
atracer.start();
for (int i = 0; i < 1000; i++) {
aSignal.setTime(i);
aSignalInt.access(i);
aSignalInt.setTime(i);
aSignalVector.recompute(i);
aSignalVector.setTime(i);
atracer.recordTrigger(i, i);
}
atracer.stop();
atracer.clearSignalToTrace();
atracer.closeFiles();
atracer.record();
}
// Copyright 2010 Thomas Moulard. /* Copyright 2010-2019 LAAS, CNRS
// * Thomas Moulard.
// This file is part of dynamic-graph. *
// dynamic-graph is free software: you can redistribute it and/or modify */
// it under the terms of the GNU Lesser General Public License as published by
// the Free Software Foundation, either version 3 of the License, or
// (at your option) any later version.
//
// dynamic-graph is distributed in the hope that it will be useful,
// but WITHOUT ANY WARRANTY; without even the implied warranty of
// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
// GNU Lesser General Public License for more details.
// You should have received a copy of the GNU Lesser General Public License
// along with dynamic-graph. If not, see <http://www.gnu.org/licenses/>.
#include <sstream> #define ENABLE_RT_LOG
#include <dynamic-graph/command-direct-getter.h>
#include <dynamic-graph/command-direct-setter.h>
#include <dynamic-graph/entity.h> #include <dynamic-graph/entity.h>
#include <dynamic-graph/exception-factory.h> #include <dynamic-graph/exception-factory.h>
#include <dynamic-graph/real-time-logger.h>
#include <dynamic-graph/signal-ptr.h>
#include <dynamic-graph/signal-time-dependent.h>
#include <sstream>
#include "dynamic-graph/factory.h" #include "dynamic-graph/factory.h"
#include "dynamic-graph/pool.h" #include "dynamic-graph/pool.h"
#define BOOST_TEST_MODULE entity #define BOOST_TEST_MODULE entity
#include <boost/test/unit_test.hpp> #if BOOST_VERSION >= 105900
#include <boost/test/tools/output_test_stream.hpp>
#else
#include <boost/test/output_test_stream.hpp> #include <boost/test/output_test_stream.hpp>
#endif
#include <boost/test/unit_test.hpp>
using boost::test_tools::output_test_stream; using boost::test_tools::output_test_stream;
namespace dynamicgraph namespace dynamicgraph {
{ class CustomEntity : public Entity {
class CustomEntity : public Entity public:
{ dynamicgraph::SignalPtr<double, int> m_sigdSIN, m_sigdSIN2;
public: dynamicgraph::SignalTimeDependent<double, int> m_sigdTimeDepSOUT;
static const std::string CLASS_NAME;
virtual const std::string& getClassName () const static const std::string CLASS_NAME;
{ virtual const std::string &getClassName() const { return CLASS_NAME; }
return CLASS_NAME; explicit CustomEntity(const std::string &n)
: Entity(n),
m_sigdSIN(NULL, "CustomEntity(" + name + ")::input(double)::in_double"),
m_sigdSIN2(NULL,
"CustomEntity(" + name + ")::input(double)::in_double"),
m_sigdTimeDepSOUT(
boost::bind(&CustomEntity::update, this, _1, _2), m_sigdSIN,
"CustomEntity(" + name + ")::input(double)::out_double"),
m_value(0.0) {}
~CustomEntity() { entityDeregistration(); }
void addSignal() {
signalRegistration(m_sigdSIN << m_sigdTimeDepSOUT);
/// Try a second time to generate an exception
try {
signalRegistration(m_sigdSIN2 << m_sigdTimeDepSOUT);
} catch (ExceptionFactory &aef) {
BOOST_CHECK_EQUAL(aef.getCode(),
dynamicgraph::ExceptionFactory::SIGNAL_CONFLICT);
} }
CustomEntity (const std::string n) }
: Entity (n)
{ void rmValidSignal() {
} signalDeregistration("in_double");
}; signalDeregistration("out_double");
DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN (CustomEntity,"CustomEntity"); }
}
double &update(double &res, const int &inTime) {
const double &aDouble = m_sigdSIN(inTime);
res = aDouble;
return res;
}
public:
double m_value;
};
DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN(CustomEntity, "CustomEntity");
} // namespace dynamicgraph
BOOST_AUTO_TEST_CASE(constructor) {
namespace dg = dynamicgraph;
namespace dgc = dynamicgraph::command;
BOOST_CHECK_EQUAL(dg::CustomEntity::CLASS_NAME, "CustomEntity");
dg::Entity &entity = *dg::FactoryStorage::getInstance()->newEntity(
"CustomEntity", "my-entity");
BOOST_CHECK_EQUAL(entity.getName(), "my-entity");
BOOST_CHECK_EQUAL(entity.getClassName(), dg::CustomEntity::CLASS_NAME);
dg::CustomEntity entity2("");
// Test Commands
dgc::DirectGetter<dg::CustomEntity, double> a_direct_getter(
entity2, &entity2.m_value,
dgc::docDirectGetter("Get value m_value", "double"));
dgc::DirectSetter<dg::CustomEntity, double> a_direct_setter(
entity2, &entity2.m_value,
dgc::docDirectSetter("Set value m_value", "double"));
dgc::Value aValue(2.0);
std::vector<dgc::Value> values;
values.push_back(aValue);
a_direct_setter.setParameterValues(values);
a_direct_setter.execute();
a_direct_getter.execute();
output_test_stream output;
output << entity2.m_value;
output << entity2;
BOOST_AUTO_TEST_CASE (constructor) entity.getDocString();
{
BOOST_CHECK_EQUAL (dynamicgraph::CustomEntity::CLASS_NAME, "CustomEntity");
dynamicgraph::Entity& entity =
*dynamicgraph::FactoryStorage::getInstance()->newEntity("CustomEntity",
"my-entity");
BOOST_CHECK_EQUAL (entity.getName (), "my-entity");
BOOST_CHECK_EQUAL (entity.getClassName (),
dynamicgraph::CustomEntity::CLASS_NAME);
dynamicgraph::CustomEntity entity2 ("");
} }
BOOST_AUTO_TEST_CASE (signal) BOOST_AUTO_TEST_CASE(signal) {
{ dynamicgraph::Entity &entity =
dynamicgraph::Entity& entity = dynamicgraph::PoolStorage::getInstance()->getEntity("my-entity");
dynamicgraph::PoolStorage::getInstance()->getEntity("my-entity");
// Non const getter. // Non const getter.
try try {
{ entity.getSignal("I do not exist");
entity.getSignal ("I do not exist"); BOOST_ERROR("Should never happen.");
BOOST_ERROR ("Should never happen."); } catch (const dynamicgraph::ExceptionFactory &exception) {
} BOOST_CHECK_EQUAL(exception.getCode(),
catch (const dynamicgraph::ExceptionFactory& exception) dynamicgraph::ExceptionFactory::UNREFERED_SIGNAL);
{ }
BOOST_CHECK_EQUAL (exception.getCode (),
dynamicgraph::ExceptionFactory::UNREFERED_SIGNAL);
}
// Const getter. // Const getter.
try try {
{ const dynamicgraph::Entity &entityConst = entity;
const dynamicgraph::Entity& entityConst = entity; entityConst.getSignal("I do not exist");
entityConst.getSignal ("I do not exist"); BOOST_ERROR("Should never happen.");
BOOST_ERROR ("Should never happen."); } catch (const dynamicgraph::ExceptionFactory &exception) {
} BOOST_CHECK_EQUAL(exception.getCode(),
catch (const dynamicgraph::ExceptionFactory& exception) dynamicgraph::ExceptionFactory::UNREFERED_SIGNAL);
{ }
BOOST_CHECK_EQUAL (exception.getCode (), // deregistration
dynamicgraph::ExceptionFactory::UNREFERED_SIGNAL); try {
} dynamicgraph::CustomEntity *customEntity =
dynamic_cast<dynamicgraph::CustomEntity *>(&entity);
customEntity->addSignal();
std::string signame("CustomEntity(my-entity)::input(double)::in_double");
customEntity->Entity::hasSignal(signame);
output_test_stream output;
customEntity->Entity::displaySignalList(output);
dynamicgraph::Entity::SignalMap asigmap = customEntity->getSignalMap();
output << customEntity;
// Removing signals is working the first time
customEntity->rmValidSignal();
// Removing signals generates an exception the second time.
customEntity->rmValidSignal();
BOOST_ERROR("Should never happen.");
} catch (const dynamicgraph::ExceptionFactory &exception) {
BOOST_CHECK_EQUAL(exception.getCode(),
dynamicgraph::ExceptionFactory::UNREFERED_SIGNAL);
}
} }
BOOST_AUTO_TEST_CASE (displaySignalList) BOOST_AUTO_TEST_CASE(displaySignalList) {
{ dynamicgraph::Entity &entity =
dynamicgraph::Entity& entity = dynamicgraph::PoolStorage::getInstance()->getEntity("my-entity");
dynamicgraph::PoolStorage::getInstance()->getEntity("my-entity");
output_test_stream output; output_test_stream output;
entity.displaySignalList(output); entity.displaySignalList(output);
BOOST_CHECK (output.is_equal ("--- <my-entity> signal list: \n")); BOOST_CHECK(output.is_equal("--- <my-entity> signal list: \n"));
} }
BOOST_AUTO_TEST_CASE (display) BOOST_AUTO_TEST_CASE(display) {
{ dynamicgraph::Entity &entity =
dynamicgraph::Entity& entity = dynamicgraph::PoolStorage::getInstance()->getEntity("my-entity");
dynamicgraph::PoolStorage::getInstance()->getEntity("my-entity");
output_test_stream output; output_test_stream output;
entity.display(output); entity.display(output);
BOOST_CHECK (output.is_equal ("CustomEntity: my-entity")); BOOST_CHECK(output.is_equal("CustomEntity: my-entity"));
}
BOOST_AUTO_TEST_CASE(getCommandList) {
dynamicgraph::Entity &entity =
dynamicgraph::PoolStorage::getInstance()->getEntity("my-entity");
BOOST_CHECK_EQUAL(entity.getCommandList(), "print\nsignals\nsignalDep");
} }
BOOST_AUTO_TEST_CASE (getCommandList) BOOST_AUTO_TEST_CASE(writeGraph) {
{ dynamicgraph::Entity &entity =
dynamicgraph::Entity& entity = dynamicgraph::PoolStorage::getInstance()->getEntity("my-entity");
dynamicgraph::PoolStorage::getInstance()->getEntity("my-entity");
output_test_stream output;
entity.writeGraph(output);
BOOST_CHECK_EQUAL (entity.getCommandList (), "print\nsignals\nsignalDep"); BOOST_CHECK(output.is_equal(""));
} }
BOOST_AUTO_TEST_CASE (writeGraph) BOOST_AUTO_TEST_CASE(writeCompletionList) {
{ dynamicgraph::Entity &entity =
dynamicgraph::Entity& entity = dynamicgraph::PoolStorage::getInstance()->getEntity("my-entity");
dynamicgraph::PoolStorage::getInstance()->getEntity("my-entity");
output_test_stream output; output_test_stream output;
entity.writeGraph (output); entity.writeCompletionList(output);
BOOST_CHECK (output.is_equal ("")); BOOST_CHECK(output.is_equal("print\nsignals\nsignalDep\n"));
} }
BOOST_AUTO_TEST_CASE (writeCompletionList) BOOST_AUTO_TEST_CASE(sendMsg) {
{ std::ofstream of;
dynamicgraph::Entity& entity = of.open("/tmp/dg-LOGS.txt", std::ofstream::out | std::ofstream::app);
dynamicgraph::PoolStorage::getInstance()->getEntity("my-entity"); dgADD_OSTREAM_TO_RTLOG(of);
dynamicgraph::Entity &entity =
dynamicgraph::PoolStorage::getInstance()->getEntity("my-entity");
output_test_stream output; output_test_stream output;
entity.writeGraph (output);
BOOST_CHECK (output.is_equal ("")); for (unsigned int i = 0; i < 4; i++) {
for (unsigned int j = 0; j < 2000; j++) {
dynamicgraph::LoggerVerbosity aLoggerVerbosityLevel =
(dynamicgraph::LoggerVerbosity)i;
entity.setLoggerVerbosityLevel(aLoggerVerbosityLevel);
if (entity.getLoggerVerbosityLevel() != aLoggerVerbosityLevel)
output << "Mismatch output";
#define __FILELINE__ __FILE__ BOOST_PP_STRINGIZE(__LINE__)
entity.logger().stream(dynamicgraph::MSG_TYPE_DEBUG, __FILELINE__)
<< "Auto Test Case"
<< " DEBUG" << '\n';
entity.logger().stream(dynamicgraph::MSG_TYPE_INFO, __FILELINE__)
<< "Auto Test Case"
<< " INFO" << '\n';
entity.logger().stream(dynamicgraph::MSG_TYPE_WARNING, __FILELINE__)
<< "Auto Test Case"
<< " WARNING" << '\n';
entity.logger().stream(dynamicgraph::MSG_TYPE_ERROR, __FILELINE__)
<< "Auto Test Case"
<< " ERROR" << '\n';
#undef __FILELINE__
};
};
BOOST_CHECK(output.is_equal(""));
dynamicgraph::RealTimeLogger::destroy();
} }
// WTF? // WTF?
BOOST_AUTO_TEST_CASE (wtf) BOOST_AUTO_TEST_CASE(wtf) {
{ dynamicgraph::Entity &entity =
dynamicgraph::Entity& entity = dynamicgraph::PoolStorage::getInstance()->getEntity("my-entity");
dynamicgraph::PoolStorage::getInstance()->getEntity("my-entity");
BOOST_CHECK_EQUAL (entity.test (), BOOST_CHECK_EQUAL(entity.test(),
static_cast<dynamicgraph::SignalBase<int>*> (0)); static_cast<dynamicgraph::SignalBase<int> *>(0));
entity.test2 (static_cast<dynamicgraph::SignalBase<int>*> (0)); entity.test2(static_cast<dynamicgraph::SignalBase<int> *>(0));
} }
// Copyright 2020 Olivier Stasse
// LAAS, CNRS
#include <dynamic-graph/exception-abstract.h>
#include <dynamic-graph/exception-factory.h>
#include <dynamic-graph/exception-signal.h>
#include <dynamic-graph/exception-traces.h>
#include <boost/version.hpp>
#include <sstream>
#if BOOST_VERSION >= 105900
#include <boost/test/tools/output_test_stream.hpp>
#else
#include <boost/test/output_test_stream.hpp>
#endif
#include <boost/test/unit_test.hpp>
#include <boost/test/unit_test_suite.hpp>
using boost::test_tools::output_test_stream;
using namespace dynamicgraph;
BOOST_AUTO_TEST_CASE(exception_abstract_param) {
/// Test param from Exception
/// Default constructor
ExceptionAbstract::Param aParamSimple;
/// Advanced constructor
ExceptionAbstract::Param aParam(60, "function_test", "my_file");
aParamSimple.initCopy(aParam);
}
BOOST_AUTO_TEST_CASE(exception_abstract) {
/// Test exception abstract with a simple message
std::string msg_aea("Test exception abstract");
ExceptionAbstract aEA(10, msg_aea);
const char *aC = aEA.getMessage();
output_test_stream output;
output << aC;
BOOST_CHECK(output.is_equal("Test exception abstract"));
output << aEA;
BOOST_CHECK(
output.is_equal("AbstractError [#10]: Test exception abstract\n"));
}
BOOST_AUTO_TEST_CASE(exception_traces) {
std::string msg_aet("Test exception traces simple");
ExceptionTraces aET(ExceptionTraces::GENERIC, msg_aet);
output_test_stream output;
output << aET;
BOOST_CHECK(
output.is_equal("TracesError [#300]: Test exception traces simple\n"));
/// Test exception traces with a format.
int a = 2, b = 3;
std::string msg_aet2("Test exception traces ");
ExceptionTraces aET2(ExceptionTraces::GENERIC, msg_aet2, "(%d,%d)", a, b);
output << aET2;
BOOST_CHECK(
output.is_equal("TracesError [#300]: Test exception traces (2,3)\n"));
}
// Copyright 2010 Thomas Moulard. // Copyright 2010 Thomas Moulard.
// //
// This file is part of dynamic-graph.
// dynamic-graph is free software: you can redistribute it and/or modify
// it under the terms of the GNU Lesser General Public License as published by
// the Free Software Foundation, either version 3 of the License, or
// (at your option) any later version.
//
// dynamic-graph is distributed in the hope that it will be useful,
// but WITHOUT ANY WARRANTY; without even the implied warranty of
// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
// GNU Lesser General Public License for more details.
// You should have received a copy of the GNU Lesser General Public License
// along with dynamic-graph. If not, see <http://www.gnu.org/licenses/>.
#include <sstream>
#include <dynamic-graph/factory.h>
#include <dynamic-graph/entity.h> #include <dynamic-graph/entity.h>
#include <dynamic-graph/exception-factory.h> #include <dynamic-graph/exception-factory.h>
#include <dynamic-graph/factory.h>
#include <sstream>
#define BOOST_TEST_MODULE factory #define BOOST_TEST_MODULE factory
#include <boost/test/unit_test.hpp> #if BOOST_VERSION >= 105900
#include <boost/test/tools/output_test_stream.hpp>
#else
#include <boost/test/output_test_stream.hpp> #include <boost/test/output_test_stream.hpp>
#endif
#include <boost/test/unit_test.hpp>
using boost::test_tools::output_test_stream; using boost::test_tools::output_test_stream;
namespace dynamicgraph {
class CustomEntity : public Entity {
namespace dynamicgraph public:
{ static const std::string CLASS_NAME;
class CustomEntity : public Entity virtual const std::string &getClassName() const { return CLASS_NAME; }
{ explicit CustomEntity(const std::string &n) : Entity(n) {}
public: };
static const std::string CLASS_NAME; const std::string CustomEntity::CLASS_NAME = "CustomEntity";
virtual const std::string& getClassName () const } // namespace dynamicgraph
{
return CLASS_NAME; dynamicgraph::Entity *makeEntity(const std::string &objectName) {
} return new dynamicgraph::CustomEntity(objectName);
CustomEntity (const std::string n)
: Entity (n)
{
}
};
const std::string CustomEntity::CLASS_NAME = "CustomEntity";
} }
BOOST_AUTO_TEST_CASE(constructor) {
dynamicgraph::Entity* makeEntity(const std::string& objectName) dynamicgraph::FactoryStorage::getInstance();
{
return new dynamicgraph::CustomEntity (objectName);
} }
BOOST_AUTO_TEST_CASE(registerEntity) {
dynamicgraph::FactoryStorage::getInstance()->registerEntity("myEntity",
&makeEntity);
try {
dynamicgraph::FactoryStorage::getInstance()->registerEntity("myEntity",
&makeEntity);
BOOST_ERROR("Should never happen.");
} catch (const dynamicgraph::ExceptionFactory &exception) {
BOOST_CHECK_EQUAL(exception.getCode(),
dynamicgraph::ExceptionFactory::OBJECT_CONFLICT);
}
BOOST_AUTO_TEST_CASE (constructor) try {
{ dynamicgraph::FactoryStorage::getInstance()->registerEntity("myEntity", 0);
dynamicgraph::FactoryStorage::getInstance(); BOOST_ERROR("Should never happen.");
} catch (const dynamicgraph::ExceptionFactory &exception) {
BOOST_CHECK_EQUAL(exception.getCode(),
dynamicgraph::ExceptionFactory::OBJECT_CONFLICT);
}
} }
BOOST_AUTO_TEST_CASE (registerEntity) BOOST_AUTO_TEST_CASE(unregisterEntity) {
{ dynamicgraph::FactoryStorage::getInstance()->deregisterEntity("myEntity");
dynamicgraph::FactoryStorage::getInstance()->registerEntity
("myEntity", &makeEntity);
try
{
dynamicgraph::FactoryStorage::getInstance()->registerEntity
("myEntity", &makeEntity);
BOOST_ERROR ("Should never happen.");
}
catch (const dynamicgraph::ExceptionFactory& exception)
{
BOOST_CHECK_EQUAL (exception.getCode (),
dynamicgraph::ExceptionFactory::OBJECT_CONFLICT);
}
try
{
dynamicgraph::FactoryStorage::getInstance()->registerEntity
("myEntity", 0);
BOOST_ERROR ("Should never happen.");
}
catch (const dynamicgraph::ExceptionFactory& exception)
{
BOOST_CHECK_EQUAL (exception.getCode (),
dynamicgraph::ExceptionFactory::OBJECT_CONFLICT);
}
}
BOOST_AUTO_TEST_CASE (unregisterEntity) try {
{ dynamicgraph::FactoryStorage::getInstance()->deregisterEntity("myEntity");
dynamicgraph::FactoryStorage::getInstance()->deregisterEntity ("myEntity"); BOOST_ERROR("Should never happen.");
} catch (const dynamicgraph::ExceptionFactory &exception) {
try BOOST_CHECK_EQUAL(exception.getCode(),
{ dynamicgraph::ExceptionFactory::OBJECT_CONFLICT);
dynamicgraph::FactoryStorage::getInstance()->deregisterEntity("myEntity"); }
BOOST_ERROR ("Should never happen.");
} try {
catch (const dynamicgraph::ExceptionFactory& exception) dynamicgraph::FactoryStorage::getInstance()->deregisterEntity(
{ "I do not exist.");
BOOST_CHECK_EQUAL (exception.getCode (), BOOST_ERROR("Should never happen.");
dynamicgraph::ExceptionFactory::OBJECT_CONFLICT); } catch (const dynamicgraph::ExceptionFactory &exception) {
} BOOST_CHECK_EQUAL(exception.getCode(),
dynamicgraph::ExceptionFactory::OBJECT_CONFLICT);
try }
{
dynamicgraph::FactoryStorage::getInstance()->deregisterEntity
("I do not exist.");
BOOST_ERROR ("Should never happen.");
}
catch (const dynamicgraph::ExceptionFactory& exception)
{
BOOST_CHECK_EQUAL (exception.getCode (),
dynamicgraph::ExceptionFactory::OBJECT_CONFLICT);
}
} }
BOOST_AUTO_TEST_CASE (newEntity) BOOST_AUTO_TEST_CASE(newEntity) {
{ dynamicgraph::FactoryStorage::getInstance()->registerEntity("myEntity",
dynamicgraph::FactoryStorage::getInstance()->registerEntity &makeEntity);
("myEntity", &makeEntity);
{ {
boost::shared_ptr<dynamicgraph::Entity> entity boost::shared_ptr<dynamicgraph::Entity> entity(
(dynamicgraph::FactoryStorage::getInstance()->newEntity dynamicgraph::FactoryStorage::getInstance()->newEntity("myEntity",
("myEntity", "foo")); "foo"));
boost::shared_ptr<dynamicgraph::Entity> entity2 boost::shared_ptr<dynamicgraph::Entity> entity2(
(dynamicgraph::FactoryStorage::getInstance()->newEntity dynamicgraph::FactoryStorage::getInstance()->newEntity("myEntity",
("myEntity", "foo2")); "foo2"));
boost::shared_ptr<dynamicgraph::Entity> entity3 boost::shared_ptr<dynamicgraph::Entity> entity3(
(dynamicgraph::FactoryStorage::getInstance()->newEntity dynamicgraph::FactoryStorage::getInstance()->newEntity("myEntity", ""));
("myEntity", ""));
} }
try try {
{ dynamicgraph::FactoryStorage::getInstance()->newEntity("I do not exist.",
dynamicgraph::FactoryStorage::getInstance()->newEntity "");
("I do not exist.", ""); BOOST_ERROR("Should never happen.");
BOOST_ERROR ("Should never happen."); } catch (const dynamicgraph::ExceptionFactory &exception) {
} BOOST_CHECK_EQUAL(exception.getCode(),
catch (const dynamicgraph::ExceptionFactory& exception) dynamicgraph::ExceptionFactory::UNREFERED_OBJECT);
{ }
BOOST_CHECK_EQUAL (exception.getCode (),
dynamicgraph::ExceptionFactory::UNREFERED_OBJECT); try {
} dynamicgraph::FactoryStorage::getInstance()->destroy();
dynamicgraph::FactoryStorage::getInstance()->existEntity("myEntity");
// BOOST_ERROR ("Should never happen.");
} catch (const dynamicgraph::ExceptionFactory &exception) {
BOOST_CHECK_EQUAL(exception.getCode(),
dynamicgraph::ExceptionFactory::UNREFERED_OBJECT);
}
} }
BOOST_AUTO_TEST_CASE (existEntity) BOOST_AUTO_TEST_CASE(existEntity) {
{ // BOOST_CHECK (dynamicgraph::FactoryStorage::getInstance()->existEntity
BOOST_CHECK (dynamicgraph::FactoryStorage::getInstance()->existEntity // ("myEntity"));
("myEntity")); BOOST_CHECK(
BOOST_CHECK (!dynamicgraph::FactoryStorage::getInstance()->existEntity !dynamicgraph::FactoryStorage::getInstance()->existEntity("myEntity2"));
("myEntity2")); BOOST_CHECK(!dynamicgraph::FactoryStorage::getInstance()->existEntity(""));
BOOST_CHECK (!dynamicgraph::FactoryStorage::getInstance()->existEntity (""));
} }
// Copyright 2010 Thomas Moulard.
//
// This file is part of dynamic-graph.
// dynamic-graph is free software: you can redistribute it and/or modify
// it under the terms of the GNU Lesser General Public License as published by
// the Free Software Foundation, either version 3 of the License, or
// (at your option) any later version.
//
// dynamic-graph is distributed in the hope that it will be useful,
// but WITHOUT ANY WARRANTY; without even the implied warranty of
// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
// GNU Lesser General Public License for more details.
// You should have received a copy of the GNU Lesser General Public License
// along with dynamic-graph. If not, see <http://www.gnu.org/licenses/>.
#include <sstream>
#include <dynamic-graph/exception-factory.h>
#include <dynamic-graph/interpreter.h>
#include <dynamic-graph/plugin-loader.h>
#define BOOST_TEST_MODULE tracer
#include <boost/test/unit_test.hpp>
#include <boost/test/output_test_stream.hpp>
#include "interpreter.h"
using boost::test_tools::output_test_stream;
// Check that plug-in loading/unloading is working.
BOOST_AUTO_TEST_CASE (cmd_tracer)
{
dynamicgraph::PluginLoader pl;
// Push paths.
{
RUN_COMMAND ("pushImportPaths", TESTS_DATADIR);
BOOST_CHECK (output.is_empty ());
}
{
RUN_COMMAND ("pushImportPaths", TESTS_PLUGINDIR);
BOOST_CHECK (output.is_empty ());
}
// Import tracer.dg
{
RUN_COMMAND ("import", "interpreter-tracer.dg");
BOOST_CHECK (output.is_empty ());
}
}
// Copyright 2010 Thomas Moulard. // Copyright 2010 Thomas Moulard.
// //
// This file is part of dynamic-graph.
// dynamic-graph is free software: you can redistribute it and/or modify
// it under the terms of the GNU Lesser General Public License as published by
// the Free Software Foundation, either version 3 of the License, or
// (at your option) any later version.
//
// dynamic-graph is distributed in the hope that it will be useful,
// but WITHOUT ANY WARRANTY; without even the implied warranty of
// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
// GNU Lesser General Public License for more details.
// You should have received a copy of the GNU Lesser General Public License
// along with dynamic-graph. If not, see <http://www.gnu.org/licenses/>.
#include <sstream>
#include <dynamic-graph/entity.h> #include <dynamic-graph/entity.h>
#include <dynamic-graph/factory.h>
#include <dynamic-graph/exception-factory.h> #include <dynamic-graph/exception-factory.h>
#include <dynamic-graph/factory.h>
#include <dynamic-graph/pool.h> #include <dynamic-graph/pool.h>
#include <dynamic-graph/signal-ptr.h>
#include <dynamic-graph/signal-time-dependent.h>
#include <iostream>
#include <sstream>
#define BOOST_TEST_MODULE pool #define BOOST_TEST_MODULE pool
#include <boost/test/unit_test.hpp> #if BOOST_VERSION >= 105900
#include <boost/test/tools/output_test_stream.hpp>
#else
#include <boost/test/output_test_stream.hpp> #include <boost/test/output_test_stream.hpp>
#endif
#include <boost/test/unit_test.hpp>
using boost::test_tools::output_test_stream; using boost::test_tools::output_test_stream;
struct MyEntity : public dynamicgraph::Entity struct MyEntity : public dynamicgraph::Entity {
{
static const std::string CLASS_NAME; static const std::string CLASS_NAME;
MyEntity (const std::string& name) dynamicgraph::SignalPtr<double, int> m_sigdSIN;
: Entity (name) dynamicgraph::SignalTimeDependent<double, int> m_sigdTimeDepSOUT;
{}
explicit MyEntity(const std::string &name)
: Entity(name),
m_sigdSIN(NULL, "MyEntity(" + name + ")::input(double)::in_double"),
m_sigdTimeDepSOUT(boost::bind(&MyEntity::update, this, _1, _2),
m_sigdSIN,
"MyEntity(" + name + ")::input(double)::out_double") {
signalRegistration(m_sigdSIN << m_sigdTimeDepSOUT);
}
virtual void display (std::ostream& os) const virtual void display(std::ostream &os) const {
{ os << "Hello! My name is " << getName() << " !" << std::endl;
os << "Hello! My name is " << getName () << " !" << std::endl;
} }
virtual const std::string& getClassName () const virtual const std::string &getClassName() const { return CLASS_NAME; }
{
return CLASS_NAME; double &update(double &res, const int &inTime) {
const double &aDouble = m_sigdSIN(inTime);
res = aDouble;
return res;
} }
}; };
DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN (MyEntity, "MyEntity"); DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN(MyEntity, "MyEntity");
namespace dg = dynamicgraph;
BOOST_AUTO_TEST_CASE(pool_display) {
/// Create Entity
dg::Entity *entity =
dg::FactoryStorage::getInstance()->newEntity("MyEntity", "MyEntityInst");
/// Test exception catching when registering Entity
bool res = false;
try {
dg::Entity *entity2 = dg::FactoryStorage::getInstance()->newEntity(
"MyEntity", "MyEntityInst");
bool res2 = (entity2 == entity);
BOOST_CHECK(res2);
} catch (const dg::ExceptionFactory &aef) {
res = (aef.getCode() == dg::ExceptionFactory::OBJECT_CONFLICT);
}
BOOST_CHECK(res);
BOOST_AUTO_TEST_CASE (pool_display) /// Test exception catching when deregistering Entity
{ res = false;
dynamicgraph::Entity* entity = try {
dynamicgraph::FactoryStorage::getInstance()-> dg::FactoryStorage::getInstance()->deregisterEntity("MyEntityInstFailure");
newEntity("MyEntity", "MyEntityInst"); } catch (const dg::ExceptionFactory &aef) {
res = (aef.getCode() == dg::ExceptionFactory::OBJECT_CONFLICT);
}
BOOST_CHECK(res);
/// Search for an entity inside the map
output_test_stream output; output_test_stream output;
dynamicgraph::Entity& e = dynamicgraph::PoolStorage::getInstance()->getEntity dg::Entity &e = dg::PoolStorage::getInstance()->getEntity("MyEntityInst");
("MyEntityInst");
e.display(output); e.display(output);
BOOST_CHECK (output.is_equal ("Hello! My name is MyEntityInst !\n")); BOOST_CHECK(output.is_equal("Hello! My name is MyEntityInst !\n"));
dynamicgraph::PoolStorage::getInstance()->deregisterEntity
(entity->getName()); /// Search for an entity inside the map
dynamicgraph::PoolStorage::destroy(); res = false;
try {
dg::PoolStorage::getInstance()->getEntity("MyEntityInstFailure");
} catch (const dg::ExceptionFactory &aef) {
res = (aef.getCode() == dg::ExceptionFactory::UNREFERED_OBJECT);
}
BOOST_CHECK(res);
/// Testing entityMap
const dg::PoolStorage::Entities &anEntityMap =
dg::PoolStorage::getInstance()->getEntityMap();
bool testExistence = anEntityMap.find("MyEntityInst") == anEntityMap.end();
BOOST_CHECK(!testExistence);
/// Testing the existence of an entity
testExistence =
dg::PoolStorage::getInstance()->existEntity("MyEntityInst", entity);
BOOST_CHECK(testExistence);
/// Testing the completion list of pool storage
dg::PoolStorage::getInstance()->writeCompletionList(output);
BOOST_CHECK(
output.is_equal("MyEntityInst.in_double\nMyEntityInst.out_double\n"
"print\nsignals\nsignalDep\n"));
/// Checking the graph generated by the pool
dg::PoolStorage::getInstance()->writeGraph("output.dot");
std::fstream the_debug_file;
the_debug_file.open("output.dot");
std::ostringstream oss_output_wgph;
oss_output_wgph << the_debug_file.rdbuf();
the_debug_file.close();
/// Use a predefined output
std::string str_to_test =
"/* This graph has been automatically generated.\n"
" 2019 Month: 2 Day: 28 Time: 11:28 */\n"
"digraph \"output\" { \t graph [ label=\"output\" "
"bgcolor = white rankdir=LR ]\n"
"\t node [ fontcolor = black, color = black,fillcolor = gold1,"
" style=filled, shape=box ] ; \n"
"\tsubgraph cluster_Entities { \n"
"\t} \n"
"\"MyEntityInst\" [ label = \"MyEntityInst\" ,\n"
" fontcolor = black, color = black, fillcolor=cyan, style=filled,"
" shape=box ]\n"
"}\n";
/// Check the two substring (remove the date) -
std::string s_output_wgph = oss_output_wgph.str();
std::string s_crmk = "*/";
std::size_t find_s_output_wgph = s_output_wgph.find(s_crmk);
std::string sub_s_output_wgph =
s_output_wgph.substr(find_s_output_wgph, s_output_wgph.length());
std::size_t find_str_to_test = str_to_test.find(s_crmk);
std::string sub_str_to_test =
str_to_test.substr(find_str_to_test, str_to_test.length());
bool two_sub_string_identical;
two_sub_string_identical = sub_str_to_test == sub_s_output_wgph;
std::cout << sub_str_to_test << std::endl;
std::cout << sub_s_output_wgph << std::endl;
std::cout << sub_str_to_test.compare(sub_s_output_wgph) << std::endl;
BOOST_CHECK(two_sub_string_identical);
/// Test name of a valid signal.
std::istringstream an_iss("MyEntityInst.in_double");
dg::SignalBase<int> &aSignal =
dg::PoolStorage::getInstance()->getSignal(an_iss);
std::string aSignalName = aSignal.getName();
testExistence =
aSignalName == "MyEntity(MyEntityInst)::input(double)::in_double";
BOOST_CHECK(testExistence);
/// Test name of an unvalid signal.
an_iss.str("MyEntityInst.in2double");
try {
dg::PoolStorage::getInstance()->getSignal(an_iss);
} catch (const dg::ExceptionFactory &aef) {
res = (aef.getCode() == dg::ExceptionFactory::UNREFERED_SIGNAL);
}
BOOST_CHECK(res);
/// Deregister the entity.
dg::PoolStorage::getInstance()->deregisterEntity(entity->getName());
/// Testing the existance of an entity
testExistence =
dg::PoolStorage::getInstance()->existEntity("MyEntityInst", entity);
BOOST_CHECK(!testExistence);
/// Create Entity
std::string name_entity("MyEntityInst2");
dg::PoolStorage::getInstance()->clearPlugin(name_entity);
dg::PoolStorage::destroy();
} }