17 using std::numeric_limits;
32 vectorToOrigin = (0.5 * mapLength).matrix();
45 const Length& mapLength,
const double& resolution)
51 vectorToFirstCell = (vectorToOrigin.array() - 0.5 * resolution).matrix();
57 return -Eigen::Matrix2i::Identity();
61 return {-index[0], -index[1]};
70 return {-vector[0], -vector[1]};
74 return {-vector[0], -vector[1]};
79 return ((bufferStartIndex == 0).all());
84 const Size& bufferSize,
85 const Index& bufferStartIndex)
94 const Size& bufferSize,
95 const Index& bufferStartIndex)
102 if (index[0] >= bufferStartIndex[0] && index[1] >= bufferStartIndex[1]) {
105 if (index[0] >= bufferStartIndex[0] && index[1] < bufferStartIndex[1]) {
108 if (index[0] < bufferStartIndex[0] && index[1] >= bufferStartIndex[1]) {
111 if (index[0] < bufferStartIndex[0] && index[1] < bufferStartIndex[1]) {
134 const double& resolution,
135 const Size& bufferSize,
136 const Index& bufferStartIndex)
151 const double& resolution,
152 const Size& bufferSize,
153 const Index& bufferStartIndex)
157 Vector indexVector = ((position - offset - mapPosition).array() / resolution).matrix();
170 return positionTransformed.x() >= 0.0 && positionTransformed.y() >= 0.0
171 && positionTransformed.x() < mapLength(0) && positionTransformed.y() < mapLength(1);
180 positionOfOrigin = position + vectorToOrigin;
184 const Vector& positionShift,
185 const double& resolution)
187 Vector indexShiftVectorTemp = (positionShift.array() / resolution).matrix();
188 Eigen::Vector2i indexShiftVector;
190 for (
int i = 0; i < indexShiftVector.size(); i++) {
191 indexShiftVector[i] =
static_cast<int>(indexShiftVectorTemp[i] + 0.5 * (indexShiftVectorTemp[i] > 0 ? 1 : -1));
199 const Index& indexShift,
200 const double& resolution)
208 return index[0] >= 0 && index[1] >= 0 && index[0] < bufferSize[0] && index[1] < bufferSize[1];
213 for (
int i = 0; i < index.size(); i++) {
222 }
else if (index >= bufferSize) {
223 index = bufferSize - 1;
229 for (
int i = 0; i < index.size(); i++) {
237 if (index < bufferSize){
240 }
else if(index >= -bufferSize){
244 index = index % bufferSize;
247 }
else if(index < bufferSize*2){
251 index = index % bufferSize;
259 Position positionShifted = position - mapPosition + vectorToOrigin;
262 for (
int i = 0; i < positionShifted.size(); i++) {
264 double epsilon = 10.0 * numeric_limits<double>::epsilon();
265 if (std::fabs(position(i)) > 1.0) {
266 epsilon *= std::fabs(position(i));
269 if (positionShifted(i) <= 0) {
270 positionShifted(i) = epsilon;
273 if (positionShifted(i) >= mapLength(i)) {
274 positionShifted(i) = mapLength(i) - epsilon;
279 position = positionShifted + mapPosition - vectorToOrigin;
288 Size& submapBufferSize,
291 Index& requestedIndexInSubmap,
292 const Position& requestedSubmapPosition,
293 const Length& requestedSubmapLength,
296 const double& resolution,
297 const Size& bufferSize,
298 const Index& bufferStartIndex)
304 Position topLeftPosition = requestedSubmapPosition - halfTransform * requestedSubmapLength.matrix();
306 if (!
getIndexFromPosition(submapTopLeftIndex, topLeftPosition, mapLength, mapPosition, resolution, bufferSize, bufferStartIndex)) {
312 Position bottomRightPosition = requestedSubmapPosition + halfTransform * requestedSubmapLength.matrix();
314 Index bottomRightIndex;
315 if (!
getIndexFromPosition(bottomRightIndex, bottomRightPosition, mapLength, mapPosition, resolution, bufferSize, bufferStartIndex)) {
322 if (!
getPositionFromIndex(topLeftCorner, submapTopLeftIndex, mapLength, mapPosition, resolution, bufferSize, bufferStartIndex)) {
325 topLeftCorner -= halfTransform * Position::Constant(resolution);
328 submapBufferSize = bottomRightIndex - topLeftIndex + Index::Ones();
331 submapLength = submapBufferSize.cast<
double>() * resolution;
334 Vector vectorToSubmapOrigin;
336 submapPosition = topLeftCorner - vectorToSubmapOrigin;
340 return getIndexFromPosition(requestedIndexInSubmap, requestedSubmapPosition, submapLength, submapPosition, resolution, submapBufferSize);
344 const Size& bufferSize,
const Index& bufferStartIndex)
348 return Size(unwrappedBottomRightIndex - unwrappedTopLeftIndex + Size::Ones());
352 const Index& submapIndex,
353 const Size& submapBufferSize,
354 const Size& bufferSize,
355 const Index& bufferStartIndex)
357 if ((
getIndexFromBufferIndex(submapIndex, bufferSize, bufferStartIndex) + submapBufferSize > bufferSize).any()) {
361 submapBufferRegions.clear();
363 Index bottomRightIndex = submapIndex + submapBufferSize - Index::Ones();
377 Size topLeftSize(submapBufferSize(0), bufferSize(1) - submapIndex(1));
380 Index topRightIndex(submapIndex(0), 0);
381 Size topRightSize(submapBufferSize(0), submapBufferSize(1) - topLeftSize(1));
387 Size topLeftSize(bufferSize(0) - submapIndex(0), submapBufferSize(1));
390 Index bottomLeftIndex(0, submapIndex(1));
391 Size bottomLeftSize(submapBufferSize(0) - topLeftSize(0), submapBufferSize(1));
397 Size topLeftSize(bufferSize(0) - submapIndex(0), bufferSize(1) - submapIndex(1));
400 Index topRightIndex(submapIndex(0), 0);
401 Size topRightSize(bufferSize(0) - submapIndex(0), submapBufferSize(1) - topLeftSize(1));
404 Index bottomLeftIndex(0, submapIndex(1));
405 Size bottomLeftSize(submapBufferSize(0) - topLeftSize(0), bufferSize(1) - submapIndex(1));
408 Index bottomRightIndex = Index::Zero();
409 Size bottomRightSize(bottomLeftSize(0), topRightSize(1));
423 Size topRightSize(bufferSize(0) - submapIndex(0), submapBufferSize(1));
426 Index bottomRightIndex(0, submapIndex(1));
427 Size bottomRightSize(submapBufferSize(0) - topRightSize(0), submapBufferSize(1));
440 Size bottomLeftSize(submapBufferSize(0), bufferSize(1) - submapIndex(1));
443 Index bottomRightIndex(submapIndex(0), 0);
444 Size bottomRightSize(submapBufferSize(0), submapBufferSize(1) - bottomLeftSize(1));
466 if (unwrappedIndex(1) + 1 < bufferSize(1)) {
472 unwrappedIndex[1] = 0;
486 const Size& submapBufferSize,
const Size& bufferSize,
487 const Index& bufferStartIndex)
490 Index tempIndex = index;
491 Index tempSubmapIndex = submapIndex;
494 if (tempSubmapIndex[1] + 1 < submapBufferSize[1]) {
496 tempSubmapIndex[1]++;
499 tempSubmapIndex[0]++;
500 tempSubmapIndex[1] = 0;
510 tempIndex =
getBufferIndexFromIndex(unwrappedSubmapTopLeftIndex + tempSubmapIndex, bufferSize, bufferStartIndex);
514 submapIndex = tempSubmapIndex;
524 Index index = bufferIndex - bufferStartIndex;
535 Index bufferIndex = index + bufferStartIndex;
543 return index(1) * bufferSize(0) + index(0);
545 return index(0) * bufferSize(1) + index(1);
551 return Index((
int)linearIndex % bufferSize(0), (
int)linearIndex / bufferSize(0));
553 return Index((
int)linearIndex / bufferSize(1), (
int)linearIndex % bufferSize(1));
558 colorVector(0) = (colorValue >> 16) & 0x0000ff;
559 colorVector(1) = (colorValue >> 8) & 0x0000ff;
560 colorVector(2) = colorValue & 0x0000ff;
566 Eigen::Vector3i tempColorVector;
568 colorVector = ((tempColorVector.cast<
float>()).array() / 255.0).matrix();
575 const unsigned long tempColorValue = *
reinterpret_cast<const unsigned long*
>(&colorValue);
582 colorValue = ((int)colorVector(0)) << 16 | ((
int)colorVector(1)) << 8 | ((
int)colorVector(2));
589 colors.
longColor_ = (colorVector(0) << 16) + (colorVector(1) << 8) + colorVector(2);
595 Eigen::Vector3i tempColorVector = (colorVector * 255.0).cast<
int>();
bool incrementIndexForSubmap(Index &submapIndex, Index &index, const Index &submapTopLeftIndex, const Size &submapBufferSize, const Size &bufferSize, const Index &bufferStartIndex=Index::Zero())
void wrapIndexToRange(Index &index, const Size &bufferSize)
bool getBufferRegionsForSubmap(std::vector< BufferRegion > &submapBufferRegions, const Index &submapIndex, const Size &submapBufferSize, const Size &bufferSize, const Index &bufferStartIndex=Index::Zero())
Index getIndexFromBufferIndex(const Index &bufferIndex, const Size &bufferSize, const Index &bufferStartIndex)
Index transformMapFrameToBufferOrder(const Vector &vector)
bool getSubmapInformation(Index &submapTopLeftIndex, Size &submapBufferSize, Position &submapPosition, Length &submapLength, Index &requestedIndexInSubmap, const Position &requestedSubmapPosition, const Length &requestedSubmapLength, const Length &mapLength, const Position &mapPosition, const double &resolution, const Size &bufferSize, const Index &bufferStartIndex=Index::Zero())
size_t getLinearIndexFromIndex(const Index &index, const Size &bufferSize, bool rowMajor=false)
Index getIndexFromIndexVector(const Vector &indexVector, const Size &bufferSize, const Index &bufferStartIndex)
bool getIndexFromPosition(Index &index, const Position &position, const Length &mapLength, const Position &mapPosition, const double &resolution, const Size &bufferSize, const Index &bufferStartIndex=Index::Zero())
Size getSubmapSizeFromCornerIndices(const Index &topLeftIndex, const Index &bottomRightIndex, const Size &bufferSize, const Index &bufferStartIndex)
Eigen::Matrix2i getBufferOrderToMapFrameTransformation()
bool checkIfPositionWithinMap(const Position &position, const Length &mapLength, const Position &mapPosition)
bool getPositionShiftFromIndexShift(Vector &positionShift, const Index &indexShift, const double &resolution)
bool colorVectorToValue(const Eigen::Vector3i &colorVector, unsigned long &colorValue)
bool incrementIndex(Index &index, const Size &bufferSize, const Index &bufferStartIndex=Index::Zero())
bool getVectorToOrigin(Vector &vectorToOrigin, const Length &mapLength)
void getPositionOfDataStructureOrigin(const Position &position, const Length &mapLength, Position &positionOfOrigin)
BufferRegion::Quadrant getQuadrant(const Index &index, const Index &bufferStartIndex)
Vector transformBufferOrderToMapFrame(const Index &index)
void boundIndexToRange(Index &index, const Size &bufferSize)
bool checkIfIndexInRange(const Index &index, const Size &bufferSize)
Vector getIndexVectorFromIndex(const Index &index, const Size &bufferSize, const Index &bufferStartIndex)
bool getPositionFromIndex(Position &position, const Index &index, const Length &mapLength, const Position &mapPosition, const double &resolution, const Size &bufferSize, const Index &bufferStartIndex=Index::Zero())
Index getBufferIndexFromIndex(const Index &index, const Size &bufferSize, const Index &bufferStartIndex)
bool getVectorToFirstCell(Vector &vectorToFirstCell, const Length &mapLength, const double &resolution)
void boundPositionToRange(Position &position, const Length &mapLength, const Position &mapPosition)
bool colorValueToVector(const unsigned long &colorValue, Eigen::Vector3i &colorVector)
bool getIndexShiftFromPositionShift(Index &indexShift, const Vector &positionShift, const double &resolution)
Eigen::Matrix2i getBufferOrderToMapFrameAlignment()
Eigen::Matrix2i getMapFrameToBufferOrderTransformation()
bool checkIfStartIndexAtDefaultPosition(const Index &bufferStartIndex)
Index getIndexFromLinearIndex(size_t linearIndex, const Size &bufferSize, bool rowMajor=false)