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"
00018  *AND *
00019  * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00020  **
00021  * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE *
00022  * DISCLAIMED. IN NO EVENT SHALL Markus Bader BE LIABLE FOR ANY *
00023  * DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES *
00024  * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00025  **
00026  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND *
00027  * ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT *
00028  * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00029  **
00030  * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00031  **                       *
00032  ***********************************************************************************/
00033 
00034 #include "rawlog_play_node.h"
00035 #include <boost/interprocess/sync/scoped_lock.hpp>
00036 #include <mrpt_bridge/pose.h>
00037 #include <mrpt_bridge/laser_scan.h>
00038 #include <mrpt_bridge/time.h>
00039 #include <mrpt_bridge/beacon.h>
00040 #include <mrpt_bridge/landmark.h>
00041 #include <mrpt/system/filesystem.h>
00042 
00043 #include <mrpt/version.h>
00044 #include <mrpt/obs/CSensoryFrame.h>
00045 #include <mrpt/obs/CRawlog.h>
00046 #include <mrpt/obs/CObservation2DRangeScan.h>
00047 #include <mrpt/obs/CObservationBeaconRanges.h>
00048 #include <mrpt/obs/CObservationBearingRange.h>
00049 using namespace mrpt::obs;
00050 
00051 #if MRPT_VERSION >= 0x199
00052 #include <mrpt/serialization/CArchive.h>
00053 #endif
00054 
00055 int main(int argc, char** argv)
00056 {
00057         ros::init(argc, argv, "rawlog_play");
00058         ros::NodeHandle n;
00059         RawlogPlayNode my_node(n);
00060         my_node.init();
00061         my_node.loop();
00062         return 0;
00063 }
00064 
00065 RawlogPlayNode::~RawlogPlayNode() {}
00066 RawlogPlayNode::RawlogPlayNode(ros::NodeHandle& n)
00067         : RawlogPlay(new RawlogPlayNode::ParametersNode()), n_(n), loop_count_(0)
00068 {
00069 }
00070 
00071 RawlogPlayNode::ParametersNode* RawlogPlayNode::param()
00072 {
00073         return (RawlogPlayNode::ParametersNode*)param_;
00074 }
00075 
00076 void RawlogPlayNode::init()
00077 {
00078         if (!mrpt::system::fileExists(param_->rawlog_file))
00079         {
00080                 ROS_ERROR("raw_file: %s does not exit", param_->rawlog_file.c_str());
00081         }
00082         rawlog_stream_.open(param_->rawlog_file);
00083         pub_laser_ = n_.advertise<sensor_msgs::LaserScan>("scan", 10);
00084         pub_beacon_ = n_.advertise<mrpt_msgs::ObservationRangeBeacon>("beacon", 10);
00085         pub_landmark_ =
00086                 n_.advertise<mrpt_msgs::ObservationRangeBearing>("landmark", 10);
00087         odom_frame_ = tf::resolve(param()->tf_prefix, param()->odom_frame);
00088         base_frame_ = tf::resolve(param()->tf_prefix, param()->base_frame);
00089         robotPose = mrpt::poses::CPose3DPDFGaussian();
00090 }
00091 
00092 void RawlogPlayNode::publishSingleObservation(
00093         const mrpt::obs::CObservation::Ptr& o)
00094 {
00095         mrpt::poses::CPose3D pose_sensor;
00096         o->getSensorPose(pose_sensor);
00097 
00098         geometry_msgs::Pose msg_pose_sensor;
00099         tf::Transform transform;
00100 
00101         if (IS_CLASS(o, CObservation2DRangeScan))
00102         {  // laser observation detected
00103                 auto laser = mrpt::ptr_cast<CObservation2DRangeScan>::from(o);
00104                 mrpt_bridge::convert(*laser, msg_laser_, msg_pose_sensor);
00105                 if (msg_laser_.header.frame_id.empty())
00106                         msg_laser_.header.frame_id = "laser_link";
00107                 std::string childframe =
00108                         tf::resolve(param()->tf_prefix, msg_laser_.header.frame_id);
00109                 msg_laser_.header.stamp = ros::Time::now();
00110                 mrpt_bridge::convert(pose_sensor, transform);
00111                 tf_broadcaster_.sendTransform(tf::StampedTransform(
00112                         transform, msg_laser_.header.stamp + ros::Duration(0.05),
00113                         base_frame_, childframe));
00114                 pub_laser_.publish(msg_laser_);
00115         }
00116         else if (IS_CLASS(o, CObservationBeaconRanges))
00117         {
00118                 auto beacon = mrpt::ptr_cast<CObservationBeaconRanges>::from(o);
00119                 mrpt_bridge::convert(*beacon, msg_beacon_, msg_pose_sensor);
00120                 if (msg_beacon_.header.frame_id.empty())
00121                         msg_beacon_.header.frame_id = "beacon_link";
00122                 std::string childframe =
00123                         tf::resolve(param()->tf_prefix, msg_beacon_.header.frame_id);
00124                 msg_beacon_.header.stamp = ros::Time::now();
00125                 mrpt_bridge::convert(pose_sensor, transform);
00126                 tf_broadcaster_.sendTransform(tf::StampedTransform(
00127                         transform, msg_beacon_.header.stamp + ros::Duration(0.05),
00128                         base_frame_, childframe));
00129                 pub_beacon_.publish(msg_beacon_);
00130         }
00131         else if (IS_CLASS(o, CObservationBearingRange))
00132         {
00133                 auto landmark = mrpt::ptr_cast<CObservationBearingRange>::from(o);
00134                 mrpt_bridge::convert(*landmark, msg_landmark_, msg_pose_sensor);
00135                 if (msg_landmark_.header.frame_id.empty())
00136                         msg_landmark_.header.frame_id = "landmark_link";
00137                 std::string childframe =
00138                         tf::resolve(param()->tf_prefix, msg_landmark_.header.frame_id);
00139                 msg_landmark_.header.stamp = ros::Time::now();
00140                 mrpt_bridge::convert(pose_sensor, transform);
00141                 tf_broadcaster_.sendTransform(tf::StampedTransform(
00142                         transform, msg_landmark_.header.stamp + ros::Duration(0.05),
00143                         base_frame_, childframe));
00144                 pub_landmark_.publish(msg_landmark_);
00145         }
00146         else
00147         {
00148                 ROS_WARN(
00149                         "Observation mapping to ROS not implemented: %s",
00150                         o->GetRuntimeClass()->className);
00151         }
00152 }  // end publishSingleObservation()
00153 
00154 bool RawlogPlayNode::nextEntry()
00155 {
00156         CActionCollection::Ptr action;
00157         CSensoryFrame::Ptr observations;
00158         CObservation::Ptr obs;
00159 
00160 #if MRPT_VERSION >= 0x199
00161         auto rs = mrpt::serialization::archiveFrom(rawlog_stream_);
00162 #else
00163         auto& rs = rawlog_stream_;
00164 #endif
00165 
00166         if (!CRawlog::getActionObservationPairOrObservation(
00167                         rs, action, observations, obs, entry_))
00168         {
00169                 ROS_INFO("end of stream!");
00170                 return true;
00171         }
00172         tf::Transform transform;
00173 
00174         // Process single obs, if present:
00175         if (obs) publishSingleObservation(obs);
00176         // and process all obs into a CSensoryFrame, if present:
00177         for (const auto& o : *observations) publishSingleObservation(o);
00178 
00179         mrpt::poses::CPose3DPDFGaussian out_pose_increment;
00180         action->getFirstMovementEstimation(out_pose_increment);
00181         robotPose -= out_pose_increment;
00182 
00183         msg_odom_.header.frame_id = "odom";
00184         msg_odom_.child_frame_id = base_frame_;
00185         if (!msg_laser_.header.frame_id.empty())
00186         {
00187                 msg_odom_.header.stamp = msg_laser_.header.stamp;
00188                 msg_odom_.header.seq = msg_laser_.header.seq;
00189         }
00190         else if (!msg_beacon_.header.frame_id.empty())
00191         {
00192                 msg_odom_.header.stamp = msg_beacon_.header.stamp;
00193                 msg_odom_.header.seq = msg_beacon_.header.seq;
00194         }
00195         else if (!msg_landmark_.header.frame_id.empty())
00196         {
00197                 msg_odom_.header.stamp = msg_landmark_.header.stamp;
00198                 msg_odom_.header.seq = msg_landmark_.header.seq;
00199         }
00200         mrpt_bridge::convert(robotPose, msg_odom_.pose);
00201         mrpt_bridge::convert(robotPose, transform);
00202 
00203         msg_odom_.header.stamp = ros::Time::now();
00204 
00205         tf_broadcaster_.sendTransform(tf::StampedTransform(
00206                 transform.inverse(), msg_odom_.header.stamp + ros::Duration(0.05),
00207                 odom_frame_, base_frame_));
00208         return false;
00209 }
00210 
00211 void RawlogPlayNode::loop()
00212 {
00213         bool end = false;
00214         for (ros::Rate rate(param()->rate); ros::ok() && !end; loop_count_++)
00215         {
00216                 param()->update(loop_count_);
00217                 end = nextEntry();
00218                 ros::spinOnce();
00219                 rate.sleep();
00220         }
00221 }


mrpt_rawlog
Author(s):
autogenerated on Thu Jun 6 2019 21:53:23