crsm_slamParameters.h
Go to the documentation of this file.
00001 /*
00002  *      This file is part of CrsmSlam.
00003     CrsmSlam is free software: you can redistribute it and/or modify 
00004     it under the terms of the GNU General Public License as published by
00005     the Free Software Foundation, either version 3 of the License, or
00006     (at your option) any later version.
00007 
00008     CrsmSlam is distributed in the hope that it will be useful,
00009     but WITHOUT ANY WARRANTY; without even the implied warranty of
00010     MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00011     GNU General Public License for more details.
00012 
00013     You should have received a copy of the GNU General Public License
00014     along with CrsmSlam.  If not, see <http://www.gnu.org/licenses/>.
00015 * 
00016 * Author : Manos Tsardoulias, etsardou@gmail.com
00017 * Organization : AUTH, PANDORA Robotics Team
00018 * */
00019 
00020 #ifndef CRSM_SLAM_PARAMS_HEADER
00021 #define CRSM_SLAM_PARAMS_HEADER
00022 
00023 #define pi                      3.141592654
00024 #define pi_double       6.283185308
00025 
00026 #include <cstring>
00027 
00028 namespace crsm_slam{
00029 
00034         struct CrsmSlamParameters{
00035                 int disparity;                                          
00036                 int map_size;                                           
00037                 double ocgd;                                            
00038                 double density;                                 
00039                 double obstacle_density;                        
00040                 double scan_selection_meters;           
00041                 int max_hill_climbing_iterations;       
00042                 double dx_laser_robotCenter;            
00043                         
00044                 double occupancy_grid_map_freq; 
00045                 double robot_pose_tf_freq;                      
00046                 double trajectory_freq;                 
00047                 
00048                 int desired_number_of_picked_rays;      
00049                 double robot_width;                                     
00050                 double robot_length;                                    
00051                 
00052                 std::string occupancy_grid_publish_topic;       
00053                 std::string robot_trajectory_publish_topic;     
00054                 std::string trajectory_publisher_frame_id;      
00055                 std::string laser_subscriber_topic;                     
00056                 
00057                 std::string world_frame;                        
00058                 std::string base_footprint_frame;       
00059                 std::string base_frame;                         
00060                 std::string map_frame;                          
00061                 std::string laser_frame;                        
00062         };
00063 
00064 }
00065 #endif


crsm_slam
Author(s): Manos Tsardoulias
autogenerated on Sat Jun 8 2019 19:18:57