Commit cf8b569e authored by Olivier Stasse's avatar Olivier Stasse
Browse files

[clang-format] Apply Google style.

parent af2e0f25
/* Copyright 2018, CNRS
* Author: O. Stasse
*
*
BSD 2-Clause License
Copyright (c) 2017, Stack Of Tasks development team
......@@ -32,33 +32,37 @@ OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
/**
\mainpage
\section sec_intro Introduction
This package provides a link between the Stack-Of-Tasks framework and roscontrol.
It assumes that a robot has a
<a href="https://github.com/ros-controls/ros_control/search?q=hardware_interface&unscoped_q=hardware_interface">hardware_interface</a> provided by roscontrol.
It also assumes that the robot has a Device class specialized for the robot.
For instance in the passive walker yoyoman available <a href="https://github.com/Gepetto/yoyoman01_robot">here</a>, this device is
This package provides a link between the Stack-Of-Tasks framework and
roscontrol. It assumes that a robot has a <a
href="https://github.com/ros-controls/ros_control/search?q=hardware_interface&unscoped_q=hardware_interface">hardware_interface</a>
provided by roscontrol. It also assumes that the robot has a Device class
specialized for the robot. For instance in the passive walker yoyoman available
<a href="https://github.com/Gepetto/yoyoman01_robot">here</a>, this device is
provided in the directory sot-yoyoman01.
In general a wrapper is needed to make this Device class usable in the robot itself, or in a simulator (Gazebo, or OpenHRP).
When an abstract interface is provided, which is the case with ros-control, a yaml file is sufficient to do the wrapping.
For two working examples you can have a look to the <a href="https://github.com/stack-of-tasks/talos_metapkg_ros_control_sot">package for the Talos robot</a>,
or the directory
<a href="https://github.com/Gepetto/yoyoman01_robot/tree/master/yoyoman_metapkg_ros_control_sot">yoyoman_metapkg_ros_control_sot</a>
In general a wrapper is needed to make this Device class usable in the robot
itself, or in a simulator (Gazebo, or OpenHRP). When an abstract interface is
provided, which is the case with ros-control, a yaml file is sufficient to do
the wrapping. For two working examples you can have a look to the <a
href="https://github.com/stack-of-tasks/talos_metapkg_ros_control_sot">package
for the Talos robot</a>, or the directory <a
href="https://github.com/Gepetto/yoyoman01_robot/tree/master/yoyoman_metapkg_ros_control_sot">yoyoman_metapkg_ros_control_sot</a>
for the yoyoman passive walker.
\section sec_install Install
\subsection subsec_install_bin Binary installation
For binary installation we rely on the robotpkg project which is providing an apt repository.
Please follow the instructions given <a href="http://robotpkg.openrobots.org/debian.html">here</a> to access this apt repository.
Once this is done, installing roscontrol_sot can be done with:
For binary installation we rely on the robotpkg project which is providing an
apt repository. Please follow the instructions given <a
href="http://robotpkg.openrobots.org/debian.html">here</a> to access this apt
repository. Once this is done, installing roscontrol_sot can be done with:
\code{.sh}
sudo apt-get install robotpkg-roscontrol-sot
\endcode
WARNING: the roscontrol-sot provided by robotpkg is compiled over the PAL-robotics fork of roscontrol
and not the ros packages roscontrol.
WARNING: the roscontrol-sot provided by robotpkg is compiled over the
PAL-robotics fork of roscontrol and not the ros packages roscontrol.
\subsection subsec_install_src Source Installation
......@@ -66,11 +70,12 @@ First you must install dynamic-graph-bridge-v3:
\code{.sh}
sudo apt-get install robotpkg-dynamic-graph-bridge-v3
\endcode
This should be done after following the previous step to access the robotpkg apt repository.
This should be done after following the previous step to access the robotpkg apt
repository.
Then you can clone the repository:
\code{.sh}
git clone https://github.com/stack-of-tasks/roscontrol_sot.git
git clone https://github.com/stack-of-tasks/roscontrol_sot.git
\endcode
You can either compile it with:
......@@ -106,8 +111,8 @@ functions accessing the real hardware or a simulator to read the sensors
and write the command respectively.
On the other hand the UpdateCmd() functions implements a the computation of
a control law.
The roscontrol framework is providing an abstract interface to the hardware interface
and the controllers.
The roscontrol framework is providing an abstract interface to the hardware
interface and the controllers.
The previous code is then rewritten the following way:
\code{.c}
......@@ -121,7 +126,7 @@ void * RosControlRealTimeLoop(void *argument)
The interaction between the controller manager and the robot hardware is done
through a hardware interface exposing double which are either publishing sensor
information or control values.
information or control values.
The abstract interface is allowing to have a normalized way to interact with
the robot hardware.
......@@ -134,8 +139,8 @@ maps of doubles are used.
The maps provide sensor information and the value of the control computed by
the SoT.
The size of double vector and the map key are computed automatically depending on the number of sensors and actuators provided
by the robot_hardware_interface.
The size of double vector and the map key are computed automatically depending
on the number of sensors and actuators provided by the robot_hardware_interface.
\section section_yamlfile Setting the YAML file.
......@@ -145,12 +150,11 @@ All the parameters regarding the SoT inside roscontrol are in the namespace
/sot_controller
\endcode
\subsection subsection_setsot Setting the SoT dynamic library which contains the robot device.
\subsection subsection_setsot Setting the SoT dynamic library which contains the
robot device.
In order to control a robot, an appropriate YAML file need to be written such as:
\code{.sh}
sot_robot_param.yaml
\endcode
In order to control a robot, an appropriate YAML file need to be written such
as: \code{.sh} sot_robot_param.yaml \endcode
If its SoT device entity is located inside the following dynamic library:
\code{.sh}
......@@ -163,40 +167,41 @@ Then inside the file sot_robot_param.yaml
\endcode
\subsection subsec_spec_act_state Specifying the actuated state vector
To map the joints from the URDF model to the SoT actuated state vector, it is simply done by giving the ordered list of the joints name in the URDF model.
For instance:
\code{.sh}
joint_names: [ leg_left_1_joint, leg_left_2_joint, leg_left_3_joint, leg_left_4_joint, leg_left_5_joint, leg_left_6_joint,
leg_right_1_joint, leg_right_2_joint, leg_right_3_joint, leg_right_4_joint, leg_right_5_joint, leg_right_6_joint,
torso_1_joint,torso_2_joint,head_1_joint, head_2_joint,
arm_left_1_joint, arm_left_2_joint, arm_left_3_joint, arm_left_4_joint, arm_left_5_joint, arm_left_6_joint, arm_left_7_joint, gripper_left_joint,
arm_right_1_joint, arm_right_2_joint, arm_right_3_joint, arm_right_4_joint, arm_right_5_joint, arm_right_6_joint, arm_right_7_joint, gripper_right_joint
]
To map the joints from the URDF model to the SoT actuated state vector, it is
simply done by giving the ordered list of the joints name in the URDF model. For
instance: \code{.sh} joint_names: [ leg_left_1_joint, leg_left_2_joint,
leg_left_3_joint, leg_left_4_joint, leg_left_5_joint, leg_left_6_joint,
leg_right_1_joint, leg_right_2_joint, leg_right_3_joint, leg_right_4_joint,
leg_right_5_joint, leg_right_6_joint, torso_1_joint,torso_2_joint,head_1_joint,
head_2_joint, arm_left_1_joint, arm_left_2_joint, arm_left_3_joint,
arm_left_4_joint, arm_left_5_joint, arm_left_6_joint, arm_left_7_joint,
gripper_left_joint, arm_right_1_joint, arm_right_2_joint, arm_right_3_joint,
arm_right_4_joint, arm_right_5_joint, arm_right_6_joint, arm_right_7_joint,
gripper_right_joint
]
\endcode
\subsection subsec_spec_map Specifying the map between the ros control data and the sot device entity.
\subsection subsec_spec_map Specifying the map between the ros control data and
the sot device entity.
This ros-control plugin connect to the robot (or simulated robot) by requesting the available ressources such as:
<ol>
<li> motor-angles: Reading of the motor position</li>
<li> joint-angles: Reading of the joint position</li>
<li> velocities: Reading/estimation of the joint velocities</li>
<li> torques: Reading/estimation of the joint torques</li>
<li> cmd-position: Command for the joint positions</li>
<li> cmd-effort: Command for the joint torques</li>
This ros-control plugin connect to the robot (or simulated robot) by requesting
the available ressources such as: <ol> <li> motor-angles: Reading of the motor
position</li> <li> joint-angles: Reading of the joint position</li> <li>
velocities: Reading/estimation of the joint velocities</li> <li> torques:
Reading/estimation of the joint torques</li> <li> cmd-position: Command for the
joint positions</li> <li> cmd-effort: Command for the joint torques</li>
</ol>
For instance the map for a robot which maps __cmd-position__ to __joints__ and __cmd-effort__ to __effort__ in its device will have
have the following lines in its param file:
\code{.sh}
map_rc_to_sot_device: { motor-angles: motor-angles ,
For instance the map for a robot which maps __cmd-position__ to __joints__ and
__cmd-effort__ to __effort__ in its device will have have the following lines in
its param file: \code{.sh} map_rc_to_sot_device: { motor-angles: motor-angles ,
joint-angles: joint-angles, velocities: velocities,
torques: torques, cmd-joints: joints, cmd-effort: effort }
\endcode
\subsection spec_cont_mode Specifying the control mode
Robots with __ros-control__ can be controlled either in position (POSITION) or in torque (EFFORT)
using the __control_mode__ variable:
Robots with __ros-control__ can be controlled either in position (POSITION) or
in torque (EFFORT) using the __control_mode__ variable:
\code{.sh}
control_mode: EFFORT
......
/*
/*
Olivier Stasse CNRS,
31/07/2012
Object to log the low-level informations of a robot.
......@@ -9,210 +9,189 @@
#include <fstream>
#include <iomanip>
using namespace std;
using namespace rc_sot_system;
DataToLog::DataToLog()
{
}
DataToLog::DataToLog() {}
void DataToLog::init(ProfileLog &aProfileLog)
{
void DataToLog::init(ProfileLog& aProfileLog) {
profileLog_ = aProfileLog;
motor_angle.resize(aProfileLog.nbDofs*aProfileLog.length);
joint_angle.resize(aProfileLog.nbDofs*aProfileLog.length);
velocities.resize(aProfileLog.nbDofs*aProfileLog.length);
torques.resize(aProfileLog.nbDofs*aProfileLog.length);
motor_currents.resize(aProfileLog.nbDofs*aProfileLog.length);
orientation.resize(4*aProfileLog.length);
accelerometer.resize(3*aProfileLog.length);
gyrometer.resize(3*aProfileLog.length);
force_sensors.resize(aProfileLog.nbForceSensors*6*aProfileLog.length);
temperatures.resize(aProfileLog.nbDofs*aProfileLog.length);
controls.resize(aProfileLog.nbDofs*aProfileLog.length);
motor_angle.resize(aProfileLog.nbDofs * aProfileLog.length);
joint_angle.resize(aProfileLog.nbDofs * aProfileLog.length);
velocities.resize(aProfileLog.nbDofs * aProfileLog.length);
torques.resize(aProfileLog.nbDofs * aProfileLog.length);
motor_currents.resize(aProfileLog.nbDofs * aProfileLog.length);
orientation.resize(4 * aProfileLog.length);
accelerometer.resize(3 * aProfileLog.length);
gyrometer.resize(3 * aProfileLog.length);
force_sensors.resize(aProfileLog.nbForceSensors * 6 * aProfileLog.length);
temperatures.resize(aProfileLog.nbDofs * aProfileLog.length);
controls.resize(aProfileLog.nbDofs * aProfileLog.length);
timestamp.resize(aProfileLog.length);
duration.resize(aProfileLog.length);
for(unsigned int i=0;i<aProfileLog.nbDofs*aProfileLog.length;i++)
{ motor_angle[i] = joint_angle[i] =
velocities[i] = 0.0; }
for (unsigned int i = 0; i < aProfileLog.nbDofs * aProfileLog.length; i++) {
motor_angle[i] = joint_angle[i] = velocities[i] = 0.0;
}
}
Log::Log() : lref_(0), lrefts_(0) {}
Log::Log():
lref_(0),
lrefts_(0)
{
}
void Log::init(ProfileLog &aProfileLog)
{
void Log::init(ProfileLog& aProfileLog) {
profileLog_ = aProfileLog;
lref_ =0;
lrefts_=0;
lref_ = 0;
lrefts_ = 0;
StoredData_.init(aProfileLog);
struct timeval current;
gettimeofday(&current,0);
gettimeofday(&current, 0);
timeorigin_ = (double)current.tv_sec + 0.000001 * ((double)current.tv_usec);
}
void Log::record(DataToLog &aDataToLog)
{
if ( (aDataToLog.motor_angle.size()!=profileLog_.nbDofs) ||
(aDataToLog.velocities.size()!=profileLog_.nbDofs))
void Log::record(DataToLog& aDataToLog) {
if ((aDataToLog.motor_angle.size() != profileLog_.nbDofs) ||
(aDataToLog.velocities.size() != profileLog_.nbDofs))
return;
for(unsigned int JointID=0;JointID<aDataToLog.nbDofs();JointID++)
{
if (aDataToLog.motor_angle.size()>JointID)
StoredData_.motor_angle[JointID+lref_]= aDataToLog.motor_angle[JointID];
if (aDataToLog.joint_angle.size()>JointID)
StoredData_.joint_angle[JointID+lref_]= aDataToLog.joint_angle[JointID];
if (aDataToLog.velocities.size()>JointID)
StoredData_.velocities[JointID+lref_]= aDataToLog.velocities[JointID];
if (aDataToLog.torques.size()>JointID)
StoredData_.torques[JointID+lref_]= aDataToLog.torques[JointID];
if (aDataToLog.motor_currents.size()>JointID)
StoredData_.motor_currents[JointID+lref_]= aDataToLog.motor_currents[JointID];
if (aDataToLog.temperatures.size()>JointID)
StoredData_.temperatures[JointID+lref_]= aDataToLog.temperatures[JointID];
if (aDataToLog.controls.size()>JointID)
StoredData_.controls[JointID+lref_]= aDataToLog.controls[JointID];
for (unsigned int JointID = 0; JointID < aDataToLog.nbDofs(); JointID++) {
if (aDataToLog.motor_angle.size() > JointID)
StoredData_.motor_angle[JointID + lref_] =
aDataToLog.motor_angle[JointID];
if (aDataToLog.joint_angle.size() > JointID)
StoredData_.joint_angle[JointID + lref_] =
aDataToLog.joint_angle[JointID];
if (aDataToLog.velocities.size() > JointID)
StoredData_.velocities[JointID + lref_] = aDataToLog.velocities[JointID];
if (aDataToLog.torques.size() > JointID)
StoredData_.torques[JointID + lref_] = aDataToLog.torques[JointID];
if (aDataToLog.motor_currents.size() > JointID)
StoredData_.motor_currents[JointID + lref_] =
aDataToLog.motor_currents[JointID];
if (aDataToLog.temperatures.size() > JointID)
StoredData_.temperatures[JointID + lref_] =
aDataToLog.temperatures[JointID];
if (aDataToLog.controls.size() > JointID)
StoredData_.controls[JointID + lref_] = aDataToLog.controls[JointID];
}
for (unsigned int axis = 0; axis < 3; axis++) {
StoredData_.accelerometer[lrefts_ * 3 + axis] =
aDataToLog.accelerometer[axis];
StoredData_.gyrometer[lrefts_ * 3 + axis] = aDataToLog.gyrometer[axis];
}
std::size_t width_pad = 6 * profileLog_.nbForceSensors;
for (unsigned int fsID = 0; fsID < profileLog_.nbForceSensors; fsID++) {
for (unsigned int axis = 0; axis < 6; axis++) {
StoredData_.force_sensors[lrefts_ * width_pad + fsID * 6 + axis] =
aDataToLog.force_sensors[fsID * 6 + axis];
}
for(unsigned int axis=0;axis<3;axis++)
{
StoredData_.accelerometer[lrefts_*3+axis] = aDataToLog.accelerometer[axis];
StoredData_.gyrometer[lrefts_*3+axis] = aDataToLog.gyrometer[axis];
}
std::size_t width_pad= 6 * profileLog_.nbForceSensors;
for(unsigned int fsID=0;fsID<profileLog_.nbForceSensors;fsID++)
{
for(unsigned int axis=0;axis<6;axis++)
{
StoredData_.force_sensors[lrefts_*width_pad+fsID*6+axis] =
aDataToLog.force_sensors[fsID*6+axis];
}
}
}
struct timeval current;
gettimeofday(&current,0);
gettimeofday(&current, 0);
StoredData_.timestamp[lrefts_] =
((double)current.tv_sec + 0.000001 * (double)current.tv_usec) - timeorigin_;
StoredData_.timestamp[lrefts_] =
((double)current.tv_sec + 0.000001 * (double)current.tv_usec) -
timeorigin_;
StoredData_.duration[lrefts_] = time_stop_it_ - time_start_it_;
lref_ += profileLog_.nbDofs;
lrefts_ ++;
if (lref_>=profileLog_.nbDofs*profileLog_.length)
{
lref_=0;
lrefts_=0;
}
lrefts_++;
if (lref_ >= profileLog_.nbDofs * profileLog_.length) {
lref_ = 0;
lrefts_ = 0;
}
}
void Log::start_it()
{
void Log::start_it() {
struct timeval current;
gettimeofday(&current,0);
gettimeofday(&current, 0);
time_start_it_ =
((double)current.tv_sec + 0.000001 * (double)current.tv_usec) - timeorigin_;
time_start_it_ =
((double)current.tv_sec + 0.000001 * (double)current.tv_usec) -
timeorigin_;
}
void Log::stop_it()
{
void Log::stop_it() {
struct timeval current;
gettimeofday(&current,0);
gettimeofday(&current, 0);
time_stop_it_ =
((double)current.tv_sec + 0.000001 * (double)current.tv_usec) - timeorigin_;
time_stop_it_ =
((double)current.tv_sec + 0.000001 * (double)current.tv_usec) -
timeorigin_;
}
void Log::save(std::string &fileName)
{
void Log::save(std::string& fileName) {
std::string suffix("-mastate.log");
saveVector(fileName,suffix,StoredData_.motor_angle, profileLog_.nbDofs);
suffix="-jastate.log";
saveVector(fileName,suffix,StoredData_.joint_angle, profileLog_.nbDofs);
saveVector(fileName, suffix, StoredData_.motor_angle, profileLog_.nbDofs);
suffix = "-jastate.log";
saveVector(fileName, suffix, StoredData_.joint_angle, profileLog_.nbDofs);
suffix = "-vstate.log";
saveVector(fileName,suffix,StoredData_.velocities, profileLog_.nbDofs);
saveVector(fileName, suffix, StoredData_.velocities, profileLog_.nbDofs);
suffix = "-torques.log";
saveVector(fileName,suffix,StoredData_.torques, profileLog_.nbDofs);
saveVector(fileName, suffix, StoredData_.torques, profileLog_.nbDofs);
suffix = "-motor-currents.log";
saveVector(fileName,suffix,StoredData_.motor_currents, profileLog_.nbDofs);
saveVector(fileName, suffix, StoredData_.motor_currents, profileLog_.nbDofs);
suffix = "-accelero.log";
saveVector(fileName,suffix,StoredData_.accelerometer, 3);
saveVector(fileName, suffix, StoredData_.accelerometer, 3);
suffix = "-gyro.log";
saveVector(fileName,suffix,StoredData_.gyrometer, 3);
saveVector(fileName, suffix, StoredData_.gyrometer, 3);
ostringstream oss;
oss << "-forceSensors.log";
suffix = oss.str();
saveVector(fileName,suffix,StoredData_.force_sensors, 6 * profileLog_.nbForceSensors);
saveVector(fileName, suffix, StoredData_.force_sensors,
6 * profileLog_.nbForceSensors);
suffix = "-temperatures.log";
saveVector(fileName,suffix,StoredData_.temperatures, profileLog_.nbDofs);
saveVector(fileName, suffix, StoredData_.temperatures, profileLog_.nbDofs);
suffix = "-controls.log";
saveVector(fileName,suffix,StoredData_.controls, profileLog_.nbDofs);
saveVector(fileName, suffix, StoredData_.controls, profileLog_.nbDofs);
suffix = "-duration.log";
saveVector(fileName,suffix,StoredData_.duration, 1);
saveVector(fileName, suffix, StoredData_.duration, 1);
}
inline void writeHeaderToBinaryBuffer (ofstream& of,
const std::size_t& nVector,
const std::size_t& vectorSize)
{
of.write ((const char*)(&nVector) , sizeof(std::size_t));
of.write ((const char*)(&vectorSize), sizeof(std::size_t));
inline void writeHeaderToBinaryBuffer(ofstream& of, const std::size_t& nVector,
const std::size_t& vectorSize) {
of.write((const char*)(&nVector), sizeof(std::size_t));
of.write((const char*)(&vectorSize), sizeof(std::size_t));
}
inline void writeToBinaryFile (ofstream& of,
const double& t, const double& dt,
const std::vector<double>& data, const std::size_t& idx, const std::size_t& size)
{
of.write ((const char*)&t , sizeof(double));
of.write ((const char*)&dt , sizeof(double));
of.write ((const char*)(&data[idx]), size*(sizeof(double)));
inline void writeToBinaryFile(ofstream& of, const double& t, const double& dt,
const std::vector<double>& data,
const std::size_t& idx, const std::size_t& size) {
of.write((const char*)&t, sizeof(double));
of.write((const char*)&dt, sizeof(double));
of.write((const char*)(&data[idx]), size * (sizeof(double)));
}
void Log::saveVector(std::string &fileName,std::string &suffix,
const std::vector<double> &avector,
std::size_t size)
{
void Log::saveVector(std::string& fileName, std::string& suffix,
const std::vector<double>& avector, std::size_t size) {
ostringstream oss;
oss << fileName;
oss << suffix.c_str();
std::string actualFileName= oss.str();
std::string actualFileName = oss.str();
ofstream aof(actualFileName.c_str(), std::ios::binary | std::ios::trunc);
std::size_t idx = 0;
double dt;
if (aof.is_open())
{
writeHeaderToBinaryBuffer (aof, profileLog_.length, size+2);
for(unsigned long int i=0;i<profileLog_.length;i++)
{
// Compute and save dt
if (i==0)
dt = StoredData_.timestamp[i] - StoredData_.timestamp
[profileLog_.length-1];
else
dt = StoredData_.timestamp[i] - StoredData_.timestamp[i-1];
writeToBinaryFile (aof, StoredData_.timestamp[i], dt, avector, idx, size);
idx += size;
}
aof.close();
ROS_INFO_STREAM("Wrote log file " << actualFileName);
if (aof.is_open()) {
writeHeaderToBinaryBuffer(aof, profileLog_.length, size + 2);
for (unsigned long int i = 0; i < profileLog_.length; i++) {
// Compute and save dt
if (i == 0)
dt = StoredData_.timestamp[i] -
StoredData_.timestamp[profileLog_.length - 1];
else
dt = StoredData_.timestamp[i] - StoredData_.timestamp[i - 1];
writeToBinaryFile(aof, StoredData_.timestamp[i], dt, avector, idx, size);
idx += size;
}
aof.close();
ROS_INFO_STREAM("Wrote log file " << actualFileName);
}
}
/*
/*
Olivier Stasse CNRS,
19/12/2016
Object to control the low-level part of TALOS.
......@@ -12,95 +12,87 @@
namespace rc_sot_system {
struct ProfileLog
{
std::size_t nbDofs;
std::size_t nbForceSensors;
std::size_t length;
};
struct DataToLog
{
// Measured angle values at the motor side.
std::vector<double> motor_angle;
// Measured angle at the joint side.
std::vector<double> joint_angle;
// Measured or computed velocities.
std::vector<double> velocities;
// Measured torques.
std::vector<double> torques;
// Reconstructed orientation (from internal IMU).
std::vector<double> orientation;
// Measured linear acceleration
std::vector<double> accelerometer;
// Measured angular velocities
std::vector<double> gyrometer;
// Measured force sensors
std::vector<double> force_sensors;
// Measured motor currents
std::vector<double> motor_currents;
// Measured temperatures
std::vector<double> temperatures;
// Control
std::vector<double> controls;
// Timestamp
std::vector<double> timestamp;
// Duration
std::vector<double> duration;
ProfileLog profileLog_;
DataToLog();
void init(ProfileLog &aProfileLog);
std::size_t nbDofs() { return profileLog_.nbDofs;}
std::size_t nbForceSensors() { return profileLog_.nbForceSensors;}
std::size_t length() { return profileLog_.length;}
};
class Log
{
private:
/// Profile Log
ProfileLog profileLog_;
// Current position in the circular buffer for angles.
long unsigned int lref_;
// Current position int the circular buffer for timestamp
// lref_ = lrefts_ * nbDofs_
long unsigned int lrefts_;
// Circular buffer for all the data.
DataToLog StoredData_;
double timeorigin_;
double time_start_it_;
double time_stop_it_;
// Save one vector of information.
void saveVector(std::string &filename,
std::string &suffix,
const std::vector<double> &avector,
std::size_t);
public:
Log();
void init(ProfileLog &aProfileLog);
void record(DataToLog &aDataToLog);