18 #ifndef OPEN_KARTO_KARTO_H 19 #define OPEN_KARTO_KARTO_H 37 #include <boost/thread.hpp> 40 #include <Poco/Mutex.h> 46 #define KARTO_Object(name) \ 47 virtual const char* GetClassName() const { return #name; } \ 48 virtual kt_objecttype GetObjectType() const { return ObjectType_##name; } 94 , m_ErrorCode(errorCode)
102 : m_Message(rException.m_Message)
103 , m_ErrorCode(rException.m_ErrorCode)
216 Poco::FastMutex::ScopedLock lock(m_Mutex);
218 if (m_pPointer == NULL)
230 Poco::FastMutex m_Mutex;
300 if (m_ParameterLookup.find(rName) != m_ParameterLookup.end())
302 return m_ParameterLookup[rName];
305 std::cout <<
"Unknown parameter: " << rName << std::endl;
376 : m_Name(rOther.m_Name)
377 , m_Scope(rOther.m_Scope)
404 std::string::size_type pos = rName.find_last_of(
'/');
405 if (pos != 0 && pos != std::string::npos)
407 throw Exception(
"Name can't contain a scope!");
445 name.append(m_Scope);
473 return (m_Name == rOther.
m_Name) && (m_Scope == rOther.
m_Scope);
481 return !(*
this == rOther);
489 return ToString() < rOther.
ToString();
508 void Parse(
const std::string& rName)
510 std::string::size_type pos = rName.find_last_of(
'/');
512 if (pos == std::string::npos)
518 m_Scope = rName.substr(0, pos);
519 m_Name = rName.substr(pos+1, rName.size());
522 if (m_Scope.size() > 0 && m_Scope[0] ==
'/')
524 m_Scope = m_Scope.substr(1, m_Scope.size());
543 for (
size_t i = 1; i < rName.size(); ++i)
548 throw Exception(
"Invalid character in name. Valid characters must be within the ranges A-Z, a-z, 0-9, '/', '_' and '-'.");
554 throw Exception(
"Invalid first character in name. Valid characters must be within the ranges A-Z, a-z, and '/'.");
565 return (isalpha(c) || c ==
'/');
575 return (isalnum(c) || c ==
'/' || c ==
'_' || c ==
'-');
623 virtual const char* GetClassName()
const = 0;
637 return m_pParameterManager;
647 return m_pParameterManager->Get(rName);
656 inline void SetParameter(
const std::string& rName, T value);
664 return m_pParameterManager->GetParameterVector();
774 Module(
const std::string& rName);
785 virtual void Reset() = 0;
836 : m_Width(rOther.m_Width)
837 , m_Height(rOther.m_Height)
1024 return sqrt(SquaredLength());
1033 return (*
this - rOther).SquaredLength();
1043 return sqrt(SquaredDistance(rOther));
1089 inline void operator /= (T scalar)
1091 m_Values[0] /= scalar;
1092 m_Values[1] /= scalar;
1102 return Vector2(m_Values[0] / scalar, m_Values[1] / scalar);
1112 return m_Values[0] * rOther.
m_Values[0] + m_Values[1] * rOther.
m_Values[1];
1121 return Vector2(m_Values[0] * scalar, m_Values[1] * scalar);
1130 return Vector2(m_Values[0] - scalar, m_Values[1] - scalar);
1137 inline void operator *= (T scalar)
1139 m_Values[0] *= scalar;
1140 m_Values[1] *= scalar;
1149 return (m_Values[0] == rOther.
m_Values[0] && m_Values[1] == rOther.
m_Values[1]);
1158 return (m_Values[0] != rOther.
m_Values[0] || m_Values[1] != rOther.
m_Values[1]);
1168 if (m_Values[0] < rOther.
m_Values[0])
1170 else if (m_Values[0] > rOther.
m_Values[0])
1173 return (m_Values[1] < rOther.
m_Values[1]);
1183 rStream << rVector.
GetX() <<
" " << rVector.
GetY();
1191 friend inline std::istream& operator >> (std::istream& rStream,
const Vector2& )
1213 template<
typename T>
1343 return sqrt(SquaredLength());
1352 std::stringstream converter;
1353 converter.precision(std::numeric_limits<double>::digits10);
1355 converter << GetX() <<
" " << GetY() <<
" " << GetZ();
1357 return converter.str();
1392 return Vector3(m_Values[0] + scalar,
1393 m_Values[1] + scalar,
1394 m_Values[2] + scalar);
1416 return Vector3(m_Values[0] - scalar, m_Values[1] - scalar, m_Values[2] - scalar);
1425 return Vector3(m_Values[0] * scalar, m_Values[1] * scalar, m_Values[2] * scalar);
1434 return (m_Values[0] == rOther.
m_Values[0] &&
1435 m_Values[1] == rOther.
m_Values[1] &&
1436 m_Values[2] == rOther.
m_Values[2]);
1445 return (m_Values[0] != rOther.
m_Values[0] ||
1446 m_Values[1] != rOther.
m_Values[1] ||
1447 m_Values[2] != rOther.
m_Values[2]);
1465 friend inline std::istream& operator >> (std::istream& rStream,
const Vector3& )
1534 m_Values[0] = rQuaternion.
m_Values[0];
1535 m_Values[1] = rQuaternion.
m_Values[1];
1536 m_Values[2] = rQuaternion.
m_Values[2];
1537 m_Values[3] = rQuaternion.
m_Values[3];
1622 kt_double test = m_Values[0] * m_Values[1] + m_Values[2] * m_Values[3];
1627 rYaw = 2 * atan2(m_Values[0], m_Values[3]);;
1631 else if (test < -0.499)
1634 rYaw = -2 * atan2(m_Values[0], m_Values[3]);
1640 kt_double sqx = m_Values[0] * m_Values[0];
1641 kt_double sqy = m_Values[1] * m_Values[1];
1642 kt_double sqz = m_Values[2] * m_Values[2];
1644 rYaw = atan2(2 * m_Values[1] * m_Values[3] - 2 * m_Values[0] * m_Values[2], 1 - 2 * sqy - 2 * sqz);
1645 rPitch = asin(2 * test);
1646 rRoll = atan2(2 * m_Values[0] * m_Values[3] - 2 * m_Values[1] * m_Values[2], 1 - 2 * sqx - 2 * sqz);
1665 angle = pitch * 0.5;
1673 m_Values[0] = sYaw * sPitch * cRoll + cYaw * cPitch * sRoll;
1674 m_Values[1] = sYaw * cPitch * cRoll + cYaw * sPitch * sRoll;
1675 m_Values[2] = cYaw * sPitch * cRoll - sYaw * cPitch * sRoll;
1676 m_Values[3] = cYaw * cPitch * cRoll - sYaw * sPitch * sRoll;
1685 m_Values[0] = rQuaternion.
m_Values[0];
1686 m_Values[1] = rQuaternion.
m_Values[1];
1687 m_Values[2] = rQuaternion.
m_Values[2];
1688 m_Values[3] = rQuaternion.
m_Values[3];
1699 return (m_Values[0] == rOther.
m_Values[0] &&
1700 m_Values[1] == rOther.
m_Values[1] &&
1701 m_Values[2] == rOther.
m_Values[2] &&
1702 m_Values[3] == rOther.
m_Values[3]);
1711 return (m_Values[0] != rOther.
m_Values[0] ||
1712 m_Values[1] != rOther.
m_Values[1] ||
1713 m_Values[2] != rOther.
m_Values[2] ||
1714 m_Values[3] != rOther.
m_Values[3]);
1724 rStream << rQuaternion.
m_Values[0] <<
" " 1743 template<
typename T>
1763 , m_Size(width, height)
1773 : m_Position(rPosition)
1782 : m_Position(rOther.m_Position)
1783 , m_Size(rOther.m_Size)
1794 return m_Position.GetX();
1812 return m_Position.GetY();
1830 return m_Size.GetWidth();
1839 m_Size.SetWidth(width);
1848 return m_Size.GetHeight();
1857 m_Size.SetHeight(height);
1885 m_Position = rPosition;
1912 return Vector2<T>(m_Position.GetX() + m_Size.GetWidth() * 0.5, m_Position.GetY() + m_Size.GetHeight() * 0.5);
1974 : m_Position(rPosition)
1975 , m_Heading(heading)
1987 , m_Heading(heading)
2000 : m_Position(rOther.m_Position)
2001 , m_Heading(rOther.m_Heading)
2012 return m_Position.GetX();
2030 return m_Position.GetY();
2057 m_Position = rPosition;
2075 m_Heading = heading;
2084 return m_Position.SquaredDistance(rOther.
m_Position);
2118 inline void operator += (
const Pose2& rOther)
2148 friend inline std::istream& operator >> (std::istream& rStream,
const Pose2& )
2202 : m_Position(rPosition)
2212 : m_Position(rPosition)
2213 , m_Orientation(rOrientation)
2221 : m_Position(rOther.m_Position)
2222 , m_Orientation(rOther.m_Orientation)
2232 m_Orientation.FromEulerAngles(rPose.
GetHeading(), 0.0, 0.0);
2251 m_Position = rPosition;
2260 return m_Orientation;
2269 m_Orientation = rOrientation;
2278 std::stringstream converter;
2279 converter.precision(std::numeric_limits<double>::digits10);
2281 converter << GetPosition() <<
" " << GetOrientation();
2283 return converter.str();
2329 friend inline std::istream& operator >> (std::istream& rStream,
const Pose3& )
2372 memset(m_Matrix, 0, 9*
sizeof(
kt_double));
2376 m_Matrix[i][i] = 1.0;
2385 memset(m_Matrix, 0, 9*
sizeof(
kt_double));
2399 kt_double oneMinusCos = 1.0 - cosRadians;
2413 m_Matrix[0][0] = xx * oneMinusCos + cosRadians;
2414 m_Matrix[0][1] = xyMCos - zSin;
2415 m_Matrix[0][2] = xzMCos + ySin;
2417 m_Matrix[1][0] = xyMCos + zSin;
2418 m_Matrix[1][1] = yy * oneMinusCos + cosRadians;
2419 m_Matrix[1][2] = yzMCos - xSin;
2421 m_Matrix[2][0] = xzMCos - ySin;
2422 m_Matrix[2][1] = yzMCos + xSin;
2423 m_Matrix[2][2] = zz * oneMinusCos + cosRadians;
2438 transpose.
m_Matrix[row][col] = m_Matrix[col][row];
2451 kt_bool haveInverse = InverseFast(kInverse, 1e-14);
2452 if (haveInverse ==
false)
2467 rkInverse.
m_Matrix[0][0] = m_Matrix[1][1]*m_Matrix[2][2] - m_Matrix[1][2]*m_Matrix[2][1];
2468 rkInverse.
m_Matrix[0][1] = m_Matrix[0][2]*m_Matrix[2][1] - m_Matrix[0][1]*m_Matrix[2][2];
2469 rkInverse.
m_Matrix[0][2] = m_Matrix[0][1]*m_Matrix[1][2] - m_Matrix[0][2]*m_Matrix[1][1];
2470 rkInverse.
m_Matrix[1][0] = m_Matrix[1][2]*m_Matrix[2][0] - m_Matrix[1][0]*m_Matrix[2][2];
2471 rkInverse.
m_Matrix[1][1] = m_Matrix[0][0]*m_Matrix[2][2] - m_Matrix[0][2]*m_Matrix[2][0];
2472 rkInverse.
m_Matrix[1][2] = m_Matrix[0][2]*m_Matrix[1][0] - m_Matrix[0][0]*m_Matrix[1][2];
2473 rkInverse.
m_Matrix[2][0] = m_Matrix[1][0]*m_Matrix[2][1] - m_Matrix[1][1]*m_Matrix[2][0];
2474 rkInverse.
m_Matrix[2][1] = m_Matrix[0][1]*m_Matrix[2][0] - m_Matrix[0][0]*m_Matrix[2][1];
2475 rkInverse.
m_Matrix[2][2] = m_Matrix[0][0]*m_Matrix[1][1] - m_Matrix[0][1]*m_Matrix[1][0];
2478 m_Matrix[0][1]*rkInverse.
m_Matrix[1][0] +
2479 m_Matrix[0][2]*rkInverse.
m_Matrix[2][0];
2481 if (fabs(fDet) <= fTolerance)
2487 for (
size_t row = 0; row < 3; row++)
2489 for (
size_t col = 0; col < 3; col++)
2491 rkInverse.
m_Matrix[row][col] *= fInvDet;
2504 std::stringstream converter;
2505 converter.precision(std::numeric_limits<double>::digits10);
2507 for (
int row = 0; row < 3; row++)
2509 for (
int col = 0; col < 3; col++)
2511 converter << m_Matrix[row][col] <<
" ";
2515 return converter.str();
2536 return m_Matrix[row][column];
2547 return m_Matrix[row][column];
2559 for (
size_t row = 0; row < 3; row++)
2561 for (
size_t col = 0; col < 3; col++)
2564 m_Matrix[row][1]*rOther.
m_Matrix[1][col] +
2565 m_Matrix[row][2]*rOther.
m_Matrix[2][col];
2581 pose2.
SetX(m_Matrix[0][0] * rPose2.
GetX() + m_Matrix[0][1] *
2583 pose2.
SetY(m_Matrix[1][0] * rPose2.
GetX() + m_Matrix[1][1] *
2585 pose2.
SetHeading(m_Matrix[2][0] * rPose2.
GetX() + m_Matrix[2][1] *
2601 m_Matrix[row][col] += rkMatrix.
m_Matrix[row][col];
2636 , m_Columns(columns)
2658 if (m_pData != NULL)
2660 memset(m_pData, 0,
sizeof(
kt_double) * m_Rows * m_Columns);
2690 RangeCheck(row, column);
2692 return m_pData[row + column * m_Rows];
2703 RangeCheck(row, column);
2705 return m_pData[row + column * m_Rows];
2716 if (m_pData != NULL)
2721 m_pData =
new kt_double[m_Rows * m_Columns];
2723 catch (
const std::bad_alloc& ex)
2725 throw Exception(
"Matrix allocation error");
2728 if (m_pData == NULL)
2730 throw Exception(
"Matrix allocation error");
2743 throw Exception(
"Matrix - RangeCheck ERROR!!!!");
2748 throw Exception(
"Matrix - RangeCheck ERROR!!!!");
2773 : m_Minimum(999999999999999999.99999, 999999999999999999.99999)
2774 , m_Maximum(-999999999999999999.99999, -999999999999999999.99999)
2792 m_Minimum = mMinimum;
2808 m_Maximum = rMaximum;
2826 m_Minimum.MakeFloor(rPoint);
2827 m_Maximum.MakeCeil(rPoint);
2871 SetTransform(
Pose2(), rPose);
2881 SetTransform(rPose1, rPose2);
2892 Pose2 newPosition = m_Transform + m_Rotation * rSourcePose;
2905 Pose2 newPosition = m_InverseRotation * (rSourcePose - m_Transform);
2920 if (rPose1 == rPose2)
2922 m_Rotation.SetToIdentity();
2923 m_InverseRotation.SetToIdentity();
2924 m_Transform =
Pose2();
2934 if (rPose1.
GetX() != 0.0 || rPose1.
GetY() != 0.0)
2936 newPosition = rPose2 - m_Rotation * rPose1;
2940 newPosition = rPose2;
2992 if (pParameterManger != NULL)
2994 pParameterManger->Add(
this);
3005 const std::string& rDescription,
3008 , m_Description(rDescription)
3011 if (pParameterManger != NULL)
3013 pParameterManger->Add(
this);
3040 return m_Description;
3047 virtual const std::string GetValueAsString()
const = 0;
3053 virtual void SetValueFromString(
const std::string& rStringValue) = 0;
3069 rStream.precision(6);
3070 rStream.flags(std::ios::fixed);
3088 template<
typename T>
3112 const std::string& rDescription,
3152 std::stringstream converter;
3153 converter << m_Value;
3154 return converter.str();
3163 std::stringstream converter;
3164 converter.str(rStringValue);
3165 converter >> m_Value;
3174 return new Parameter(GetName(), GetDescription(), GetValue());
3191 T operator = (T value)
3208 int precision = std::numeric_limits<double>::digits10;
3209 std::stringstream converter;
3210 converter.precision(precision);
3212 converter.str(rStringValue);
3215 converter >> m_Value;
3221 std::stringstream converter;
3222 converter.precision(std::numeric_limits<double>::digits10);
3223 converter << m_Value;
3224 return converter.str();
3230 if (rStringValue ==
"true" || rStringValue ==
"TRUE")
3243 if (m_Value ==
true)
3301 if (m_EnumDefines.find(rStringValue) != m_EnumDefines.end())
3303 m_Value = m_EnumDefines[rStringValue];
3307 std::string validValues;
3311 validValues += iter->first +
", ";
3314 throw Exception(
"Unable to set enum: " + rStringValue +
". Valid values are: " + validValues);
3326 if (iter->second == m_Value)
3332 throw Exception(
"Unable to lookup enum");
3342 if (m_EnumDefines.find(rName) == m_EnumDefines.end())
3344 m_EnumDefines[rName] = value;
3348 std::cerr <<
"Overriding enum value: " << m_EnumDefines[rName] <<
" with " << value << std::endl;
3350 m_EnumDefines[rName] = value;
3453 return m_pOffsetPose->GetValue();
3462 m_pOffsetPose->SetValue(rPose);
3469 virtual kt_bool Validate() = 0;
3548 if ((m_Sensors.find(pSensor->
GetName()) != m_Sensors.end()) && !
override)
3550 throw Exception(
"Cannot register sensor: already registered: [" +
3552 "] (Consider setting 'override' to true)");
3555 std::cout <<
"Registering sensor: [" << pSensor->
GetName().
ToString() <<
"]" << std::endl;
3557 m_Sensors[pSensor->
GetName()] = pSensor;
3568 if (m_Sensors.find(pSensor->
GetName()) != m_Sensors.end())
3570 std::cout <<
"Unregistering sensor: " << pSensor->
GetName().
ToString() << std::endl;
3572 m_Sensors.erase(pSensor->
GetName());
3587 if (m_Sensors.find(rName) != m_Sensors.end())
3589 return m_Sensors[rName];
3592 throw Exception(
"Sensor not registered: [" + rName.
ToString() +
"] (Did you add the sensor to the Dataset?)");
3603 Sensor* pSensor = GetSensorByName(rName);
3605 return dynamic_cast<T*
>(pSensor);
3614 SensorVector sensors;
3616 forEach(SensorManagerMap, &m_Sensors)
3618 sensors.push_back(iter->second);
3631 if (pSensor == NULL)
3633 throw Exception(
"Invalid sensor: NULL");
3637 throw Exception(
"Invalid sensor: nameless");
3689 if (pSensorData == NULL)
3743 return m_pMinimumRange->GetValue();
3752 m_pMinimumRange->SetValue(minimumRange);
3754 SetRangeThreshold(GetRangeThreshold());
3763 return m_pMaximumRange->GetValue();
3772 m_pMaximumRange->SetValue(maximumRange);
3774 SetRangeThreshold(GetRangeThreshold());
3783 return m_pRangeThreshold->GetValue();
3793 m_pRangeThreshold->SetValue(
math::Clip(rangeThreshold, GetMinimumRange(), GetMaximumRange()));
3797 std::cout <<
"Info: clipped range threshold to be within minimum and maximum range!" << std::endl;
3807 return m_pMinimumAngle->GetValue();
3816 m_pMinimumAngle->SetValue(minimumAngle);
3827 return m_pMaximumAngle->GetValue();
3836 m_pMaximumAngle->SetValue(maximumAngle);
3847 return m_pAngularResolution->GetValue();
3858 m_pAngularResolution->SetValue(angularResolution);
3872 std::stringstream stream;
3873 stream <<
"Invalid resolution for Sick LMS100: ";
3874 stream << angularResolution;
3895 std::stringstream stream;
3896 stream <<
"Invalid resolution for Sick LMS291: ";
3897 stream << angularResolution;
3903 throw Exception(
"Can't set angular resolution, please create a LaserRangeFinder of type Custom");
3914 return m_pType->GetValue();
3923 return m_NumberOfRangeReadings;
3930 if (
math::InRange(GetRangeThreshold(), GetMinimumRange(), GetMaximumRange()) ==
false)
3932 std::cout <<
"Please set range threshold to a value between [" 3933 << GetMinimumRange() <<
";" << GetMaximumRange() <<
"]" << std::endl;
3951 kt_bool ignoreThresholdPoints =
true,
4097 Pose2 defaultOffset;
4110 , m_NumberOfRangeReadings(0)
4120 GetParameterManager());
4141 / GetAngularResolution()) + 1);
4209 return value * m_Scale;
4220 kt_double gridX = (rWorld.
GetX() - m_Offset.GetX()) * m_Scale;
4225 gridY = (rWorld.
GetY() - m_Offset.GetY()) * m_Scale;
4229 gridY = (m_Size.GetHeight() / m_Scale - rWorld.
GetY() + m_Offset.GetY()) * m_Scale;
4248 worldY = m_Offset.GetY() + rGrid.
GetY() / m_Scale;
4252 worldY = m_Offset.GetY() + (m_Size.GetHeight() - rGrid.
GetY()) / m_Scale;
4318 return 1.0 / m_Scale;
4327 m_Scale = 1.0 / resolution;
4340 kt_double maxX = minX + GetSize().GetWidth() * GetResolution();
4341 kt_double maxY = minY + GetSize().GetHeight() * GetResolution();
4362 template<
typename T>
4375 Grid* pGrid =
new Grid(width, height);
4388 delete m_pCoordinateConverter;
4397 memset(m_pData, 0, GetDataSize() *
sizeof(T));
4406 Grid* pGrid = CreateGrid(GetWidth(), GetHeight(), GetResolution());
4409 memcpy(pGrid->
GetDataPointer(), GetDataPointer(), GetDataSize());
4423 m_WidthStep = math::AlignValue<kt_int32s>(width, 8);
4425 if (m_pData != NULL)
4433 m_pData =
new T[GetDataSize()];
4435 if (m_pCoordinateConverter == NULL)
4471 if (boundaryCheck ==
true)
4473 if (IsValidGridIndex(rGrid) ==
false)
4475 std::stringstream error;
4476 error <<
"Index " << rGrid <<
" out of range. Index must be between [0; " 4477 << m_Width <<
") and [0; " << m_Height <<
")";
4484 if (boundaryCheck ==
true)
4501 grid.
SetY(index / m_WidthStep);
4502 grid.
SetX(index - grid.
GetY() * m_WidthStep);
4515 return GetCoordinateConverter()->WorldToGrid(rWorld, flipY);
4526 return GetCoordinateConverter()->GridToWorld(rGrid, flipY);
4536 kt_int32s index = GridIndex(rGrid,
true);
4537 return m_pData + index;
4547 kt_int32s index = GridIndex(rGrid,
true);
4548 return m_pData + index;
4611 return m_WidthStep * m_Height;
4622 return m_pData[index];
4631 return m_pCoordinateConverter;
4640 return GetCoordinateConverter()->GetResolution();
4649 return GetCoordinateConverter()->GetBoundingBox();
4663 kt_bool steep = abs(y1 - y0) > abs(x1 - x0);
4707 if (2 * error >= deltaX)
4714 if (IsValidGridIndex(gridIndex))
4716 kt_int32s index = GridIndex(gridIndex,
false);
4717 T* pGridPointer = GetDataPointer();
4718 pGridPointer[index]++;
4736 , m_pCoordinateConverter(NULL)
4738 Resize(width, height);
4786 virtual const std::string Write()
const = 0;
4792 virtual void Read(
const std::string& rValue) = 0;
4840 m_StateId = stateId;
4858 m_UniqueId = uniqueId;
4885 return m_SensorName;
4894 m_CustomData.push_back(pCustomData);
4903 return m_CustomData;
4973 , m_pRangeReadings(NULL)
4974 , m_NumberOfRangeReadings(0)
4985 , m_pRangeReadings(NULL)
4986 , m_NumberOfRangeReadings(0)
4988 assert(rSensorName.
ToString() !=
"");
4990 SetRangeReadings(rRangeReadings);
4998 delete [] m_pRangeReadings;
5008 return m_pRangeReadings;
5031 if (!rRangeReadings.empty())
5033 if (rRangeReadings.size() != m_NumberOfRangeReadings)
5036 delete [] m_pRangeReadings;
5039 m_NumberOfRangeReadings =
static_cast<kt_int32u>(rRangeReadings.size());
5042 m_pRangeReadings =
new kt_double[m_NumberOfRangeReadings];
5049 m_pRangeReadings[index++] = *iter;
5054 delete [] m_pRangeReadings;
5055 m_pRangeReadings = NULL;
5074 return m_NumberOfRangeReadings;
5124 return m_OdometricPose;
5133 m_OdometricPose = rPose;
5191 return m_OdometricPose;
5200 m_OdometricPose = rPose;
5213 return m_CorrectedPose;
5222 m_CorrectedPose = rPose;
5232 boost::shared_lock<boost::shared_mutex> lock(m_Lock);
5237 boost::unique_lock<boost::shared_mutex> uniqueLock(m_Lock);
5241 return m_BarycenterPose;
5251 boost::shared_lock<boost::shared_mutex> lock(m_Lock);
5256 boost::unique_lock<boost::shared_mutex> uniqueLock(m_Lock);
5260 return useBarycenter ? GetBarycenterPose() : GetSensorPose();
5269 return GetSensorAt(m_CorrectedPose);
5278 Pose2 deviceOffsetPose2 = GetLaserRangeFinder()->GetOffsetPose();
5281 kt_double angleoffset = atan2(deviceOffsetPose2.
GetY(), deviceOffsetPose2.
GetX());
5283 Pose2 worldSensorOffset =
Pose2(offsetLength * cos(correctedHeading + angleoffset - offsetHeading),
5284 offsetLength * sin(correctedHeading + angleoffset - offsetHeading),
5287 m_CorrectedPose = rScanPose - worldSensorOffset;
5308 boost::shared_lock<boost::shared_mutex> lock(m_Lock);
5313 boost::unique_lock<boost::shared_mutex> uniqueLock(m_Lock);
5317 return m_BoundingBox;
5325 boost::shared_lock<boost::shared_mutex> lock(m_Lock);
5330 boost::unique_lock<boost::shared_mutex> uniqueLock(m_Lock);
5334 if (wantFiltered ==
true)
5336 return m_PointReadings;
5340 return m_UnfilteredPointReadings;
5353 if (pLaserRangeFinder != NULL)
5355 m_PointReadings.clear();
5356 m_UnfilteredPointReadings.clear();
5361 Pose2 scanPose = GetSensorPose();
5368 kt_double rangeReading = GetRangeReadings()[i];
5374 point.
SetX(scanPose.
GetX() + (rangeReading * cos(angle)));
5375 point.
SetY(scanPose.
GetY() + (rangeReading * sin(angle)));
5377 m_UnfilteredPointReadings.push_back(point);
5384 point.
SetX(scanPose.
GetX() + (rangeReading * cos(angle)));
5385 point.
SetY(scanPose.
GetY() + (rangeReading * sin(angle)));
5387 m_PointReadings.push_back(point);
5388 m_UnfilteredPointReadings.push_back(point);
5390 rangePointsSum += point;
5398 m_BarycenterPose =
Pose2(averagePosition, 0.0);
5402 m_BarycenterPose = scanPose;
5408 forEach(PointVectorDouble, &m_PointReadings)
5410 m_BoundingBox.Add(*iter);
5484 const PointVectorDouble& rPoints)
5485 : m_Points(rPoints),
5503 m_PointReadings.clear();
5504 m_UnfilteredPointReadings.clear();
5506 Pose2 scanPose = GetSensorPose();
5507 Pose2 robotPose = GetCorrectedPose();
5511 for (
kt_int32u i = 0; i < m_Points.size(); i++)
5514 if (!std::isfinite(m_Points[i].GetX()) || !std::isfinite(m_Points[i].GetY()))
5517 m_UnfilteredPointReadings.push_back(point);
5523 Pose2 pointPose(m_Points[i].GetX(), m_Points[i].GetY(), 0);
5527 m_PointReadings.push_back(point);
5528 m_UnfilteredPointReadings.push_back(point);
5530 rangePointsSum += point;
5538 m_BarycenterPose =
Pose2(averagePosition, 0.0);
5542 m_BarycenterPose = scanPose;
5548 forEach(PointVectorDouble, &m_PointReadings)
5550 m_BoundingBox.Add(*iter);
5574 : m_pOccupancyGrid(pGrid)
5582 virtual void operator() (
kt_int32u index);
5594 friend class IncrementalOccupancyGrid;
5606 , m_pCellPassCnt(
Grid<
kt_int32u>::CreateGrid(0, 0, resolution))
5607 , m_pCellHitsCnt(
Grid<
kt_int32u>::CreateGrid(0, 0, resolution))
5608 , m_pCellUpdater(NULL)
5614 throw Exception(
"Resolution cannot be 0");
5620 GetCoordinateConverter()->SetScale(1.0 / resolution);
5621 GetCoordinateConverter()->SetOffset(rOffset);
5629 delete m_pCellUpdater;
5631 delete m_pCellPassCnt;
5632 delete m_pCellHitsCnt;
5634 delete m_pMinPassThrough;
5635 delete m_pOccupancyThreshold;
5653 ComputeDimensions(rScans, resolution, width, height, offset);
5657 return pOccupancyGrid;
5668 GetCoordinateConverter()->GetOffset(),
5669 1.0 / GetCoordinateConverter()->GetScale());
5670 memcpy(pOccupancyGrid->
GetDataPointer(), GetDataPointer(), GetDataSize());
5676 return pOccupancyGrid;
5704 double scale = GetCoordinateConverter()->GetScale();
5713 kt_double xStop = x + maxRange * cosTheta;
5714 kt_double xSteps = 1 + fabs(xStop - x) * scale;
5716 kt_double yStop = y + maxRange * sinTheta;
5717 kt_double ySteps = 1 + fabs(yStop - y) * scale;
5729 if (IsValidGridIndex(gridIndex) && IsFree(gridIndex))
5731 distance = (i + 1) * delta;
5739 return (distance < maxRange)? distance : maxRange;
5749 m_pMinPassThrough->SetValue(count);
5758 m_pOccupancyThreshold->SetValue(thresh);
5768 return m_pCellHitsCnt;
5777 return m_pCellPassCnt;
5798 boundingBox.
Add((*iter)->GetBoundingBox());
5815 m_pCellPassCnt->Resize(GetWidth(), GetHeight());
5816 m_pCellPassCnt->GetCoordinateConverter()->SetOffset(GetCoordinateConverter()->GetOffset());
5818 m_pCellHitsCnt->Resize(GetWidth(), GetHeight());
5819 m_pCellHitsCnt->GetCoordinateConverter()->SetOffset(GetCoordinateConverter()->GetOffset());
5858 if (rangeReading <= minRange || rangeReading >= maxRange || std::isnan(rangeReading))
5864 else if (rangeReading >= rangeThreshold)
5867 kt_double ratio = rangeThreshold / rangeReading;
5870 point.
SetX(scanPosition.
GetX() + ratio * dx);
5871 point.
SetY(scanPosition.
GetY() + ratio * dy);
5874 kt_bool isInMap = RayTrace(scanPosition, point, isEndPointValid, doUpdate);
5900 assert(m_pCellPassCnt != NULL && m_pCellHitsCnt != NULL);
5905 CellUpdater* pCellUpdater = doUpdate ? m_pCellUpdater : NULL;
5906 m_pCellPassCnt->TraceLine(gridFrom.
GetX(), gridFrom.
GetY(), gridTo.
GetX(), gridTo.
GetY(), pCellUpdater);
5909 if (isEndPointValid)
5911 if (m_pCellPassCnt->IsValidGridIndex(gridTo))
5913 kt_int32s index = m_pCellPassCnt->GridIndex(gridTo,
false);
5915 kt_int32u* pCellPassCntPtr = m_pCellPassCnt->GetDataPointer();
5916 kt_int32u* pCellHitCntPtr = m_pCellHitsCnt->GetDataPointer();
5919 pCellPassCntPtr[index]++;
5920 pCellHitCntPtr[index]++;
5924 (*m_pCellUpdater)(index);
5929 return m_pCellPassCnt->IsValidGridIndex(gridTo);
5940 if (cellPassCnt > m_pMinPassThrough->GetValue())
5942 kt_double hitRatio =
static_cast<kt_double>(cellHitCnt) / static_cast<kt_double>(cellPassCnt);
5944 if (hitRatio > m_pOccupancyThreshold->GetValue())
5960 assert(m_pCellPassCnt != NULL && m_pCellHitsCnt != NULL);
5966 kt_int8u* pDataPtr = GetDataPointer();
5967 kt_int32u* pCellPassCntPtr = m_pCellPassCnt->GetDataPointer();
5968 kt_int32u* pCellHitCntPtr = m_pCellHitsCnt->GetDataPointer();
5971 for (
kt_int32u i = 0; i < nBytes; i++, pDataPtr++, pCellPassCntPtr++, pCellHitCntPtr++)
5973 UpdateCell(pDataPtr, *pCellPassCntPtr, *pCellHitCntPtr);
5985 m_pCellPassCnt->Resize(width, height);
5986 m_pCellHitsCnt->Resize(width, height);
6061 return m_pTitle->GetValue();
6069 return m_pAuthor->GetValue();
6077 return m_pDescription->GetValue();
6085 return m_pCopyright->GetValue();
6114 : m_pDatasetInfo(NULL)
6133 if (pObject != NULL)
6135 if (dynamic_cast<Sensor*>(pObject))
6138 if (pSensor != NULL)
6140 m_SensorNameLookup[pSensor->
GetName()] = pSensor;
6145 m_Objects.push_back(pObject);
6147 else if (dynamic_cast<SensorData*>(pObject))
6150 m_Objects.push_back(pSensorData);
6152 else if (dynamic_cast<DatasetInfo*>(pObject))
6154 m_pDatasetInfo =
dynamic_cast<DatasetInfo*
>(pObject);
6158 m_Objects.push_back(pObject);
6178 return m_pDatasetInfo;
6186 for (std::map<Name, Sensor*>::iterator iter = m_SensorNameLookup.begin(); iter != m_SensorNameLookup.end(); ++iter)
6191 forEach(ObjectVector, &m_Objects)
6198 if (m_pDatasetInfo != NULL)
6200 delete m_pDatasetInfo;
6201 m_pDatasetInfo = NULL;
6237 assert(m_pArray != NULL);
6249 memset(m_pArray, 0,
sizeof(
kt_int32s) * m_Capacity);
6269 if (size > m_Capacity)
6271 if (m_pArray != NULL)
6289 assert(index < m_Size);
6291 return m_pArray[index];
6301 assert(index < m_Size);
6303 return m_pArray[index];
6347 template<
typename T>
6359 , m_ppLookupArray(NULL)
6381 return m_ppLookupArray[index];
6405 assert(angleOffset != 0.0);
6406 assert(angleResolution != 0.0);
6419 Pose2Vector localPoints;
6423 Pose2 vec = transform.InverseTransformPose(
Pose2(*iter, 0.0));
6424 localPoints.push_back(vec);
6430 kt_double startAngle = angleCenter - angleOffset;
6431 for (
kt_int32u angleIndex = 0; angleIndex < nAngles; angleIndex++)
6433 angle = startAngle + angleIndex * angleResolution;
6434 ComputeOffsets(angleIndex, angle, localPoints, pScan);
6448 m_ppLookupArray[angleIndex]->SetSize(static_cast<kt_int32u>(rLocalPoints.size()));
6449 m_Angles.at(angleIndex) = angle;
6454 const Vector2<kt_double>& rGridOffset = m_pGrid->GetCoordinateConverter()->GetOffset();
6461 kt_int32s* pAngleIndexPointer = m_ppLookupArray[angleIndex]->GetArrayPointer();
6479 offset.
SetX(cosine * rPosition.
GetX() - sine * rPosition.
GetY());
6480 offset.
SetY(sine * rPosition.
GetX() + cosine * rPosition.
GetY());
6486 kt_int32s lookupIndex = m_pGrid->Grid<T>::GridIndex(gridPoint,
false);
6488 pAngleIndexPointer[readingIndex] = lookupIndex;
6492 assert(readingIndex == rLocalPoints.size());
6503 if (size > m_Capacity)
6505 if (m_ppLookupArray != NULL)
6512 for (
kt_int32u i = 0; i < m_Capacity; i++)
6520 m_Angles.resize(size);
6528 for (
kt_int32u i = 0; i < m_Capacity; i++)
6530 delete m_ppLookupArray[i];
6533 delete[] m_ppLookupArray;
6534 m_ppLookupArray = NULL;
6554 : m_Position(rPose.GetPosition().GetX(), rPose.GetPosition().GetY())
6568 template<
typename T>
6572 if (pParameter != NULL)
6574 std::stringstream stream;
6580 throw Exception(
"Parameter does not exist: " + rName);
6588 if (pParameter != NULL)
6594 throw Exception(
"Parameter does not exist: " + rName);
6603 #endif // OPEN_KARTO_KARTO_H kt_int32s GetHeight() const
void Add(const BoundingBox2 &rBoundingBox)
BoundingBox2 m_BoundingBox
const Pose2 & GetOdometricPose() const
kt_bool InverseFast(Matrix3 &rkInverse, kt_double fTolerance=KT_TOLERANCE) const
std::vector< kt_double > m_Angles
Parameters(const std::string &rName)
const kt_objecttype ObjectType_Misc
const kt_objecttype ObjectType_CustomData
std::string m_Description
void SetSize(const Size2< kt_int32s > &rSize)
kt_int32s GetStateId() const
kt_double Distance(const Vector2 &rOther) const
RangeReadingsVector GetRangeReadingsVector() const
DrivePose(const Name &rSensorName)
AbstractParameter(const std::string &rName, const std::string &rDescription, ParameterManager *pParameterManger=NULL)
PointVectorDouble m_UnfilteredPointReadings
Matrix3(const Matrix3 &rOther)
virtual kt_bool Validate()
Size2< kt_int32s > m_Size
void SetSize(const Size2< T > &rSize)
kt_int32s GetDataSize() const
const kt_objecttype ObjectType_LocalizedRangeScan
std::vector< Sensor * > SensorVector
kt_int32u GetNumberOfRangeReadings() const
virtual kt_objecttype GetObjectType() const =0
Exception(const std::string &rMessage="Karto Exception", kt_int32s errorCode=0)
CellUpdater * m_pCellUpdater
Parameter< kt_double > * m_pOccupancyThreshold
kt_bool IsSensorData(Object *pObject)
Pose3(const Vector3< kt_double > &rPosition)
const Size2< kt_int32s > GetSize() const
Pose2(kt_double x, kt_double y, kt_double heading)
kt_double SquaredLength() const
virtual ~ParameterManager()
LaserRangeScan(const Name &rSensorName)
const kt_int32s INVALID_SCAN
T * GetDataPointer() const
void SetMinimum(const Vector2< kt_double > &mMinimum)
kt_double GetHeading() const
Name(const std::string &rName)
kt_double Round(kt_double value)
const PointVectorDouble & GetPointReadings(kt_bool wantFiltered=false) const
void MakeCeil(const Vector2 &rOther)
const Vector2< kt_double > & GetMinimum() const
kt_double & operator()(kt_int32u row, kt_int32u column)
void SetUniqueId(kt_int32u uniqueId)
Vector2< kt_double > GridToWorld(const Vector2< kt_int32s > &rGrid, kt_bool flipY=false) const
static void Validate(Sensor *pSensor)
kt_int32u GetColumns() const
kt_int32s GetWidthStep() const
const Pose2 & GetOffsetPose() const
const std::string & GetTitle() const
std::vector< Vector2< kt_double > > PointVectorDouble
const kt_objecttype ObjectType_DatasetInfo
void SetValue(const T &rValue)
const kt_objecttype ObjectType_CameraImage
Pose2(const Vector2< kt_double > &rPosition, kt_double heading)
const std::string & GetCopyright() const
void FromEulerAngles(kt_double yaw, kt_double pitch, kt_double roll)
void DefineEnumValue(kt_int32s value, const std::string &rName)
void SetPosition(const T &rX, const T &rY)
kt_bool IsValidFirst(char c)
void SetRangeThreshold(kt_double rangeThreshold)
const kt_objecttype ObjectType_Module
std::vector< Object * > ObjectVector
const Size2< kt_int32s > & GetSize() const
kt_int32s * GetArrayPointer()
Vector2< kt_int32s > WorldToGrid(const Vector2< kt_double > &rWorld, kt_bool flipY=false) const
kt_int32u m_NumberOfRangeReadings
const T & GetValue() const
Vector2< kt_double > m_Maximum
Pose2 GetReferencePose(kt_bool useBarycenter) const
kt_bool IsLocalizedRangeScanWithPoints(Object *pObject)
const T & Maximum(const T &value1, const T &value2)
BoundingBox2 GetBoundingBox() const
kt_double DegreesToRadians(kt_double degrees)
void SetScope(const std::string &rScope)
const kt_objecttype ObjectType_None
AbstractParameter(const std::string &rName, ParameterManager *pParameterManger=NULL)
const kt_objecttype ObjectType_Header
Parameter< kt_double > * m_pMinimumAngle
virtual ~LaserRangeFinder()
const CustomDataVector & GetCustomData() const
const std::string & GetName() const
BoundingBox2 GetBoundingBox() const
virtual const std::string GetValueAsString() const
LaserRangeFinder(const Name &rName)
LocalizedRangeScanWithPoints(const Name &rSensorName, const RangeReadingsVector &rReadings, const PointVectorDouble &rPoints)
Size2(const Size2 &rOther)
kt_double GetAngularResolution() const
const Pose2 & GetBarycenterPose() const
Vector3(const Vector3 &rOther)
Parameter(const std::string &rName, T value, ParameterManager *pParameterManger=NULL)
void SetParameter(const std::string &rName, T value)
kt_int32s GetWidth() const
const Name & GetName() const
AbstractParameter * Get(const std::string &rName)
Matrix3 Transpose() const
void SetStateId(kt_int32s stateId)
LaserRangeScan(const Name &rSensorName, const RangeReadingsVector &rRangeReadings)
Parameter< Pose2 > * m_pOffsetPose
Parameter(const std::string &rName, const std::string &rDescription, T value, ParameterManager *pParameterManger=NULL)
virtual void UpdateCell(kt_int8u *pCell, kt_int32u cellPassCnt, kt_int32u cellHitCnt)
#define forEach(listtype, list)
const kt_objecttype ObjectType_LaserRangeFinder
boost::shared_mutex m_Lock
static void ComputeDimensions(const LocalizedRangeScanVector &rScans, kt_double resolution, kt_int32s &rWidth, kt_int32s &rHeight, Vector2< kt_double > &rOffset)
virtual Grid< kt_int32u > * GetCellPassCounts()
const PointVectorDouble m_Points
Parameter< std::string > * m_pAuthor
void SetSensorPose(const Pose2 &rScanPose)
void SetMinimumAngle(kt_double minimumAngle)
std::string ToString() const
void Add(const Vector2< kt_double > &rPoint)
void SetMaximumRange(kt_double maximumRange)
Drive(const std::string &rName)
void SetOffsetPose(const Pose2 &rPose)
Sensor * GetSensorByName(const Name &rName)
Parameter< std::string > * m_pDescription
Rectangle2(const Rectangle2 &rOther)
const Vector2< T > GetCenter() const
Parameter< kt_double > * m_pAngularResolution
Pose3(const Vector3< kt_double > &rPosition, const karto::Quaternion &rOrientation)
const kt_objecttype ObjectType_Sensor
void ComputeOffsets(kt_int32u angleIndex, kt_double angle, const Pose2Vector &rLocalPoints, LocalizedRangeScan *pScan)
void SetPosition(const Vector2< T > &rPosition)
Pose2(const Pose2 &rOther)
virtual const std::string GetValueAsString() const
void SetResolution(kt_double resolution)
kt_double & operator()(kt_int32u row, kt_int32u column)
Pose2 GetSensorPose() const
virtual kt_bool AddScan(LocalizedRangeScan *pScan, kt_bool doUpdate=false)
std::vector< kt_double > RangeReadingsVector
void SetAngularResolution(kt_double angularResolution)
void Add(Object *pObject)
const kt_objecttype ObjectType_Camera
const kt_objecttype ObjectType_SensorData
Parameter< std::string > * m_pTitle
Pose3(const Pose3 &rOther)
void ComputeOffsets(LocalizedRangeScan *pScan, kt_double angleCenter, kt_double angleOffset, kt_double angleResolution)
const BoundingBox2 & GetBoundingBox() const
std::string ToString() const
virtual ~LaserRangeScan()
const std::string & GetErrorMessage() const
Parameter< kt_int32u > * m_pMinPassThrough
void SetScale(kt_double scale)
const std::string & GetName() const
Quaternion(const Quaternion &rQuaternion)
kt_double SquaredDistance(const Pose2 &rOther) const
void TraceLine(kt_int32s x0, kt_int32s y0, kt_int32s x1, kt_int32s y1, Functor *f=NULL)
T * GetDataPointer(const Vector2< kt_int32s > &rGrid) const
virtual kt_bool Validate()
Quaternion(kt_double x, kt_double y, kt_double z, kt_double w)
Vector2< kt_double > m_Position
virtual ParameterManager * GetParameterManager()
void SetMaximumAngle(kt_double maximumAngle)
std::vector< CustomData * > CustomDataVector
const T & Clip(const T &n, const T &minValue, const T &maxValue)
kt_bool IsLaserRangeFinder(Object *pObject)
kt_bool IsInBounds(const Vector2< kt_double > &rPoint) const
const Name & GetSensorName() const
const ParameterVector & GetParameterVector() const
Size2< kt_double > GetSize() const
kt_double GetResolution() const
virtual void Resize(kt_int32s width, kt_int32s height)
SensorVector GetAllSensors()
ParameterManager * m_pParameterManager
#define KARTO_Object(name)
virtual kt_double RayCast(const Pose2 &rPose2, kt_double maxRange) const
void SetOccupancyThreshold(kt_double thresh)
virtual ~AbstractParameter()
virtual void Resize(kt_int32s width, kt_int32s height)
T * GetSensorByName(const Name &rName)
const LookupArray * GetLookupArray(kt_int32u index) const
kt_int32s GetUniqueId() const
void MakeFloor(const Vector2 &rOther)
kt_bool IsDatasetInfo(Object *pObject)
static Grid * CreateGrid(kt_int32s width, kt_int32s height, kt_double resolution)
void UnregisterSensor(Sensor *pSensor)
std::map< std::string, kt_int32s > EnumMap
Parameter< kt_double > * m_pRangeThreshold
virtual kt_bool RayTrace(const Vector2< kt_double > &rWorldFrom, const Vector2< kt_double > &rWorldTo, kt_bool isEndPointValid, kt_bool doUpdate=false)
void SetPosition(const Vector3< kt_double > &rPosition)
Grid< kt_int32u > * m_pCellPassCnt
Vector2< kt_int32s > IndexToGrid(kt_int32s index) const
virtual ~LocalizedRangeScanWithPoints()
const std::vector< kt_double > & GetAngles() const
Parameter< kt_double > * m_pMinimumRange
std::vector< Pose2 > Pose2Vector
virtual const std::string GetValueAsString() const =0
void SetOffset(const Vector2< kt_double > &rOffset)
const ParameterVector & GetParameters() const
DatasetInfo * GetDatasetInfo()
const std::string & GetDescription() const
virtual kt_int32s GridIndex(const Vector2< kt_int32s > &rGrid, kt_bool boundaryCheck=true) const
virtual Parameter * Clone()
Rectangle2(const Vector2< T > &rPosition, const Size2< T > &rSize)
T * GetDataPointer(const Vector2< kt_int32s > &rGrid)
kt_double * m_pRangeReadings
std::map< std::string, AbstractParameter * > m_ParameterLookup
kt_double GetTime() const
kt_bool InRange(const T &value, const T &a, const T &b)
kt_double SquaredDistance(const Vector2 &rOther) const
kt_int32u GetRows() const
const kt_double KT_TOLERANCE
kt_double NormalizeAngle(kt_double angle)
kt_int32u m_NumberOfRangeReadings
static SensorManager * GetInstance()
#define const_forEach(listtype, list)
Matrix(kt_int32u rows, kt_int32u columns)
ParameterVector m_Parameters
static OccupancyGrid * CreateFromScans(const LocalizedRangeScanVector &rScans, kt_double resolution)
Parameter< kt_double > * m_pMaximumRange
void RangeCheck(kt_int32u row, kt_int32u column) const
void SetSize(kt_int32u size)
GridIndexLookup(Grid< T > *pGrid)
const Vector2< T > & GetPosition() const
kt_double GetMinimumAngle() const
kt_bool IsParameters(Object *pObject)
Vector2< kt_double > m_Offset
kt_int32u GetSize() const
virtual void SetValueFromString(const std::string &rStringValue)=0
void SetOdometricPose(const Pose2 &rPose)
virtual void CreateFromScans(const LocalizedRangeScanVector &rScans)
void Validate(const std::string &rName)
static LaserRangeFinder * CreateLaserRangeFinder(LaserRangeFinderType type, const Name &rName)
Vector2< kt_double > m_Minimum
const kt_objecttype ObjectType_DrivePose
const std::string & GetAuthor() const
DatasetInfo * m_pDatasetInfo
kt_double operator()(kt_int32u row, kt_int32u column) const
const Vector2< kt_double > & GetOffset() const
void SetName(const std::string &rName)
const std::string & GetScope() const
virtual ~GridIndexLookup()
virtual void SetValueFromString(const std::string &rStringValue)
const kt_double & operator()(kt_int32u row, kt_int32u column) const
virtual kt_bool IsFree(const Vector2< kt_int32s > &rPose) const
virtual ~LocalizedRangeScan()
LookupArray ** m_ppLookupArray
void SetPosition(const Vector2< kt_double > &rPosition)
CoordinateConverter * GetCoordinateConverter() const
kt_int32s * GetArrayPointer() const
OccupancyGrid * Clone() const
void Parse(const std::string &rName)
void SetSize(kt_int32u size)
void SetMinimumRange(kt_double minimumRange)
LaserRangeFinder * GetLaserRangeFinder() const
CustomDataVector m_CustomData
const std::string & GetDescription() const
void SetRangeReadings(const RangeReadingsVector &rRangeReadings)
Vector2< kt_double > GridToWorld(const Vector2< kt_int32s > &rGrid, kt_bool flipY=false) const
virtual Parameter< kt_int32s > * Clone()
void SetCorrectedPose(const Pose2 &rPose)
Parameter< std::string > * m_pCopyright
Pose2 GetSensorAt(const Pose2 &rPose) const
virtual kt_bool Process(karto::Object *)
Parameter< kt_double > * m_pMaximumAngle
Rectangle2(T x, T y, T width, T height)
void MakeFloor(const Vector3 &rOther)
void SetOdometricPose(const Pose3 &rPose)
kt_bool IsSensor(Object *pObject)
kt_double SquaredLength() const
T GetValue(const Vector2< kt_int32s > &rGrid) const
AbstractParameter * GetParameter(const std::string &rName) const
PointVectorDouble m_PointReadings
void SetTime(kt_double time)
kt_double GetResolution() const
const Vector3< kt_double > & GetPosition() const
const Pose3 & GetOdometricPose() const
OccupancyGrid * m_pOccupancyGrid
kt_bool DoubleEqual(kt_double a, kt_double b)
kt_double GetMaximumAngle() const
const Quaternion & GetOrientation() const
const ObjectVector & GetObjects() const
Pose3(const Pose2 &rPose)
void SetHeading(kt_double heading)
CoordinateConverter * m_pCoordinateConverter
SensorManagerMap m_Sensors
void RegisterSensor(Sensor *pSensor, kt_bool override=false)
const kt_objecttype ObjectType_Parameters
OccupancyGrid(kt_int32s width, kt_int32s height, const Vector2< kt_double > &rOffset, kt_double resolution)
kt_double GetMinimumRange() const
void SetMaximum(const Vector2< kt_double > &rMaximum)
kt_double GetScale() const
const Vector2< kt_double > & GetMaximum() const
std::ostream & operator<<(std::ostream &rStream, Exception &rException)
void SetOrientation(const Quaternion &rOrientation)
Grid< kt_int32u > * m_pCellHitsCnt
virtual Grid< kt_int32u > * GetCellHitsCounts()
const kt_objecttype ObjectType_LaserRangeScan
LocalizedRangeScan(const Name &rSensorName, const RangeReadingsVector &rReadings)
const Vector2< kt_double > & GetPosition() const
std::vector< AbstractParameter * > ParameterVector
const T GetHeight() const
kt_bool IsValidGridIndex(const Vector2< kt_int32s > &rGrid) const
ParameterEnum(const std::string &rName, kt_int32s value, ParameterManager *pParameterManger=NULL)
std::map< Name, Sensor * > m_SensorNameLookup
#define const_forEachAs(listtype, list, iter)
kt_double * GetRangeReadings() const
const kt_objecttype ObjectType_LocalizedRangeScanWithPoints
kt_double GetRangeThreshold() const
kt_int32u GetNumberOfRangeReadings() const
Vector2< kt_int32s > WorldToGrid(const Vector2< kt_double > &rWorld, kt_bool flipY=false) const
virtual kt_bool Validate(SensorData *pSensorData)
const Pose2 & GetCorrectedPose() const
CellUpdater(OccupancyGrid *pGrid)
kt_bool IsUpTo(const T &value, const T &maximum)
Exception(const Exception &rException)
std::map< Name, Sensor * > SensorManagerMap
kt_bool IsLocalizedRangeScan(Object *pObject)
virtual void SetValueFromString(const std::string &rStringValue)
const kt_objecttype ObjectType_Drive
Grid(kt_int32s width, kt_int32s height)
std::vector< LocalizedRangeScan * > LocalizedRangeScanVector
void ToEulerAngles(kt_double &rYaw, kt_double &rPitch, kt_double &rRoll) const
void AddCustomData(CustomData *pCustomData)
void SetMinPassThrough(kt_int32u count)
Vector3< kt_double > m_Position
kt_double Transform(kt_double value)
kt_double GetMaximumRange() const
const Size2< T > & GetSize() const
std::string ToString() const
void FromAxisAngle(kt_double x, kt_double y, kt_double z, const kt_double radians)
void MakeCeil(const Vector3 &rOther)