44 ROS_INFO(
"parameter_update_skip: %i", parameter_update_skip);
46 ROS_INFO(
"rawlog_file: %s", rawlog_file.c_str());
48 ROS_INFO(
"odom_frame: %s", odom_frame.c_str());
50 ROS_INFO(
"base_frame: %s", base_frame.c_str());
52 ROS_INFO(
"tf_prefix: %s", tf_prefix.c_str());
62 if (loop_count == 0)
ROS_INFO(
"debug: %s", (debug ?
"true" :
"false"));
66 mrpt_rawlog::RawLogRecordConfig& config, uint32_t level)
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);
82 "gaussianModel.minStdXY: %f",
83 motionModelOptions.gaussianModel.minStdXY);
85 "gaussianModel.minStdPHI: %f",
86 motionModelOptions.gaussianModel.minStdPHI);
#define RAWLOG_PLAY_NODE_DEFAULT_PARAMETER_UPDATE_SKIP
void callbackParameters(mrpt_rawlog::RawLogRecordConfig &config, uint32_t level)
static const int MOTION_MODEL_GAUSSIAN
int parameter_update_skip
#define RAWLOG_PLAY_NODE_DEFAULT_RATE
void update(const unsigned long &loop_count)
bool param(const std::string ¶m_name, T ¶m_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