-
Notifications
You must be signed in to change notification settings - Fork 31
/
yarpdataplayer.patch
213 lines (206 loc) · 10.1 KB
/
yarpdataplayer.patch
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
diff --git a/src/libYARP_dataplayer/src/yarp/dataplayer/YarpDataplayer.cpp b/src/libYARP_dataplayer/src/yarp/dataplayer/YarpDataplayer.cpp
index 9b5340b0f..2cad85f4e 100644
--- a/src/libYARP_dataplayer/src/yarp/dataplayer/YarpDataplayer.cpp
+++ b/src/libYARP_dataplayer/src/yarp/dataplayer/YarpDataplayer.cpp
@@ -650,10 +650,9 @@ void DataplayerWorker::run()
ret = sendImages(part, frame);
}
else if (strcmp(utilities->partDetails[part].type.c_str(), "Bottle") == 0) {
- ret = sendBottle(part, frame);
- // the above line can be safely replaced with sendGenericData<Bottle>.
- // I kept it for no particular reason, thinking that maybe it could be convenient (later)
- // to process Bottles in a different way.
+ ret = sendGenericData<Bottle>(part, frame);
+ //the above line could be replaced with sendBottle(part, frame) if
+ //specifically different behaviour is required for a bottle.
}
else if (strcmp(utilities->partDetails[part].type.c_str(), "sensor_msgs/LaserScan") == 0) {
ret = sendGenericData<yarp::rosmsg::sensor_msgs::LaserScan>(part, frame);
@@ -721,6 +720,10 @@ int DataplayerWorker::sendBottle(int part, int frame)
Bottle& outBot = the_port->prepare();
outBot = tmp;
+ /* Note: sendBottle differs from sendGenericData as the envelope is a single
+ timestamp, ionstead of the standard yarp::os::Stamp which includes
+ also the sequence number */
+
//propagate timestamp
std::string time = yarp::conf::numeric::to_string(utilities->partDetails[part].timestamp[frame]);
Bottle ts(time);
@@ -1053,43 +1056,48 @@ void DataplayerEngine::stepFromCmd()
/**********************************************************/
void DataplayerEngine::runNormally()
{
- for (int i=0; i < this->numPart; i++){
+ for (int i=0; i < this->numPart; i++) {
+ //get a reference to the part we are interested in
+ PartsData &this_part = this->utilities->partDetails[i];
+
+ //if we have alredy stopped we have nothing to do
+ if(this_part.hasNotified)
+ continue;
+
+ //if this port is not active, keep progressing though the frames without
+ //sending, so if the part activates it is in synch
bool isActive = this->isPartActive[i];
- if ( this->utilities->partDetails[i].currFrame <= this->utilities->partDetails[i].maxFrame ){
- if ( this->virtualTime >= this->utilities->partDetails[i].timestamp[ this->utilities->partDetails[i].currFrame ] ){
- if ( this->initTime > 300 && this->virtualTime < this->utilities->partDetails[i].timestamp[this->utilities->partDetails[i].timestamp.length()-1]){
- this->initTime = 0;
- }
- if (!this->utilities->partDetails[i].hasNotified){
- this->utilities->partDetails[i].worker->sendData(this->utilities->partDetails[i].currFrame, isActive, this->virtualTime );
- this->utilities->partDetails[i].currFrame++;
- }
- }
- } else {
+
+ //send all available frames up to the current virtualTime
+ while (this_part.currFrame <= this_part.maxFrame &&
+ this->virtualTime >= this_part.timestamp[this_part.currFrame]) {
+ this_part.worker->sendData(this_part.currFrame++, isActive, this->virtualTime);
+ }
+
+ //if we have sent all frames perform reset/stop
+ if(this_part.currFrame > this_part.maxFrame) {
if (this->utilities->repeat) {
+ //restart the part
this->initThread();
- this->utilities->partDetails[i].worker->init();
+ this_part.worker->init();
} else {
- if ( !this->utilities->partDetails[i].hasNotified ) {
- if (utilities->verbose){
- yInfo() << "partID:" << i << "has finished";
- }
- this->utilities->partDetails[i].hasNotified = true;
+ //this part has finished
+ if (utilities->verbose) {
+ yInfo() << "partID:" << i << "has finished";
}
+ this_part.hasNotified = true;
+ //perform a check to see if ALL parts have finished
int stopAll = 0;
for (int x=0; x < this->numPart; x++){
- if (this->utilities->partDetails[x].hasNotified){
- stopAll++;
- }
-
- if (stopAll == this->numPart){
- if (utilities->verbose) {
- yInfo() << "All parts have Finished!";
- }
- this->utilities->stopAtEnd();
- this->allPartsStatus = true;
+ stopAll += this->utilities->partDetails[x].hasNotified ? 1 : 0;
+ }
+ if (stopAll == this->numPart) {
+ if (utilities->verbose) {
+ yInfo() << "All parts have Finished!";
}
+ this->utilities->stopAtEnd();
+ this->allPartsStatus = true;
}
}
}
@@ -1097,7 +1105,6 @@ void DataplayerEngine::runNormally()
this->virtualTime += this->diff_seconds() * this->utilities->speed;
this->tick();
- this->initTime++;
}
/**********************************************************/
diff --git a/src/libYARP_dataplayer/src/yarp/dataplayer/YarpDataplayer.h b/src/libYARP_dataplayer/src/yarp/dataplayer/YarpDataplayer.h
index 861b97006..7a23a34e7 100644
--- a/src/libYARP_dataplayer/src/yarp/dataplayer/YarpDataplayer.h
+++ b/src/libYARP_dataplayer/src/yarp/dataplayer/YarpDataplayer.h
@@ -265,7 +265,7 @@ protected:
public:
void SetDataplayerEngine(DataplayerEngine &dataplayerEngine)
{ this->dataplayerEngine = &dataplayerEngine; }
- dataplayer_thread (double _period=0.002);
+ dataplayer_thread (double _period=0.0001);
bool threadInit() override;
void run() override;
diff --git a/src/yarpdataplayer/src/worker.cpp b/src/yarpdataplayer/src/worker.cpp
index e6e91c6e4..6bcd73f16 100644
--- a/src/yarpdataplayer/src/worker.cpp
+++ b/src/yarpdataplayer/src/worker.cpp
@@ -94,43 +94,52 @@ void QEngine::stepFromCmd()
void QEngine::runNormally()
{
for (int i=0; i < this->numPart; i++){
- bool isActive = ((MainWindow*)gui)->getPartActivation(qutils->partDetails[i].name.c_str());
- if ( qutils->partDetails[i].currFrame <= qutils->partDetails[i].maxFrame ){
- if ( this->virtualTime >= qutils->partDetails[i].timestamp[ qutils->partDetails[i].currFrame ] ){
- if ( this->initTime > 300 && this->virtualTime < qutils->partDetails[i].timestamp[qutils->partDetails[i].timestamp.length()-1]){
- emit qutils->updateGuiThread();
- this->initTime = 0;
- }
- if (!qutils->partDetails[i].hasNotified){
- qutils->partDetails[i].worker->sendData(qutils->partDetails[i].currFrame, isActive, this->virtualTime );
- qutils->partDetails[i].currFrame++;
- }
- }
- } else {
+ //get a reference to the part we are interested in
+ yarp::yarpDataplayer::PartsData &this_part = qutils->partDetails[i];
+
+ //if we have alredy stopped we have nothing to do
+ if(this_part.hasNotified)
+ continue;
+
+ //if this port is not active, keep progressing though the frames without
+ //sending, so if the part activates it is in synch
+ bool isActive = ((MainWindow*)gui)->getPartActivation(this_part.name.c_str());
+
+ //send all available frames up to the current virtualTime
+ while (this_part.currFrame <= this_part.maxFrame &&
+ this->virtualTime >= this_part.timestamp[this_part.currFrame]) {
+ this_part.worker->sendData(this_part.currFrame++, isActive, this->virtualTime);
+ }
+
+ //check if to update the Gui
+ if (this->initTime > 300 && this->virtualTime < this_part.timestamp[this_part.timestamp.length() - 1]) {
+ emit qutils->updateGuiThread();
+ this->initTime = 0;
+ }
+
+ //if we have sent all frames perform reset/stop
+ if(this_part.currFrame > this_part.maxFrame) {
if (qutils->repeat) {
this->initThread();
- qutils->partDetails[i].worker->init();
+ this_part.worker->init();
} else {
- if ( !qutils->partDetails[i].hasNotified ) {
- yInfo() << "partID: " << i << " has finished";
- qutils->partDetails[i].hasNotified = true;
- }
+ yInfo() << "partID: " << i << " has finished";
+ this_part.hasNotified = true;
+ //perform a check to see if ALL parts have finished
int stopAll = 0;
for (int x=0; x < this->numPart; x++){
- if (qutils->partDetails[x].hasNotified){
- stopAll++;
- }
+ stopAll += qutils->partDetails[x].hasNotified ? 1 : 0;
+ }
- if (stopAll == this->numPart){
- yInfo() << "All parts have Finished!";
- if (qutils->partDetails[i].currFrame > 1) {
- emit qutils->updateGuiThread();
- }
- qutils->stopAtEnd();
- qutils->resetButton();
- allPartsStatus = true;
+ if (stopAll == this->numPart){
+ yInfo() << "All parts have Finished!";
+ if (this_part.currFrame > 1) {
+ emit qutils->updateGuiThread();
}
+ qutils->stopAtEnd();
+ qutils->resetButton();
+ allPartsStatus = true;
}
}
}