rawlog_play_node_parameters.cpp
Go to the documentation of this file.
00001 /***********************************************************************************
00002  * Revised BSD License *
00003  * Copyright (c) 2014, Markus Bader <markus.bader@tuwien.ac.at> *
00004  * All rights reserved. *
00005  *                                                                                 *
00006  * Redistribution and use in source and binary forms, with or without *
00007  * modification, are permitted provided that the following conditions are met: *
00008  *     * Redistributions of source code must retain the above copyright *
00009  *       notice, this list of conditions and the following disclaimer. *
00010  *     * Redistributions in binary form must reproduce the above copyright *
00011  *       notice, this list of conditions and the following disclaimer in the *
00012  *       documentation and/or other materials provided with the distribution. *
00013  *     * Neither the name of the Vienna University of Technology nor the *
00014  *       names of its contributors may be used to endorse or promote products *
00015  *       derived from this software without specific prior written permission. *
00016  *                                                                                 *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  *AND *
00019  * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00020  **
00021  * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE *
00022  * DISCLAIMED. IN NO EVENT SHALL Markus Bader BE LIABLE FOR ANY *
00023  * DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES *
00024  * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00025  **
00026  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND *
00027  * ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT *
00028  * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00029  **
00030  * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00031  **                       *
00032  ***********************************************************************************/
00033 
00034 #include "rawlog_play_node.h"
00035 #include "rawlog_play_node_defaults.h"
00036 
00037 RawlogPlayNode::ParametersNode::ParametersNode() : Parameters(), node("~")
00038 {
00039         node.param<double>("rate", rate, RAWLOG_PLAY_NODE_DEFAULT_RATE);
00040         ROS_INFO("rate: %f", rate);
00041         node.param<int>(
00042                 "parameter_update_skip", parameter_update_skip,
00043                 RAWLOG_PLAY_NODE_DEFAULT_PARAMETER_UPDATE_SKIP);
00044         ROS_INFO("parameter_update_skip: %i", parameter_update_skip);
00045         node.getParam("rawlog_file", rawlog_file);
00046         ROS_INFO("rawlog_file: %s", rawlog_file.c_str());
00047         node.param<std::string>("odom_frame", odom_frame, "odom");
00048         ROS_INFO("odom_frame: %s", odom_frame.c_str());
00049         node.param<std::string>("base_frame", base_frame, "base_link");
00050         ROS_INFO("base_frame: %s", base_frame.c_str());
00051         node.param<std::string>("tf_prefix", tf_prefix, "");
00052         ROS_INFO("tf_prefix: %s", tf_prefix.c_str());
00053         reconfigureFnc_ = boost::bind(
00054                 &RawlogPlayNode::ParametersNode::callbackParameters, this, _1, _2);
00055         reconfigureServer_.setCallback(reconfigureFnc_);
00056 }
00057 
00058 void RawlogPlayNode::ParametersNode::update(const unsigned long& loop_count)
00059 {
00060         if (loop_count % parameter_update_skip) return;
00061         node.getParam("debug", debug);
00062         if (loop_count == 0) ROS_INFO("debug:  %s", (debug ? "true" : "false"));
00063 }
00064 
00065 void RawlogPlayNode::ParametersNode::callbackParameters(
00066         mrpt_rawlog::RawLogRecordConfig& config, uint32_t level)
00067 {
00068         if (config.motion_noise_type == MOTION_MODEL_GAUSSIAN)
00069         {
00070                 motionModelOptions.modelSelection = CActionRobotMovement2D::mmGaussian;
00071                 motionModelOptions.gaussianModel.a1 = config.motion_gaussian_alpha_1;
00072                 motionModelOptions.gaussianModel.a2 = config.motion_gaussian_alpha_2;
00073                 motionModelOptions.gaussianModel.a3 = config.motion_gaussian_alpha_3;
00074                 motionModelOptions.gaussianModel.a4 = config.motion_gaussian_alpha_4;
00075                 motionModelOptions.gaussianModel.minStdXY = config.motion_gaussian_alpha_xy;
00076                 motionModelOptions.gaussianModel.minStdPHI = config.motion_gaussian_alpha_phi;
00077                 ROS_INFO("gaussianModel.a1: %f", motionModelOptions.gaussianModel.a1);
00078                 ROS_INFO("gaussianModel.a2: %f", motionModelOptions.gaussianModel.a2);
00079                 ROS_INFO("gaussianModel.a3: %f", motionModelOptions.gaussianModel.a3);
00080                 ROS_INFO("gaussianModel.a4: %f", motionModelOptions.gaussianModel.a4);
00081                 ROS_INFO(
00082                         "gaussianModel.minStdXY: %f",
00083                         motionModelOptions.gaussianModel.minStdXY);
00084                 ROS_INFO(
00085                         "gaussianModel.minStdPHI: %f",
00086                         motionModelOptions.gaussianModel.minStdPHI);
00087         }
00088 }


mrpt_rawlog
Author(s):
autogenerated on Thu Jun 6 2019 21:53:23