41 ROS_INFO(
"transform_tolerance: %f", transform_tolerance);
43 ROS_INFO(
"no_update_tolerance: %f", no_update_tolerance);
46 std::numeric_limits<double>::infinity());
48 "no_inputs_tolerance: %f", no_inputs_tolerance);
50 ROS_INFO(
"rate: %f", rate);
52 ROS_INFO(
"gui_mrpt: %s",
gui_mrpt ?
"true" :
"false");
56 ROS_INFO(
"parameter_update_skip: %i", parameter_update_skip);
58 ROS_INFO(
"ini_file: %s",
ini_file.c_str());
60 ROS_INFO(
"map_file: %s",
map_file.c_str());
64 ROS_INFO(
"tf_prefix: %s", tf_prefix.c_str());
66 ROS_INFO(
"global_frame_id: %s", global_frame_id.c_str());
68 ROS_INFO(
"odom_frame_id: %s", odom_frame_id.c_str());
70 ROS_INFO(
"base_frame_id: %s", base_frame_id.c_str());
72 ROS_INFO(
"pose_broadcast: %s", pose_broadcast ?
"true" :
"false");
74 ROS_INFO(
"tf_broadcast: %s", tf_broadcast ?
"true" :
"false");
76 ROS_INFO(
"use_map_topic: %s", use_map_topic ?
"true" :
"false");
78 ROS_INFO(
"first_map_only: %s", first_map_only ?
"true" :
"false");
80 ROS_INFO(
"debug: %s", debug ?
"true" :
"false");
91 if (loop_count == 0)
ROS_INFO(
"debug: %s",
debug ?
"true" :
"false");
97 if (v != particlecloud_update_skip)
99 "particlecloud_update_skip: %i", particlecloud_update_skip);
106 if (v != map_update_skip)
107 ROS_INFO(
"map_update_skip: %i", map_update_skip);
117 CActionRobotMovement2D::mmGaussian;
125 config.gaussian_alpha_phi;
126 ROS_INFO(
"gaussianModel.type: gaussian");
136 "gaussianModel.minStdXY: %f",
139 "gaussianModel.minStdPHI: %f",
144 ROS_INFO(
"We support at the moment only gaussian motion models");
148 "use_motion_model_default_options: %s",
151 config.default_noise_xy;
153 "default_noise_xy: %f",
156 config.default_noise_phi;
158 "default_noise_phi: %f",
std::string base_frame_id
Parameters(PFLocalizationNode *p)
#define MRPT_LOCALIZATION_NODE_DEFAULT_PARTICLECLOUD_UPDATE_SKIP
TDrawSampleMotionModel modelSelection
dynamic_reconfigure::Server< mrpt_localization::MotionConfig > reconfigure_server_
std::string global_frame_id
#define MRPT_LOCALIZATION_NODE_DEFAULT_PARAMETER_UPDATE_SKIP
struct OBS_IMPEXP mrpt::obs::CActionRobotMovement2D::TMotionModelOptions::TOptions_GaussianModel gaussianModel
int parameter_update_skip
we wait before start complaining
bool * use_motion_model_default_options
dynamic_reconfigure::Server< mrpt_localization::MotionConfig >::CallbackType reconfigure_cb_
void callbackParameters(mrpt_localization::MotionConfig &config, uint32_t level)
CActionRobotMovement2D::TMotionModelOptions * motion_model_options
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
static const int MOTION_MODEL_GAUSSIAN
#define MRPT_LOCALIZATION_NODE_DEFAULT_MAP_UPDATE_SKIP
CActionRobotMovement2D::TMotionModelOptions * motion_model_default_options
std::string odom_frame_id
double transform_tolerance
std::string sensor_sources
bool update_while_stopped
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
int particlecloud_update_skip
#define MRPT_LOCALIZATION_NODE_DEFAULT_RATE
double no_update_tolerance
the published tf to extend its validity