rawlog_record.cpp
Go to the documentation of this file.
00001 /***********************************************************************************
00002  * Revised BSD License                                                             *
00003  * Copyright (c) 2014, Markus Bader <markus.bader@tuwien.ac.at>                    *
00004  * All rights reserved.                                                            *
00005  *                                                                                 *
00006  * Redistribution and use in source and binary forms, with or without              *
00007  * modification, are permitted provided that the following conditions are met:     *
00008  *     * Redistributions of source code must retain the above copyright            *
00009  *       notice, this list of conditions and the following disclaimer.             *
00010  *     * Redistributions in binary form must reproduce the above copyright         *
00011  *       notice, this list of conditions and the following disclaimer in the       *
00012  *       documentation and/or other materials provided with the distribution.      *
00013  *     * Neither the name of the Vienna University of Technology nor the           *
00014  *       names of its contributors may be used to endorse or promote products      *
00015  *       derived from this software without specific prior written permission.     *
00016  *                                                                                 *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND *
00018  * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED   *
00019  * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE          *
00020  * DISCLAIMED. IN NO EVENT SHALL Markus Bader BE LIABLE FOR ANY                    *
00021  * DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES      *
00022  * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;    *
00023  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND     *
00024  * ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT      *
00025  * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS   *
00026  * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.                    *                       *
00027  ***********************************************************************************/
00028 #include <stdio.h>
00029 #include <stdarg.h>
00030 
00031 #include <mrpt_rawlog_record/rawlog_record.h>
00032 #include <mrpt_rawlog_record/rawlog_record_defaults.h>
00033 
00034 RawlogRecord::~RawlogRecord()
00035 {
00036     log_info("write data");
00037     MRPT_TODO("RawlogRecord writes the rawlog only on exit (Ctrl-C)");
00038     log_info("pRawLog    entries %i", pRawLog->size());
00039     log_info("pRawLogASF entries %i", pRawLogASF->size());
00040     if(pRawLog->size() > 0)  {
00041       std::string filename = param_->raw_log_folder + "/" + param_->raw_log_name;
00042       log_info("write %s", filename.c_str());
00043       pRawLog->saveToRawLogFile(filename);
00044     }
00045     if(pRawLogASF->size() > 0)   {
00046       std::string filename = param_->raw_log_folder + "/" + param_->raw_log_name_asf;
00047       log_info("write %s", filename.c_str());
00048       pRawLogASF->saveToRawLogFile(filename);
00049     }
00050     delete pRawLog;
00051     delete pRawLogASF;
00052 }
00053 
00054 RawlogRecord::RawlogRecord(Parameters *param)
00055     :param_(param) {
00056     pRawLog = new mrpt::slam::CRawlog;
00057     pRawLogASF = new mrpt::slam::CRawlog;
00058 }
00059 void RawlogRecord::updateRawLogName(const mrpt::system::TTimeStamp &t) {
00060     uint64_t        tmp = (t - ((uint64_t)116444736*1000000000));
00061     time_t          auxTime = tmp / (uint64_t)10000000;
00062     unsigned int    secFractions = (unsigned int)( 1000000 * (tmp % 10000000) / 10000000.0 );
00063     tm  *ptm = localtime( &auxTime );
00064     param_->raw_log_name = mrpt::format(
00065                                "%u-%02u-%02u--%02u-%02u-%02u--%s",
00066                                1900+ptm->tm_year,
00067                                ptm->tm_mon+1,
00068                                ptm->tm_mday,
00069                                ptm->tm_hour,
00070                                ptm->tm_min,
00071                                (unsigned int)ptm->tm_sec,
00072                                param_->raw_log_name.c_str());
00073     param_->raw_log_name_asf = mrpt::format(
00074                                    "%u-%02u-%02u--%02u-%02u-%02u--%s",
00075                                    1900+ptm->tm_year,
00076                                    ptm->tm_mon+1,
00077                                    ptm->tm_mday,
00078                                    ptm->tm_hour,
00079                                    ptm->tm_min,
00080                                    (unsigned int)ptm->tm_sec,
00081                                    param_->raw_log_name_asf.c_str());
00082 }
00083 
00084 
00085 void RawlogRecord::observation(mrpt::slam::CObservation2DRangeScanPtr laser, mrpt::slam::CObservationOdometryPtr odometry) {
00086 
00087     pRawLog->addObservationMemoryReference(odometry);
00088     pRawLog->addObservationMemoryReference(laser);
00089 
00090     if(odomLastPose_.empty()) {
00091         odomLastPose_ = odometry->odometry;
00092     }
00093 
00094     mrpt::poses::CPose2D incOdoPose = odometry->odometry - odomLastPose_;
00095 
00096 
00097     mrpt::slam::CActionRobotMovement2D odom_move;
00098     odom_move.timestamp = odometry->timestamp;
00099     odom_move.computeFromOdometry(incOdoPose, param_->motionModelOptions);
00100     mrpt::slam::CActionCollectionPtr action = mrpt::slam::CActionCollection::Create();
00101     action->insert(odom_move);
00102     pRawLogASF->addActionsMemoryReference(action);
00103 
00104     mrpt::slam::CSensoryFramePtr sf = mrpt::slam::CSensoryFrame::Create();
00105     mrpt::slam::CObservationPtr obs = mrpt::slam::CObservationPtr(laser);
00106     sf->insert(obs);
00107     pRawLogASF->addObservationsMemoryReference(sf);
00108 
00109     odomLastPose_ = odometry->odometry;
00110 }


mrpt_rawlog
Author(s):
autogenerated on Mon Aug 11 2014 11:23:25