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
bool load(ros::NodeHandle &nh)
Definition: parameters.cpp:43
double update_downsample_x_
Definition: parameters.h:53
double expansion_var_z_
Definition: parameters.h:71
double resample_var_roll_
Definition: parameters.h:66
double odom_err_lin_ang_
Definition: parameters.h:81
double unmatch_output_dist_
Definition: parameters.h:90
double match_output_dist_
Definition: parameters.h:89
double update_downsample_z_
Definition: parameters.h:55
double expansion_var_roll_
Definition: parameters.h:72
double map_downsample_x_
Definition: parameters.h:50
std::shared_ptr< ros::Duration > map_update_interval_
Definition: parameters.h:84
double global_localization_grid_
Definition: parameters.h:58
double odom_err_ang_ang_
Definition: parameters.h:83
double expansion_var_y_
Definition: parameters.h:70
State6DOF initial_pose_std_
Definition: parameters.h:109
double map_downsample_y_
Definition: parameters.h:51
std::array< float, 3 > std_warn_thresh_
Definition: parameters.h:107
double odom_err_integ_lin_tc_
Definition: parameters.h:94
double resample_var_yaw_
Definition: parameters.h:68
double odom_err_lin_lin_
Definition: parameters.h:80
double expansion_var_yaw_
Definition: parameters.h:74
double map_downsample_z_
Definition: parameters.h:52
double resample_var_z_
Definition: parameters.h:65
double odom_err_ang_lin_
Definition: parameters.h:82
std::map< std::string, std::string > frame_ids_
Definition: parameters.h:106
double resample_var_y_
Definition: parameters.h:64
double expansion_var_x_
Definition: parameters.h:69
double expansion_var_pitch_
Definition: parameters.h:73
double odom_err_integ_ang_tc_
Definition: parameters.h:96
double match_ratio_thresh_
Definition: parameters.h:75
bool use_random_sampler_with_normal_
Definition: parameters.h:110
std::shared_ptr< ros::Duration > match_output_interval_
Definition: parameters.h:98
std::shared_ptr< ros::Duration > tf_tolerance_
Definition: parameters.h:99
double odom_err_integ_lin_sigma_
Definition: parameters.h:95
State6DOF initial_pose_
Definition: parameters.h:108
double update_downsample_y_
Definition: parameters.h:54
int global_localization_div_yaw_
Definition: parameters.h:59
double odom_err_integ_ang_sigma_
Definition: parameters.h:97
double resample_var_x_
Definition: parameters.h:63
double resample_var_pitch_
Definition: parameters.h:67
std::array< float, 4 > dist_weight_
Definition: parameters.h:102


mcl_3dl
Author(s): Atsushi Watanabe
autogenerated on Wed May 12 2021 02:16:29