forked from gazebosim/gazebo-classic
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathgz_log.cc
1121 lines (940 loc) · 29.9 KB
/
gz_log.cc
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
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
/*
* Copyright (C) 2012 Open Source Robotics Foundation
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
*/
#include <boost/algorithm/string.hpp>
#include <boost/date_time/posix_time/posix_time.hpp>
#include <boost/date_time/posix_time/posix_time_io.hpp>
#include <boost/iostreams/filter/bzip2.hpp>
#include <boost/iostreams/filter/zlib.hpp>
#include <boost/iostreams/filtering_stream.hpp>
#include <boost/iostreams/copy.hpp>
#include <ignition/math/Pose3.hh>
#include <ignition/math/Vector3.hh>
#include <gazebo/util/util.hh>
#include "gz_log.hh"
sdf::ElementPtr g_stateSdf;
using namespace gazebo;
/////////////////////////////////////////////////
FilterBase::FilterBase(bool _xmlOutput, const std::string &_stamp)
: xmlOutput(_xmlOutput), stamp(_stamp)
{
}
/////////////////////////////////////////////////
std::ostringstream &FilterBase::Out(std::ostringstream &_stream,
const gazebo::physics::State &_state)
{
if (!this->xmlOutput && !this->stamp.empty())
{
std::ios_base::fmtflags flags = _stream.flags();
_stream.setf(std::ios::fixed);
if (this->stamp == "sim")
_stream << _state.GetSimTime().Double() << " ";
else if (this->stamp == "real")
_stream << _state.GetRealTime().Double() << " ";
else if (this->stamp == "wall")
_stream << _state.GetWallTime().Double() << " ";
else if (this->stamp == "iterations")
_stream << _state.GetIterations() << " ";
_stream.setf(flags);
}
return _stream;
}
/////////////////////////////////////////////////
std::string FilterBase::FilterPose(const ignition::math::Pose3d &_pose,
const std::string &_xmlName,
std::string _filter,
const gazebo::physics::State &_state)
{
std::ostringstream result;
std::string xmlPrefix, xmlSuffix;
// Remove brackets, if they exist
boost::erase_all(_filter, "[");
boost::erase_all(_filter, "]");
// Output XML tags if required.
if (this->xmlOutput)
{
xmlPrefix = std::string("<") + _xmlName + ">";
xmlSuffix = std::string("</") + _xmlName + ">";
}
// Get the euler angles.
ignition::math::Vector3d rpy = _pose.Rot().Euler();
// If the filter is empty, then output the whole pose.
if (!_filter.empty())
{
// Get the list of pose elements from the filter
std::list<std::string> elements;
boost::split(elements, _filter, boost::is_any_of(","));
if (elements.empty() && !_filter.empty())
elements.push_back(_filter);
// Iterate over the list of pose elements.
for (std::list<std::string>::iterator elemIter =
elements.begin(); elemIter != elements.end();
++elemIter)
{
switch ((*elemIter)[0])
{
case 'X':
case 'x':
this->Out(result, _state) << std::fixed
<< _pose.Pos().X() << " ";
break;
case 'Y':
case 'y':
this->Out(result, _state) << std::fixed
<< _pose.Pos().Y() << " ";
break;
case 'Z':
case 'z':
this->Out(result, _state) << std::fixed
<< _pose.Pos().Z() << " ";
break;
case 'R':
case 'r':
this->Out(result, _state) << std::fixed << rpy.X() << " ";
break;
case 'P':
case 'p':
this->Out(result, _state) << std::fixed << rpy.Y() << " ";
break;
case 'A':
case 'a':
this->Out(result, _state) << std::fixed << rpy.Z() << " ";
break;
default:
std::cerr << "Invalid pose value[" << *elemIter << "]\n";
break;
}
}
result << std::endl;
}
else
{
// No filter, so output the whole pose.
if (!xmlPrefix.empty())
{
result << std::fixed << xmlPrefix << _pose
<< xmlSuffix << std::endl;
}
else
this->Out(result, _state) << _pose << std::endl;
}
return result.str();
}
/////////////////////////////////////////////////
JointFilter::JointFilter(bool _xmlOutput, const std::string &_stamp)
: FilterBase(_xmlOutput, _stamp)
{
}
/////////////////////////////////////////////////
void JointFilter::Init(const std::string &_filter)
{
this->parts.clear();
if (!_filter.empty())
{
boost::split(this->parts, _filter, boost::is_any_of("."));
if (this->parts.empty())
this->parts.push_back(_filter);
}
}
/////////////////////////////////////////////////
std::string JointFilter::FilterParts(gazebo::physics::JointState &_state,
std::list<std::string>::iterator _partIter)
{
std::ostringstream result;
std::string part = *_partIter;
// Remove brackets, if they exist
boost::erase_all(part, "[");
boost::erase_all(part, "]");
// If the filter is empty, then output all the angles.
if (!part.empty())
{
// Get the list of axis elements from the filter
std::list<std::string> elements;
boost::split(elements, part, boost::is_any_of(","));
if (elements.empty() && !part.empty())
elements.push_back(part);
// Iterate over the list of axis elements.
for (std::list<std::string>::iterator elemIter =
elements.begin(); elemIter != elements.end();
++elemIter)
{
try
{
unsigned int axis =
boost::lexical_cast<unsigned int>(*elemIter);
if (axis >= _state.GetAngleCount())
continue;
auto angle = _state.Position(axis);
if (this->xmlOutput)
{
result << "<angle axis='" << *elemIter << "'>"
<< std::fixed << angle << "</angle>\n";
}
else
this->Out(result, _state) << std::fixed << angle << " ";
}
catch(...)
{
std::cerr << "Invalid axis value[" << *elemIter << "]\n";
}
}
}
return result.str();
}
/////////////////////////////////////////////////
std::string JointFilter::Filter(gazebo::physics::ModelState &_state)
{
std::ostringstream result;
gazebo::physics::JointState_M states;
std::list<std::string>::iterator partIter;
/// Get an iterator to the list of the command line parts.
partIter = this->parts.begin();
// The first element in the filter must be a link name or a star.
std::string regexStr = *partIter;
boost::replace_all(regexStr, "*", ".*");
boost::regex regex(regexStr);
states = _state.GetJointStates(regex);
++partIter;
// Filter all the link states that were found.
for (gazebo::physics::JointState_M::iterator iter =
states.begin(); iter != states.end(); ++iter)
{
// Filter the elements of the joint (angle).
// If no filter parts were specified,
// then output the whole joint state.
if (partIter != this->parts.end())
{
if (this->xmlOutput)
result << "<joint name='" << iter->first << "'>\n";
result << this->FilterParts(iter->second, partIter);
if (this->xmlOutput)
result << "</joint>\n";
}
else
{
if (!this->xmlOutput && iter->second.GetAngleCount() == 1)
result << std::fixed << iter->second.Position(0);
else
result << std::fixed << iter->second;
}
}
return result.str();
}
/////////////////////////////////////////////////
LinkFilter::LinkFilter(bool _xmlOutput, const std::string &_stamp)
: FilterBase(_xmlOutput, _stamp)
{
}
/////////////////////////////////////////////////
void LinkFilter::Init(const std::string &_filter)
{
this->parts.clear();
if (!_filter.empty())
{
boost::split(this->parts, _filter, boost::is_any_of("."));
if (this->parts.empty())
this->parts.push_back(_filter);
}
}
/////////////////////////////////////////////////
std::string LinkFilter::FilterParts(gazebo::physics::LinkState &_state,
std::list<std::string>::iterator _partIter)
{
std::ostringstream result;
std::string part = *_partIter;
std::string elemParts;
++_partIter;
if (_partIter != this->parts.end())
elemParts = *_partIter;
if (part == "pose")
{
result << this->FilterPose(_state.Pose(), part, elemParts, _state);
}
else if (part == "acceleration")
{
result << this->FilterPose(_state.Acceleration(), part,
elemParts, _state);
}
else if (part == "velocity")
{
result << this->FilterPose(_state.Velocity(), part, elemParts,
_state);
}
else if (part == "wrench")
{
result << this->FilterPose(_state.Wrench(), part, elemParts,
_state);
}
return result.str();
}
/////////////////////////////////////////////////
std::string LinkFilter::Filter(gazebo::physics::ModelState &_state)
{
std::ostringstream result;
gazebo::physics::LinkState_M states;
std::list<std::string>::iterator partIter;
/// Get an iterator to the list of the command line parts.
partIter = this->parts.begin();
// The first element in the filter must be a link name or a star.
if (*partIter != "*")
{
std::string regexStr = *partIter;
boost::replace_all(regexStr, "*", ".*");
boost::regex regex(regexStr);
states = _state.GetLinkStates(regex);
}
else
states = _state.GetLinkStates();
++partIter;
// Filter all the link states that were found.
for (gazebo::physics::LinkState_M::iterator iter =
states.begin(); iter != states.end(); ++iter)
{
// Filter the elements of the link (pose, velocity,
// acceleration, wrench). If no filter parts were specified,
// then output the whole link state.
if (partIter != this->parts.end())
{
if (this->xmlOutput)
result << "<link name='" << iter->second.GetName() << "'>\n";
result << this->FilterParts(iter->second, partIter);
if (this->xmlOutput)
result << "</link>\n";
}
else
result << std::fixed << iter->second << std::endl;
}
return result.str();
}
/////////////////////////////////////////////////
ModelFilter::ModelFilter(bool _xmlOutput, const std::string &_stamp)
: FilterBase(_xmlOutput, _stamp)
{
this->linkFilter = NULL;
this->jointFilter = NULL;
}
/////////////////////////////////////////////////
ModelFilter::~ModelFilter()
{
delete this->linkFilter;
delete this->jointFilter;
}
/////////////////////////////////////////////////
void ModelFilter::Init(const std::string &_filter)
{
this->linkFilter = NULL;
this->jointFilter = NULL;
this->parts.clear();
if (_filter.empty())
return;
std::list<std::string> mainParts;
boost::split(mainParts, _filter, boost::is_any_of("/"));
// Create the model filter
if (!mainParts.empty())
{
boost::split(this->parts, mainParts.front(),
boost::is_any_of("."));
if (this->parts.empty() && !mainParts.front().empty())
this->parts.push_back(mainParts.front());
}
if (mainParts.empty())
return;
mainParts.pop_front();
// Create the link filter
if (!mainParts.empty() && !mainParts.front().empty())
{
this->linkFilter = new LinkFilter(this->xmlOutput, this->stamp);
this->linkFilter->Init(mainParts.front());
}
if (mainParts.empty())
return;
mainParts.pop_front();
// Create the joint filter
if (!mainParts.empty())
{
this->jointFilter = new JointFilter(this->xmlOutput,
this->stamp);
this->jointFilter->Init(mainParts.front());
}
}
/////////////////////////////////////////////////
std::string ModelFilter::FilterParts(gazebo::physics::ModelState &_state,
std::list<std::string>::iterator _partIter)
{
std::ostringstream result;
// Currently a model can only have a pose.
if (*_partIter == "pose")
{
// Get the model state pose
ignition::math::Pose3d pose = _state.Pose();
++_partIter;
// Get the elements to filter pose by.
std::string elemParts;
if (_partIter != this->parts.end())
elemParts = *_partIter;
// Output the filtered pose.
result << this->FilterPose(pose, "pose", elemParts, _state);
}
else
std::cerr << "Invalid model state component["
<< *_partIter << "]\n";
return result.str();
}
/////////////////////////////////////////////////
std::string ModelFilter::Filter(gazebo::physics::WorldState &_state)
{
std::ostringstream result;
gazebo::physics::ModelState_M states;
std::list<std::string>::iterator partIter = this->parts.begin();
// The first element in the filter must be a model name or a star.
if (partIter != this->parts.end() && !this->parts.empty() &&
!(*partIter).empty() && (*partIter) != "*")
{
std::string regexStr = *partIter;
boost::replace_all(regexStr, "*", ".*");
boost::regex regex(regexStr);
states = _state.GetModelStates(regex);
}
else
states = _state.GetModelStates();
++partIter;
// Filter all the model states that were found.
for (gazebo::physics::ModelState_M::iterator iter =
states.begin(); iter != states.end(); ++iter)
{
// If no link filter, and no model parts, then output the
// whole model state.
if (!this->linkFilter && !this->jointFilter &&
partIter == this->parts.end())
result << std::fixed << iter->second;
else
{
if (this->xmlOutput)
result << "<model name='" << iter->second.GetName() << "'>\n";
// Filter the pose of the model.
if (partIter != this->parts.end())
result << this->FilterParts(iter->second, partIter);
// Apply link filtering, if a link filter exists.
if (this->linkFilter)
result << this->linkFilter->Filter(iter->second);
// Apply link filtering, if a link filter exists.
if (this->jointFilter)
result << this->jointFilter->Filter(iter->second);
if (this->xmlOutput)
result << "</model>\n";
}
}
return result.str();
}
/////////////////////////////////////////////////
StateFilter::StateFilter(bool _xmlOutput, const std::string &_stamp,
double _hz)
: FilterBase(_xmlOutput, _stamp), filter(_xmlOutput, _stamp),
hz(_hz)
{}
/////////////////////////////////////////////////
void StateFilter::Init(const std::string &_filter)
{
this->filter.Init(_filter);
}
/////////////////////////////////////////////////
std::string StateFilter::Filter(const std::string &_stateString)
{
gazebo::physics::WorldState state;
// Read and parse the state information
g_stateSdf->Clear();
sdf::readString(_stateString, g_stateSdf);
state.Load(g_stateSdf);
std::ostringstream result;
if (this->hz > 0.0 && this->prevTime != gazebo::common::Time::Zero)
{
if ((state.GetSimTime() - this->prevTime).Double() <
1.0 / this->hz)
{
return result.str();
}
}
if (this->xmlOutput)
{
result << "<sdf version='" << SDF_VERSION << "'>\n"
<< "<state world_name='" << state.GetName() << "'>\n"
<< "<sim_time>" << state.GetSimTime() << "</sim_time>\n"
<< "<real_time>" << state.GetRealTime() << "</real_time>\n"
<< "<wall_time>" << state.GetWallTime() << "</wall_time>\n"
<< "<iterations>" << state.GetIterations() << "</iterations>\n";
auto insertions = state.Insertions();
if (insertions.size() > 0)
result << "<insertions>" << std::endl;
for (auto insertion : insertions)
result << insertion << std::endl;
if (insertions.size() > 0)
result << "</insertions>" << std::endl;
auto deletions = state.Deletions();
if (deletions.size() > 0)
result << "<deletions>" << std::endl;
for (auto deletion : deletions)
result << "<name>" << deletion << "</name>" << std::endl;
if (deletions.size() > 0)
result << "</deletions>" << std::endl;
}
result << this->filter.Filter(state);
if (this->xmlOutput)
result << "</state></sdf>\n";
this->prevTime = state.GetSimTime();
return result.str();
}
/////////////////////////////////////////////////
LogCommand::LogCommand()
: Command("log", "Introspects and manipulates Gazebo log files.")
{
// Options that are visible to the user through help.
this->visibleOptions.add_options()
("info,i", "Output information about a log file. "
"Log filename should be specified using the --file option")
("echo,e", "Output the contents of a log file to screen.")
("step,s", "Step through the contents of a log file.")
("record,d", po::value<bool>(),
"Start/stop recording a log file from an active Gazebo server."
"O=stop record, 1=start recording.")
("world-name,w", po::value<std::string>(), "World name, used when "
"starting or stopping recording.")
("raw,r", "Output the data from echo and step without XML formatting."
"Used in conjuction with --echo or --step.")
("stamp", po::value<std::string>(), "Add a timestamp to each line of "
"output. Valid values are (sim,real,wall)")
("hz,z", po::value<double>(), "Filter output to the specified Hz rate."
"Only valid for echo and step commands.")
("file,f", po::value<std::string>(), "Path to a log file.")
("output,o", po::value<std::string>(),
"Output file, valid in conjunction with the filter, raw, hz, and "
"encoding commands. By default, the output file will have the same "
"encoding as the source file. Override with the --encoding option")
("encoding,n", po::value<std::string>(),
"Specify the encoding (txt, zlib, or bz2) for an output file. "
"Valid in conjunction with the output command. See also the "
"--output argument.")
("filter", po::value<std::string>(),
"Filter output. Valid only with the echo, step, and output commands");
}
/////////////////////////////////////////////////
void LogCommand::HelpDetailed()
{
std::cerr <<
"\tIntrospect and manipulate Gazebo log files. The log \n"
"\tcommand can also start and stop data log recording from \n"
"\tan active Gazebo server.\n"
<< std::endl;
}
/////////////////////////////////////////////////
bool LogCommand::TransportRequired()
{
return this->vm.count("record");
}
/////////////////////////////////////////////////
bool LogCommand::RunImpl()
{
std::string filename, filter, stamp, worldName;
double hz = 0;
bool raw = false;
if (this->vm.count("world-name"))
worldName = this->vm["world-name"].as<std::string>();
if (this->TransportRequired())
{
this->node.reset(new transport::Node());
this->node->Init(worldName);
}
// Get filter
filter = this->vm.count("filter") ? this->vm["filter"].as<std::string>() : "";
// Get stamp
stamp = this->vm.count("stamp") ? this->vm["stamp"].as<std::string>() : "";
// Get hz
hz = this->vm.count("hz") ? this->vm["hz"].as<double>() : 0;
raw = this->vm.count("raw");
if (!this->vm.count("record"))
{
// Load the log file
if (this->vm.count("file"))
filename = vm["file"].as<std::string>();
else
{
std::cerr << "No log file specified\n";
std::cerr << "For more info: gz help log\n";
return false;
}
// Load log file from string
if (!this->LoadLogFromFile(filename))
{
return false;
}
}
// Create a state sdf element.
g_stateSdf.reset(new sdf::Element);
sdf::initFile("state.sdf", g_stateSdf);
if (this->vm.count("output"))
{
std::string encoding = this->vm.count("encoding") ?
this->vm["encoding"].as<std::string>() : "";
this->Output(this->vm["output"].as<std::string>(), filter, raw, stamp, hz,
encoding);
}
else if (this->vm.count("echo"))
this->Echo(filter, raw, stamp, hz);
else if (this->vm.count("step"))
this->Step(filter, raw, stamp, hz);
else if (this->vm.count("record"))
this->Record(this->vm["record"].as<bool>());
else if (this->vm.count("info"))
this->Info(filename);
else
this->Help();
return true;
}
/////////////////////////////////////////////////
void LogCommand::Info(const std::string &_filename)
{
gazebo::util::LogPlay *play = gazebo::util::LogPlay::Instance();
// Get the SDF world description from the log file
std::string sdfString;
gazebo::util::LogPlay::Instance()->Step(sdfString);
// Parse the first SDF world description
sdf::ElementPtr sdf(new sdf::Element);
sdf::initFile("root.sdf", sdf);
sdf::readString(sdfString, sdf);
gazebo::physics::WorldState state;
// unsigned int modelCount = 0;
gazebo::common::Time endTime(0, 0);
gazebo::common::Time startTime(0, 0);
if (sdf)
{
// Check for a world element
if (sdf->HasElement("world"))
{
// Get a pointer to the world element
sdf::ElementPtr worldElem = sdf->GetElement("world");
// Check for a model
if (worldElem->HasElement("model"))
{
// Get a pointer to the first model element.
sdf::ElementPtr modelElem = worldElem->GetElement("model");
// Count all the model elements.
while (modelElem)
{
// modelCount++;
modelElem = modelElem->GetNextElement("model");
}
}
// Get the state for the world at the start.
if (worldElem->HasElement("state"))
{
state.Load(worldElem->GetElement("state"));
// Store the start time.
startTime = state.GetWallTime();
}
}
// Get the last chunk for the endTime
if (play->ChunkCount() > 1)
{
std::string stateString;
play->Chunk(play->ChunkCount()-1, stateString);
g_stateSdf->Clear();
sdf::readString(stateString, g_stateSdf);
state.Load(g_stateSdf);
endTime = state.GetWallTime();
}
else
endTime = startTime;
}
// Tell cout how to output boost dates
boost::posix_time::time_facet *facet =
new boost::posix_time::time_facet("%b %d %y %H:%M:%S");
std::cout.imbue(std::locale(std::locale::classic(), facet));
// Compute the duration
gazebo::common::Time deltaTime = endTime - startTime;
// int hours = deltaTime.sec / 3600;
// int minutes = (deltaTime.sec - hours * 3600) / 60;
// int seconds = (deltaTime.sec - hours * 3600 - minutes * 60);
// Output info
std::cout
<< "Log Version: " << play->LogVersion() << "\n"
<< "Gazebo Version: " << play->GazeboVersion() << "\n"
<< "Random Seed: " << play->RandSeed() << "\n"
// << "Start: " << boost::posix_time::from_time_t(startTime.sec)
// << "." << startTime.nsec << "\n"
// << "End: " << boost::posix_time::from_time_t(endTime.sec)
// << "." << endTime.nsec << "\n"
// << "Duration: " << std::setfill('0') << std::setw(2)
// << hours << ":"
// << std::setfill('0')
// << std::setw(2) << minutes << ":"
// << std::setfill('0') << std::setw(2)
// << seconds << "."
// << deltaTime.nsec << "\n"
// << "Steps: " << play->GetChunkCount() << "\n"
<< "Size: " << this->GetFileSizeStr(_filename) << "\n"
<< "Encoding: " << play->Encoding() << "\n"
// << "Model Count: " << modelCount << "\n"
<< "\n";
}
/////////////////////////////////////////////////
void LogCommand::Output(const std::string &_outFilename,
const std::string &_filter, const bool _raw,
const std::string &_stamp, const double _hz, const std::string &_encoding)
{
std::ofstream outFile(_outFilename, std::fstream::out | std::ios::binary);
if (!outFile.is_open())
{
std::cerr << "Unable to open file[" << _outFilename << "] for writing.\n";
return;
}
gazebo::util::LogPlay *play = gazebo::util::LogPlay::Instance();
if (!play->IsOpen())
{
std::cerr << "No source log file specified. Use the -f command line "
<< "argument.\n";
return;
}
std::string stateString, bufferString;
std::string encoding = _encoding.empty() ? play->Encoding() : _encoding;
if (encoding != "txt" && encoding != "zlib" && encoding != "bz2")
{
std::cerr << "Invalid log file encoding[" << encoding << "]. "
<< "Use one of: txt, bz2, zlib.\n";
outFile.close();
return;
}
// Output the header
if (!_raw)
{
std::string header = play->Header();
outFile.write(header.c_str(), header.size());
}
StateFilter filter(!_raw, _stamp, _hz);
filter.Init(_filter);
unsigned int i = 0;
while (play->Step(stateString))
{
if (i == 0 && !_raw)
{
this->OutputWriter(outFile, stateString, _raw, encoding);
}
else
{
bufferString += filter.Filter(stateString);
if (i%1000 == 0 && !bufferString.empty())
{
this->OutputWriter(outFile, bufferString, _raw, encoding);
bufferString.clear();
}
}
++i;
}
if (!bufferString.empty())
this->OutputWriter(outFile, bufferString, _raw, encoding);
if (!_raw)
{
std::string endTag = "</gazebo_log>\n";
outFile.write(endTag.c_str(), endTag.size());
}
outFile.close();
}
/////////////////////////////////////////////////
void LogCommand::Echo(const std::string &_filter, bool _raw,
const std::string &_stamp, double _hz)
{
gazebo::util::LogPlay *play = gazebo::util::LogPlay::Instance();
std::string stateString;
// Output the header
if (!_raw)
std::cout << play->Header() << std::endl;
StateFilter filter(!_raw, _stamp, _hz);
filter.Init(_filter);
unsigned int i = 0;
while (play->Step(stateString))
{
if (i > 0)
stateString = filter.Filter(stateString);
else if (i == 0 && _raw)
stateString.clear();
if (!stateString.empty())
{
if (!_raw)
std::cout << "<chunk encoding='txt'><![CDATA[\n";
std::cout << stateString;
if (!_raw)
std::cout << "]]></chunk>\n";
}
++i;
}
if (!_raw)
std::cout << "</gazebo_log>\n";
}
/////////////////////////////////////////////////
void LogCommand::Step(const std::string &_filter, bool _raw,
const std::string &_stamp, double _hz)
{
std::string stateString;
gazebo::util::LogPlay *play = gazebo::util::LogPlay::Instance();
if (!_raw)
std::cout << play->Header() << std::endl;
char c = '\0';
StateFilter filter(!_raw, _stamp, _hz);
filter.Init(_filter);
unsigned int i = 0;
while (play->Step(stateString) && c != 'q')
{
if (i > 0)
stateString = filter.Filter(stateString);
else if (i == 0 && _raw)
stateString.clear();
// Only wait for user input if there is some state to output.
if (!stateString.empty())
{
if (!_raw)
std::cout << "<chunk encoding='txt'><![CDATA[\n";
std::cout << stateString;
if (!_raw)
std::cout << "]]></chunk>\n";
std::cout << "\n--- Press space to continue, 'q' to quit ---\n";
c = '\0';
// Wait for a space or 'q' key press
while (c != ' ' && c != 'q')
c = this->GetChar();
}
++i;
}
if (!_raw)
std::cout << "</gazebo_log>\n";
}
/////////////////////////////////////////////////
void LogCommand::Record(bool _start)
{
gazebo::transport::PublisherPtr pub =
this->node->Advertise<gazebo::msgs::LogControl>("~/log/control");
if (!pub->WaitForConnection(gazebo::common::Time(10, 0)))
{
std::cerr << "Unable to create a connection to topic ~/log/control.\n";
return;
}
gazebo::msgs::LogControl msg;
_start ? msg.set_start(true) : msg.set_stop(true);
pub->Publish<gazebo::msgs::LogControl>(msg, true);
}
/////////////////////////////////////////////////