37 #include <mrpt/version.h> 42 : node(
"~"), base_param_(base_params)
49 ROS_INFO(
"parameter_update_skip: %i", parameter_update_skip);
51 ROS_INFO(
"tf_prefix: %s", tf_prefix.c_str());
53 ROS_INFO(
"odom_frame_id: %s", odom_frame_id.c_str());
55 ROS_INFO(
"base_frame_id: %s", base_frame_id.c_str());
64 "record_range_scan: %s",
69 "record_bearing_range: %s",
74 "record_beacon_range: %s",
96 motionModelOptions.
modelSelection = CActionRobotMovement2D::mmGaussian;
97 motionModelOptions.gaussianModel.a1 = config.motion_gaussian_alpha_1;
98 motionModelOptions.gaussianModel.a2 = config.motion_gaussian_alpha_2;
99 motionModelOptions.gaussianModel.a3 = config.motion_gaussian_alpha_3;
100 motionModelOptions.gaussianModel.a4 = config.motion_gaussian_alpha_4;
101 motionModelOptions.gaussianModel.minStdXY =
102 config.motion_gaussian_alpha_xy;
103 motionModelOptions.gaussianModel.minStdPHI =
104 config.motion_gaussian_alpha_phi;
105 ROS_INFO(
"gaussianModel.a1: %f", motionModelOptions.gaussianModel.a1);
106 ROS_INFO(
"gaussianModel.a2: %f", motionModelOptions.gaussianModel.a2);
107 ROS_INFO(
"gaussianModel.a3: %f", motionModelOptions.gaussianModel.a3);
108 ROS_INFO(
"gaussianModel.a4: %f", motionModelOptions.gaussianModel.a4);
110 "gaussianModel.minStdXY: %f",
111 motionModelOptions.gaussianModel.minStdXY);
113 "gaussianModel.minStdPHI: %f",
114 motionModelOptions.gaussianModel.minStdPHI);
120 "bearing_range_std_range: %f",
125 "bearing_range_std_pitch: %f",
double bearing_range_std_pitch
TDrawSampleMotionModel modelSelection
ParametersNode(RawlogRecord::Parameters &base_params)
dynamic_reconfigure::Server< mrpt_rawlog::RawLogRecordConfig >::CallbackType reconfigureFnc_
double sensor_frame_sync_threshold
RawlogRecord::Parameters & base_param_
static const int MOTION_MODEL_GAUSSIAN
double bearing_range_std_range
CActionRobotMovement2D::TMotionModelOptions motionModelOptions
std::string odom_frame_id
#define RAWLOG_RECORD_NODE_DEFAULT_RATE
std::string base_frame_id
double bearing_range_std_yaw
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
#define RAWLOG_RECORD_NODE_DEFAULT_PARAMETER_UPDATE_SKIP
dynamic_reconfigure::Server< mrpt_rawlog::RawLogRecordConfig > reconfigureServer_
bool getParam(const std::string &key, std::string &s) const
std::string raw_log_folder
int parameter_update_skip
void update(const unsigned long &loop_count)
void callbackParameters(mrpt_rawlog::RawLogRecordConfig &config, uint32_t level)
bool record_bearing_range