Skip to content

Commit 496023c

Browse files
author
Olivier Stasse
authored
Merge pull request #37 from jmirabel/master
Add some logs to geometric_simu.
2 parents e57af6b + 01b9009 commit 496023c

File tree

3 files changed

+69
-10
lines changed

3 files changed

+69
-10
lines changed

include/dynamic_graph_bridge/sot_loader.hh

Lines changed: 5 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -34,6 +34,7 @@
3434
#include <boost/program_options.hpp>
3535
#include <boost/foreach.hpp>
3636
#include <boost/format.hpp>
37+
#include <boost/thread/thread.hpp>
3738

3839
// ROS includes
3940
#include "ros/ros.h"
@@ -82,6 +83,9 @@ protected:
8283
std::string robot_desc_string_;
8384

8485

86+
/// The thread running dynamic graph
87+
boost::thread thread_;
88+
8589
// \brief Start control loop
8690
virtual void startControlLoop();
8791

@@ -92,7 +96,7 @@ protected:
9296

9397
public:
9498
SotLoader();
95-
~SotLoader() {};
99+
~SotLoader();
96100

97101
// \brief Create a thread for ROS and start the control loop.
98102
void initializeRosNode(int argc, char *argv[]);

src/geometric_simu.cpp

Lines changed: 2 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -32,8 +32,6 @@ int main(int argc, char *argv[])
3232

3333
aSotLoader.initializeRosNode(argc,argv);
3434

35-
while(true){
36-
usleep(5000);
37-
}
38-
35+
ros::spin();
36+
return 0;
3937
}

src/sot_loader.cpp

Lines changed: 62 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -26,7 +26,6 @@
2626
// POSIX.1-2001
2727
#include <dlfcn.h>
2828

29-
#include <boost/thread/thread.hpp>
3029
#include <boost/thread/condition.hpp>
3130

3231
boost::condition_variable cond;
@@ -35,20 +34,71 @@ using namespace std;
3534
using namespace dynamicgraph::sot;
3635
namespace po = boost::program_options;
3736

37+
struct DataToLog
38+
{
39+
const std::size_t N;
40+
std::size_t idx;
41+
42+
std::vector<double> times;
43+
44+
DataToLog (std::size_t N_)
45+
: N (N_)
46+
, idx (0)
47+
, times (N, 0)
48+
{}
49+
50+
void record (const double t)
51+
{
52+
times[idx] = t;
53+
++idx;
54+
if (idx == N) idx = 0;
55+
}
56+
57+
void save (const char* prefix)
58+
{
59+
std::ostringstream oss;
60+
oss << prefix << "-times.log";
61+
62+
std::ofstream aof(oss.str().c_str());
63+
if (aof.is_open()) {
64+
for (std::size_t k = 0; k < N; ++k) {
65+
aof << times[ (idx + k) % N ] << '\n';
66+
}
67+
}
68+
aof.close();
69+
}
70+
};
3871

3972

4073
void workThreadLoader(SotLoader *aSotLoader)
4174
{
75+
unsigned period = 1000; // micro seconds
76+
if (ros::param::has("/sot_controller/dt")) {
77+
double periodd;
78+
ros::param::get("/sot_controller/dt", periodd);
79+
period = unsigned(1e6 * periodd);
80+
}
81+
DataToLog dataToLog (5000);
82+
4283
while(aSotLoader->isDynamicGraphStopped())
4384
{
44-
usleep(5000);
85+
usleep(period);
4586
}
4687

88+
struct timeval start, stop;
4789
while(!aSotLoader->isDynamicGraphStopped())
4890
{
91+
gettimeofday(&start,0);
4992
aSotLoader->oneIteration();
50-
usleep(5000);
93+
gettimeofday(&stop,0);
94+
95+
unsigned long long dt = 1000000 * (stop.tv_sec - start.tv_sec) + (stop.tv_usec - start.tv_usec);
96+
dataToLog.record ((double)dt * 1e-6);
97+
if (period > dt) {
98+
usleep(period - (unsigned)dt);
99+
}
51100
}
101+
dataToLog.save ("/tmp/geometric_simu");
52102
cond.notify_all();
53103
ros::waitForShutdown();
54104
}
@@ -62,15 +112,22 @@ SotLoader::SotLoader():
62112
torques_ (),
63113
baseAtt_ (),
64114
accelerometer_ (3),
65-
gyrometer_ (3)
115+
gyrometer_ (3),
116+
thread_ ()
66117
{
67118
readSotVectorStateParam();
68119
initPublication();
69120
}
70121

122+
SotLoader::~SotLoader()
123+
{
124+
dynamic_graph_stopped_ = true;
125+
thread_.join();
126+
}
127+
71128
void SotLoader::startControlLoop()
72129
{
73-
boost::thread thr(workThreadLoader, this);
130+
thread_ = boost::thread (workThreadLoader, this);
74131
}
75132

76133
void SotLoader::initializeRosNode(int argc, char *argv[])

0 commit comments

Comments
 (0)