diff --git a/crosbot_fastslam/include/crosbot_fastslam/heightmap.hpp b/crosbot_fastslam/include/crosbot_fastslam/heightmap.hpp index 5c95f9f5790889494d9e3cfc7f24c02edbad65ae..537d537653d156df46be330c1fa5d4f9319f47d4 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 0000000000000000000000000000000000000000..00f6c586ba60adfa96f0b609142c8f837c60a47b --- /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 ef1605ac8667992d672b1f8330c834c6ce192c43..64228b262ab120cbe3fdb5338c00c1571db6c217 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