58 if (loop_count % parameter_update_skip)
return;
59 node.getParam(
"debug", debug);
60 if (loop_count == 0)
ROS_INFO(
"debug: %s", (debug ?
"true" :
"false"));
64 mrpt_rawlog::RawLogRecordConfig& config, uint32_t level)
66 using mrpt::obs::CActionRobotMovement2D;
68 if (config.motion_noise_type == MOTION_MODEL_GAUSSIAN)
70 auto& m = motionModelOptions;
72 m.modelSelection = CActionRobotMovement2D::mmGaussian;
73 m.gaussianModel.a1 = config.motion_gaussian_alpha_1;
74 m.gaussianModel.a2 = config.motion_gaussian_alpha_2;
75 m.gaussianModel.a3 = config.motion_gaussian_alpha_3;
76 m.gaussianModel.a4 = config.motion_gaussian_alpha_4;
77 m.gaussianModel.minStdXY = config.motion_gaussian_alpha_xy;
78 m.gaussianModel.minStdPHI = config.motion_gaussian_alpha_phi;
80 ROS_INFO(
"gaussianModel.a1: %f", m.gaussianModel.a1);
81 ROS_INFO(
"gaussianModel.a2: %f", m.gaussianModel.a2);
82 ROS_INFO(
"gaussianModel.a3: %f", m.gaussianModel.a3);
83 ROS_INFO(
"gaussianModel.a4: %f", m.gaussianModel.a4);
84 ROS_INFO(
"gaussianModel.minStdXY: %f", m.gaussianModel.minStdXY);
85 ROS_INFO(
"gaussianModel.minStdPHI: %f", m.gaussianModel.minStdPHI);