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 namespace mcl_3dl
33 {
35 {
36 public:
43  double map_grid_min_;
44  double map_grid_max_;
47  double downsample_x_;
48  double downsample_y_;
49  double downsample_z_;
63  double jump_dist_;
64  double jump_ang_;
65  double fix_dist_;
66  double fix_ang_;
71  std::shared_ptr<ros::Duration> map_update_interval_;
78  double bias_var_ang_;
79  double acc_var_;
84  std::shared_ptr<ros::Duration> match_output_interval_;
85  std::shared_ptr<ros::Duration> tf_tolerance_;
86  double lpf_step_;
87 };
88 } // namespace mcl_3dl
89 
90 #endif // MCL_3DL_PARAMETERS_H
double update_downsample_x_
Definition: parameters.h:40
double expansion_var_z_
Definition: parameters.h:58
double resample_var_roll_
Definition: parameters.h:53
double odom_err_lin_ang_
Definition: parameters.h:68
double unmatch_output_dist_
Definition: parameters.h:76
double match_output_dist_
Definition: parameters.h:75
double update_downsample_z_
Definition: parameters.h:42
double expansion_var_roll_
Definition: parameters.h:59
double map_downsample_x_
Definition: parameters.h:37
std::shared_ptr< ros::Duration > map_update_interval_
Definition: parameters.h:71
double global_localization_grid_
Definition: parameters.h:45
double odom_err_ang_ang_
Definition: parameters.h:70
double expansion_var_y_
Definition: parameters.h:57
double map_downsample_y_
Definition: parameters.h:38
double odom_err_integ_lin_tc_
Definition: parameters.h:80
double resample_var_yaw_
Definition: parameters.h:55
double odom_err_lin_lin_
Definition: parameters.h:67
double expansion_var_yaw_
Definition: parameters.h:61
double map_downsample_z_
Definition: parameters.h:39
double resample_var_z_
Definition: parameters.h:52
double odom_err_ang_lin_
Definition: parameters.h:69
double resample_var_y_
Definition: parameters.h:51
double expansion_var_x_
Definition: parameters.h:56
double expansion_var_pitch_
Definition: parameters.h:60
double odom_err_integ_ang_tc_
Definition: parameters.h:82
double match_ratio_thresh_
Definition: parameters.h:62
std::shared_ptr< ros::Duration > match_output_interval_
Definition: parameters.h:84
std::shared_ptr< ros::Duration > tf_tolerance_
Definition: parameters.h:85
double odom_err_integ_lin_sigma_
Definition: parameters.h:81
double update_downsample_y_
Definition: parameters.h:41
int global_localization_div_yaw_
Definition: parameters.h:46
double odom_err_integ_ang_sigma_
Definition: parameters.h:83
double resample_var_x_
Definition: parameters.h:50
double resample_var_pitch_
Definition: parameters.h:54


mcl_3dl
Author(s): Atsushi Watanabe
autogenerated on Mon Jul 8 2019 03:32:36