mrpt_localization_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 "mrpt_localization_node.h"
36 
38  : PFLocalization::Parameters(p), node("~")
39 {
40  node.param<double>("transform_tolerance", transform_tolerance, 0.1);
41  ROS_INFO("transform_tolerance: %f", transform_tolerance);
42  node.param<double>("no_update_tolerance", no_update_tolerance, 1.0);
43  ROS_INFO("no_update_tolerance: %f", no_update_tolerance);
44  node.param<double>(
45  "no_inputs_tolerance", no_inputs_tolerance,
46  std::numeric_limits<double>::infinity());
47  ROS_INFO(
48  "no_inputs_tolerance: %f", no_inputs_tolerance); // disabled by default
50  ROS_INFO("rate: %f", rate);
51  node.getParam("gui_mrpt", gui_mrpt);
52  ROS_INFO("gui_mrpt: %s", gui_mrpt ? "true" : "false");
53  node.param<int>(
54  "parameter_update_skip", parameter_update_skip,
56  ROS_INFO("parameter_update_skip: %i", parameter_update_skip);
57  node.getParam("ini_file", ini_file);
58  ROS_INFO("ini_file: %s", ini_file.c_str());
59  node.getParam("map_file", map_file);
60  ROS_INFO("map_file: %s", map_file.c_str());
61  node.getParam("sensor_sources", sensor_sources);
62  ROS_INFO("sensor_sources: %s", sensor_sources.c_str());
63  node.param<std::string>("tf_prefix", tf_prefix, "");
64  ROS_INFO("tf_prefix: %s", tf_prefix.c_str());
65  node.param<std::string>("global_frame_id", global_frame_id, "map");
66  ROS_INFO("global_frame_id: %s", global_frame_id.c_str());
67  node.param<std::string>("odom_frame_id", odom_frame_id, "odom");
68  ROS_INFO("odom_frame_id: %s", odom_frame_id.c_str());
69  node.param<std::string>("base_frame_id", base_frame_id, "base_link");
70  ROS_INFO("base_frame_id: %s", base_frame_id.c_str());
71  node.param<bool>("pose_broadcast", pose_broadcast, false);
72  ROS_INFO("pose_broadcast: %s", pose_broadcast ? "true" : "false");
73  node.param<bool>("tf_broadcast", tf_broadcast, true);
74  ROS_INFO("tf_broadcast: %s", tf_broadcast ? "true" : "false");
75  node.param<bool>("use_map_topic", use_map_topic, false);
76  ROS_INFO("use_map_topic: %s", use_map_topic ? "true" : "false");
77  node.param<bool>("first_map_only", first_map_only, false);
78  ROS_INFO("first_map_only: %s", first_map_only ? "true" : "false");
79  node.param<bool>("debug", debug, true);
80  ROS_INFO("debug: %s", debug ? "true" : "false");
81 
82  reconfigure_cb_ = boost::bind(
85 }
86 
87 void PFLocalizationNode::Parameters::update(const unsigned long& loop_count)
88 {
89  if (loop_count % parameter_update_skip) return;
90  node.getParam("debug", debug);
91  if (loop_count == 0) ROS_INFO("debug: %s", debug ? "true" : "false");
92  {
94  node.param<int>(
95  "particlecloud_update_skip", particlecloud_update_skip,
97  if (v != particlecloud_update_skip)
98  ROS_INFO(
99  "particlecloud_update_skip: %i", particlecloud_update_skip);
100  }
101  {
102  int v = map_update_skip;
103  node.param<int>(
104  "map_update_skip", map_update_skip,
106  if (v != map_update_skip)
107  ROS_INFO("map_update_skip: %i", map_update_skip);
108  }
109 }
110 
112  mrpt_localization::MotionConfig& config, uint32_t level)
113 {
114  if (config.motion_noise_type == MOTION_MODEL_GAUSSIAN)
115  {
116  motion_model_options->modelSelection =
117  CActionRobotMovement2D::mmGaussian;
118 
119  motion_model_options->gaussianModel.a1 = config.gaussian_alpha_1;
120  motion_model_options->gaussianModel.a2 = config.gaussian_alpha_2;
121  motion_model_options->gaussianModel.a3 = config.gaussian_alpha_3;
122  motion_model_options->gaussianModel.a4 = config.gaussian_alpha_4;
123  motion_model_options->gaussianModel.minStdXY = config.gaussian_alpha_xy;
124  motion_model_options->gaussianModel.minStdPHI =
125  config.gaussian_alpha_phi;
126  ROS_INFO("gaussianModel.type: gaussian");
127  ROS_INFO(
128  "gaussianModel.a1: %f", motion_model_options->gaussianModel.a1);
129  ROS_INFO(
130  "gaussianModel.a2: %f", motion_model_options->gaussianModel.a2);
131  ROS_INFO(
132  "gaussianModel.a3: %f", motion_model_options->gaussianModel.a3);
133  ROS_INFO(
134  "gaussianModel.a4: %f", motion_model_options->gaussianModel.a4);
135  ROS_INFO(
136  "gaussianModel.minStdXY: %f",
137  motion_model_options->gaussianModel.minStdXY);
138  ROS_INFO(
139  "gaussianModel.minStdPHI: %f",
140  motion_model_options->gaussianModel.minStdPHI);
141  }
142  else
143  {
144  ROS_INFO("We support at the moment only gaussian motion models");
145  }
146  *use_motion_model_default_options = config.use_default_motion;
147  ROS_INFO(
148  "use_motion_model_default_options: %s",
149  use_motion_model_default_options ? "true" : "false");
150  motion_model_default_options->gaussianModel.minStdXY =
151  config.default_noise_xy;
152  ROS_INFO(
153  "default_noise_xy: %f",
154  motion_model_default_options->gaussianModel.minStdXY);
155  motion_model_default_options->gaussianModel.minStdPHI =
156  config.default_noise_phi;
157  ROS_INFO(
158  "default_noise_phi: %f",
159  motion_model_default_options->gaussianModel.minStdPHI);
160  update_while_stopped = config.update_while_stopped;
161  ROS_INFO(
162  "update_while_stopped: %s", update_while_stopped ? "true" : "false");
163 }
#define MRPT_LOCALIZATION_NODE_DEFAULT_PARTICLECLOUD_UPDATE_SKIP
dynamic_reconfigure::Server< mrpt_localization::MotionConfig > reconfigure_server_
#define MRPT_LOCALIZATION_NODE_DEFAULT_PARAMETER_UPDATE_SKIP
int parameter_update_skip
we wait before start complaining
dynamic_reconfigure::Server< mrpt_localization::MotionConfig >::CallbackType reconfigure_cb_
void callbackParameters(mrpt_localization::MotionConfig &config, uint32_t level)
CActionRobotMovement2D::TMotionModelOptions * motion_model_options
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
#define MRPT_LOCALIZATION_NODE_DEFAULT_MAP_UPDATE_SKIP
CActionRobotMovement2D::TMotionModelOptions * motion_model_default_options
void update(const unsigned long &loop_count)
double no_inputs_tolerance
using filter time instead of Time::now
bool getParam(const std::string &key, std::string &s) const
#define MRPT_LOCALIZATION_NODE_DEFAULT_RATE
double no_update_tolerance
the published tf to extend its validity


mrpt_localization
Author(s): Markus Bader, Raphael Zack
autogenerated on Thu Jun 6 2019 19:44:49