00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034 #include "mrpt_localization_node.h"
00035 #include "mrpt_localization_node_defaults.h"
00036
00037 PFLocalizationNode::Parameters::Parameters(PFLocalizationNode* p)
00038 : PFLocalization::Parameters(p), node("~")
00039 {
00040 node.param<double>("transform_tolerance", transform_tolerance, 0.1);
00041 ROS_INFO("transform_tolerance: %f", transform_tolerance);
00042 node.param<double>("no_update_tolerance", no_update_tolerance, 1.0);
00043 ROS_INFO("no_update_tolerance: %f", no_update_tolerance);
00044 node.param<double>(
00045 "no_inputs_tolerance", no_inputs_tolerance,
00046 std::numeric_limits<double>::infinity());
00047 ROS_INFO(
00048 "no_inputs_tolerance: %f", no_inputs_tolerance);
00049 node.param<double>("rate", rate, MRPT_LOCALIZATION_NODE_DEFAULT_RATE);
00050 ROS_INFO("rate: %f", rate);
00051 node.getParam("gui_mrpt", gui_mrpt);
00052 ROS_INFO("gui_mrpt: %s", gui_mrpt ? "true" : "false");
00053 node.param<int>(
00054 "parameter_update_skip", parameter_update_skip,
00055 MRPT_LOCALIZATION_NODE_DEFAULT_PARAMETER_UPDATE_SKIP);
00056 ROS_INFO("parameter_update_skip: %i", parameter_update_skip);
00057 node.getParam("ini_file", ini_file);
00058 ROS_INFO("ini_file: %s", ini_file.c_str());
00059 node.getParam("map_file", map_file);
00060 ROS_INFO("map_file: %s", map_file.c_str());
00061 node.getParam("sensor_sources", sensor_sources);
00062 ROS_INFO("sensor_sources: %s", sensor_sources.c_str());
00063 node.param<std::string>("tf_prefix", tf_prefix, "");
00064 ROS_INFO("tf_prefix: %s", tf_prefix.c_str());
00065 node.param<std::string>("global_frame_id", global_frame_id, "map");
00066 ROS_INFO("global_frame_id: %s", global_frame_id.c_str());
00067 node.param<std::string>("odom_frame_id", odom_frame_id, "odom");
00068 ROS_INFO("odom_frame_id: %s", odom_frame_id.c_str());
00069 node.param<std::string>("base_frame_id", base_frame_id, "base_link");
00070 ROS_INFO("base_frame_id: %s", base_frame_id.c_str());
00071 node.param<bool>("pose_broadcast", pose_broadcast, false);
00072 ROS_INFO("pose_broadcast: %s", pose_broadcast ? "true" : "false");
00073 node.param<bool>("tf_broadcast", tf_broadcast, true);
00074 ROS_INFO("tf_broadcast: %s", tf_broadcast ? "true" : "false");
00075 node.param<bool>("use_map_topic", use_map_topic, false);
00076 ROS_INFO("use_map_topic: %s", use_map_topic ? "true" : "false");
00077 node.param<bool>("first_map_only", first_map_only, false);
00078 ROS_INFO("first_map_only: %s", first_map_only ? "true" : "false");
00079 node.param<bool>("debug", debug, true);
00080 ROS_INFO("debug: %s", debug ? "true" : "false");
00081
00082 reconfigure_cb_ = boost::bind(
00083 &PFLocalizationNode::Parameters::callbackParameters, this, _1, _2);
00084 reconfigure_server_.setCallback(reconfigure_cb_);
00085 }
00086
00087 void PFLocalizationNode::Parameters::update(const unsigned long& loop_count)
00088 {
00089 if (loop_count % parameter_update_skip) return;
00090 node.getParam("debug", debug);
00091 if (loop_count == 0) ROS_INFO("debug: %s", debug ? "true" : "false");
00092 {
00093 int v = particlecloud_update_skip;
00094 node.param<int>(
00095 "particlecloud_update_skip", particlecloud_update_skip,
00096 MRPT_LOCALIZATION_NODE_DEFAULT_PARTICLECLOUD_UPDATE_SKIP);
00097 if (v != particlecloud_update_skip)
00098 ROS_INFO(
00099 "particlecloud_update_skip: %i", particlecloud_update_skip);
00100 }
00101 {
00102 int v = map_update_skip;
00103 node.param<int>(
00104 "map_update_skip", map_update_skip,
00105 MRPT_LOCALIZATION_NODE_DEFAULT_MAP_UPDATE_SKIP);
00106 if (v != map_update_skip)
00107 ROS_INFO("map_update_skip: %i", map_update_skip);
00108 }
00109 }
00110
00111 void PFLocalizationNode::Parameters::callbackParameters(
00112 mrpt_localization::MotionConfig& config, uint32_t level)
00113 {
00114 if (config.motion_noise_type == MOTION_MODEL_GAUSSIAN)
00115 {
00116 motion_model_options->modelSelection =
00117 CActionRobotMovement2D::mmGaussian;
00118
00119 motion_model_options->gaussianModel.a1 = config.gaussian_alpha_1;
00120 motion_model_options->gaussianModel.a2 = config.gaussian_alpha_2;
00121 motion_model_options->gaussianModel.a3 = config.gaussian_alpha_3;
00122 motion_model_options->gaussianModel.a4 = config.gaussian_alpha_4;
00123 motion_model_options->gaussianModel.minStdXY = config.gaussian_alpha_xy;
00124 motion_model_options->gaussianModel.minStdPHI =
00125 config.gaussian_alpha_phi;
00126 ROS_INFO("gaussianModel.type: gaussian");
00127 ROS_INFO(
00128 "gaussianModel.a1: %f", motion_model_options->gaussianModel.a1);
00129 ROS_INFO(
00130 "gaussianModel.a2: %f", motion_model_options->gaussianModel.a2);
00131 ROS_INFO(
00132 "gaussianModel.a3: %f", motion_model_options->gaussianModel.a3);
00133 ROS_INFO(
00134 "gaussianModel.a4: %f", motion_model_options->gaussianModel.a4);
00135 ROS_INFO(
00136 "gaussianModel.minStdXY: %f",
00137 motion_model_options->gaussianModel.minStdXY);
00138 ROS_INFO(
00139 "gaussianModel.minStdPHI: %f",
00140 motion_model_options->gaussianModel.minStdPHI);
00141 }
00142 else
00143 {
00144 ROS_INFO("We support at the moment only gaussian motion models");
00145 }
00146 *use_motion_model_default_options = config.use_default_motion;
00147 ROS_INFO(
00148 "use_motion_model_default_options: %s",
00149 use_motion_model_default_options ? "true" : "false");
00150 motion_model_default_options->gaussianModel.minStdXY =
00151 config.default_noise_xy;
00152 ROS_INFO(
00153 "default_noise_xy: %f",
00154 motion_model_default_options->gaussianModel.minStdXY);
00155 motion_model_default_options->gaussianModel.minStdPHI =
00156 config.default_noise_phi;
00157 ROS_INFO(
00158 "default_noise_phi: %f",
00159 motion_model_default_options->gaussianModel.minStdPHI);
00160 update_while_stopped = config.update_while_stopped;
00161 ROS_INFO(
00162 "update_while_stopped: %s", update_while_stopped ? "true" : "false");
00163 }