38 #include <gtest/gtest.h> 44 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
45 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
46 0, 0, 0, 0, 0, 0, 0, 200, 200, 200,
47 0, 0, 0, 0, 100, 0, 0, 200, 200, 200,
48 0, 0, 0, 0, 100, 0, 0, 200, 200, 200,
49 70, 70, 0, 0, 0, 0, 0, 0, 0, 0,
50 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
51 0, 0, 0, 200, 200, 200, 0, 0, 0, 0,
52 0, 0, 0, 0, 0, 0, 0, 255, 255, 255,
53 0, 0, 0, 0, 0, 0, 0, 255, 255, 255
74 const double MAX_Z(1.0);
79 bool find(
const std::vector<unsigned int>& l,
unsigned int n){
80 for(std::vector<unsigned int>::const_iterator it = l.begin(); it != l.end(); ++it){
91 TEST(costmap, testResetForStaticMap){
93 std::vector<unsigned char> staticMap;
94 for(
unsigned int i=0; i<10; i++){
95 for(
unsigned int j=0; j<10; j++){
101 Costmap2D map(10, 10,
RESOLUTION, 0.0, 0.0, 3, 3, 3,
OBSTACLE_RANGE,
MAX_Z,
RAYTRACE_RANGE, 25, staticMap,
THRESHOLD);
104 pcl::PointCloud<pcl::PointXYZ> cloud;
105 cloud.points.resize(40);
108 unsigned int ind = 0;
109 for (
unsigned int i = 0; i < 10; i++){
111 cloud.points[ind].x = 0;
112 cloud.points[ind].y = i;
113 cloud.points[ind].z =
MAX_Z;
117 cloud.points[ind].x = i;
118 cloud.points[ind].y = 0;
119 cloud.points[ind].z =
MAX_Z;
123 cloud.points[ind].x = 9;
124 cloud.points[ind].y = i;
125 cloud.points[ind].z =
MAX_Z;
129 cloud.points[ind].x = i;
130 cloud.points[ind].y = 9;
131 cloud.points[ind].z =
MAX_Z;
135 double wx = 5.0, wy = 5.0;
136 geometry_msgs::Point p;
141 std::vector<Observation> obsBuf;
142 obsBuf.push_back(obs);
145 map.updateWorld(wx, wy, obsBuf, obsBuf);
150 for(
unsigned int i=0; i < 10; ++i){
151 for(
unsigned int j=0; j < 10; ++j){
157 ASSERT_EQ(hitCount, 36);
161 for(
unsigned int i=0; i < 10; ++i){
162 for(
unsigned int j=0; j < 10; ++j){
167 ASSERT_EQ(hitCount, 64);
170 map.resetMapOutsideWindow(wx, wy, 0.0, 0.0);
174 for(
unsigned int i=0; i < 10; ++i){
175 for(
unsigned int j=0; j < 10; ++j){
180 ASSERT_EQ(hitCount, 100);
187 TEST(costmap, testCostFunctionCorrectness){
193 ASSERT_EQ(map.getCircumscribedCost(), c);
196 pcl::PointCloud<pcl::PointXYZ> cloud;
197 cloud.points.resize(1);
198 cloud.points[0].x = 50;
199 cloud.points[0].y = 50;
200 cloud.points[0].z =
MAX_Z;
202 geometry_msgs::Point p;
208 std::vector<Observation> obsBuf;
209 obsBuf.push_back(obs);
211 map.updateWorld(0, 0, obsBuf, obsBuf);
213 for(
unsigned int i = 0; i <= (
unsigned int)ceil(
ROBOT_RADIUS * 5.0); i++){
229 for(
unsigned int i = (
unsigned int)(ceil(
ROBOT_RADIUS * 5.0) + 1); i <= (
unsigned int)ceil(
ROBOT_RADIUS * 10.5); i++){
230 unsigned char expectedValue = map.computeCost(i /
RESOLUTION);
231 ASSERT_EQ(map.
getCost(50 + i, 50), expectedValue);
235 map.resetMapOutsideWindow(0, 0, 0.0, 0.0);
236 cloud.points.resize(0);
243 std::vector<Observation> obsBuf2;
244 obsBuf2.push_back(obs2);
246 map.updateWorld(0, 0, obsBuf2, obsBuf2);
248 for(
unsigned int i = 0; i < 100; i++)
249 for(
unsigned int j = 0; j < 100; j++)
261 default:
return '0' + (
unsigned char) (10 * cost / 255);
268 TEST(costmap, testWaveInterference){
274 pcl::PointCloud<pcl::PointXYZ> cloud;
275 cloud.points.resize(3);
276 cloud.points[0].x = 3;
277 cloud.points[0].y = 3;
278 cloud.points[0].z =
MAX_Z;
279 cloud.points[1].x = 5;
280 cloud.points[1].y = 5;
281 cloud.points[1].z =
MAX_Z;
282 cloud.points[2].x = 7;
283 cloud.points[2].y = 7;
284 cloud.points[2].z =
MAX_Z;
286 geometry_msgs::Point p;
292 std::vector<Observation> obsBuf;
293 obsBuf.push_back(obs);
295 map.updateWorld(0, 0, obsBuf, obsBuf);
297 int update_count = 0;
301 for(
unsigned int i = 0; i < 10; ++i){
302 for(
unsigned int j = 0; j < 10; ++j){
311 ASSERT_EQ(update_count, 79);
358 TEST(costmap, testFullyContainedStaticMapUpdate){
374 TEST(costmap, testOverlapStaticMapUpdate){
381 map.updateStaticMapWindow(-10, -10, 10, 10,
MAP_10_BY_10);
387 for(
unsigned int i = 0; i < 10; ++i){
388 for(
unsigned int j = 0; j < 10; ++j){
393 std::vector<unsigned char> blank(100);
396 map.updateStaticMapWindow(-10, -10, 10, 10, blank);
400 ASSERT_EQ(map.
getCost(i, j), 0);
404 std::vector<unsigned char> fully_contained(25);
405 fully_contained[0] = 254;
406 fully_contained[4] = 254;
407 fully_contained[5] = 254;
408 fully_contained[9] = 254;
413 map.updateStaticMapWindow(0, 0, 5, 5, fully_contained);
419 for(
unsigned int j = 0; j < 5; ++j){
420 for(
unsigned int i = 0; i < 5; ++i){
421 ASSERT_EQ(map.
getCost(i + 10, j + 10), small_static_map.
getCost(i, j));
435 pcl::PointCloud<pcl::PointXYZ> cloud;
436 cloud.points.resize(1);
437 cloud.points[0].x = 0;
438 cloud.points[0].y = 0;
439 cloud.points[0].z =
MAX_Z;
441 geometry_msgs::Point p;
447 std::vector<Observation> obsBuf;
448 obsBuf.push_back(obs);
450 map.updateWorld(0, 0, obsBuf, obsBuf);
452 int lethal_count = 0;
454 for(
unsigned int i = 0; i < 10; ++i){
455 for(
unsigned int j = 0; j < 10; ++j){
463 ASSERT_EQ(lethal_count, 21);
466 TEST(costmap, testAdjacentToObstacleCanStillMove){
469 pcl::PointCloud<pcl::PointXYZ> cloud;
470 cloud.points.resize(1);
471 cloud.points[0].x = 0;
472 cloud.points[0].y = 0;
473 cloud.points[0].z =
MAX_Z;
475 geometry_msgs::Point p;
481 std::vector<Observation> obsBuf;
482 obsBuf.push_back(obs);
484 map.updateWorld(9, 9, obsBuf, obsBuf);
494 TEST(costmap, testInflationShouldNotCreateUnknowns){
497 pcl::PointCloud<pcl::PointXYZ> cloud;
498 cloud.points.resize(1);
499 cloud.points[0].x = 0;
500 cloud.points[0].y = 0;
501 cloud.points[0].z =
MAX_Z;
503 geometry_msgs::Point p;
509 std::vector<Observation> obsBuf;
510 obsBuf.push_back(obs);
512 map.updateWorld(9, 9, obsBuf, obsBuf);
514 int unknown_count = 0;
516 for(
unsigned int i = 0; i < 10; ++i){
517 for(
unsigned int j = 0; j < 10; ++j){
523 EXPECT_EQ( 0, unknown_count );
546 std::vector<unsigned int> occupiedCells;
548 for(
unsigned int i = 0; i < 10; ++i){
549 for(
unsigned int j = 0; j < 10; ++j){
551 occupiedCells.push_back(map.
getIndex(i, j));
556 ASSERT_EQ(occupiedCells.size(), (
unsigned int)20);
559 for(std::vector<unsigned int>::const_iterator it = occupiedCells.begin(); it != occupiedCells.end(); ++it){
560 unsigned int ind = *it;
563 ASSERT_EQ(
find(occupiedCells, map.
getIndex(x, y)),
true);
565 ASSERT_EQ(map.
getCost(x, y) >= 100,
true);
569 ASSERT_EQ(
find(occupiedCells, map.
getIndex(7, 2)),
true);
570 ASSERT_EQ(
find(occupiedCells, map.
getIndex(8, 2)),
true);
571 ASSERT_EQ(
find(occupiedCells, map.
getIndex(9, 2)),
true);
572 ASSERT_EQ(
find(occupiedCells, map.
getIndex(7, 3)),
true);
573 ASSERT_EQ(
find(occupiedCells, map.
getIndex(8, 3)),
true);
574 ASSERT_EQ(
find(occupiedCells, map.
getIndex(9, 3)),
true);
575 ASSERT_EQ(
find(occupiedCells, map.
getIndex(7, 4)),
true);
576 ASSERT_EQ(
find(occupiedCells, map.
getIndex(8, 4)),
true);
577 ASSERT_EQ(
find(occupiedCells, map.
getIndex(9, 4)),
true);
580 ASSERT_EQ(
find(occupiedCells, map.
getIndex(4, 3)),
true);
581 ASSERT_EQ(
find(occupiedCells, map.
getIndex(4, 4)),
true);
584 ASSERT_EQ(
find(occupiedCells, map.
getIndex(3, 7)),
true);
585 ASSERT_EQ(
find(occupiedCells, map.
getIndex(4, 7)),
true);
586 ASSERT_EQ(
find(occupiedCells, map.
getIndex(5, 7)),
true);
590 ASSERT_EQ(
worldToIndex(map, 0.0, 0.0), (
unsigned int)0);
591 ASSERT_EQ(
worldToIndex(map, 0.0, 0.99), (
unsigned int)0);
592 ASSERT_EQ(
worldToIndex(map, 0.0, 1.0), (
unsigned int)10);
593 ASSERT_EQ(
worldToIndex(map, 1.0, 0.99), (
unsigned int)1);
594 ASSERT_EQ(
worldToIndex(map, 9.99, 9.99), (
unsigned int)99);
595 ASSERT_EQ(
worldToIndex(map, 8.2, 3.4), (
unsigned int)38);
609 TEST(costmap, testDynamicObstacles){
614 pcl::PointCloud<pcl::PointXYZ> cloud;
615 cloud.points.resize(3);
616 cloud.points[0].x = 0;
617 cloud.points[0].y = 0;
618 cloud.points[1].x = 0;
619 cloud.points[1].y = 0;
620 cloud.points[2].x = 0;
621 cloud.points[2].y = 0;
623 geometry_msgs::Point p;
629 std::vector<Observation> obsBuf;
630 obsBuf.push_back(obs);
632 map.updateWorld(0, 0, obsBuf, obsBuf);
634 std::vector<unsigned int> ids;
636 for(
unsigned int i = 0; i < 10; ++i){
637 for(
unsigned int j = 0; j < 10; ++j){
645 ASSERT_EQ(ids.size(), (
unsigned int)21);
648 map.updateWorld(0, 0, obsBuf, obsBuf);
649 ASSERT_EQ(ids.size(), (
unsigned int)21);
655 TEST(costmap, testMultipleAdditions){
660 pcl::PointCloud<pcl::PointXYZ> cloud;
661 cloud.points.resize(1);
662 cloud.points[0].x = 7;
663 cloud.points[0].y = 2;
665 geometry_msgs::Point p;
671 std::vector<Observation> obsBuf;
672 obsBuf.push_back(obs);
674 map.updateWorld(0, 0, obsBuf, obsBuf);
676 std::vector<unsigned int> ids;
678 for(
unsigned int i = 0; i < 10; ++i){
679 for(
unsigned int j = 0; j < 10; ++j){
686 ASSERT_EQ(ids.size(), (
unsigned int)20);
697 pcl::PointCloud<pcl::PointXYZ> c0;
701 c0.points[0].z = 0.4;
704 c0.points[1].z = 1.2;
706 geometry_msgs::Point p;
712 std::vector<Observation> obsBuf;
713 obsBuf.push_back(obs);
715 map.updateWorld(0, 0, obsBuf, obsBuf);
717 std::vector<unsigned int> ids;
719 for(
unsigned int i = 0; i < 10; ++i){
720 for(
unsigned int j = 0; j < 10; ++j){
727 ASSERT_EQ(ids.size(), (
unsigned int)21);
739 std::vector<unsigned int> occupiedCells;
741 for(
unsigned int i = 0; i < 10; ++i){
742 for(
unsigned int j = 0; j < 10; ++j){
744 occupiedCells.push_back(map.
getIndex(i, j));
750 std::set<unsigned int> setOfCells;
751 for(
unsigned int i=0;i<occupiedCells.size(); i++)
752 setOfCells.insert(i);
754 ASSERT_EQ(setOfCells.size(), occupiedCells.size());
755 ASSERT_EQ(setOfCells.size(), (
unsigned int)48);
758 for(std::vector<unsigned int>::const_iterator it = occupiedCells.begin(); it != occupiedCells.end(); ++it){
759 unsigned int ind = *it;
762 ASSERT_EQ(
find(occupiedCells, map.
getIndex(x, y)),
true);
767 pcl::PointCloud<pcl::PointXYZ> c0;
771 c0.points[0].z = 0.4;
773 geometry_msgs::Point p;
779 std::vector<Observation> obsBuf, empty;
780 obsBuf.push_back(obs);
782 map.updateWorld(0, 0, obsBuf, empty);
784 occupiedCells.clear();
785 for(
unsigned int i = 0; i < 10; ++i){
786 for(
unsigned int j = 0; j < 10; ++j){
788 occupiedCells.push_back(map.
getIndex(i, j));
794 ASSERT_EQ(occupiedCells.size(), (
unsigned int)51);
798 pcl::PointCloud<pcl::PointXYZ> c1;
802 c1.points[0].z = 0.0;
804 geometry_msgs::Point p1;
810 std::vector<Observation> obsBuf1;
811 obsBuf1.push_back(obs1);
813 map.updateWorld(0, 0, obsBuf1, empty);
815 occupiedCells.clear();
816 for(
unsigned int i = 0; i < 10; ++i){
817 for(
unsigned int j = 0; j < 10; ++j){
819 occupiedCells.push_back(map.
getIndex(i, j));
827 ASSERT_EQ(occupiedCells.size(), (
unsigned int)54);
831 pcl::PointCloud<pcl::PointXYZ> c2;
835 c2.points[0].z = 0.0;
837 geometry_msgs::Point p2;
843 std::vector<Observation> obsBuf2;
844 obsBuf2.push_back(obs2);
846 map.updateWorld(0, 0, obsBuf2, empty);
853 pcl::PointCloud<pcl::PointXYZ> c3;
857 c3.points[0].z = 0.0;
859 geometry_msgs::Point p3;
865 std::vector<Observation> obsBuf3;
866 obsBuf3.push_back(obs3);
868 map.updateWorld(0, 0, obsBuf3, empty);
881 pcl::PointCloud<pcl::PointXYZ> c0;
885 c0.points[0].z =
MAX_Z;
888 c0.points[1].z =
MAX_Z;
891 c0.points[2].z =
MAX_Z;
893 geometry_msgs::Point p;
899 std::vector<Observation> obsBuf;
900 obsBuf.push_back(obs);
902 map.updateWorld(0, 0, obsBuf, obsBuf);
912 std::vector<unsigned char> mapData;
915 mapData.push_back(0);
923 std::vector<unsigned int> ids;
925 for(
unsigned int i = 0; i < 10; ++i){
926 for(
unsigned int j = 0; j < 10; ++j){
933 ASSERT_EQ(ids.size(), (
unsigned int)0);
936 pcl::PointCloud<pcl::PointXYZ> c0;
940 c0.points[0].z =
MAX_Z;
942 geometry_msgs::Point p;
948 std::vector<Observation> obsBuf;
949 obsBuf.push_back(obs);
951 map.updateWorld(0, 0, obsBuf, obsBuf);
953 for(
unsigned int i = 0; i < 10; ++i){
954 for(
unsigned int j = 0; j < 10; ++j){
961 ASSERT_EQ(ids.size(), (
unsigned int)29);
964 for(
unsigned int i = 0; i < 10; ++i){
965 for(
unsigned int j = 0; j < 10; ++j){
972 ASSERT_EQ(ids.size(), (
unsigned int)5);
975 map.updateWorld(0, 0, obsBuf, obsBuf);
978 for(
unsigned int i = 0; i < 10; ++i){
979 for(
unsigned int j = 0; j < 10; ++j){
986 ASSERT_EQ(ids.size(), (
unsigned int)29);
993 TEST(costmap, testRaytracing2){
999 pcl::PointCloud<pcl::PointXYZ> c0;
1000 c0.points.resize(1);
1001 c0.points[0].x = 9.5;
1002 c0.points[0].y = 9.5;
1003 c0.points[0].z =
MAX_Z;
1005 geometry_msgs::Point p;
1011 std::vector<Observation> obsBuf;
1012 obsBuf.push_back(obs);
1014 std::vector<unsigned int> obstacles;
1016 for(
unsigned int i = 0; i < 10; ++i){
1017 for(
unsigned int j = 0; j < 10; ++j){
1019 obstacles.push_back(map.
getIndex(i, j));
1024 unsigned int obs_before = obstacles.size();
1026 map.updateWorld(0, 0, obsBuf, obsBuf);
1029 for(
unsigned int i = 0; i < 10; ++i){
1030 for(
unsigned int j = 0; j < 10; ++j){
1032 obstacles.push_back(map.
getIndex(i, j));
1038 ASSERT_EQ(obstacles.size(), obs_before - 2);
1044 unsigned char test[10]= {0, 0, 0, 253, 253, 0, 0, 253, 253, 254};
1045 for(
unsigned int i=0; i < 10; i++)
1046 ASSERT_EQ(map.
getCost(i, i), test[i]);
1055 TEST(costmap, testTrickyPropagation){
1056 const unsigned char MAP_HALL_CHAR[10 * 10] = {
1057 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
1058 254, 0, 0, 0, 0, 0, 0, 0, 0, 0,
1059 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
1060 0, 0, 0, 254, 0, 0, 0, 0, 0, 0,
1061 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
1062 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
1063 0, 0, 0, 0, 0, 254, 0, 0, 0, 0,
1064 0, 0, 0, 0, 0, 254, 0, 0, 0, 0,
1065 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
1066 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
1068 std::vector<unsigned char> MAP_HALL;
1069 for (
int i = 0; i < 10 * 10; i++) {
1070 MAP_HALL.push_back(MAP_HALL_CHAR[i]);
1078 pcl::PointCloud<pcl::PointXYZ> c2;
1079 c2.points.resize(3);
1081 c2.points[0].x = 7.0;
1082 c2.points[0].y = 8.0;
1083 c2.points[0].z = 1.0;
1086 c2.points[1].x = 3.0;
1087 c2.points[1].y = 4.0;
1088 c2.points[1].z = 1.0;
1090 c2.points[2].x = 6.0;
1091 c2.points[2].y = 3.0;
1092 c2.points[2].z = 1.0;
1094 geometry_msgs::Point p2;
1100 std::vector<Observation> obsBuf2;
1101 obsBuf2.push_back(obs2);
1103 map.updateWorld(0, 0, obsBuf2, obsBuf2);
1105 const unsigned char MAP_HALL_CHAR_TEST[10 * 10] = {
1106 253, 254, 253, 0, 0, 0, 0, 0, 0, 0,
1107 0, 253, 0, 0, 0, 0, 0, 0, 0, 0,
1108 0, 0, 0, 0, 253, 0, 0, 0, 0, 0,
1109 0, 0, 0, 253, 254, 253, 0, 0, 0, 0,
1110 0, 0, 0, 0, 253, 0, 0, 253, 0, 0,
1111 0, 0, 0, 253, 0, 0, 253, 254, 253, 0,
1112 0, 0, 253, 254, 253, 0, 0, 253, 253, 0,
1113 0, 0, 0, 253, 0, 0, 0, 253, 254, 253,
1114 0, 0, 0, 0, 0, 0, 0, 0, 253, 0,
1115 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
1119 for (
int i = 0; i < 10 * 10; i++) {
1120 ASSERT_EQ(map.
getCost(i / 10, i % 10), MAP_HALL_CHAR_TEST[i]);
1123 pcl::PointCloud<pcl::PointXYZ> c;
1126 c.points[0].x = 4.0;
1127 c.points[0].y = 5.0;
1128 c.points[0].z = 1.0;
1130 geometry_msgs::Point p3;
1136 std::vector<Observation> obsBuf3;
1137 obsBuf3.push_back(obs3);
1139 map.updateWorld(0, 0, obsBuf3, obsBuf3);
1141 const unsigned char MAP_HALL_CHAR_TEST2[10 * 10] = {
1142 253, 254, 253, 0, 0, 0, 0, 0, 0, 0,
1143 0, 253, 0, 0, 0, 0, 0, 0, 0, 0,
1144 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
1145 0, 0, 0, 0, 0, 253, 0, 0, 0, 0,
1146 0, 0, 0, 0, 253, 254, 253, 253, 0, 0,
1147 0, 0, 0, 253, 0, 253, 253, 254, 253, 0,
1148 0, 0, 253, 254, 253, 0, 0, 253, 253, 0,
1149 0, 0, 0, 253, 0, 0, 0, 253, 254, 253,
1150 0, 0, 0, 0, 0, 0, 0, 0, 253, 0,
1151 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
1155 for (
int i = 0; i < 10 * 10; i++) {
1156 ASSERT_EQ(map.
getCost(i / 10, i % 10), MAP_HALL_CHAR_TEST2[i]);
1168 for(
unsigned int i = 0; i< 5 * 5; i++){
1172 for(
unsigned int i = 0; i< 100 * 100; i++)
1175 testing::InitGoogleTest(&argc, argv);
1176 return RUN_ALL_TESTS();
void mapToWorld(unsigned int mx, unsigned int my, double &wx, double &wy) const
Convert from map coordinates to world coordinates.
const double OBSTACLE_RANGE(20.0)
TEST(costmap, testResetForStaticMap)
void indexToWorld(Costmap2D &map, unsigned int index, double &wx, double &wy)
double getOriginX() const
Accessor for the x origin of the costmap.
Stores an observation in terms of a point cloud and the origin of the source.
TFSIMD_FORCE_INLINE const tfScalar & y() const
static const unsigned char FREE_SPACE
int main(int argc, char **argv)
std::vector< unsigned char > MAP_10_BY_10
unsigned char getCost(unsigned int mx, unsigned int my) const
Get the cost of a cell in the costmap.
static const unsigned char INSCRIBED_INFLATED_OBSTACLE
const double RESOLUTION(1)
TFSIMD_FORCE_INLINE const tfScalar & x() const
unsigned int getSizeInCellsY() const
Accessor for the y size of the costmap in cells.
char printableCost(unsigned char cost)
const unsigned int GRID_WIDTH(10)
const unsigned char MAP_10_BY_10_CHAR[]
std::vector< unsigned char > MAP_5_BY_5
bool copyCostmapWindow(const Costmap2D &map, double win_origin_x, double win_origin_y, double win_size_x, double win_size_y)
Turn this costmap into a copy of a window of a costmap passed in.
const double WINDOW_LENGTH(10)
unsigned int getSizeInCellsX() const
Accessor for the x size of the costmap in cells.
static const unsigned char LETHAL_OBSTACLE
const double ROBOT_RADIUS(1.0)
static const unsigned char NO_INFORMATION
const double RAYTRACE_RANGE(20.0)
bool find(const std::vector< unsigned int > &l, unsigned int n)
void indexToCells(unsigned int index, unsigned int &mx, unsigned int &my) const
Given an index... compute the associated map coordinates.
A 2D costmap provides a mapping between points in the world and their associated "costs".
std::vector< unsigned char > EMPTY_100_BY_100
unsigned int worldToIndex(Costmap2D &map, double wx, double wy)
const unsigned char MAP_5_BY_5_CHAR[]
bool worldToMap(double wx, double wy, unsigned int &mx, unsigned int &my) const
Convert from world coordinates to map coordinates.
unsigned int getIndex(unsigned int mx, unsigned int my) const
Given two map coordinates... compute the associated index.
std::vector< unsigned char > EMPTY_10_BY_10
const unsigned char THRESHOLD(100)
const unsigned int GRID_HEIGHT(10)