update
This commit is contained in:
parent
5be1c20c80
commit
4d76ddc0c5
|
|
@ -10,7 +10,7 @@
|
|||
|
||||
#include "robot_grid_map_core/TypeDefs.hpp"
|
||||
|
||||
namespace grid_map {
|
||||
namespace robot_grid_map {
|
||||
|
||||
/*!
|
||||
* This class holds information about a rectangular region
|
||||
|
|
@ -60,4 +60,4 @@ class BufferRegion
|
|||
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
|
||||
};
|
||||
|
||||
} /* namespace grid_map */
|
||||
} /* namespace robot_grid_map */
|
||||
|
|
|
|||
|
|
@ -26,7 +26,7 @@
|
|||
* http://www.geovista.psu.edu/sites/geocomp99/Gc99/082/gc_082.htm
|
||||
*/
|
||||
|
||||
namespace grid_map {
|
||||
namespace robot_grid_map {
|
||||
|
||||
class GridMap;
|
||||
|
||||
|
|
@ -229,7 +229,7 @@ bool getUnitSquareCornerIndices(const GridMap &gridMap, const Position &queriedP
|
|||
* is closest to the queried position.
|
||||
* @param[in] gridMap - grid map with discrete function values
|
||||
* @param[in] queriedPosition - position for which the interpolation is requested
|
||||
* @param[out] index - indices of the closest point in grid_map
|
||||
* @param[out] index - indices of the closest point in robot_grid_map
|
||||
* @return - true if success
|
||||
*/
|
||||
bool getClosestPointIndices(const GridMap &gridMap, const Position &queriedPosition, Index *index);
|
||||
|
|
@ -342,4 +342,4 @@ bool computeNormalizedCoordinates(const GridMap &gridMap, const Index &originInd
|
|||
|
||||
} /* namespace bicubic */
|
||||
|
||||
} /* namespace grid_map*/
|
||||
} /* namespace robot_grid_map*/
|
||||
|
|
|
|||
|
|
@ -20,7 +20,7 @@
|
|||
#include <Eigen/Core>
|
||||
#include <Eigen/Geometry>
|
||||
|
||||
namespace grid_map {
|
||||
namespace robot_grid_map {
|
||||
|
||||
class SubmapGeometry;
|
||||
|
||||
|
|
@ -40,8 +40,8 @@ class SubmapGeometry;
|
|||
class GridMap {
|
||||
public:
|
||||
// Type traits for use with template methods/classes using GridMap as a template parameter.
|
||||
typedef grid_map::DataType DataType;
|
||||
typedef grid_map::Matrix Matrix;
|
||||
typedef robot_grid_map::DataType DataType;
|
||||
typedef robot_grid_map::Matrix Matrix;
|
||||
|
||||
/*!
|
||||
* Constructor.
|
||||
|
|
@ -176,7 +176,7 @@ class GridMap {
|
|||
* @param other the other grid map.
|
||||
* @return true if the other grid map has the same layers, false otherwise.
|
||||
*/
|
||||
bool hasSameLayers(const grid_map::GridMap& other) const;
|
||||
bool hasSameLayers(const robot_grid_map::GridMap& other) const;
|
||||
|
||||
/*!
|
||||
* Get cell data at requested position.
|
||||
|
|
@ -586,4 +586,4 @@ class GridMap {
|
|||
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
|
||||
};
|
||||
|
||||
} // namespace grid_map
|
||||
} // namespace robot_grid_map
|
||||
|
|
|
|||
|
|
@ -15,7 +15,7 @@
|
|||
#include <vector>
|
||||
#include <map>
|
||||
|
||||
namespace grid_map {
|
||||
namespace robot_grid_map {
|
||||
|
||||
union Color
|
||||
{
|
||||
|
|
@ -341,4 +341,4 @@ void colorVectorToValue(const Eigen::Vector3i& colorVector, float& colorValue);
|
|||
*/
|
||||
void colorVectorToValue(const Eigen::Vector3f& colorVector, float& colorValue);
|
||||
|
||||
} // namespace grid_map
|
||||
} // namespace robot_grid_map
|
||||
|
|
|
|||
|
|
@ -16,7 +16,7 @@
|
|||
// Eigen
|
||||
#include <Eigen/Core>
|
||||
|
||||
namespace grid_map {
|
||||
namespace robot_grid_map {
|
||||
|
||||
class Polygon
|
||||
{
|
||||
|
|
@ -246,4 +246,4 @@ class Polygon
|
|||
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
|
||||
};
|
||||
|
||||
} /* namespace grid_map */
|
||||
} /* namespace robot_grid_map */
|
||||
|
|
|
|||
|
|
@ -10,7 +10,7 @@
|
|||
|
||||
#include <robot_grid_map_core/GridMap.hpp>
|
||||
|
||||
namespace grid_map {
|
||||
namespace robot_grid_map {
|
||||
|
||||
class GridMap;
|
||||
|
||||
|
|
@ -70,4 +70,4 @@ class SubmapGeometry
|
|||
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
|
||||
};
|
||||
|
||||
} /* namespace grid_map */
|
||||
} /* namespace robot_grid_map */
|
||||
|
|
|
|||
|
|
@ -11,7 +11,7 @@
|
|||
|
||||
#include <Eigen/Core>
|
||||
|
||||
namespace grid_map {
|
||||
namespace robot_grid_map {
|
||||
|
||||
using Matrix = Eigen::MatrixXf;
|
||||
using DataType = Matrix::Scalar;
|
||||
|
|
@ -43,5 +43,5 @@ namespace grid_map {
|
|||
INTER_CUBIC // standard bicubic interpolation
|
||||
};
|
||||
|
||||
} // namespace grid_map
|
||||
} // namespace robot_grid_map
|
||||
|
||||
|
|
|
|||
|
|
@ -8,7 +8,7 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
namespace grid_map {
|
||||
namespace robot_grid_map {
|
||||
|
||||
template<typename Scalar>
|
||||
struct Clamp
|
||||
|
|
@ -25,4 +25,4 @@ struct Clamp
|
|||
Scalar min_, max_;
|
||||
};
|
||||
|
||||
} // namespace grid_map
|
||||
} // namespace robot_grid_map
|
||||
|
|
|
|||
|
|
@ -12,7 +12,7 @@
|
|||
#include <iostream>
|
||||
#include <cmath>
|
||||
|
||||
namespace grid_map {
|
||||
namespace robot_grid_map {
|
||||
|
||||
template<int N>
|
||||
Eigen::Matrix<double,N,N> randomCovariance()
|
||||
|
|
@ -136,7 +136,7 @@ namespace grid_map {
|
|||
for(int c = 0; c < (A).cols(); c++) \
|
||||
{ \
|
||||
double percentError = 0.0; \
|
||||
ASSERT_TRUE(grid_map::compareRelative( (A)(r,c), (B)(r,c), PERCENT_TOLERANCE, &percentError)) \
|
||||
ASSERT_TRUE(robot_grid_map::compareRelative( (A)(r,c), (B)(r,c), PERCENT_TOLERANCE, &percentError)) \
|
||||
<< (MSG) << "\nComparing:\n" \
|
||||
<< #A << "(" << r << "," << c << ") = " << (A)(r,c) << std::endl \
|
||||
<< #B << "(" << r << "," << c << ") = " << (B)(r,c) << std::endl \
|
||||
|
|
@ -153,7 +153,7 @@ namespace grid_map {
|
|||
for(int c = 0; c < (A).cols(); c++) \
|
||||
{ \
|
||||
double percentError = 0.0; \
|
||||
ASSERT_TRUE(grid_map::compareRelative( (A).coeff(r,c), (B).coeff(r,c), PERCENT_TOLERANCE, &percentError)) \
|
||||
ASSERT_TRUE(robot_grid_map::compareRelative( (A).coeff(r,c), (B).coeff(r,c), PERCENT_TOLERANCE, &percentError)) \
|
||||
<< (MSG) << "\nComparing:\n" \
|
||||
<< #A << "(" << r << "," << c << ") = " << (A).coeff(r,c) << std::endl \
|
||||
<< #B << "(" << r << "," << c << ") = " << (B).coeff(r,c) << std::endl \
|
||||
|
|
@ -162,4 +162,4 @@ namespace grid_map {
|
|||
} \
|
||||
}
|
||||
|
||||
} // namespace grid_map
|
||||
} // namespace robot_grid_map
|
||||
|
|
|
|||
|
|
@ -15,7 +15,7 @@
|
|||
|
||||
#include <memory>
|
||||
|
||||
namespace grid_map {
|
||||
namespace robot_grid_map {
|
||||
|
||||
/*!
|
||||
* Iterator class to iterate through a circular area of the map.
|
||||
|
|
@ -97,5 +97,5 @@ private:
|
|||
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
|
||||
};
|
||||
|
||||
} // namespace grid_map
|
||||
} // namespace robot_grid_map
|
||||
|
||||
|
|
|
|||
|
|
@ -15,7 +15,7 @@
|
|||
|
||||
#include <memory>
|
||||
|
||||
namespace grid_map {
|
||||
namespace robot_grid_map {
|
||||
|
||||
/*!
|
||||
* Iterator class to iterate through a ellipsoid area of the map.
|
||||
|
|
@ -106,5 +106,5 @@ private:
|
|||
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
|
||||
};
|
||||
|
||||
} // namespace grid_map
|
||||
} // namespace robot_grid_map
|
||||
|
||||
|
|
|
|||
|
|
@ -13,7 +13,7 @@
|
|||
// Eigen
|
||||
#include <Eigen/Core>
|
||||
|
||||
namespace grid_map {
|
||||
namespace robot_grid_map {
|
||||
|
||||
/*!
|
||||
* Iterator class to iterate trough the entire grid map.
|
||||
|
|
@ -26,7 +26,7 @@ public:
|
|||
* Constructor.
|
||||
* @param gridMap the grid map to iterate on.
|
||||
*/
|
||||
GridMapIterator(const grid_map::GridMap &gridMap);
|
||||
GridMapIterator(const robot_grid_map::GridMap &gridMap);
|
||||
|
||||
/*!
|
||||
* Copy constructor.
|
||||
|
|
@ -101,5 +101,5 @@ public:
|
|||
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
|
||||
};
|
||||
|
||||
} // namespace grid_map
|
||||
} // namespace robot_grid_map
|
||||
|
||||
|
|
|
|||
|
|
@ -13,7 +13,7 @@
|
|||
|
||||
#include <Eigen/Core>
|
||||
|
||||
namespace grid_map {
|
||||
namespace robot_grid_map {
|
||||
|
||||
/*!
|
||||
* Iterator class to iterate over a line in the map.
|
||||
|
|
@ -30,7 +30,7 @@ public:
|
|||
* @param end the ending point of the line.
|
||||
* @throw std::invalid_argument if start and end impose an ill conditioned line iteration.
|
||||
*/
|
||||
LineIterator(const grid_map::GridMap& gridMap, const Position& start, const Position& end);
|
||||
LineIterator(const robot_grid_map::GridMap& gridMap, const Position& start, const Position& end);
|
||||
|
||||
/*!
|
||||
* Constructor.
|
||||
|
|
@ -38,7 +38,7 @@ public:
|
|||
* @param start the starting index of the line.
|
||||
* @param end the ending index of the line.
|
||||
*/
|
||||
LineIterator(const grid_map::GridMap& gridMap, const Index& start, const Index& end);
|
||||
LineIterator(const robot_grid_map::GridMap& gridMap, const Index& start, const Index& end);
|
||||
|
||||
/*!
|
||||
* Compare to another iterator.
|
||||
|
|
@ -74,7 +74,7 @@ private:
|
|||
* @param end the ending index of the line.
|
||||
* @return true if successful, false otherwise.
|
||||
*/
|
||||
bool initialize(const grid_map::GridMap& gridMap, const Index& start, const Index& end);
|
||||
bool initialize(const robot_grid_map::GridMap& gridMap, const Index& start, const Index& end);
|
||||
|
||||
/*!
|
||||
* Computes the parameters requires for the line drawing algorithm.
|
||||
|
|
@ -89,7 +89,7 @@ private:
|
|||
* @param[out] index the index of the moved start position.
|
||||
* @return true if successful, false otherwise.
|
||||
*/
|
||||
static bool getIndexLimitedToMapRange(const grid_map::GridMap& gridMap, const Position& start,
|
||||
static bool getIndexLimitedToMapRange(const robot_grid_map::GridMap& gridMap, const Position& start,
|
||||
const Position& end, Index& index);
|
||||
|
||||
//! Current index.
|
||||
|
|
@ -122,5 +122,5 @@ private:
|
|||
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
|
||||
};
|
||||
|
||||
} // namespace grid_map
|
||||
} // namespace robot_grid_map
|
||||
|
||||
|
|
|
|||
|
|
@ -14,7 +14,7 @@
|
|||
|
||||
#include <memory>
|
||||
|
||||
namespace grid_map {
|
||||
namespace robot_grid_map {
|
||||
|
||||
/*!
|
||||
* Iterator class to iterate through a polygonal area of the map.
|
||||
|
|
@ -28,7 +28,7 @@ public:
|
|||
* @param gridMap the grid map to iterate on.
|
||||
* @param polygon the polygonal area to iterate on.
|
||||
*/
|
||||
PolygonIterator(const grid_map::GridMap& gridMap, const grid_map::Polygon& polygon);
|
||||
PolygonIterator(const robot_grid_map::GridMap& gridMap, const robot_grid_map::Polygon& polygon);
|
||||
|
||||
/*!
|
||||
* Compare to another iterator.
|
||||
|
|
@ -68,10 +68,10 @@ private:
|
|||
* @param[out] startIndex the start index of the submap.
|
||||
* @param[out] bufferSize the buffer size of the submap.
|
||||
*/
|
||||
void findSubmapParameters(const grid_map::Polygon& polygon, Index& startIndex,Size& bufferSize) const;
|
||||
void findSubmapParameters(const robot_grid_map::Polygon& polygon, Index& startIndex,Size& bufferSize) const;
|
||||
|
||||
//! Polygon to iterate on.
|
||||
grid_map::Polygon polygon_;
|
||||
robot_grid_map::Polygon polygon_;
|
||||
|
||||
//! Grid submap iterator.
|
||||
std::shared_ptr<SubmapIterator> internalIterator_;
|
||||
|
|
@ -87,5 +87,5 @@ private:
|
|||
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
|
||||
};
|
||||
|
||||
} // namespace grid_map
|
||||
} // namespace robot_grid_map
|
||||
|
||||
|
|
|
|||
|
|
@ -14,7 +14,7 @@
|
|||
|
||||
#include <Eigen/Core>
|
||||
|
||||
namespace grid_map {
|
||||
namespace robot_grid_map {
|
||||
|
||||
/*!
|
||||
* Iterator class to iterate trough the entire grid map with access to a layer's
|
||||
|
|
@ -91,5 +91,5 @@ private:
|
|||
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
|
||||
};
|
||||
|
||||
} // namespace grid_map
|
||||
} // namespace robot_grid_map
|
||||
|
||||
|
|
|
|||
|
|
@ -14,7 +14,7 @@
|
|||
#include <memory>
|
||||
#include <vector>
|
||||
|
||||
namespace grid_map {
|
||||
namespace robot_grid_map {
|
||||
|
||||
/*!
|
||||
* Iterator class to iterate through a circular area of the map with a spiral.
|
||||
|
|
@ -29,7 +29,7 @@ public:
|
|||
* @param center the position of the circle center.
|
||||
* @param radius the radius of the circle.
|
||||
*/
|
||||
SpiralIterator(const grid_map::GridMap& gridMap, Eigen::Vector2d center, double radius);
|
||||
SpiralIterator(const robot_grid_map::GridMap& gridMap, Eigen::Vector2d center, double radius);
|
||||
|
||||
/*!
|
||||
* Compare to another iterator.
|
||||
|
|
@ -105,5 +105,5 @@ private:
|
|||
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
|
||||
};
|
||||
|
||||
} // namespace grid_map
|
||||
} // namespace robot_grid_map
|
||||
|
||||
|
|
|
|||
|
|
@ -14,7 +14,7 @@
|
|||
|
||||
#include <Eigen/Core>
|
||||
|
||||
namespace grid_map {
|
||||
namespace robot_grid_map {
|
||||
|
||||
/*!
|
||||
* Iterator class to iterate through a rectangular part of the map (submap).
|
||||
|
|
@ -29,13 +29,13 @@ public:
|
|||
* Constructor.
|
||||
* @param submap the submap geometry to iterate over.
|
||||
*/
|
||||
SubmapIterator(const grid_map::SubmapGeometry& submap);
|
||||
SubmapIterator(const robot_grid_map::SubmapGeometry& submap);
|
||||
|
||||
/*!
|
||||
* Constructor.
|
||||
* @param submap the buffer region of a grid map to iterate over.
|
||||
*/
|
||||
SubmapIterator(const grid_map::GridMap& gridMap, const grid_map::BufferRegion& bufferRegion);
|
||||
SubmapIterator(const robot_grid_map::GridMap& gridMap, const robot_grid_map::BufferRegion& bufferRegion);
|
||||
|
||||
/*!
|
||||
* Constructor.
|
||||
|
|
@ -43,7 +43,7 @@ public:
|
|||
* @param submapStartIndex the start index of the submap, typically top-left index.
|
||||
* @param submapSize the size of the submap to iterate on.
|
||||
*/
|
||||
SubmapIterator(const grid_map::GridMap& gridMap, const Index& submapStartIndex,
|
||||
SubmapIterator(const robot_grid_map::GridMap& gridMap, const Index& submapStartIndex,
|
||||
const Size& submapSize);
|
||||
|
||||
/*!
|
||||
|
|
@ -115,5 +115,5 @@ private:
|
|||
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
|
||||
};
|
||||
|
||||
} // namespace grid_map
|
||||
} // namespace robot_grid_map
|
||||
|
||||
|
|
|
|||
|
|
@ -6,8 +6,8 @@
|
|||
<maintainer email="mwulf@anybotics.com">Maximilian Wulf</maintainer>
|
||||
<maintainer email="ynava@anybotics.com">Yoshua Nava</maintainer>
|
||||
<license>BSD</license>
|
||||
<url type="website">http://github.com/anybotics/grid_map</url>
|
||||
<url type="bugtracker">http://github.com/anybotics/grid_map/issues</url>
|
||||
<url type="website">http://github.com/anybotics/robot_grid_map</url>
|
||||
<url type="bugtracker">http://github.com/anybotics/robot_grid_map/issues</url>
|
||||
<author email="pfankhauser@anybotics.com">Péter Fankhauser</author>
|
||||
<buildtool_depend>catkin</buildtool_depend>
|
||||
<!-- <build_depend>cmake_clang_tools</build_depend> -->
|
||||
|
|
|
|||
|
|
@ -7,7 +7,7 @@
|
|||
*/
|
||||
#include <robot_grid_map_core/BufferRegion.hpp>
|
||||
|
||||
namespace grid_map {
|
||||
namespace robot_grid_map {
|
||||
|
||||
BufferRegion::BufferRegion() : startIndex_(Index::Zero()),
|
||||
size_(Size::Zero()),
|
||||
|
|
@ -51,6 +51,6 @@ void BufferRegion::setQuadrant(BufferRegion::Quadrant type)
|
|||
quadrant_ = type;
|
||||
}
|
||||
|
||||
} /* namespace grid_map */
|
||||
} /* namespace robot_grid_map */
|
||||
|
||||
|
||||
|
|
|
|||
|
|
@ -10,7 +10,7 @@
|
|||
|
||||
#include "robot_grid_map_core/GridMap.hpp"
|
||||
|
||||
namespace grid_map {
|
||||
namespace robot_grid_map {
|
||||
|
||||
unsigned int bindIndexToRange(unsigned int idReq, unsigned int nElem)
|
||||
{
|
||||
|
|
@ -101,7 +101,7 @@ bool assembleFunctionValueMatrix(const GridMap &gridMap, const std::string &laye
|
|||
* they use a coordinate frame centered around (i,j). Therefore:
|
||||
* f(i+1,j-1) in their notation corresponds to f(i-1,j+1) in ours. This is
|
||||
* because our coordinate frame sits in the top left corner, see
|
||||
* https://github.com/ANYbotics/grid_map
|
||||
* https://github.com/ANYbotics/robot_grid_map
|
||||
*/
|
||||
*data << f(i + 1, j + 1), f(i, j + 1), f(i - 1, j + 1), f(i - 2, j + 1), f(i + 1, j), f(i, j), f(
|
||||
i - 1, j), f(i - 2, j), f(i + 1, j - 1), f(i, j - 1), f(i - 1, j - 1), f(i - 2, j - 1), f(
|
||||
|
|
@ -433,4 +433,4 @@ void assembleFunctionValueMatrix(const DataMatrix &f, const DataMatrix &dfx, con
|
|||
|
||||
} /* namespace bicubic*/
|
||||
|
||||
} /* namespace grid_map */
|
||||
} /* namespace robot_grid_map */
|
||||
|
|
|
|||
|
|
@ -23,7 +23,7 @@ using std::cout;
|
|||
using std::endl;
|
||||
using std::isfinite;
|
||||
|
||||
namespace grid_map {
|
||||
namespace robot_grid_map {
|
||||
|
||||
GridMap::GridMap(const std::vector<std::string>& layers) {
|
||||
position_.setZero();
|
||||
|
|
@ -888,4 +888,4 @@ bool GridMap::atPositionBicubicInterpolated(const std::string& layer, const Posi
|
|||
}
|
||||
|
||||
|
||||
} // namespace grid_map
|
||||
} // namespace robot_grid_map
|
||||
|
|
|
|||
|
|
@ -16,7 +16,7 @@
|
|||
|
||||
using std::numeric_limits;
|
||||
|
||||
namespace grid_map {
|
||||
namespace robot_grid_map {
|
||||
|
||||
namespace internal {
|
||||
|
||||
|
|
@ -596,5 +596,5 @@ void colorVectorToValue(const Eigen::Vector3f& colorVector, float& colorValue)
|
|||
colorVectorToValue(tempColorVector, colorValue);
|
||||
}
|
||||
|
||||
} // namespace grid_map
|
||||
} // namespace robot_grid_map
|
||||
|
||||
|
|
|
|||
|
|
@ -14,7 +14,7 @@
|
|||
#include <limits>
|
||||
#include <algorithm>
|
||||
|
||||
namespace grid_map {
|
||||
namespace robot_grid_map {
|
||||
|
||||
Polygon::Polygon()
|
||||
: timestamp_(0)
|
||||
|
|
@ -268,7 +268,7 @@ Polygon Polygon::convexHullOfTwoCircles(const Position center1,
|
|||
centerToVertex.normalize();
|
||||
centerToVertex *= radius;
|
||||
|
||||
grid_map::Polygon polygon;
|
||||
robot_grid_map::Polygon polygon;
|
||||
for (int j = 0; j < ceil(nVertices / 2.0); j++) {
|
||||
double theta = M_PI_2 + j * M_PI / (ceil(nVertices / 2.0) - 1);
|
||||
Eigen::Rotation2D<double> rot2d(theta);
|
||||
|
|
@ -349,4 +349,4 @@ double Polygon::vectorsMakeClockwiseTurn(const Eigen::Vector2d &pointOrigin,
|
|||
return computeCrossProduct2D(pointA - pointOrigin, pointB - pointOrigin) <= 0;
|
||||
}
|
||||
|
||||
} /* namespace grid_map */
|
||||
} /* namespace robot_grid_map */
|
||||
|
|
|
|||
|
|
@ -9,7 +9,7 @@
|
|||
#include <robot_grid_map_core/GridMapMath.hpp>
|
||||
#include <robot_grid_map_core/SubmapGeometry.hpp>
|
||||
|
||||
namespace grid_map {
|
||||
namespace robot_grid_map {
|
||||
|
||||
SubmapGeometry::SubmapGeometry(const GridMap& gridMap, const Position& position,
|
||||
const Length& length, bool& isSuccess)
|
||||
|
|
@ -56,4 +56,4 @@ const Index& SubmapGeometry::getStartIndex() const
|
|||
return startIndex_;
|
||||
}
|
||||
|
||||
} /* namespace grid_map */
|
||||
} /* namespace robot_grid_map */
|
||||
|
|
|
|||
|
|
@ -11,7 +11,7 @@
|
|||
#include <memory>
|
||||
#include "robot_grid_map_core/GridMapMath.hpp"
|
||||
|
||||
namespace grid_map {
|
||||
namespace robot_grid_map {
|
||||
|
||||
CircleIterator::CircleIterator(const GridMap& gridMap, const Position& center, const double radius)
|
||||
: center_(center),
|
||||
|
|
@ -84,5 +84,5 @@ void CircleIterator::findSubmapParameters(const Position& center, const double r
|
|||
bufferSize = getSubmapSizeFromCornerIndices(startIndex, endIndex, bufferSize_, bufferStartIndex_);
|
||||
}
|
||||
|
||||
} /* namespace grid_map */
|
||||
} /* namespace robot_grid_map */
|
||||
|
||||
|
|
|
|||
|
|
@ -12,7 +12,7 @@
|
|||
#include <cmath>
|
||||
#include <Eigen/Geometry>
|
||||
|
||||
namespace grid_map {
|
||||
namespace robot_grid_map {
|
||||
|
||||
EllipseIterator::EllipseIterator(const GridMap& gridMap, const Position& center, const Length& length, const double rotation)
|
||||
: center_(center)
|
||||
|
|
@ -96,5 +96,5 @@ void EllipseIterator::findSubmapParameters(const Position& center, const Length&
|
|||
bufferSize = getSubmapSizeFromCornerIndices(startIndex, endIndex, bufferSize_, bufferStartIndex_);
|
||||
}
|
||||
|
||||
} /* namespace grid_map */
|
||||
} /* namespace robot_grid_map */
|
||||
|
||||
|
|
|
|||
|
|
@ -9,9 +9,9 @@
|
|||
#include "robot_grid_map_core/iterators/GridMapIterator.hpp"
|
||||
#include "robot_grid_map_core/GridMapMath.hpp"
|
||||
|
||||
namespace grid_map {
|
||||
namespace robot_grid_map {
|
||||
|
||||
GridMapIterator::GridMapIterator(const grid_map::GridMap& gridMap)
|
||||
GridMapIterator::GridMapIterator(const robot_grid_map::GridMap& gridMap)
|
||||
{
|
||||
size_ = gridMap.getSize();
|
||||
startIndex_ = gridMap.getStartIndex();
|
||||
|
|
@ -72,4 +72,4 @@ bool GridMapIterator::isPastEnd() const
|
|||
return isPastEnd_;
|
||||
}
|
||||
|
||||
} /* namespace grid_map */
|
||||
} /* namespace robot_grid_map */
|
||||
|
|
|
|||
|
|
@ -9,9 +9,9 @@
|
|||
#include "robot_grid_map_core/iterators/LineIterator.hpp"
|
||||
#include "robot_grid_map_core/GridMapMath.hpp"
|
||||
|
||||
namespace grid_map {
|
||||
namespace robot_grid_map {
|
||||
|
||||
LineIterator::LineIterator(const grid_map::GridMap& gridMap, const Position& start,
|
||||
LineIterator::LineIterator(const robot_grid_map::GridMap& gridMap, const Position& start,
|
||||
const Position& end)
|
||||
{
|
||||
Index startIndex;
|
||||
|
|
@ -25,7 +25,7 @@ LineIterator::LineIterator(const grid_map::GridMap& gridMap, const Position& sta
|
|||
}
|
||||
}
|
||||
|
||||
LineIterator::LineIterator(const grid_map::GridMap& gridMap, const Index& start, const Index& end)
|
||||
LineIterator::LineIterator(const robot_grid_map::GridMap& gridMap, const Index& start, const Index& end)
|
||||
{
|
||||
initialize(gridMap, start, end);
|
||||
}
|
||||
|
|
@ -59,7 +59,7 @@ bool LineIterator::isPastEnd() const
|
|||
return iCell_ >= nCells_;
|
||||
}
|
||||
|
||||
bool LineIterator::initialize(const grid_map::GridMap& gridMap, const Index& start, const Index& end)
|
||||
bool LineIterator::initialize(const robot_grid_map::GridMap& gridMap, const Index& start, const Index& end)
|
||||
{
|
||||
start_ = start;
|
||||
end_ = end;
|
||||
|
|
@ -72,7 +72,7 @@ bool LineIterator::initialize(const grid_map::GridMap& gridMap, const Index& sta
|
|||
return true;
|
||||
}
|
||||
|
||||
bool LineIterator::getIndexLimitedToMapRange(const grid_map::GridMap& gridMap,
|
||||
bool LineIterator::getIndexLimitedToMapRange(const robot_grid_map::GridMap& gridMap,
|
||||
const Position& start, const Position& end,
|
||||
Index& index)
|
||||
{
|
||||
|
|
@ -135,4 +135,4 @@ void LineIterator::initializeIterationParameters()
|
|||
}
|
||||
}
|
||||
|
||||
} /* namespace grid_map */
|
||||
} /* namespace robot_grid_map */
|
||||
|
|
|
|||
|
|
@ -11,9 +11,9 @@
|
|||
#include "robot_grid_map_core/iterators/PolygonIterator.hpp"
|
||||
#include "robot_grid_map_core/GridMapMath.hpp"
|
||||
|
||||
namespace grid_map {
|
||||
namespace robot_grid_map {
|
||||
|
||||
PolygonIterator::PolygonIterator(const grid_map::GridMap& gridMap, const grid_map::Polygon& polygon)
|
||||
PolygonIterator::PolygonIterator(const robot_grid_map::GridMap& gridMap, const robot_grid_map::Polygon& polygon)
|
||||
: polygon_(polygon)
|
||||
{
|
||||
mapLength_ = gridMap.getLength();
|
||||
|
|
@ -68,7 +68,7 @@ bool PolygonIterator::isInside() const
|
|||
return polygon_.isInside(position);
|
||||
}
|
||||
|
||||
void PolygonIterator::findSubmapParameters(const grid_map::Polygon& /*polygon*/, Index& startIndex, Size& bufferSize) const
|
||||
void PolygonIterator::findSubmapParameters(const robot_grid_map::Polygon& /*polygon*/, Index& startIndex, Size& bufferSize) const
|
||||
{
|
||||
Position topLeft = polygon_.getVertices()[0];
|
||||
Position bottomRight = topLeft;
|
||||
|
|
@ -84,5 +84,5 @@ void PolygonIterator::findSubmapParameters(const grid_map::Polygon& /*polygon*/,
|
|||
bufferSize = getSubmapSizeFromCornerIndices(startIndex, endIndex, bufferSize_, bufferStartIndex_);
|
||||
}
|
||||
|
||||
} /* namespace grid_map */
|
||||
} /* namespace robot_grid_map */
|
||||
|
||||
|
|
|
|||
|
|
@ -11,7 +11,7 @@
|
|||
|
||||
#include <iostream>
|
||||
|
||||
namespace grid_map {
|
||||
namespace robot_grid_map {
|
||||
|
||||
SlidingWindowIterator::SlidingWindowIterator(const GridMap& gridMap, const std::string& layer,
|
||||
const EdgeHandling& edgeHandling, const size_t windowSize)
|
||||
|
|
@ -114,4 +114,4 @@ bool SlidingWindowIterator::dataInsideMap() const
|
|||
return checkIfIndexInRange(topLeftIndex, size_) && checkIfIndexInRange(bottomRightIndex, size_);
|
||||
}
|
||||
|
||||
} /* namespace grid_map */
|
||||
} /* namespace robot_grid_map */
|
||||
|
|
|
|||
|
|
@ -13,9 +13,9 @@
|
|||
#include <utility>
|
||||
|
||||
|
||||
namespace grid_map {
|
||||
namespace robot_grid_map {
|
||||
|
||||
SpiralIterator::SpiralIterator(const grid_map::GridMap& gridMap, Eigen::Vector2d center,
|
||||
SpiralIterator::SpiralIterator(const robot_grid_map::GridMap& gridMap, Eigen::Vector2d center,
|
||||
const double radius)
|
||||
: center_(std::move(center)),
|
||||
radius_(radius),
|
||||
|
|
@ -106,5 +106,5 @@ double SpiralIterator::getCurrentRadius() const
|
|||
return radius.matrix().norm() * resolution_;
|
||||
}
|
||||
|
||||
} /* namespace grid_map */
|
||||
} /* namespace robot_grid_map */
|
||||
|
||||
|
|
|
|||
|
|
@ -11,21 +11,21 @@
|
|||
|
||||
|
||||
|
||||
namespace grid_map {
|
||||
namespace robot_grid_map {
|
||||
|
||||
SubmapIterator::SubmapIterator(const grid_map::SubmapGeometry& submap)
|
||||
SubmapIterator::SubmapIterator(const robot_grid_map::SubmapGeometry& submap)
|
||||
: SubmapIterator(submap.getGridMap(), submap.getStartIndex(), submap.getSize())
|
||||
{
|
||||
}
|
||||
|
||||
SubmapIterator::SubmapIterator(const grid_map::GridMap& gridMap,
|
||||
const grid_map::BufferRegion& bufferRegion)
|
||||
SubmapIterator::SubmapIterator(const robot_grid_map::GridMap& gridMap,
|
||||
const robot_grid_map::BufferRegion& bufferRegion)
|
||||
: SubmapIterator(gridMap, bufferRegion.getStartIndex(), bufferRegion.getSize())
|
||||
{
|
||||
}
|
||||
|
||||
|
||||
SubmapIterator::SubmapIterator(const grid_map::GridMap& gridMap, const Index& submapStartIndex,
|
||||
SubmapIterator::SubmapIterator(const robot_grid_map::GridMap& gridMap, const Index& submapStartIndex,
|
||||
const Size& submapSize)
|
||||
{
|
||||
size_ = gridMap.getSize();
|
||||
|
|
@ -80,5 +80,5 @@ const Size& SubmapIterator::getSubmapSize() const
|
|||
return submapSize_;
|
||||
}
|
||||
|
||||
} /* namespace grid_map */
|
||||
} /* namespace robot_grid_map */
|
||||
|
||||
|
|
|
|||
|
|
@ -13,7 +13,7 @@
|
|||
// gtest
|
||||
#include <gtest/gtest.h>
|
||||
|
||||
namespace gm = grid_map;
|
||||
namespace gm = robot_grid_map;
|
||||
namespace gmt = grid_map_test;
|
||||
|
||||
TEST(CubicConvolutionInterpolation, FlatWorld)
|
||||
|
|
|
|||
|
|
@ -13,7 +13,7 @@
|
|||
// gtest
|
||||
#include <gtest/gtest.h>
|
||||
|
||||
namespace gm = grid_map;
|
||||
namespace gm = robot_grid_map;
|
||||
namespace gmt = grid_map_test;
|
||||
|
||||
TEST(CubicInterpolation, FlatWorld)
|
||||
|
|
|
|||
|
|
@ -106,7 +106,7 @@ TEST(EigenMatrixBaseAddons, clamp)
|
|||
Eigen::Matrix3f matrix;
|
||||
matrix << vector.segment(0, 3), vector.segment(3, 3), vector.segment(6, 3);
|
||||
matrix(1, 1) = NAN;
|
||||
matrix = matrix.unaryExpr(grid_map::Clamp<float>(2.1, 7.0));
|
||||
matrix = matrix.unaryExpr(robot_grid_map::Clamp<float>(2.1, 7.0));
|
||||
EXPECT_NEAR(2.1, matrix(0, 0), 1e-7);
|
||||
EXPECT_NEAR(2.1, matrix(1, 0), 1e-7);
|
||||
EXPECT_NEAR(3.0, matrix(2, 0), 1e-7);
|
||||
|
|
|
|||
|
|
@ -15,10 +15,10 @@
|
|||
// Vector
|
||||
#include <vector>
|
||||
|
||||
using grid_map::GridMap;
|
||||
using grid_map::Length;
|
||||
using grid_map::Position;
|
||||
using grid_map::EllipseIterator;
|
||||
using robot_grid_map::GridMap;
|
||||
using robot_grid_map::Length;
|
||||
using robot_grid_map::Position;
|
||||
using robot_grid_map::EllipseIterator;
|
||||
|
||||
TEST(EllipseIterator, OneCellWideEllipse)
|
||||
{
|
||||
|
|
|
|||
|
|
@ -15,10 +15,10 @@
|
|||
// Vector
|
||||
#include <vector>
|
||||
|
||||
using grid_map::GridMap;
|
||||
using grid_map::Length;
|
||||
using grid_map::Position;
|
||||
using grid_map::GridMapIterator;
|
||||
using robot_grid_map::GridMap;
|
||||
using robot_grid_map::Length;
|
||||
using robot_grid_map::Position;
|
||||
using robot_grid_map::GridMapIterator;
|
||||
|
||||
TEST(GridMapIterator, Simple)
|
||||
{
|
||||
|
|
|
|||
|
|
@ -19,7 +19,7 @@
|
|||
|
||||
using std::numeric_limits;
|
||||
|
||||
namespace grid_map{
|
||||
namespace robot_grid_map{
|
||||
|
||||
TEST(PositionFromIndex, Simple)
|
||||
{
|
||||
|
|
@ -1036,4 +1036,4 @@ TEST(getIndexFromLinearIndex, Simple)
|
|||
EXPECT_TRUE((Index(7, 4) == getIndexFromLinearIndex(39, Size(8, 5), false)).all());
|
||||
}
|
||||
|
||||
} // namespace grid_map
|
||||
} // namespace robot_grid_map
|
||||
|
|
@ -11,7 +11,7 @@
|
|||
// gtest
|
||||
#include <gtest/gtest.h>
|
||||
|
||||
namespace grid_map {
|
||||
namespace robot_grid_map {
|
||||
|
||||
TEST(GridMap, CopyConstructor) {
|
||||
GridMap map({"layer_a", "layer_b"});
|
||||
|
|
@ -493,4 +493,4 @@ TEST(ValueAtPosition, LinearInterpolated)
|
|||
EXPECT_NEAR(2.1963200, value, 0.0000001);
|
||||
}
|
||||
|
||||
} // namespace grid_map
|
||||
} // namespace robot_grid_map
|
||||
|
|
@ -12,7 +12,7 @@
|
|||
// gtest
|
||||
#include <gtest/gtest.h>
|
||||
|
||||
namespace grid_map {
|
||||
namespace robot_grid_map {
|
||||
|
||||
TEST(LineIterator, StartOutsideMap) {
|
||||
GridMap map( { "types" });
|
||||
|
|
@ -175,4 +175,4 @@ TEST(LineIterator, StartAndEndOutsideMovedMap)
|
|||
EXPECT_TRUE(iterator.isPastEnd());
|
||||
}
|
||||
|
||||
} // namespace grid_map
|
||||
} // namespace robot_grid_map
|
||||
|
|
@ -16,11 +16,11 @@
|
|||
// Vector
|
||||
#include <vector>
|
||||
|
||||
using grid_map::GridMap;
|
||||
using grid_map::Length;
|
||||
using grid_map::Polygon;
|
||||
using grid_map::PolygonIterator;
|
||||
using grid_map::Position;
|
||||
using robot_grid_map::GridMap;
|
||||
using robot_grid_map::Length;
|
||||
using robot_grid_map::Polygon;
|
||||
using robot_grid_map::PolygonIterator;
|
||||
using robot_grid_map::Position;
|
||||
|
||||
TEST(PolygonIterator, FullCover) {
|
||||
std::vector<std::string> types;
|
||||
|
|
|
|||
|
|
@ -18,9 +18,9 @@ using Eigen::MatrixXd;
|
|||
using Eigen::Vector2d;
|
||||
using Eigen::VectorXd;
|
||||
|
||||
using grid_map::Length;
|
||||
using grid_map::Polygon;
|
||||
using grid_map::Position;
|
||||
using robot_grid_map::Length;
|
||||
using robot_grid_map::Polygon;
|
||||
using robot_grid_map::Position;
|
||||
|
||||
TEST(Polygon, getCentroidTriangle)
|
||||
{
|
||||
|
|
|
|||
|
|
@ -12,11 +12,11 @@
|
|||
#include <gtest/gtest.h>
|
||||
#include <vector>
|
||||
|
||||
using grid_map::GridMap;
|
||||
using grid_map::Index;
|
||||
using grid_map::Length;
|
||||
using grid_map::Position;
|
||||
using grid_map::SlidingWindowIterator;
|
||||
using robot_grid_map::GridMap;
|
||||
using robot_grid_map::Index;
|
||||
using robot_grid_map::Length;
|
||||
using robot_grid_map::Position;
|
||||
using robot_grid_map::SlidingWindowIterator;
|
||||
|
||||
TEST(SlidingWindowIterator, WindowSize3Cutoff)
|
||||
{
|
||||
|
|
|
|||
|
|
@ -15,10 +15,10 @@
|
|||
// Vector
|
||||
#include <vector>
|
||||
|
||||
using grid_map::GridMap;
|
||||
using grid_map::Length;
|
||||
using grid_map::Position;
|
||||
using grid_map::SpiralIterator;
|
||||
using robot_grid_map::GridMap;
|
||||
using robot_grid_map::Length;
|
||||
using robot_grid_map::Position;
|
||||
using robot_grid_map::SpiralIterator;
|
||||
|
||||
TEST(SpiralIterator, CenterOutOfMap)
|
||||
{
|
||||
|
|
|
|||
|
|
@ -21,7 +21,7 @@
|
|||
using std::vector;
|
||||
using std::string;
|
||||
|
||||
namespace grid_map{
|
||||
namespace robot_grid_map{
|
||||
|
||||
TEST(SubmapIterator, Simple) {
|
||||
Eigen::Array2i submapTopLeftIndex(3, 1);
|
||||
|
|
@ -191,8 +191,8 @@ TEST(SubmapIterator, CircularBuffer) {
|
|||
* +----------------------------+
|
||||
*/
|
||||
TEST(SubmapIterator, InterleavedExecutionWithMove) {
|
||||
grid_map::Index submapTopLeftIndex(3, 1);
|
||||
grid_map::Size submapSize(2, 2);
|
||||
robot_grid_map::Index submapTopLeftIndex(3, 1);
|
||||
robot_grid_map::Size submapSize(2, 2);
|
||||
|
||||
GridMap map({"layer"});
|
||||
|
||||
|
|
@ -264,4 +264,4 @@ TEST(SubmapIterator, InterleavedExecutionWithMove) {
|
|||
// });
|
||||
}
|
||||
|
||||
} // namespace grid_map
|
||||
} // namespace robot_grid_map
|
||||
|
|
|
|||
|
|
@ -18,7 +18,7 @@ namespace grid_map_test {
|
|||
|
||||
std::mt19937 rndGenerator;
|
||||
|
||||
AnalyticalFunctions createFlatWorld(grid_map::GridMap *map)
|
||||
AnalyticalFunctions createFlatWorld(robot_grid_map::GridMap *map)
|
||||
{
|
||||
|
||||
AnalyticalFunctions func;
|
||||
|
|
@ -33,7 +33,7 @@ AnalyticalFunctions createFlatWorld(grid_map::GridMap *map)
|
|||
|
||||
}
|
||||
|
||||
AnalyticalFunctions createRationalFunctionWorld(grid_map::GridMap *map)
|
||||
AnalyticalFunctions createRationalFunctionWorld(robot_grid_map::GridMap *map)
|
||||
{
|
||||
|
||||
AnalyticalFunctions func;
|
||||
|
|
@ -54,7 +54,7 @@ AnalyticalFunctions createRationalFunctionWorld(grid_map::GridMap *map)
|
|||
|
||||
}
|
||||
|
||||
AnalyticalFunctions createSecondOrderPolyWorld(grid_map::GridMap *map)
|
||||
AnalyticalFunctions createSecondOrderPolyWorld(robot_grid_map::GridMap *map)
|
||||
{
|
||||
|
||||
AnalyticalFunctions func;
|
||||
|
|
@ -69,7 +69,7 @@ AnalyticalFunctions createSecondOrderPolyWorld(grid_map::GridMap *map)
|
|||
|
||||
}
|
||||
|
||||
AnalyticalFunctions createSaddleWorld(grid_map::GridMap *map)
|
||||
AnalyticalFunctions createSaddleWorld(robot_grid_map::GridMap *map)
|
||||
{
|
||||
AnalyticalFunctions func;
|
||||
|
||||
|
|
@ -83,7 +83,7 @@ AnalyticalFunctions createSaddleWorld(grid_map::GridMap *map)
|
|||
|
||||
}
|
||||
|
||||
AnalyticalFunctions createSineWorld(grid_map::GridMap *map)
|
||||
AnalyticalFunctions createSineWorld(robot_grid_map::GridMap *map)
|
||||
{
|
||||
|
||||
AnalyticalFunctions func;
|
||||
|
|
@ -104,7 +104,7 @@ AnalyticalFunctions createSineWorld(grid_map::GridMap *map)
|
|||
|
||||
}
|
||||
|
||||
AnalyticalFunctions createTanhWorld(grid_map::GridMap *map)
|
||||
AnalyticalFunctions createTanhWorld(robot_grid_map::GridMap *map)
|
||||
{
|
||||
|
||||
AnalyticalFunctions func;
|
||||
|
|
@ -121,7 +121,7 @@ AnalyticalFunctions createTanhWorld(grid_map::GridMap *map)
|
|||
return func;
|
||||
}
|
||||
|
||||
AnalyticalFunctions createGaussianWorld(grid_map::GridMap *map)
|
||||
AnalyticalFunctions createGaussianWorld(robot_grid_map::GridMap *map)
|
||||
{
|
||||
|
||||
struct Gaussian
|
||||
|
|
@ -166,13 +166,13 @@ AnalyticalFunctions createGaussianWorld(grid_map::GridMap *map)
|
|||
return func;
|
||||
}
|
||||
|
||||
void fillGridMap(grid_map::GridMap *map, const AnalyticalFunctions &functions)
|
||||
void fillGridMap(robot_grid_map::GridMap *map, const AnalyticalFunctions &functions)
|
||||
{
|
||||
using grid_map::DataType;
|
||||
using grid_map::GridMapIterator;
|
||||
using grid_map::Index;
|
||||
using grid_map::Matrix;
|
||||
using grid_map::Position;
|
||||
using robot_grid_map::DataType;
|
||||
using robot_grid_map::GridMapIterator;
|
||||
using robot_grid_map::Index;
|
||||
using robot_grid_map::Matrix;
|
||||
using robot_grid_map::Position;
|
||||
|
||||
Matrix& data = (*map)[testLayer];
|
||||
for (GridMapIterator iterator(*map); !iterator.isPastEnd(); ++iterator) {
|
||||
|
|
@ -183,10 +183,10 @@ void fillGridMap(grid_map::GridMap *map, const AnalyticalFunctions &functions)
|
|||
}
|
||||
}
|
||||
|
||||
grid_map::GridMap createMap(const grid_map::Length &length, double resolution,
|
||||
const grid_map::Position &pos)
|
||||
robot_grid_map::GridMap createMap(const robot_grid_map::Length &length, double resolution,
|
||||
const robot_grid_map::Position &pos)
|
||||
{
|
||||
grid_map::GridMap map;
|
||||
robot_grid_map::GridMap map;
|
||||
|
||||
map.setGeometry(length, resolution, pos);
|
||||
map.add(testLayer, 0.0);
|
||||
|
|
@ -195,7 +195,7 @@ grid_map::GridMap createMap(const grid_map::Length &length, double resolution,
|
|||
return map;
|
||||
}
|
||||
|
||||
std::vector<Point2D> uniformlyDitributedPointsWithinMap(const grid_map::GridMap &map,
|
||||
std::vector<Point2D> uniformlyDitributedPointsWithinMap(const robot_grid_map::GridMap &map,
|
||||
unsigned int numPoints)
|
||||
{
|
||||
|
||||
|
|
@ -215,11 +215,11 @@ std::vector<Point2D> uniformlyDitributedPointsWithinMap(const grid_map::GridMap
|
|||
return points;
|
||||
}
|
||||
|
||||
void verifyValuesAtQueryPointsAreClose(const grid_map::GridMap &map, const AnalyticalFunctions &trueValues,
|
||||
void verifyValuesAtQueryPointsAreClose(const robot_grid_map::GridMap &map, const AnalyticalFunctions &trueValues,
|
||||
const std::vector<Point2D> &queryPoints,
|
||||
grid_map::InterpolationMethods interpolationMethod){
|
||||
robot_grid_map::InterpolationMethods interpolationMethod){
|
||||
for (const auto point : queryPoints) {
|
||||
const grid_map::Position p(point.x_, point.y_);
|
||||
const robot_grid_map::Position p(point.x_, point.y_);
|
||||
const double trueValue = trueValues.f_(p.x(), p.y());
|
||||
const double interpolatedValue = map.atPosition(
|
||||
grid_map_test::testLayer, p, interpolationMethod);
|
||||
|
|
|
|||
|
|
@ -12,7 +12,7 @@
|
|||
#include <vector>
|
||||
#include <random>
|
||||
|
||||
namespace grid_map {
|
||||
namespace robot_grid_map {
|
||||
class GridMap;
|
||||
}
|
||||
|
||||
|
|
@ -48,8 +48,8 @@ extern std::mt19937 rndGenerator;
|
|||
// Maximal tolerance when comparing doubles in tests.
|
||||
const double maxAbsErrorValue = 1e-3;
|
||||
|
||||
grid_map::GridMap createMap(const grid_map::Length &length, double resolution,
|
||||
const grid_map::Position &pos);
|
||||
robot_grid_map::GridMap createMap(const robot_grid_map::Length &length, double resolution,
|
||||
const robot_grid_map::Position &pos);
|
||||
|
||||
/*
|
||||
* Collections of methods that modify the grid map.
|
||||
|
|
@ -64,24 +64,24 @@ grid_map::GridMap createMap(const grid_map::Length &length, double resolution,
|
|||
* function.
|
||||
* Each method returns a structure containing the analytical function.
|
||||
*/
|
||||
AnalyticalFunctions createFlatWorld(grid_map::GridMap *map);
|
||||
AnalyticalFunctions createRationalFunctionWorld(grid_map::GridMap *map);
|
||||
AnalyticalFunctions createSaddleWorld(grid_map::GridMap *map);
|
||||
AnalyticalFunctions createSecondOrderPolyWorld(grid_map::GridMap *map);
|
||||
AnalyticalFunctions createSineWorld(grid_map::GridMap *map);
|
||||
AnalyticalFunctions createTanhWorld(grid_map::GridMap *map);
|
||||
AnalyticalFunctions createGaussianWorld(grid_map::GridMap *map);
|
||||
AnalyticalFunctions createFlatWorld(robot_grid_map::GridMap *map);
|
||||
AnalyticalFunctions createRationalFunctionWorld(robot_grid_map::GridMap *map);
|
||||
AnalyticalFunctions createSaddleWorld(robot_grid_map::GridMap *map);
|
||||
AnalyticalFunctions createSecondOrderPolyWorld(robot_grid_map::GridMap *map);
|
||||
AnalyticalFunctions createSineWorld(robot_grid_map::GridMap *map);
|
||||
AnalyticalFunctions createTanhWorld(robot_grid_map::GridMap *map);
|
||||
AnalyticalFunctions createGaussianWorld(robot_grid_map::GridMap *map);
|
||||
|
||||
/*
|
||||
* Iterates over the grid map and fill it with values.
|
||||
* values are calculated by evaluating analytical function.
|
||||
*/
|
||||
void fillGridMap(grid_map::GridMap *map, const AnalyticalFunctions &functions);
|
||||
void fillGridMap(robot_grid_map::GridMap *map, const AnalyticalFunctions &functions);
|
||||
|
||||
/*
|
||||
* Create numPoints uniformly distributed random points that lie within the grid map.
|
||||
*/
|
||||
std::vector<Point2D> uniformlyDitributedPointsWithinMap(const grid_map::GridMap &map,
|
||||
std::vector<Point2D> uniformlyDitributedPointsWithinMap(const robot_grid_map::GridMap &map,
|
||||
unsigned int numPoints);
|
||||
|
||||
/*
|
||||
|
|
@ -89,8 +89,8 @@ std::vector<Point2D> uniformlyDitributedPointsWithinMap(const grid_map::GridMap
|
|||
* is close to the ground truth which is contained in Analytical functions structure.
|
||||
* Called inside the tests. Calls macros from gtest.
|
||||
*/
|
||||
void verifyValuesAtQueryPointsAreClose(const grid_map::GridMap &map, const AnalyticalFunctions &trueValues,
|
||||
void verifyValuesAtQueryPointsAreClose(const robot_grid_map::GridMap &map, const AnalyticalFunctions &trueValues,
|
||||
const std::vector<Point2D> &queryPoints,
|
||||
grid_map::InterpolationMethods interpolationMethod);
|
||||
robot_grid_map::InterpolationMethods interpolationMethod);
|
||||
|
||||
} // namespace grid_map_test
|
||||
|
|
|
|||
Loading…
Reference in New Issue
Block a user