rawlog_record_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_RECORD_NODE_H
35 #define MRPT_RAWLOG_RECORD_NODE_H
36 
37 #include <dynamic_reconfigure/server.h>
38 #include <marker_msgs/MarkerDetection.h>
39 #include <nav_msgs/Odometry.h>
40 #include <ros/ros.h>
41 #include <sensor_msgs/LaserScan.h>
42 
43 #include "mrpt_rawlog/RawLogRecordConfig.h"
46 #include "tf2_ros/buffer.h"
49 
52 {
53  public:
54  struct ParametersNode
55  {
56  static const int MOTION_MODEL_GAUSSIAN = 0;
57  static const int MOTION_MODEL_THRUN = 1;
61  void callbackParameters(
62  mrpt_rawlog::RawLogRecordConfig& config, uint32_t level);
63  dynamic_reconfigure::Server<mrpt_rawlog::RawLogRecordConfig>
65  dynamic_reconfigure::Server<
66  mrpt_rawlog::RawLogRecordConfig>::CallbackType reconfigureFnc_;
67  void update(const unsigned long& loop_count);
68  double rate;
70  std::string odom_frame_id;
71  std::string base_frame_id;
73  };
74 
77  void init();
78  void loop();
79  void callbackLaser(
80  const sensor_msgs::LaserScan&);
81  void callbackMarker(const marker_msgs::MarkerDetection&);
83  void callbackOdometry(const nav_msgs::Odometry&);
84 
85  private: // functions
87  void update();
88  bool getStaticTF(std::string source_frame, mrpt::poses::CPose3D& des);
92 
95 
96  mrpt::obs::CObservationBearingRange::Ptr last_bearing_range_;
97  mrpt::obs::CObservationBeaconRanges::Ptr last_beacon_range_;
98  mrpt::obs::CObservation2DRangeScan::Ptr last_range_scan_;
99  mrpt::obs::CObservationOdometry::Ptr last_odometry_;
100  unsigned int sync_attempts_sensor_frame_;
101  std::map<std::string, mrpt::poses::CPose3D> static_tf_;
103  void addObservation(const ros::Time& time);
104  bool waitForTransform(
105  mrpt::poses::CPose3D& des, const std::string& target_frame,
106  const std::string& source_frame, const ros::Time& time,
107  const ros::Duration& timeout,
108  const ros::Duration& polling_sleep_duration = ros::Duration(0.01));
109 
110  void convert(
111  const nav_msgs::Odometry& src, mrpt::obs::CObservationOdometry& des);
112 };
113 
114 #endif // MRPT_RAWLOG_RECORD_NODE_H
RawlogRecordNode::ParametersNode
Definition: rawlog_record_node.h:85
RawlogRecordNode::ParametersNode::update
void update(const unsigned long &loop_count)
Definition: rawlog_record_node_parameters.cpp:75
RawlogRecordNode::static_tf_
std::map< std::string, mrpt::poses::CPose3D > static_tf_
Definition: rawlog_record_node.h:132
RawlogRecordNode::callbackOdometry
void callbackOdometry(const nav_msgs::Odometry &)
Definition: rawlog_record_node.cpp:117
RawlogRecordNode::subLaser_
ros::Subscriber subLaser_
Definition: rawlog_record_node.h:120
RawlogRecordNode::ParametersNode::sensor_frame_sync_threshold
double sensor_frame_sync_threshold
Definition: rawlog_record_node.h:134
RawlogRecordNode::ParametersNode::base_param_
RawlogRecord::Parameters & base_param_
Definition: rawlog_record_node.h:122
ros.h
RawlogRecordNode::ParametersNode::reconfigureFnc_
dynamic_reconfigure::Server< mrpt_rawlog::RawLogRecordConfig >::CallbackType reconfigureFnc_
Definition: rawlog_record_node.h:128
RawlogRecordNode::last_beacon_range_
mrpt::obs::CObservationBeaconRanges::Ptr last_beacon_range_
Definition: rawlog_record_node.h:128
RawlogRecordNode::ParametersNode::ParametersNode
ParametersNode(RawlogRecord::Parameters &base_params)
Definition: rawlog_record_node_parameters.cpp:39
RawlogRecordNode::init
void init()
Definition: rawlog_record_node.cpp:59
RawlogRecordNode::ParametersNode::MOTION_MODEL_GAUSSIAN
static const int MOTION_MODEL_GAUSSIAN
Definition: rawlog_record_node.h:118
buffer.h
rawlog_record.h
RawlogRecord
Definition: rawlog_record.h:53
RawlogRecordNode::RawlogRecordNode
RawlogRecordNode(ros::NodeHandle &n)
Definition: rawlog_record_node.cpp:57
RawlogRecordNode::callbackMarker
void callbackMarker(const marker_msgs::MarkerDetection &)
commands
Definition: rawlog_record_node.cpp:146
RawlogRecordNode::~RawlogRecordNode
~RawlogRecordNode()
Definition: rawlog_record_node.cpp:56
RawlogRecordNode::tf_buffer_
tf2_ros::Buffer tf_buffer_
Definition: rawlog_record_node.h:124
RawlogRecord::Parameters
Definition: rawlog_record.h:59
RawlogRecordNode::addObservation
void addObservation(const ros::Time &time)
Definition: rawlog_record_node.cpp:177
transform_broadcaster.h
RawlogRecordNode::convert
void convert(const nav_msgs::Odometry &src, mrpt::obs::CObservationOdometry &des)
Definition: rawlog_record_node.cpp:104
tf2_ros::TransformListener
RawlogRecordNode::loop
void loop()
Definition: rawlog_record_node.cpp:77
RawlogRecordNode::ParametersNode::rate
double rate
Definition: rawlog_record_node.h:130
RawlogRecordNode
ROS Node.
Definition: rawlog_record_node.h:51
RawlogRecordNode::ParametersNode::base_frame_id
std::string base_frame_id
Definition: rawlog_record_node.h:133
RawlogRecordNode::getStaticTF
bool getStaticTF(std::string source_frame, mrpt::poses::CPose3D &des)
Definition: rawlog_record_node.cpp:273
RawlogRecordNode::n_
ros::NodeHandle n_
Definition: rawlog_record_node.h:133
RawlogRecordNode::listenerTF_
tf2_ros::TransformListener listenerTF_
Definition: rawlog_record_node.h:125
RawlogRecordNode::update
void update()
RawlogRecordNode::last_odometry_
mrpt::obs::CObservationOdometry::Ptr last_odometry_
Definition: rawlog_record_node.h:130
RawlogRecordNode::callbackLaser
void callbackLaser(const sensor_msgs::LaserScan &)
Definition: rawlog_record_node.cpp:128
RawlogRecordNode::last_bearing_range_
mrpt::obs::CObservationBearingRange::Ptr last_bearing_range_
Definition: rawlog_record_node.h:127
RawlogRecordNode::ParametersNode::node
ros::NodeHandle node
Definition: rawlog_record_node.h:121
RawlogRecordNode::ParametersNode::odom_frame_id
std::string odom_frame_id
Definition: rawlog_record_node.h:132
RawlogRecordNode::ParametersNode::MOTION_MODEL_THRUN
static const int MOTION_MODEL_THRUN
Definition: rawlog_record_node.h:119
tf2_ros::Buffer
RawlogRecordNode::subMarker_
ros::Subscriber subMarker_
Definition: rawlog_record_node.h:121
RawlogRecordNode::ParametersNode::reconfigureServer_
dynamic_reconfigure::Server< mrpt_rawlog::RawLogRecordConfig > reconfigureServer_
Definition: rawlog_record_node.h:126
transform_listener.h
RawlogRecordNode::subOdometry_
ros::Subscriber subOdometry_
Definition: rawlog_record_node.h:122
ros::Time
RawlogRecordNode::last_range_scan_
mrpt::obs::CObservation2DRangeScan::Ptr last_range_scan_
Definition: rawlog_record_node.h:129
RawlogRecordNode::sync_attempts_sensor_frame_
unsigned int sync_attempts_sensor_frame_
Definition: rawlog_record_node.h:131
RawlogRecordNode::ParametersNode::callbackParameters
void callbackParameters(mrpt_rawlog::RawLogRecordConfig &config, uint32_t level)
Definition: rawlog_record_node_parameters.cpp:83
tf2_geometry_msgs.h
RawlogRecordNode::param_
ParametersNode param_
Definition: rawlog_record_node.h:117
RawlogRecordNode::ParametersNode::parameter_update_skip
int parameter_update_skip
Definition: rawlog_record_node.h:131
ros::Duration
RawlogRecord::base_param_
Parameters base_param_
Definition: rawlog_record.h:77
RawlogRecordNode::waitForTransform
bool 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=ros::Duration(0.01))
Definition: rawlog_record_node.cpp:79
ros::NodeHandle
ros::Subscriber


mrpt_rawlog
Author(s):
autogenerated on Tue Sep 17 2024 02:10:22