rawlog_play_node.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 
00029 #include "rawlog_play_node.h"
00030 #include <boost/interprocess/sync/scoped_lock.hpp>
00031 #include <mrpt_bridge/pose.h>
00032 #include <mrpt_bridge/laser_scan.h>
00033 #include <mrpt_bridge/time.h>
00034 #include <mrpt/base.h>
00035 #include <mrpt/slam.h>
00036 #include <mrpt/gui.h>
00037 
00038 
00039 int main(int argc, char **argv) {
00040 
00041     ros::init(argc, argv, "DataLogger");
00042     ros::NodeHandle n;
00043     RawlogPlayNode my_node(n);
00044     my_node.init();
00045     my_node.loop();
00046     return 0;
00047 }
00048 
00049 RawlogPlayNode::~RawlogPlayNode() {
00050 }
00051 
00052 RawlogPlayNode::RawlogPlayNode(ros::NodeHandle &n) :
00053     RawlogPlay(new RawlogPlayNode::ParametersNode()), n_(n), loop_count_(0) {
00054 
00055 }
00056 
00057 RawlogPlayNode::ParametersNode *RawlogPlayNode::param() {
00058     return (RawlogPlayNode::ParametersNode*) param_;
00059 }
00060 
00061 void RawlogPlayNode::init() {
00062 
00063     if(!mrpt::utils::fileExists(param_->rawlog_file)) {
00064         ROS_ERROR("raw_file: %s does not exit", param_->rawlog_file.c_str());
00065     }
00066     rawlog_stream_.open(param_->rawlog_file);
00067     pub_laser_ = n_.advertise<sensor_msgs::LaserScan>("scan", 10);
00068     odom_frame_ = tf::resolve(param()->tf_prefix, param()->odom_frame);
00069     base_frame_ = tf::resolve(param()->tf_prefix, param()->base_frame);
00070     robotPose = mrpt::poses::CPose3DPDFGaussian();
00071 }
00072 
00073 bool RawlogPlayNode::nextEntry() {
00074     mrpt::slam::CActionCollectionPtr action;
00075     mrpt::slam::CSensoryFramePtr     observations;
00076     mrpt::slam::CObservationPtr      obs;
00077 
00078     if(!mrpt::slam::CRawlog::getActionObservationPairOrObservation( rawlog_stream_, action, observations, obs, entry_)) {
00079         ROS_INFO("end of stream!");
00080         return true;
00081     }
00082     mrpt::poses::CPose3D pose_laser;
00083     geometry_msgs::Pose msg_pose_laser;
00084     tf::Transform transform;
00085 
00086     // loop over laser overservations
00087     for(size_t i = 0;i < observations->size() ;i++){
00088         mrpt::slam::CObservation2DRangeScanPtr laser = observations->getObservationByClass<mrpt::slam::CObservation2DRangeScan>(i);
00089         if(laser.pointer() == NULL) break;
00090         mrpt_bridge::convert(*laser, msg_laser_, msg_pose_laser);
00091         laser->getSensorPose(pose_laser);
00092         mrpt_bridge::convert(pose_laser, transform);
00093         std::string childframe = tf::resolve(param()->tf_prefix, msg_laser_.header.frame_id);
00094         tf_broadcaster_.sendTransform(tf::StampedTransform(transform, msg_laser_.header.stamp, base_frame_, childframe));
00095         pub_laser_.publish(msg_laser_);
00096         laser = observations->getObservationByClass<mrpt::slam::CObservation2DRangeScan>();
00097     }
00098     mrpt::poses::CPose3DPDFGaussian out_pose_increment;
00099     action->getFirstMovementEstimation (out_pose_increment);
00100     robotPose -= out_pose_increment;
00101 
00102     msg_odom_.header.frame_id = "odom";
00103     msg_odom_.child_frame_id = base_frame_;
00104     msg_odom_.header.stamp = msg_laser_.header.stamp;
00105     msg_odom_.header.seq = msg_laser_.header.seq;
00106     mrpt_bridge::convert(robotPose, msg_odom_.pose);
00107     mrpt_bridge::convert(robotPose, transform);
00108     tf_broadcaster_.sendTransform(tf::StampedTransform(transform, msg_odom_.header.stamp, base_frame_, odom_frame_));
00109     return false;
00110 
00111 }
00112 
00113 void RawlogPlayNode::loop() {
00114     bool end = false;
00115     for (ros::Rate rate(param()->rate); ros::ok() && !end; loop_count_++) {
00116         param()->update(loop_count_);
00117         end = nextEntry();
00118         ros::spinOnce();
00119         rate.sleep();
00120     }
00121 }


mrpt_rawlog
Author(s):
autogenerated on Tue Aug 5 2014 10:58:08