rawlog_record_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_record_node.h"
00030 #include <boost/interprocess/sync/scoped_lock.hpp>
00031 
00032 #include <mrpt_bridge/pose.h>
00033 #include <mrpt_bridge/laser_scan.h>
00034 #include <mrpt_bridge/time.h>
00035 #include <mrpt/base.h>
00036 #include <mrpt/slam.h>
00037 #include <mrpt/gui.h>
00038 
00039 
00040 int main(int argc, char **argv) {
00041 
00042     ros::init(argc, argv, "DataLogger");
00043     ros::NodeHandle n;
00044     RawlogRecordNode my_node(n);
00045     my_node.init();
00046     my_node.loop();
00047     return 0;
00048 }
00049 
00050 RawlogRecordNode::~RawlogRecordNode() {
00051 }
00052 
00053 RawlogRecordNode::RawlogRecordNode(ros::NodeHandle &n) :
00054     RawlogRecord(new RawlogRecordNode::ParametersNode()), n_(n), loop_count_(0) {
00055 
00056 }
00057 
00058 RawlogRecordNode::ParametersNode *RawlogRecordNode::param() {
00059     return (RawlogRecordNode::ParametersNode*) param_;
00060 }
00061 
00062 void RawlogRecordNode::init() {
00063     updateRawLogName(mrpt::system::getCurrentLocalTime());
00064     ROS_INFO("rawlog file: %s", param_->raw_log_name.c_str());
00065     subLaser0_ = n_.subscribe("scan", 1, &RawlogRecordNode::callbackLaser, this);
00066     subLaser1_ = n_.subscribe("scan1", 1, &RawlogRecordNode::callbackLaser, this);
00067     subLaser2_ = n_.subscribe("scan2", 1, &RawlogRecordNode::callbackLaser, this);
00068 }
00069 
00070 void RawlogRecordNode::loop() {
00071     for (ros::Rate rate(param()->rate); ros::ok(); loop_count_++) {
00072         param()->update(loop_count_);
00073         ros::spinOnce();
00074         rate.sleep();
00075     }
00076 }
00077 
00078 
00079 bool RawlogRecordNode::waitForTransform(mrpt::poses::CPose3D &des, const std::string& target_frame, const std::string& source_frame, const ros::Time& time, const ros::Duration& timeout, const ros::Duration& polling_sleep_duration){
00080     tf::StampedTransform transform;
00081     try
00082     {
00083         listenerTF_.waitForTransform(target_frame, source_frame,  time, polling_sleep_duration);
00084         listenerTF_.lookupTransform(target_frame, source_frame,  time, transform);
00085     }
00086     catch(tf::TransformException)
00087     {
00088         ROS_INFO("Failed to get transform target_frame (%s) to source_frame (%s)", target_frame.c_str(), source_frame.c_str());
00089         return false;
00090     }
00091     mrpt_bridge::convert(transform, des);
00092     return true;
00093 }
00094 
00095 void RawlogRecordNode::callbackLaser (const sensor_msgs::LaserScan &_msg) {
00096     //ROS_INFO("callbackLaser");
00097     mrpt::slam::CObservation2DRangeScanPtr laser = mrpt::slam::CObservation2DRangeScan::Create();
00098 
00099     if(laser_poses_.find(_msg.header.frame_id) == laser_poses_.end()) {
00100         updateLaserPose (_msg.header.frame_id);
00101     } else {
00102         //mrpt::poses::CPose3D pose = laser_poses_[_msg.header.frame_id];
00103         //ROS_INFO("LASER POSE %4.3f, %4.3f, %4.3f, %4.3f, %4.3f, %4.3f",  pose.x(), pose.y(), pose.z(), pose.roll(), pose.pitch(), pose.yaw());
00104         mrpt_bridge::convert(_msg, laser_poses_[_msg.header.frame_id],  *laser);
00105 
00106 
00107         std::string base_frame_id = tf::resolve(param()->tf_prefix, param()->base_frame_id);
00108         std::string odom_frame_id = tf::resolve(param()->tf_prefix, param()->odom_frame_id);
00109         mrpt::poses::CPose3D poseOdom;
00110         if(this->waitForTransform(poseOdom, odom_frame_id, base_frame_id, _msg.header.stamp, ros::Duration(1))){
00111             mrpt::slam::CObservationOdometryPtr odometry = mrpt::slam::CObservationOdometry::Create();
00112             odometry->sensorLabel = odom_frame_id;
00113             odometry->hasEncodersInfo = false;
00114             odometry->hasVelocities = false;
00115             odometry->odometry.x() = poseOdom.x();
00116             odometry->odometry.y() = poseOdom.y();
00117             odometry->odometry.phi() = poseOdom.yaw();
00118 
00119             observation(laser, odometry);
00120         } else {
00121             ROS_INFO("Failed to get odom for laser observation!");
00122         }
00123     }
00124 }
00125 
00126 void RawlogRecordNode::updateLaserPose (std::string _frame_id) {
00127     std::string base_frame_id = tf::resolve(param()->tf_prefix, param()->base_frame_id);
00128     mrpt::poses::CPose3D pose;
00129     tf::StampedTransform transform;
00130     try {
00131 
00132         listenerTF_.lookupTransform(base_frame_id, _frame_id, ros::Time(0), transform);
00133         ROS_INFO("Requesting laser pose for %s!", _frame_id.c_str());
00134         tf::Vector3 translation = transform.getOrigin();
00135         tf::Quaternion quat = transform.getRotation();
00136         pose.x() = translation.x();
00137         pose.y() = translation.y();
00138         pose.z() = translation.z();
00139         double roll, pitch, yaw;
00140         tf::Matrix3x3 Rsrc(quat);
00141         mrpt::poses::CMatrixDouble33 Rdes;
00142         for(int c = 0; c < 3; c++)
00143             for(int r = 0; r < 3; r++)
00144                 Rdes(r,c) = Rsrc.getRow(r)[c];
00145         pose.setRotationMatrix(Rdes);
00146         laser_poses_[_frame_id] = pose;
00147     }
00148     catch (tf::TransformException ex) {
00149         ROS_ERROR("%s",ex.what());
00150         ros::Duration(1.0).sleep();
00151     }
00152 
00153 }
00154 


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