pcl_video.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2011, Geoffrey Biggs
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of the copyright holder(s) nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *
00034  *  \author Geoffrey Biggs
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             // When creating a block, the track number must be specified. Currently,
00072             // all blocks belong to track 1 (because this program only records one
00073             // track). A timecode must also be given.  It is an offset from the
00074             // cluster's timecode measured in the segment's timecode scale.
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             // Here the frame data itself is added to the block
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             // Benchmarking
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             // Check if the cluster has enough data in it.
00096             // What "enough" is depends on your own needs. Generally, a cluster
00097             // shouldn't be allowed to get too big in data size or too long in time, or
00098             // it has an adverse affect on seeking through the file. We will aim for 1
00099             // second of data per cluster.
00100             bpt::time_duration cluster_len(
00101                     bpt::microsec_clock::local_time() - cltr_start_);
00102             if (cluster_len.total_seconds() >= 1)
00103             {
00104                 // Finalise the cluster
00105                 cluster_->finalise(stream_);
00106                 // Create a new cluster
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             // Write the EBML PCLHeader. This specifies that the file is an EBML
00118             // file, and is a Tide document.
00119             tide::EBMLElement ebml_el;
00120             ebml_el.write(stream_);
00121 
00122             // Open a new segment in the file. This will write some initial meta-data
00123             // and place some padding at the start of the file for final meta-data to
00124             // be written after tracks, clusters, etc. have been written.
00125             tide::Segment segment;
00126             segment.write(stream_);
00127             // Set up the segment information so it can be used while writing tracks
00128             // and clusters.
00129             // A UID is not required, but is highly recommended.
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             // The filename can be nice to know.
00136             segment.info.filename(filename_);
00137             // The segment's timecode scale is possibly the most important value in the
00138             // segment meta-data data. Without it, timely playback of frames is not
00139             // possible. It has a sensible default (defined in the Tide specification),
00140             // but here we set it to ten milliseconds for demonstrative purposes.
00141             segment.info.timecode_scale(10000000);
00142             // The segment's date should be set. It is the somewhat-awkward value of
00143             // the number of seconds since the start of the millennium. Boost::Date_Time
00144             // to the rescue!
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             // Let's give the segment an inspirational title.
00150             segment.info.title(title_);
00151             // It sometimes helps to know what created a Tide file.
00152             segment.info.muxing_app("libtide-0.1");
00153             segment.info.writing_app("pcl_video");
00154 
00155             // Set up the tracks meta-data and write it to the file.
00156             tide::Tracks tracks;
00157             // Each track is represented in the Tracks information by a TrackEntry.
00158             // This specifies such things as the track number, the track's UID and the
00159             // codec used.
00160             tide::TrackEntry::Ptr track(new tide::TrackEntry(1, 1, "pointcloud2"));
00161             track->name("3D video");
00162             track->codec_name("pcl::PCLPointCloud2");
00163             // Adding each level 1 element (only the first occurance, in the case of
00164             // clusters) to the index makes opening the file later much faster.
00165             segment.index.insert(std::make_pair(tracks.id(),
00166                         segment.to_segment_offset(stream_.tellp())));
00167             // Now we can write the Tracks element.
00168             tracks.insert(track);
00169             tracks.write(stream_);
00170             // The file is now ready for writing the data. The data itself is stored in
00171             // clusters. Each cluster contains a number of blocks, with each block
00172             // containing a single frame of data. Different cluster implementations are
00173             // (will be) available using different optimisations. Here, we use the
00174             // implementation that stores all its blocks in memory before writing them
00175             // all to the file at once. As with the segment, clusters must be opened
00176             // for writing before blocks are added. Once the cluster is complete, it is
00177             // finalised. How many blocks each cluster contains is relatively flexible:
00178             // the only limitation is on the range of block timecodes that can be
00179             // stored. Each timecode is a signed 16-bit integer, and usually blocks
00180             // have timecodes that are positive, limiting the range to 32767. The unit
00181             // of this value is the segment's timecode scale. The default timecode
00182             // scale therefore gives approximately 65 seconds of total range, with 32
00183             // seconds being usable.
00184             // The first cluster will appear at this point in the file, so it is
00185             // recorded in the segment's index for faster file reading.
00186             segment.index.insert(std::make_pair(tide::ids::Cluster,
00187                         segment.to_segment_offset(stream_.tellp())));
00188 
00189             // Set up a callback to get clouds from a grabber and write them to the
00190             // file.
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             // Start the first cluster
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             // Close the last open cluster
00209             if (cluster_)
00210             {
00211                 cluster_->finalise(stream_);
00212             }
00213 
00214             // Now that the data has been written, the last thing to do is to finalise
00215             // the segment.
00216             segment.finalise(stream_);
00217             // And finally, close the file.
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             //viewer_.setBackgroundColor(0, 0, 0);
00242             //viewer_.initCameraParameters();
00243         }
00244 
00245         int Run()
00246         {
00247             // Open the file and check for the EBML header. This confirms that the file
00248             // is an EBML file, and is a Tide document.
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             // Open the file's segment. This will read some meta-data about the segment
00278             // and read (or build, if necessary) an index of the level 1 elements. With
00279             // this index, we will be able to quickly jump to important elements such
00280             // as the Tracks and the first Cluster.
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             // The segment's date is stored as the number of nanoseconds since the
00290             // start of the millenium. Boost::Date_Time is invaluable here.
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             // The segment is now open and we can start reading its child elements. To
00296             // begin with, we get the tracks element (their may be more than one, if
00297             // the document was created by merging other documents) but generally only
00298             // one will exist).
00299             // We can guarantee that there is at least one in the index because
00300             // otherwise the call to segment.read() would have thrown an error.
00301             std::streampos tracks_pos(segment.index.find(tide::ids::Tracks)->second);
00302             stream.seekg(segment.to_stream_offset(tracks_pos));
00303             // To be sure, we can check it really is a Tracks element, but this is
00304             // usually not necessary.
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             // Read the tracks
00312             tide::Tracks tracks;
00313             tracks.read(stream);
00314             // Now we can introspect the tracks available in the file.
00315             if (tracks.empty())
00316             {
00317                 std::cerr << "No tracks found.\n";
00318                 return 1;
00319             }
00320             // Let's check that the file contains the codec we expect for the first
00321             // track.
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             // Now we can start reading the clusters. Get an iterator to the clusters
00332             // in the segment.
00333             // In this case, we are using a file-based cluster implementation, which
00334             // reads blocks from the file on demand. This is usually a better
00335             // option tham the memory-based cluster when the size of the stored
00336             // data is large.
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                 // If the current playback time is ahead of this block, skip it
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                 // Some blocks may actually contain multiple frames in a lace.
00353                 // In this case, we are reading blocks that do not use lacing,
00354                 // so there is only one frame per block. This is the general
00355                 // case; lacing is typically only used when the frame size is
00356                 // very small to reduce overhead.
00357                 tide::BlockElement::FramePtr frame_data(*block->begin());
00358                 // Copy the frame data into a serialised cloud structure
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                 // Sleep until the block's display time. The played_time is
00386                 // updated to account for the time spent preparing the data.
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                 //viewer_.removePointCloud("1");
00393                 //viewer_.addPointCloud(cloud, "1");
00394                 //viewer_.spinOnce();
00395                 //if (viewer_.wasStopped())
00396                 //{
00397                     //break;
00398                 //}
00399             }
00400 
00401             return 0;
00402         }
00403 
00404     private:
00405         std::string filename_;
00406         //pcl::visualization::PCLVisualizer viewer_;
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 


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:28:11