rawlog_play_node.h
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 #ifndef MRPT_RAWLOG_PLAY_NODE_H
35 #define MRPT_RAWLOG_PLAY_NODE_H
36 
37 #include "ros/ros.h"
39 #include <tf/transform_listener.h>
40 #include <nav_msgs/Odometry.h>
41 #include <sensor_msgs/LaserScan.h>
42 #include <dynamic_reconfigure/server.h>
43 #include "mrpt_rawlog/RawLogRecordConfig.h"
45 #include <mrpt_msgs/ObservationRangeBeacon.h>
46 #include <mrpt_msgs/ObservationRangeBearing.h>
47 #include <mrpt/obs/CObservation.h>
48 
50 class RawlogPlayNode : public RawlogPlay
51 {
52  public:
53  struct ParametersNode : public Parameters
54  {
55  static const int MOTION_MODEL_GAUSSIAN = 0;
56  static const int MOTION_MODEL_THRUN = 1;
59  void callbackParameters(
60  mrpt_rawlog::RawLogRecordConfig& config, uint32_t level);
61  dynamic_reconfigure::Server<mrpt_rawlog::RawLogRecordConfig>
63  dynamic_reconfigure::Server<
64  mrpt_rawlog::RawLogRecordConfig>::CallbackType reconfigureFnc_;
65  void update(const unsigned long& loop_count);
66  double rate;
67  std::string base_frame;
68  std::string odom_frame;
69  std::string tf_prefix;
71  };
72 
75  void init();
76  void loop();
77 
78  private: // functions
80  bool nextEntry();
81  void publishSingleObservation(const mrpt::obs::CObservation::Ptr& o);
82 
83  private: // variables
85  unsigned long loop_count_;
86  sensor_msgs::LaserScan msg_laser_;
87  mrpt_msgs::ObservationRangeBeacon msg_beacon_;
88  mrpt_msgs::ObservationRangeBearing msg_landmark_;
89  nav_msgs::Odometry msg_odom_;
93  std::string odom_frame_;
94  std::string base_frame_;
96 };
97 
98 #endif // MRPT_RAWLOG_PLAY_NODE_H
ros::Publisher pub_landmark_
void callbackParameters(mrpt_rawlog::RawLogRecordConfig &config, uint32_t level)
ros::NodeHandle n_
static const int MOTION_MODEL_GAUSSIAN
ParametersNode * param()
RawlogPlayNode(ros::NodeHandle &n)
sensor_msgs::LaserScan msg_laser_
void update(const unsigned long &loop_count)
nav_msgs::Odometry msg_odom_
void publishSingleObservation(const mrpt::obs::CObservation::Ptr &o)
mrpt_msgs::ObservationRangeBearing msg_landmark_
std::string base_frame_
tf::TransformBroadcaster tf_broadcaster_
dynamic_reconfigure::Server< mrpt_rawlog::RawLogRecordConfig > reconfigureServer_
std::string odom_frame_
dynamic_reconfigure::Server< mrpt_rawlog::RawLogRecordConfig >::CallbackType reconfigureFnc_
ros::Publisher pub_beacon_
unsigned long loop_count_
mrpt_msgs::ObservationRangeBeacon msg_beacon_
ros::Publisher pub_laser_


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