rawlog_play_node.cpp
Go to the documentation of this file.
1 /***********************************************************************************
2  * Revised BSD License *
3  * Copyright (c) 2014, Markus Bader <markus.bader@tuwien.ac.at> *
4  * All rights reserved. *
5  * *
6  * Redistribution and use in source and binary forms, with or without *
7  * modification, are permitted provided that the following conditions are met: *
8  * * Redistributions of source code must retain the above copyright *
9  * notice, this list of conditions and the following disclaimer. *
10  * * Redistributions in binary form must reproduce the above copyright *
11  * notice, this list of conditions and the following disclaimer in the *
12  * documentation and/or other materials provided with the distribution. *
13  * * Neither the name of the Vienna University of Technology nor the *
14  * names of its contributors may be used to endorse or promote products *
15  * derived from this software without specific prior written permission. *
16  * *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  *AND *
19  * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
20  **
21  * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE *
22  * DISCLAIMED. IN NO EVENT SHALL Markus Bader BE LIABLE FOR ANY *
23  * DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES *
24  * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
25  **
26  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND *
27  * ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT *
28  * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
29  **
30  * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
31  ** *
32  ***********************************************************************************/
33 
34 #include "rawlog_play_node.h"
35 #include <boost/interprocess/sync/scoped_lock.hpp>
36 #include <mrpt_bridge/pose.h>
37 #include <mrpt_bridge/laser_scan.h>
38 #include <mrpt_bridge/time.h>
39 #include <mrpt_bridge/beacon.h>
40 #include <mrpt_bridge/landmark.h>
41 #include <mrpt/system/filesystem.h>
42 
43 #include <mrpt/version.h>
44 #include <mrpt/obs/CSensoryFrame.h>
45 #include <mrpt/obs/CRawlog.h>
46 #include <mrpt/obs/CObservation2DRangeScan.h>
47 #include <mrpt/obs/CObservationBeaconRanges.h>
48 #include <mrpt/obs/CObservationBearingRange.h>
49 using namespace mrpt::obs;
50 
51 #if MRPT_VERSION >= 0x199
52 #include <mrpt/serialization/CArchive.h>
53 #endif
54 
55 int main(int argc, char** argv)
56 {
57  ros::init(argc, argv, "rawlog_play");
59  RawlogPlayNode my_node(n);
60  my_node.init();
61  my_node.loop();
62  return 0;
63 }
64 
67  : RawlogPlay(new RawlogPlayNode::ParametersNode()), n_(n), loop_count_(0)
68 {
69 }
70 
72 {
74 }
75 
77 {
78  if (!mrpt::system::fileExists(param_->rawlog_file))
79  {
80  ROS_ERROR("raw_file: %s does not exit", param_->rawlog_file.c_str());
81  }
83  pub_laser_ = n_.advertise<sensor_msgs::LaserScan>("scan", 10);
84  pub_beacon_ = n_.advertise<mrpt_msgs::ObservationRangeBeacon>("beacon", 10);
86  n_.advertise<mrpt_msgs::ObservationRangeBearing>("landmark", 10);
87  odom_frame_ = tf::resolve(param()->tf_prefix, param()->odom_frame);
88  base_frame_ = tf::resolve(param()->tf_prefix, param()->base_frame);
89  robotPose = mrpt::poses::CPose3DPDFGaussian();
90 }
91 
93  const mrpt::obs::CObservation::Ptr& o)
94 {
95  mrpt::poses::CPose3D pose_sensor;
96  o->getSensorPose(pose_sensor);
97 
98  geometry_msgs::Pose msg_pose_sensor;
99  tf::Transform transform;
100 
101  if (IS_CLASS(o, CObservation2DRangeScan))
102  { // laser observation detected
103  auto laser = mrpt::ptr_cast<CObservation2DRangeScan>::from(o);
104  mrpt_bridge::convert(*laser, msg_laser_, msg_pose_sensor);
105  if (msg_laser_.header.frame_id.empty())
106  msg_laser_.header.frame_id = "laser_link";
107  std::string childframe =
108  tf::resolve(param()->tf_prefix, msg_laser_.header.frame_id);
109  msg_laser_.header.stamp = ros::Time::now();
110  mrpt_bridge::convert(pose_sensor, transform);
112  transform, msg_laser_.header.stamp + ros::Duration(0.05),
113  base_frame_, childframe));
115  }
116  else if (IS_CLASS(o, CObservationBeaconRanges))
117  {
118  auto beacon = mrpt::ptr_cast<CObservationBeaconRanges>::from(o);
119  mrpt_bridge::convert(*beacon, msg_beacon_, msg_pose_sensor);
120  if (msg_beacon_.header.frame_id.empty())
121  msg_beacon_.header.frame_id = "beacon_link";
122  std::string childframe =
123  tf::resolve(param()->tf_prefix, msg_beacon_.header.frame_id);
124  msg_beacon_.header.stamp = ros::Time::now();
125  mrpt_bridge::convert(pose_sensor, transform);
127  transform, msg_beacon_.header.stamp + ros::Duration(0.05),
128  base_frame_, childframe));
130  }
131  else if (IS_CLASS(o, CObservationBearingRange))
132  {
133  auto landmark = mrpt::ptr_cast<CObservationBearingRange>::from(o);
134  mrpt_bridge::convert(*landmark, msg_landmark_, msg_pose_sensor);
135  if (msg_landmark_.header.frame_id.empty())
136  msg_landmark_.header.frame_id = "landmark_link";
137  std::string childframe =
138  tf::resolve(param()->tf_prefix, msg_landmark_.header.frame_id);
139  msg_landmark_.header.stamp = ros::Time::now();
140  mrpt_bridge::convert(pose_sensor, transform);
142  transform, msg_landmark_.header.stamp + ros::Duration(0.05),
143  base_frame_, childframe));
145  }
146  else
147  {
148  ROS_WARN(
149  "Observation mapping to ROS not implemented: %s",
150  o->GetRuntimeClass()->className);
151  }
152 } // end publishSingleObservation()
153 
155 {
156  CActionCollection::Ptr action;
157  CSensoryFrame::Ptr observations;
158  CObservation::Ptr obs;
159 
160 #if MRPT_VERSION >= 0x199
161  auto rs = mrpt::serialization::archiveFrom(rawlog_stream_);
162 #else
163  auto& rs = rawlog_stream_;
164 #endif
165 
166  if (!CRawlog::getActionObservationPairOrObservation(
167  rs, action, observations, obs, entry_))
168  {
169  ROS_INFO("end of stream!");
170  return true;
171  }
172  tf::Transform transform;
173 
174  // Process single obs, if present:
175  if (obs) publishSingleObservation(obs);
176  // and process all obs into a CSensoryFrame, if present:
177  for (const auto& o : *observations) publishSingleObservation(o);
178 
179  mrpt::poses::CPose3DPDFGaussian out_pose_increment;
180  action->getFirstMovementEstimation(out_pose_increment);
181  robotPose -= out_pose_increment;
182 
183  msg_odom_.header.frame_id = "odom";
184  msg_odom_.child_frame_id = base_frame_;
185  if (!msg_laser_.header.frame_id.empty())
186  {
187  msg_odom_.header.stamp = msg_laser_.header.stamp;
188  msg_odom_.header.seq = msg_laser_.header.seq;
189  }
190  else if (!msg_beacon_.header.frame_id.empty())
191  {
192  msg_odom_.header.stamp = msg_beacon_.header.stamp;
193  msg_odom_.header.seq = msg_beacon_.header.seq;
194  }
195  else if (!msg_landmark_.header.frame_id.empty())
196  {
197  msg_odom_.header.stamp = msg_landmark_.header.stamp;
198  msg_odom_.header.seq = msg_landmark_.header.seq;
199  }
200  mrpt_bridge::convert(robotPose, msg_odom_.pose);
201  mrpt_bridge::convert(robotPose, transform);
202 
203  msg_odom_.header.stamp = ros::Time::now();
204 
206  transform.inverse(), msg_odom_.header.stamp + ros::Duration(0.05),
208  return false;
209 }
210 
212 {
213  bool end = false;
214  for (ros::Rate rate(param()->rate); ros::ok() && !end; loop_count_++)
215  {
217  end = nextEntry();
218  ros::spinOnce();
219  rate.sleep();
220  }
221 }
int main(int argc, char **argv)
ros::Publisher pub_landmark_
void publish(const boost::shared_ptr< M > &message) const
std::string rawlog_file
Definition: rawlog_play.h:63
Parameters * param_
Definition: rawlog_play.h:70
ros::NodeHandle n_
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ParametersNode * param()
size_t entry_
Definition: rawlog_play.h:73
RawlogPlayNode(ros::NodeHandle &n)
#define ROS_WARN(...)
sensor_msgs::LaserScan msg_laser_
void update(const unsigned long &loop_count)
std::string resolve(const std::string &prefix, const std::string &frame_name)
mrpt::poses::CPose3DPDFGaussian robotPose
Definition: rawlog_play.h:72
nav_msgs::Odometry msg_odom_
void publishSingleObservation(const mrpt::obs::CObservation::Ptr &o)
mrpt_msgs::ObservationRangeBearing msg_landmark_
#define ROS_INFO(...)
ROSCPP_DECL bool ok()
void sendTransform(const StampedTransform &transform)
std::string base_frame_
Transform inverse() const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
tf::TransformBroadcaster tf_broadcaster_
action
std::string odom_frame_
static Time now()
ros::Publisher pub_beacon_
ROSCPP_DECL void spinOnce()
unsigned long loop_count_
mrpt_msgs::ObservationRangeBeacon msg_beacon_
#define ROS_ERROR(...)
ros::Publisher pub_laser_
CFileGZInputStream rawlog_stream_
Definition: rawlog_play.h:71


mrpt_rawlog
Author(s):
autogenerated on Thu Jun 6 2019 19:44:53