From 6476ceba40a6d694e0cf59c90498c80c061f0675 Mon Sep 17 00:00:00 2001 From: Timothy Wiley Date: Fri, 28 Apr 2017 10:54:26 +1000 Subject: [PATCH] crosbot_fastslam: move fastslam parameters class into separate header --- .../include/crosbot_fastslam/heightmap.hpp | 45 +---------- .../include/crosbot_fastslam/parameters.hpp | 79 +++++++++++++++++++ .../include/crosbot_fastslam/probtable.hpp | 2 +- 3 files changed, 81 insertions(+), 45 deletions(-) create mode 100644 crosbot_fastslam/include/crosbot_fastslam/parameters.hpp diff --git a/crosbot_fastslam/include/crosbot_fastslam/heightmap.hpp b/crosbot_fastslam/include/crosbot_fastslam/heightmap.hpp index 5c95f9f..537d537 100644 --- a/crosbot_fastslam/include/crosbot_fastslam/heightmap.hpp +++ b/crosbot_fastslam/include/crosbot_fastslam/heightmap.hpp @@ -9,6 +9,7 @@ #define CROSBOT_FASTSLAM_HEIGHTMAP_HPP_ #include +#include #include #include #include @@ -44,50 +45,6 @@ struct MapCloud : public PointCloud { } }; -struct FastSLAMParameters { -public: - uint32_t numberOfParticles; - double gain; - float initialOccupiedOdds; - double initialZ; - - double updateThresholdXY, updateThresholdTheta; - - double minDistanceBetweenSnaps; - - crosbot::Pose searchPose; - double searchDistance, searchFOV; - double maxSensorRange; - - unsigned int mapRows, mapColumns, patchRows, patchColumns; - - double maxHeight, minHeight; - bool addMotionCopy; - - FastSLAMParameters() { - numberOfParticles = DEFAULT_NUMPARTICLES; - gain = DEFAULT_GAINVALUE; - - initialOccupiedOdds = ProbabilityTable.lodds(DEFAULT_UNOBSERVEDLODDS); - initialZ = 0; - - updateThresholdXY = DEFAULT_DISTANCETHRESHOLD; - updateThresholdTheta = DEG2RAD(DEFAULT_ANGULARTHRESHOLD); - - minDistanceBetweenSnaps = DEFAULT_SNAP_THRESHOLD; - - searchDistance = -1; - searchFOV = DEG2RAD(60); - - mapRows = MULTIMAP_ROWS; mapColumns = MULTIMAP_COLUMNS; - patchRows = HEIGHTMAP_ROWS; patchColumns = HEIGHTMAP_COLUMNS; - - minHeight = 0; maxHeight = INFINITY; - maxSensorRange = INFINITY; - addMotionCopy = false; - } -}; - /* * The actual map values * Keep this as small as possible diff --git a/crosbot_fastslam/include/crosbot_fastslam/parameters.hpp b/crosbot_fastslam/include/crosbot_fastslam/parameters.hpp new file mode 100644 index 0000000..00f6c58 --- /dev/null +++ b/crosbot_fastslam/include/crosbot_fastslam/parameters.hpp @@ -0,0 +1,79 @@ +/* + * parameters.hpp + * + * FASTSlam Parameters + * + * Created on: 28/04/2017 + * Author: rescue + */ + +#ifndef CROSBOT_FASTSLAM_PARAMETERS_HPP_ +#define CROSBOT_FASTSLAM_PARAMETERS_HPP_ + +#include +#include +#include +#include + +#include + +namespace crosbot { +namespace fastslam { + +struct FastSLAMParameters { +public: + uint32_t numberOfParticles; + double gain; + float initialOccupiedOdds; + double initialZ; + + double updateThresholdXY; + double updateThresholdTheta; + + double minDistanceBetweenSnaps; + + crosbot::Pose searchPose; + double searchDistance; + double searchFOV; + double maxSensorRange; + + unsigned int mapRows; + unsigned int mapColumns; + unsigned int patchRows; + unsigned int patchColumns; + + double maxHeight; + double minHeight; + bool addMotionCopy; + + FastSLAMParameters() { + numberOfParticles = DEFAULT_NUMPARTICLES; + gain = DEFAULT_GAINVALUE; + + initialOccupiedOdds = ProbabilityTable.lodds(DEFAULT_UNOBSERVEDLODDS); + initialZ = 0; + + updateThresholdXY = DEFAULT_DISTANCETHRESHOLD; + updateThresholdTheta = DEG2RAD(DEFAULT_ANGULARTHRESHOLD); + + minDistanceBetweenSnaps = DEFAULT_SNAP_THRESHOLD; + + searchDistance = -1; + searchFOV = DEG2RAD(60); + + mapRows = MULTIMAP_ROWS; + mapColumns = MULTIMAP_COLUMNS; + patchRows = HEIGHTMAP_ROWS; + patchColumns = HEIGHTMAP_COLUMNS; + + minHeight = 0; + maxHeight = INFINITY; + maxSensorRange = INFINITY; + addMotionCopy = false; + } +}; + +} // namespace fastslam +} // namespace crosbot + +#endif /* PARAMETERS_HPP_ */ diff --git a/crosbot_fastslam/include/crosbot_fastslam/probtable.hpp b/crosbot_fastslam/include/crosbot_fastslam/probtable.hpp index ef1605a..64228b2 100644 --- a/crosbot_fastslam/include/crosbot_fastslam/probtable.hpp +++ b/crosbot_fastslam/include/crosbot_fastslam/probtable.hpp @@ -8,7 +8,7 @@ #ifndef CROSBOT_FASTSLAM_PROBTABLE_H_ #define CROSBOT_FASTSLAM_PROBTABLE_H_ -#include "constants.hpp" +#include #include #include -- GitLab