rawlog_play_node_parameters.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"
36 
38 {
39  node.param<double>("rate", rate, RAWLOG_PLAY_NODE_DEFAULT_RATE);
40  ROS_INFO("rate: %f", rate);
41  node.param<int>(
42  "parameter_update_skip", parameter_update_skip,
44  ROS_INFO("parameter_update_skip: %i", parameter_update_skip);
45  node.getParam("rawlog_file", rawlog_file);
46  ROS_INFO("rawlog_file: %s", rawlog_file.c_str());
47  node.param<std::string>("odom_frame", odom_frame, "odom");
48  ROS_INFO("odom_frame: %s", odom_frame.c_str());
49  node.param<std::string>("base_frame", base_frame, "base_link");
50  ROS_INFO("base_frame: %s", base_frame.c_str());
51  node.param<std::string>("tf_prefix", tf_prefix, "");
52  ROS_INFO("tf_prefix: %s", tf_prefix.c_str());
53  reconfigureFnc_ = boost::bind(
55  reconfigureServer_.setCallback(reconfigureFnc_);
56 }
57 
58 void RawlogPlayNode::ParametersNode::update(const unsigned long& loop_count)
59 {
60  if (loop_count % parameter_update_skip) return;
61  node.getParam("debug", debug);
62  if (loop_count == 0) ROS_INFO("debug: %s", (debug ? "true" : "false"));
63 }
64 
66  mrpt_rawlog::RawLogRecordConfig& config, uint32_t level)
67 {
68  if (config.motion_noise_type == MOTION_MODEL_GAUSSIAN)
69  {
70  motionModelOptions.modelSelection = CActionRobotMovement2D::mmGaussian;
71  motionModelOptions.gaussianModel.a1 = config.motion_gaussian_alpha_1;
72  motionModelOptions.gaussianModel.a2 = config.motion_gaussian_alpha_2;
73  motionModelOptions.gaussianModel.a3 = config.motion_gaussian_alpha_3;
74  motionModelOptions.gaussianModel.a4 = config.motion_gaussian_alpha_4;
75  motionModelOptions.gaussianModel.minStdXY = config.motion_gaussian_alpha_xy;
76  motionModelOptions.gaussianModel.minStdPHI = config.motion_gaussian_alpha_phi;
77  ROS_INFO("gaussianModel.a1: %f", motionModelOptions.gaussianModel.a1);
78  ROS_INFO("gaussianModel.a2: %f", motionModelOptions.gaussianModel.a2);
79  ROS_INFO("gaussianModel.a3: %f", motionModelOptions.gaussianModel.a3);
80  ROS_INFO("gaussianModel.a4: %f", motionModelOptions.gaussianModel.a4);
81  ROS_INFO(
82  "gaussianModel.minStdXY: %f",
83  motionModelOptions.gaussianModel.minStdXY);
84  ROS_INFO(
85  "gaussianModel.minStdPHI: %f",
86  motionModelOptions.gaussianModel.minStdPHI);
87  }
88 }
#define RAWLOG_PLAY_NODE_DEFAULT_PARAMETER_UPDATE_SKIP
void callbackParameters(mrpt_rawlog::RawLogRecordConfig &config, uint32_t level)
static const int MOTION_MODEL_GAUSSIAN
#define RAWLOG_PLAY_NODE_DEFAULT_RATE
void update(const unsigned long &loop_count)
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
dynamic_reconfigure::Server< mrpt_rawlog::RawLogRecordConfig > reconfigureServer_
dynamic_reconfigure::Server< mrpt_rawlog::RawLogRecordConfig >::CallbackType reconfigureFnc_
bool getParam(const std::string &key, std::string &s) const


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