parameters.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2016-2018, the mcl_3dl authors
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the copyright holder nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 #ifndef MCL_3DL_PARAMETERS_H
30 #define MCL_3DL_PARAMETERS_H
31 
32 #include <map>
33 #include <memory>
34 #include <string>
35 
36 #include <ros/ros.h>
37 
38 #include <mcl_3dl/quat.h>
39 #include <mcl_3dl/state_6dof.h>
40 #include <mcl_3dl/vec3.h>
41 
42 namespace mcl_3dl
43 {
45 {
46 public:
47  bool load(ros::NodeHandle& nh);
48 
56  double map_grid_min_;
57  double map_grid_max_;
60  double downsample_x_;
61  double downsample_y_;
62  double downsample_z_;
76  double jump_dist_;
77  double jump_ang_;
78  double fix_dist_;
79  double fix_ang_;
84  std::shared_ptr<ros::Duration> map_update_interval_;
92  double bias_var_ang_;
93  double acc_var_;
98  std::shared_ptr<ros::Duration> match_output_interval_;
99  std::shared_ptr<ros::Duration> tf_tolerance_;
100  double lpf_step_;
102  std::array<float, 4> dist_weight_;
105  double map_chunk_;
106  std::map<std::string, std::string> frame_ids_;
107  std::array<float, 3> std_warn_thresh_;
111 };
112 } // namespace mcl_3dl
113 
114 #endif // MCL_3DL_PARAMETERS_H
mcl_3dl::Parameters::bias_var_ang_
double bias_var_ang_
Definition: parameters.h:92
mcl_3dl::Parameters::expansion_var_yaw_
double expansion_var_yaw_
Definition: parameters.h:74
mcl_3dl::Parameters::fake_odom_
bool fake_odom_
Definition: parameters.h:49
mcl_3dl::Parameters
Definition: parameters.h:44
mcl_3dl::Parameters::acc_var_
double acc_var_
Definition: parameters.h:93
mcl_3dl::Parameters::expansion_var_z_
double expansion_var_z_
Definition: parameters.h:71
mcl_3dl::Parameters::fix_dist_
double fix_dist_
Definition: parameters.h:78
mcl_3dl::Parameters::global_localization_grid_
double global_localization_grid_
Definition: parameters.h:58
mcl_3dl::Parameters::update_downsample_y_
double update_downsample_y_
Definition: parameters.h:54
mcl_3dl::Parameters::update_downsample_x_
double update_downsample_x_
Definition: parameters.h:53
mcl_3dl::Parameters::downsample_y_
double downsample_y_
Definition: parameters.h:61
mcl_3dl::Parameters::downsample_x_
double downsample_x_
Definition: parameters.h:60
mcl_3dl::Parameters::resample_var_pitch_
double resample_var_pitch_
Definition: parameters.h:67
mcl_3dl::Parameters::publish_tf_
bool publish_tf_
Definition: parameters.h:104
mcl_3dl::Parameters::skip_measure_
int skip_measure_
Definition: parameters.h:86
mcl_3dl::Parameters::dist_weight_
std::array< float, 4 > dist_weight_
Definition: parameters.h:102
ros.h
mcl_3dl::Parameters::total_accum_cloud_max_
int total_accum_cloud_max_
Definition: parameters.h:88
mcl_3dl::Parameters::jump_ang_
double jump_ang_
Definition: parameters.h:77
mcl_3dl::Parameters::resample_var_roll_
double resample_var_roll_
Definition: parameters.h:66
mcl_3dl::Parameters::map_chunk_
double map_chunk_
Definition: parameters.h:105
mcl_3dl::Parameters::fix_ang_
double fix_ang_
Definition: parameters.h:79
mcl_3dl::Parameters::map_downsample_z_
double map_downsample_z_
Definition: parameters.h:52
mcl_3dl::Parameters::update_downsample_z_
double update_downsample_z_
Definition: parameters.h:55
mcl_3dl::Parameters::expansion_var_y_
double expansion_var_y_
Definition: parameters.h:70
mcl_3dl::Parameters::map_downsample_x_
double map_downsample_x_
Definition: parameters.h:50
mcl_3dl::Parameters::num_particles_
int num_particles_
Definition: parameters.h:85
vec3.h
state_6dof.h
mcl_3dl::Parameters::map_grid_max_
double map_grid_max_
Definition: parameters.h:57
mcl_3dl::Parameters::match_output_dist_
double match_output_dist_
Definition: parameters.h:89
mcl_3dl::Parameters::bias_var_dist_
double bias_var_dist_
Definition: parameters.h:91
mcl_3dl::Parameters::map_update_interval_
std::shared_ptr< ros::Duration > map_update_interval_
Definition: parameters.h:84
mcl_3dl::Parameters::unmatch_output_dist_
double unmatch_output_dist_
Definition: parameters.h:90
mcl_3dl::Parameters::map_grid_min_
double map_grid_min_
Definition: parameters.h:56
mcl_3dl::Parameters::map_downsample_y_
double map_downsample_y_
Definition: parameters.h:51
mcl_3dl::Parameters::expansion_var_x_
double expansion_var_x_
Definition: parameters.h:69
mcl_3dl::Parameters::odom_err_ang_ang_
double odom_err_ang_ang_
Definition: parameters.h:83
mcl_3dl::Parameters::use_random_sampler_with_normal_
bool use_random_sampler_with_normal_
Definition: parameters.h:110
mcl_3dl::Parameters::resample_var_z_
double resample_var_z_
Definition: parameters.h:65
quat.h
mcl_3dl::Parameters::global_localization_div_yaw_
int global_localization_div_yaw_
Definition: parameters.h:59
mcl_3dl::Parameters::odom_err_integ_lin_tc_
double odom_err_integ_lin_tc_
Definition: parameters.h:94
mcl_3dl::Parameters::odom_err_lin_lin_
double odom_err_lin_lin_
Definition: parameters.h:80
mcl_3dl
Definition: chunked_kdtree.h:43
mcl_3dl::Parameters::tf_tolerance_
std::shared_ptr< ros::Duration > tf_tolerance_
Definition: parameters.h:99
mcl_3dl::Parameters::acc_lpf_step_
double acc_lpf_step_
Definition: parameters.h:101
mcl_3dl::Parameters::std_warn_thresh_
std::array< float, 3 > std_warn_thresh_
Definition: parameters.h:107
mcl_3dl::Parameters::resample_var_y_
double resample_var_y_
Definition: parameters.h:64
mcl_3dl::Parameters::odom_err_ang_lin_
double odom_err_ang_lin_
Definition: parameters.h:82
mcl_3dl::Parameters::jump_dist_
double jump_dist_
Definition: parameters.h:76
mcl_3dl::Parameters::expansion_var_pitch_
double expansion_var_pitch_
Definition: parameters.h:73
mcl_3dl::Parameters::resample_var_yaw_
double resample_var_yaw_
Definition: parameters.h:68
mcl_3dl::Parameters::frame_ids_
std::map< std::string, std::string > frame_ids_
Definition: parameters.h:106
mcl_3dl::Parameters::match_ratio_thresh_
double match_ratio_thresh_
Definition: parameters.h:75
mcl_3dl::Parameters::load
bool load(ros::NodeHandle &nh)
Definition: parameters.cpp:43
mcl_3dl::Parameters::odom_err_lin_ang_
double odom_err_lin_ang_
Definition: parameters.h:81
mcl_3dl::Parameters::output_pcd_
bool output_pcd_
Definition: parameters.h:103
mcl_3dl::Parameters::initial_pose_std_
State6DOF initial_pose_std_
Definition: parameters.h:109
mcl_3dl::Parameters::odom_err_integ_lin_sigma_
double odom_err_integ_lin_sigma_
Definition: parameters.h:95
mcl_3dl::Parameters::lpf_step_
double lpf_step_
Definition: parameters.h:100
mcl_3dl::Parameters::expansion_var_roll_
double expansion_var_roll_
Definition: parameters.h:72
mcl_3dl::State6DOF
Definition: state_6dof.h:49
mcl_3dl::Parameters::accum_cloud_
int accum_cloud_
Definition: parameters.h:87
mcl_3dl::Parameters::fake_imu_
bool fake_imu_
Definition: parameters.h:49
mcl_3dl::Parameters::odom_err_integ_ang_tc_
double odom_err_integ_ang_tc_
Definition: parameters.h:96
mcl_3dl::Parameters::match_output_interval_
std::shared_ptr< ros::Duration > match_output_interval_
Definition: parameters.h:98
mcl_3dl::Parameters::downsample_z_
double downsample_z_
Definition: parameters.h:62
mcl_3dl::Parameters::resample_var_x_
double resample_var_x_
Definition: parameters.h:63
ros::NodeHandle
mcl_3dl::Parameters::odom_err_integ_ang_sigma_
double odom_err_integ_ang_sigma_
Definition: parameters.h:97
mcl_3dl::Parameters::initial_pose_
State6DOF initial_pose_
Definition: parameters.h:108


mcl_3dl
Author(s): Atsushi Watanabe
autogenerated on Thu Oct 17 2024 02:18:04