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 158 additions and 132 deletions
......@@ -13,17 +13,18 @@
#define ENABLE_RT_LOG
#include <dynamic-graph/logger.h>
#include <iomanip> // std::setprecision
#include <iostream>
#include <sstream>
#include <dynamic-graph/real-time-logger.h>
#include <stdio.h>
#include <dynamic-graph/real-time-logger.h>
#include <iomanip> // std::setprecision
#include <iostream>
#include <sstream>
namespace dynamicgraph {
Logger::Logger(double timeSample, double streamPrintPeriod)
: m_timeSample(timeSample), m_streamPrintPeriod(streamPrintPeriod),
: m_timeSample(timeSample),
m_streamPrintPeriod(streamPrintPeriod),
m_printCountdown(0.0) {
m_lv = VERBOSITY_ERROR;
}
......@@ -34,8 +35,7 @@ void Logger::setVerbosity(LoggerVerbosity lv) { m_lv = lv; }
LoggerVerbosity Logger::getVerbosity() { return m_lv; }
void Logger::countdown() {
if (m_printCountdown < 0.0)
m_printCountdown = m_streamPrintPeriod;
if (m_printCountdown < 0.0) m_printCountdown = m_streamPrintPeriod;
m_printCountdown -= m_timeSample;
}
......@@ -51,15 +51,13 @@ void Logger::sendMsg(std::string msg, MsgType type, const std::string &file,
}
bool Logger::setTimeSample(double t) {
if (t <= 0.0)
return false;
if (t <= 0.0) return false;
m_timeSample = t;
return true;
}
bool Logger::setStreamPrintPeriod(double s) {
if (s <= 0.0)
return false;
if (s <= 0.0) return false;
m_streamPrintPeriod = s;
return true;
}
......@@ -79,9 +77,9 @@ bool Logger::checkStreamPeriod(const std::string &lineId) {
counter -= m_timeSample;
if (counter > 0.0) {
return false;
} else // otherwise reset counter and print
} else // otherwise reset counter and print
counter = m_streamPrintPeriod;
return true;
}
} // namespace dynamicgraph
} // namespace dynamicgraph
......@@ -13,21 +13,21 @@
namespace dynamicgraph {
RealTimeLogger::RealTimeLogger(const std::size_t &bufferSize)
: buffer_(bufferSize, NULL), frontIdx_(0), backIdx_(0), oss_(NULL),
: buffer_(bufferSize, NULL),
frontIdx_(0),
backIdx_(0),
oss_(NULL),
nbDiscarded_(0) {
for (std::size_t i = 0; i < buffer_.size(); ++i)
buffer_[i] = new Data;
for (std::size_t i = 0; i < buffer_.size(); ++i) buffer_[i] = new Data;
}
RealTimeLogger::~RealTimeLogger() {
// Check that we are not spinning...
for (std::size_t i = 0; i < buffer_.size(); ++i)
delete buffer_[i];
for (std::size_t i = 0; i < buffer_.size(); ++i) delete buffer_[i];
}
bool RealTimeLogger::spinOnce() {
if (empty())
return false;
if (empty()) return false;
Data *data = buffer_[frontIdx_];
frontIdx_ = (frontIdx_ + 1) % buffer_.size();
std::string str = data->buf.str();
......@@ -67,8 +67,11 @@ struct RealTimeLogger::thread {
boost::thread t_;
explicit thread(RealTimeLogger *logger)
: requestShutdown_(false), threadPolicy_(SCHED_OTHER), threadPriority_(0),
changedThreadParams(true), t_(&thread::spin, this, logger) {}
: requestShutdown_(false),
threadPolicy_(SCHED_OTHER),
threadPriority_(0),
changedThreadParams(true),
t_(&thread::spin, this, logger) {}
// void setThreadPolicy(int policy) {
// threadPolicy_ = policy;
......@@ -107,8 +110,7 @@ struct RealTimeLogger::thread {
// Do a pause
if (!logger->spinOnce())
boost::this_thread::sleep(boost::posix_time::milliseconds(1000));
if (changedThreadParams)
changeThreadParams();
if (changedThreadParams) changeThreadParams();
}
}
};
......@@ -125,11 +127,10 @@ RealTimeLogger &RealTimeLogger::instance() {
}
void RealTimeLogger::destroy() {
if (instance_ == NULL)
return;
if (instance_ == NULL) return;
thread_->requestShutdown_ = true;
thread_->t_.join();
delete instance_;
delete thread_;
}
} // namespace dynamicgraph
} // namespace dynamicgraph
......@@ -14,9 +14,10 @@
#include <dynamic-graph/pool.h>
/*! System includes */
#include <sstream>
#include <stdlib.h>
#include <sstream>
using namespace std;
using namespace dynamicgraph;
using dynamicgraph::command::Command;
......@@ -68,7 +69,7 @@ void Entity::signalRegistration(const SignalArray<int> &signals) {
const string &signame(buffer);
SignalMap::iterator sigkey = signalMap.find(signame);
if (sigkey != signalMap.end()) // key does exist
if (sigkey != signalMap.end()) // key does exist
{
dgERRORF("Key %s already exist in the signalMap.", signame.c_str());
if (sigkey->second != &sig) {
......@@ -87,7 +88,7 @@ void Entity::signalRegistration(const SignalArray<int> &signals) {
void Entity::signalDeregistration(const std::string &signame) {
SignalMap::iterator sigkey = signalMap.find(signame);
if (sigkey == signalMap.end()) // key does not exist
if (sigkey == signalMap.end()) // key does not exist
{
dgERRORF("Key %s does not exist in the signalMap.", signame.c_str());
throw ExceptionFactory(ExceptionFactory::UNREFERED_SIGNAL,
......@@ -105,14 +106,14 @@ std::string Entity::getDocString() const {
return docString;
}
#define __DG_ENTITY_GET_SIGNAL__(ITER_TYPE) \
SignalMap::ITER_TYPE sigkey = signalMap.find(signame); \
if (sigkey == signalMap.end()) /* key does NOT exist */ \
{ \
throw ExceptionFactory(ExceptionFactory::UNREFERED_SIGNAL, \
"The requested signal is not registered", ": %s", \
signame.c_str()); \
} \
#define __DG_ENTITY_GET_SIGNAL__(ITER_TYPE) \
SignalMap::ITER_TYPE sigkey = signalMap.find(signame); \
if (sigkey == signalMap.end()) /* key does NOT exist */ \
{ \
throw ExceptionFactory(ExceptionFactory::UNREFERED_SIGNAL, \
"The requested signal is not registered", ": %s", \
signame.c_str()); \
} \
return *(sigkey->second);
bool Entity::hasSignal(const string &signame) const {
......@@ -185,9 +186,9 @@ const std::string &Entity::getCommandList() const {
/// Add a command to Entity
void Entity::addCommand(const std::string &inName, Command *command) {
if (commandMap.count(inName) != 0) {
DG_THROW ExceptionFactory(ExceptionFactory::OBJECT_CONFLICT,
"Command " + inName +
" already registered in Entity.");
DG_THROW ExceptionFactory(
ExceptionFactory::OBJECT_CONFLICT,
"Command " + inName + " already registered in Entity.");
}
std::pair<const std::string, Command *> item(inName, command);
commandMap.insert(item);
......@@ -200,14 +201,14 @@ std::map<const std::string, Command *> Entity::getNewStyleCommandMap() {
Command *Entity::getNewStyleCommand(const std::string &commandName) {
if (commandMap.count(commandName) != 1) {
DG_THROW ExceptionFactory(ExceptionFactory::UNREFERED_FUNCTION,
"Command <" + commandName +
"> is not registered in Entity.");
DG_THROW ExceptionFactory(
ExceptionFactory::UNREFERED_FUNCTION,
"Command <" + commandName + "> is not registered in Entity.");
}
return commandMap[commandName];
}
void Entity::sendMsg(const std::string &msg, MsgType t,
const std::string &lineId) {
logger_.sendMsg("[" + name + "]" + msg, t, lineId);
logger_.stream(t, lineId) << "[" << name << "]" << msg << '\n';
}
......@@ -2,10 +2,11 @@
// JRL, CNRS/AIST.
//
#include "dynamic-graph/factory.h"
#include <boost/foreach.hpp>
#include "dynamic-graph/debug.h"
#include "dynamic-graph/factory.h"
using namespace std;
using namespace dynamicgraph;
......@@ -39,9 +40,10 @@ void FactoryStorage::registerEntity(const std::string &entname,
"Another entity class already defined with the same name. ",
"(while adding entity class <%s> inside the factory).",
entname.c_str());
dgERRORF("Another entity class already defined with the same name. "
"(while adding entity class <%s> inside the factory).",
entname.c_str());
dgERRORF(
"Another entity class already defined with the same name. "
"(while adding entity class <%s> inside the factory).",
entname.c_str());
} else {
if (!ent) {
// FIXME: we should have a better error code for that.
......@@ -118,4 +120,4 @@ EntityRegisterer::~EntityRegisterer() {
// The global factory.
FactoryStorage *FactoryStorage::instance_ = NULL;
} // end of namespace dynamicgraph.
} // end of namespace dynamicgraph.
......@@ -13,13 +13,15 @@
/* --- DYNAMIC-GRAPH --- */
#include "dynamic-graph/pool.h"
#include "dynamic-graph/debug.h"
#include "dynamic-graph/entity.h"
#include <list>
#include <sstream>
#include <string>
#include <typeinfo>
#include "dynamic-graph/debug.h"
#include "dynamic-graph/entity.h"
using namespace dynamicgraph;
/* --------------------------------------------------------------------- */
......@@ -57,7 +59,7 @@ PoolStorage::~PoolStorage() {
/* --------------------------------------------------------------------- */
void PoolStorage::registerEntity(const std::string &entname, Entity *ent) {
Entities::iterator entkey = entityMap.find(entname);
if (entkey != entityMap.end()) // key does exist
if (entkey != entityMap.end()) // key does exist
{
throw ExceptionFactory(
ExceptionFactory::OBJECT_CONFLICT,
......@@ -72,7 +74,7 @@ void PoolStorage::registerEntity(const std::string &entname, Entity *ent) {
void PoolStorage::deregisterEntity(const std::string &entname) {
Entities::iterator entkey = entityMap.find(entname);
if (entkey == entityMap.end()) // key doesnot exist
if (entkey == entityMap.end()) // key doesnot exist
{
throw ExceptionFactory(ExceptionFactory::OBJECT_CONFLICT,
"Entity not defined yet. ", "Entity name is <%s>.",
......@@ -207,7 +209,7 @@ static bool objectNameParser(std::istringstream &cmdparse, std::string &objName,
char buffer[SIZE];
cmdparse >> std::ws;
cmdparse.getline(buffer, SIZE, '.');
if (!cmdparse.good()) // The callback is not an object method
if (!cmdparse.good()) // The callback is not an object method
return false;
objName = buffer;
......
......@@ -2,10 +2,11 @@
// JRL, CNRS/AIST.
//
#include <cstring>
#include <dynamic-graph/debug.h>
#include <dynamic-graph/exception-abstract.h>
#include <cstring>
namespace dynamicgraph {
const std::string ExceptionAbstract::EXCEPTION_NAME = "Abstract";
......@@ -23,8 +24,7 @@ const std::string &ExceptionAbstract::getStringMessage() const {
int ExceptionAbstract::getCode() const { return this->code; }
ExceptionAbstract::Param &ExceptionAbstract::Param::initCopy(const Param &p) {
if (&p == this)
return *this;
if (&p == this) return *this;
dgDEBUGIN(25);
if (p.pointersSet) {
......@@ -53,9 +53,9 @@ std::ostream &operator<<(std::ostream &os, const ExceptionAbstract &error) {
if (error.p.set)
os << "Thrown from " << error.p.file << ": " << error.p.function << " (#"
<< error.p.line << ")" << std::endl;
#endif // DYNAMICGRAPH_EXCEPTION_PASSING_PARAM
#endif // DYNAMICGRAPH_EXCEPTION_PASSING_PARAM
return os;
}
} // end of namespace dynamicgraph.
} // end of namespace dynamicgraph.
......@@ -7,11 +7,12 @@
*
*/
#include <cstdio>
#include <dynamic-graph/debug.h>
#include <dynamic-graph/exception-factory.h>
#include <stdarg.h>
#include <cstdio>
using namespace dynamicgraph;
/* --------------------------------------------------------------------- */
......
......@@ -7,10 +7,11 @@
*
*/
#include <cstdio>
#include <dynamic-graph/exception-signal.h>
#include <stdarg.h>
#include <cstdio>
using namespace dynamicgraph;
/* --------------------------------------------------------------------- */
......
......@@ -7,10 +7,11 @@
*
*/
#include <cstdio>
#include <dynamic-graph/exception-traces.h>
#include <stdarg.h>
#include <cstdio>
using namespace dynamicgraph;
/* --------------------------------------------------------------------- */
/* --- CLASS ----------------------------------------------------------- */
......
......@@ -2,17 +2,24 @@
* 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>
#include <dynamic-graph/process-list.hh>
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) {}
: 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,
......@@ -129,8 +136,7 @@ void System::readProcStat() {
// If we did not initialize
if (!init_) {
// Count the number of CPU.
if (lcpunb > cpuNb_)
cpuNb_ = lcpunb;
if (lcpunb > cpuNb_) cpuNb_ = lcpunb;
} else
// Otherwise process the line.
ProcessCPULine(lcpunb, anISSLine);
......
......@@ -12,15 +12,15 @@
/* --------------------------------------------------------------------- */
/* DG */
#include <boost/bind.hpp>
#include <iomanip>
#include <dynamic-graph/all-commands.h>
#include <dynamic-graph/debug.h>
#include <dynamic-graph/factory.h>
#include <dynamic-graph/pool.h>
#include <dynamic-graph/tracer-real-time.h>
#include <boost/bind.hpp>
#include <iomanip>
using namespace std;
using namespace dynamicgraph;
......@@ -103,7 +103,7 @@ TracerRealTime::TracerRealTime(const std::string &n)
addCommand("setBufferSize",
makeDirectSetter(*this, &bufferSize,
docDirectSetter("bufferSize", "int")));
} // using namespace command
} // using namespace command
dgDEBUGOUT(15);
}
......@@ -136,7 +136,7 @@ void TracerRealTime::openFile(const SignalBase<int> &sig,
dgDEBUG(5) << "Creating Outstringstream" << endl;
// std::stringstream * newbuffer = new std::stringstream ();
OutStringStream *newbuffer = new OutStringStream(); // std::stringstream ();
OutStringStream *newbuffer = new OutStringStream(); // std::stringstream ();
newbuffer->resize(bufferSize);
newbuffer->givenname = givenname;
files.push_back(newbuffer);
......@@ -187,7 +187,7 @@ void TracerRealTime::trace() {
"");
}
// std::stringstream & file = * dynamic_cast< stringstream* >(os);
OutStringStream *file = dynamic_cast<OutStringStream *>(os); // segfault
OutStringStream *file = dynamic_cast<OutStringStream *>(os); // segfault
if (NULL == file) {
DG_THROW ExceptionTraces(ExceptionTraces::NOT_OPEN,
"The buffer is not open", "");
......@@ -269,8 +269,7 @@ void TracerRealTime::display(std::ostream &os) const {
dgDEBUG(35) << "Next" << endl;
const OutStringStream *file = dynamic_cast<OutStringStream *>(*iterFile);
os << " -> " << (*iter)->getName();
if (file->givenname.length())
os << " (in " << file->givenname << ")";
if (file->givenname.length()) os << " (in " << file->givenname << ")";
os << "\t";
if (file) {
const std::streamsize PRECISION = os.precision();
......@@ -292,8 +291,7 @@ void TracerRealTime::display(std::ostream &os) const {
<< (((double)SIZE + 0.0) / (1 << dec)) << unit << "/"
<< std::setprecision(2) << (((double)MSIZE + 0.0) / (1 << dec)) << unit
<< "]\t";
if (file->full)
os << "(FULL)";
if (file->full) os << "(FULL)";
os.precision(PRECISION);
}
os << endl;
......
......@@ -12,7 +12,6 @@
/* --------------------------------------------------------------------- */
/* DG */
#include <boost/bind.hpp>
#include <dynamic-graph/all-commands.h>
#include <dynamic-graph/debug.h>
#include <dynamic-graph/factory.h>
......@@ -20,6 +19,8 @@
#include <dynamic-graph/tracer.h>
#include <dynamic-graph/value.h>
#include <boost/bind.hpp>
using namespace std;
using namespace dynamicgraph;
using namespace dynamicgraph::command;
......@@ -31,9 +32,18 @@ DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN(Tracer, "Tracer");
/* --------------------------------------------------------------------- */
Tracer::Tracer(const std::string n)
: Entity(n), toTraceSignals(), traceStyle(TRACE_STYLE_DEFAULT),
frequency(1), basename(), suffix(".dat"), rootdir(), namesSet(false),
files(), names(), play(false), timeStart(0),
: Entity(n),
toTraceSignals(),
traceStyle(TRACE_STYLE_DEFAULT),
frequency(1),
basename(),
suffix(".dat"),
rootdir(),
namesSet(false),
files(),
names(),
play(false),
timeStart(0),
triger(boost::bind(&Tracer::recordTrigger, this, _1, _2), sotNOSIGNAL,
"Tracer(" + n + ")::triger") {
signalRegistration(triger);
......@@ -62,8 +72,9 @@ Tracer::Tracer(const std::string n)
doc = docCommandVoid0("Close all the open files.");
addCommand("close", makeCommandVoid0(*this, &Tracer::closeFiles, doc));
doc = docCommandVoid0("If necessary, dump "
"(can be done automatically for some traces type).");
doc = docCommandVoid0(
"If necessary, dump "
"(can be done automatically for some traces type).");
addCommand("dump", makeCommandVoid0(*this, &Tracer::trace, doc));
doc = docCommandVoid0("Start the tracing process.");
......@@ -78,7 +89,7 @@ Tracer::Tracer(const std::string n)
addCommand("setTimeStart",
makeDirectSetter(*this, &timeStart,
docDirectSetter("timeStart", "int")));
} // using namespace command
} // using namespace command
}
/* --------------------------------------------------------------------- */
......@@ -89,8 +100,7 @@ void Tracer::addSignalToTrace(const SignalBase<int> &sig,
const string &filename) {
dgDEBUGIN(15);
// openFile may throw so it should be called first.
if (namesSet)
openFile(sig, filename);
if (namesSet) openFile(sig, filename);
toTraceSignals.push_back(&sig);
dgDEBUGF(15, "%p", &sig);
names.push_back(filename);
......@@ -129,14 +139,12 @@ void Tracer::openFiles(const std::string &rootdir_,
dgDEBUGIN(15);
std::basic_string<char>::size_type n = rootdir_.length();
rootdir = rootdir_;
if ((0 < n) & ('/' != rootdir[n - 1]))
rootdir += '/';
if ((0 < n) & ('/' != rootdir[n - 1])) rootdir += '/';
basename = basename_;
suffix = suffix_;
if (files.size())
closeFiles();
if (files.size()) closeFiles();
SignalList::const_iterator iter = toTraceSignals.begin();
NameList::const_iterator iterName = names.begin();
......
......@@ -5,14 +5,16 @@
* See LICENSE file
*
*/
#include "dynamic-graph/command-bind.h"
#include "dynamic-graph/factory.h"
#include "dynamic-graph/pool.h"
#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>
......@@ -32,7 +34,7 @@ using namespace dynamicgraph::command;
namespace dynamicgraph {
class CustomEntity : public Entity {
public:
public:
static const std::string CLASS_NAME;
bool test_zero_arg_;
bool test_one_arg_;
......@@ -127,7 +129,7 @@ public:
}
};
DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN(CustomEntity, "CustomEntity");
} // namespace dynamicgraph
} // namespace dynamicgraph
BOOST_AUTO_TEST_CASE(command_test) {
dynamicgraph::CustomEntity *ptr_entity =
......@@ -142,8 +144,7 @@ BOOST_AUTO_TEST_CASE(command_test) {
std::map<const std::string, Command *>::iterator it_map;
it_map = aCommandMap.find("0_arg");
if (it_map == aCommandMap.end())
BOOST_CHECK(false);
if (it_map == aCommandMap.end()) BOOST_CHECK(false);
it_map->second->execute();
BOOST_CHECK(entity.test_zero_arg_);
......@@ -158,8 +159,7 @@ BOOST_AUTO_TEST_CASE(command_test) {
for (unsigned int i = 0; i < 4; i++) {
it_map = aCommandMap.find(vec_fname[i]);
if (it_map == aCommandMap.end())
BOOST_CHECK(false);
if (it_map == aCommandMap.end()) BOOST_CHECK(false);
values.push_back(aValue);
it_map->second->setParameterValues(values);
it_map->second->execute();
......
......@@ -5,6 +5,7 @@
#include <dynamic-graph/exception-factory.h>
#include <dynamic-graph/factory.h>
#include <dynamic-graph/pool.h>
#include <sstream>
#define BOOST_TEST_MODULE customEntity
......
This diff is collapsed.
This diff is collapsed.
......@@ -4,8 +4,6 @@
*
*/
#include <iostream>
#include <dynamic-graph/command.h>
#include <dynamic-graph/entity.h>
#include <dynamic-graph/exception-factory.h>
......@@ -14,6 +12,8 @@
#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
......@@ -53,7 +53,7 @@ struct MyEntity : public dynamicgraph::Entity {
}
};
DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN(MyEntity, "MyEntity");
} // namespace dynamicgraph
} // namespace dynamicgraph
BOOST_AUTO_TEST_CASE(test_tracer) {
using namespace dynamicgraph;
......
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.