Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #include <iostream>
00038 #include <string>
00039 #include <tide/ebml_element.h>
00040 #include <tide/file_cluster.h>
00041 #include <tide/segment.h>
00042 #include <tide/simple_block.h>
00043 #include <tide/tide_impl.h>
00044 #include <tide/tracks.h>
00045 #include <tide/track_entry.h>
00046 #include <pcl/point_cloud.h>
00047 #include <pcl/point_types.h>
00048 #include <pcl/io/openni_grabber.h>
00049 #include <pcl/PCLPointCloud2.h>
00050 #include <pcl/conversions.h>
00051 #include <pcl/visualization/cloud_viewer.h>
00052 #include <pcl/console/parse.h>
00053 #include <pcl/common/time.h>
00054 #include "boost.h"
00055
00056 namespace bpt = boost::posix_time;
00057
00058
00059 class Recorder
00060 {
00061 public:
00062 Recorder(std::string const& filename, std::string const& title)
00063 : filename_(filename), title_(title),
00064 stream_(filename, std::ios::in|std::ios::out|std::ios::trunc),
00065 count_(0)
00066 {
00067 }
00068
00069 void Callback(pcl::PointCloud<pcl::PointXYZ>::ConstPtr const& cloud)
00070 {
00071
00072
00073
00074
00075 bpt::ptime blk_start(bpt::microsec_clock::local_time());
00076 bpt::time_duration blk_offset = blk_start - cltr_start_;
00077 tide::BlockElement::Ptr block(new tide::SimpleBlock(1,
00078 blk_offset.total_microseconds() / 10000));
00079
00080 pcl::PCLPointCloud2 blob;
00081 pcl::toPCLPointCloud2(*cloud, blob);
00082 tide::Block::FramePtr frame_ptr(new tide::Block::Frame(blob.data.begin(),
00083 blob.data.end()));
00084 block->push_back(frame_ptr);
00085 cluster_->push_back(block);
00086
00087 if (++count_ == 30)
00088 {
00089 double now = pcl::getTime();
00090 std::cerr << "Average framerate: " <<
00091 static_cast<double>(count_) / (now - last_) << "Hz\n";
00092 count_ = 0;
00093 last_ = now;
00094 }
00095
00096
00097
00098
00099
00100 bpt::time_duration cluster_len(
00101 bpt::microsec_clock::local_time() - cltr_start_);
00102 if (cluster_len.total_seconds() >= 1)
00103 {
00104
00105 cluster_->finalise(stream_);
00106
00107 cltr_start_ = bpt::microsec_clock::local_time();
00108 bpt::time_duration cltr_offset = cltr_start_ - seg_start_;
00109 cluster_.reset(new tide::FileCluster(
00110 cltr_offset.total_microseconds() / 10000));
00111 cluster_->write(stream_);
00112 }
00113 }
00114
00115 int Run()
00116 {
00117
00118
00119 tide::EBMLElement ebml_el;
00120 ebml_el.write(stream_);
00121
00122
00123
00124
00125 tide::Segment segment;
00126 segment.write(stream_);
00127
00128
00129
00130 boost::uuids::random_generator gen;
00131 boost::uuids::uuid uuid = gen();
00132 std::vector<char> uuid_data(uuid.size());
00133 std::copy(uuid.begin(), uuid.end(), uuid_data.begin());
00134 segment.info.uid(uuid_data);
00135
00136 segment.info.filename(filename_);
00137
00138
00139
00140
00141 segment.info.timecode_scale(10000000);
00142
00143
00144
00145 bpt::ptime basis(boost::gregorian::date(2001, 1, 1));
00146 seg_start_ = boost::posix_time::microsec_clock::local_time();
00147 bpt::time_duration td = seg_start_ - basis;
00148 segment.info.date(td.total_microseconds() * 1000);
00149
00150 segment.info.title(title_);
00151
00152 segment.info.muxing_app("libtide-0.1");
00153 segment.info.writing_app("pcl_video");
00154
00155
00156 tide::Tracks tracks;
00157
00158
00159
00160 tide::TrackEntry::Ptr track(new tide::TrackEntry(1, 1, "pointcloud2"));
00161 track->name("3D video");
00162 track->codec_name("pcl::PCLPointCloud2");
00163
00164
00165 segment.index.insert(std::make_pair(tracks.id(),
00166 segment.to_segment_offset(stream_.tellp())));
00167
00168 tracks.insert(track);
00169 tracks.write(stream_);
00170
00171
00172
00173
00174
00175
00176
00177
00178
00179
00180
00181
00182
00183
00184
00185
00186 segment.index.insert(std::make_pair(tide::ids::Cluster,
00187 segment.to_segment_offset(stream_.tellp())));
00188
00189
00190
00191 pcl::Grabber* interface(new pcl::OpenNIGrabber());
00192 boost::function<void (const pcl::PointCloud<pcl::PointXYZ>::ConstPtr&)> f(
00193 boost::bind(&Recorder::Callback, this, _1));
00194 interface->registerCallback(f);
00195
00196 cltr_start_ = bpt::microsec_clock::local_time();
00197 bpt::time_duration cltr_offset = cltr_start_ - seg_start_;
00198 cluster_.reset(new tide::FileCluster(
00199 cltr_offset.total_microseconds() / 10000));
00200 cluster_->write(stream_);
00201 last_ = pcl::getTime();
00202 interface->start();
00203
00204 std::cout << "Recording frames. Press any key to stop.\n";
00205 getchar();
00206
00207 interface->stop();
00208
00209 if (cluster_)
00210 {
00211 cluster_->finalise(stream_);
00212 }
00213
00214
00215
00216 segment.finalise(stream_);
00217
00218 stream_.close();
00219
00220 return 0;
00221 }
00222
00223 private:
00224 std::string filename_;
00225 std::string title_;
00226 std::fstream stream_;
00227 tide::FileCluster::Ptr cluster_;
00228 bpt::ptime seg_start_;
00229 bpt::ptime cltr_start_;
00230 unsigned int count_;
00231 double last_;
00232 };
00233
00234
00235 class Player
00236 {
00237 public:
00238 Player(std::string const& filename)
00239 : filename_(filename), viewer_("PCL Video Player: " + filename)
00240 {
00241
00242
00243 }
00244
00245 int Run()
00246 {
00247
00248
00249 std::ifstream stream(filename_, std::ios::in);
00250 tide::ids::ReadResult id = tide::ids::read(stream);
00251 if (id.first != tide::ids::EBML)
00252 {
00253 std::cerr << "File does not begin with an EBML header.\n";
00254 return 1;
00255 }
00256 tide::EBMLElement ebml_el;
00257 ebml_el.read(stream);
00258 if (ebml_el.doc_type() != tide::TideDocType)
00259 {
00260 std::cerr << "Specified EBML file is not a Tide document.\n";
00261 return 1;
00262 }
00263 if (ebml_el.read_version() > tide::TideEBMLVersion)
00264 {
00265 std::cerr << "This Tide document requires read version " <<
00266 ebml_el.read_version() << ".\n";
00267 return 1;
00268 }
00269 if (ebml_el.doc_read_version() > tide::TideVersionMajor)
00270 {
00271 std::cerr << "This Tide document requires doc read version " <<
00272 ebml_el.read_version() << ".\n";
00273 return 1;
00274 }
00275 std::cerr << "Found EBML header\n";
00276
00277
00278
00279
00280
00281 id = tide::ids::read(stream);
00282 if (id.first != tide::ids::Segment)
00283 {
00284 std::cerr << "Segment element not found\n";
00285 return 1;
00286 }
00287 tide::Segment segment;
00288 segment.read(stream);
00289
00290
00291 bpt::ptime basis(boost::gregorian::date(2001, 1, 1));
00292 bpt::time_duration sd(bpt::microseconds(segment.info.date() / 1000));
00293 bpt::ptime seg_start(basis + sd);
00294
00295
00296
00297
00298
00299
00300
00301 std::streampos tracks_pos(segment.index.find(tide::ids::Tracks)->second);
00302 stream.seekg(segment.to_stream_offset(tracks_pos));
00303
00304
00305 id = tide::ids::read(stream);
00306 if (id.first != tide::ids::Tracks)
00307 {
00308 std::cerr << "Tracks element not at indicated position.\n";
00309 return 1;
00310 }
00311
00312 tide::Tracks tracks;
00313 tracks.read(stream);
00314
00315 if (tracks.empty())
00316 {
00317 std::cerr << "No tracks found.\n";
00318 return 1;
00319 }
00320
00321
00322 if (tracks[1]->codec_id() != "pointcloud2")
00323 {
00324 std::cerr << "Track #1 has wrong codec type " <<
00325 tracks[1]->codec_id() << '\n';
00326 return 1;
00327 }
00328
00329 bpt::ptime pb_start(bpt::microsec_clock::local_time());
00330
00331
00332
00333
00334
00335
00336
00337 for (tide::Segment::FileBlockIterator block(segment.blocks_begin_file(stream));
00338 block != segment.blocks_end_file(stream); ++block)
00339 {
00340 bpt::time_duration blk_offset(bpt::microseconds((
00341 (block.cluster()->timecode() + block->timecode()) *
00342 segment.info.timecode_scale() / 1000)));
00343 bpt::time_duration played_time(bpt::microsec_clock::local_time() -
00344 pb_start);
00345
00346 if (played_time > blk_offset)
00347 {
00348 std::cerr << "Skipping block at " << blk_offset <<
00349 " because current playback time is " << played_time << '\n';
00350 continue;
00351 }
00352
00353
00354
00355
00356
00357 tide::BlockElement::FramePtr frame_data(*block->begin());
00358
00359 pcl::PCLPointCloud2 blob;
00360 blob.height = 480;
00361 blob.width = 640;
00362 pcl::PCLPointField ptype;
00363 ptype.name = "x";
00364 ptype.offset = 0;
00365 ptype.datatype = 7;
00366 ptype.count = 1;
00367 blob.fields.push_back(ptype);
00368 ptype.name = "y";
00369 ptype.offset = 4;
00370 ptype.datatype = 7;
00371 ptype.count = 1;
00372 blob.fields.push_back(ptype);
00373 ptype.name = "z";
00374 ptype.offset = 8;
00375 ptype.datatype = 7;
00376 ptype.count = 1;
00377 blob.fields.push_back(ptype);
00378 blob.is_bigendian = false;
00379 blob.point_step = 16;
00380 blob.row_step = 10240;
00381 blob.is_dense = false;
00382 blob.data.assign(frame_data->begin(), frame_data->end());
00383 pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>);
00384 pcl::fromPCLPointCloud2(blob, *cloud);
00385
00386
00387 played_time = bpt::microsec_clock::local_time() - pb_start;
00388 bpt::time_duration sleep_time(blk_offset - played_time);
00389 std::cerr << "Will sleep " << sleep_time << " until displaying block\n";
00390 boost::this_thread::sleep(sleep_time);
00391 viewer_.showCloud(cloud);
00392
00393
00394
00395
00396
00397
00398
00399 }
00400
00401 return 0;
00402 }
00403
00404 private:
00405 std::string filename_;
00406
00407 pcl::visualization::CloudViewer viewer_;
00408 };
00409
00410
00411 int main(int argc, char** argv)
00412 {
00413 std::string filename;
00414 if (pcl::console::parse_argument(argc, argv, "-f", filename) < 0)
00415 {
00416 std::cerr << "Usage: " << argv[0] << " -f filename [-p] [-t title]\n";
00417 return 1;
00418 }
00419 std::string title("PCL 3D video");
00420 pcl::console::parse_argument(argc, argv, "-t", title);
00421 if (pcl::console::find_switch(argc, argv, "-p"))
00422 {
00423 Player player(filename);
00424 return player.Run();
00425 }
00426 else
00427 {
00428 Recorder recorder(filename, title);
00429 return recorder.Run();
00430 }
00431 }
00432