Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
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
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 }