46 std::numeric_limits<double>::infinity());
97 if (loop_count % parameter_update_skip)
return;
98 node.getParam(
"debug", debug);
99 if (loop_count == 0)
ROS_INFO(
"debug: %s", debug ?
"true" :
"false");
101 int v = particlecloud_update_skip;
103 "particlecloud_update_skip", particlecloud_update_skip,
105 if (v != particlecloud_update_skip)
107 "particlecloud_update_skip: %i", particlecloud_update_skip);
110 int v = map_update_skip;
112 "map_update_skip", map_update_skip,
114 if (v != map_update_skip)
115 ROS_INFO(
"map_update_skip: %i", map_update_skip);
120 mrpt_localization::MotionConfig& config, uint32_t level)
122 if (config.motion_noise_type == MOTION_MODEL_GAUSSIAN)
124 motion_model_options->modelSelection =
125 CActionRobotMovement2D::mmGaussian;
127 motion_model_options->gaussianModel.a1 = config.gaussian_alpha_1;
128 motion_model_options->gaussianModel.a2 = config.gaussian_alpha_2;
129 motion_model_options->gaussianModel.a3 = config.gaussian_alpha_3;
130 motion_model_options->gaussianModel.a4 = config.gaussian_alpha_4;
131 motion_model_options->gaussianModel.minStdXY = config.gaussian_alpha_xy;
132 motion_model_options->gaussianModel.minStdPHI =
133 config.gaussian_alpha_phi;
134 ROS_INFO(
"gaussianModel.type: gaussian");
136 "gaussianModel.a1: %f", motion_model_options->gaussianModel.a1);
138 "gaussianModel.a2: %f", motion_model_options->gaussianModel.a2);
140 "gaussianModel.a3: %f", motion_model_options->gaussianModel.a3);
142 "gaussianModel.a4: %f", motion_model_options->gaussianModel.a4);
144 "gaussianModel.minStdXY: %f",
145 motion_model_options->gaussianModel.minStdXY);
147 "gaussianModel.minStdPHI: %f",
148 motion_model_options->gaussianModel.minStdPHI);
152 ROS_INFO(
"We support at the moment only gaussian motion models");
154 *use_motion_model_default_options = config.use_default_motion;
156 "use_motion_model_default_options: %s",
157 use_motion_model_default_options ?
"true" :
"false");
158 motion_model_default_options->gaussianModel.minStdXY =
159 config.default_noise_xy;
161 "default_noise_xy: %f",
162 motion_model_default_options->gaussianModel.minStdXY);
163 motion_model_default_options->gaussianModel.minStdPHI =
164 config.default_noise_phi;
166 "default_noise_phi: %f",
167 motion_model_default_options->gaussianModel.minStdPHI);
168 update_while_stopped = config.update_while_stopped;
170 "update_while_stopped: %s", update_while_stopped ?
"true" :
"false");
171 update_sensor_pose = config.update_sensor_pose;
172 ROS_INFO(
"update_sensor_pose: %s", update_sensor_pose ?
"true" :
"false");