tutorial1.cpp 6.5 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182
  1. /*
  2. * Copyright 2010 SRI International
  3. *
  4. * This program is free software: you can redistribute it and/or modify
  5. * it under the terms of the GNU Lesser General Public License as published by
  6. * the Free Software Foundation, either version 3 of the License, or
  7. * (at your option) any later version.
  8. *
  9. * This program is distributed in the hope that it will be useful,
  10. * but WITHOUT ANY WARRANTY; without even the implied warranty of
  11. * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  12. * GNU Lesser General Public License for more details.
  13. *
  14. * You should have received a copy of the GNU Lesser General Public License
  15. * along with this program. If not, see <http://www.gnu.org/licenses/>.
  16. */
  17. #include <open_karto/Mapper.h>
  18. /**
  19. * Sample code to demonstrate karto map creation
  20. * Create a laser range finder device and three "dummy" range scans.
  21. * Add the device and range scans to a karto Mapper.
  22. */
  23. karto::Dataset* CreateMap(karto::Mapper* pMapper)
  24. {
  25. karto::Dataset* pDataset = new karto::Dataset();
  26. /////////////////////////////////////
  27. // Create a laser range finder device - use SmartPointer to let karto subsystem manage memory.
  28. karto::Name name("laser0");
  29. karto::LaserRangeFinder* pLaserRangeFinder = karto::LaserRangeFinder::CreateLaserRangeFinder(karto::LaserRangeFinder_Custom, name);
  30. pLaserRangeFinder->SetOffsetPose(karto::Pose2(1.0, 0.0, 0.0));
  31. pLaserRangeFinder->SetAngularResolution(karto::math::DegreesToRadians(0.5));
  32. pLaserRangeFinder->SetRangeThreshold(12.0);
  33. pDataset->Add(pLaserRangeFinder);
  34. /////////////////////////////////////
  35. // Create three localized range scans, all using the same range readings, but with different poses.
  36. karto::LocalizedRangeScan* pLocalizedRangeScan = NULL;
  37. // 1. localized range scan
  38. // Create a vector of range readings. Simple example where all the measurements are the same value.
  39. std::vector<kt_double> readings;
  40. for (int i=0; i<361; i++)
  41. {
  42. readings.push_back(3.0);
  43. }
  44. // create localized range scan
  45. pLocalizedRangeScan = new karto::LocalizedRangeScan(name, readings);
  46. pLocalizedRangeScan->SetOdometricPose(karto::Pose2(0.0, 0.0, 0.0));
  47. pLocalizedRangeScan->SetCorrectedPose(karto::Pose2(0.0, 0.0, 0.0));
  48. // Add the localized range scan to the mapper
  49. pMapper->Process(pLocalizedRangeScan);
  50. std::cout << "Pose: " << pLocalizedRangeScan->GetOdometricPose() << " Corrected Pose: " << pLocalizedRangeScan->GetCorrectedPose() << std::endl;
  51. // Add the localized range scan to the dataset
  52. pDataset->Add(pLocalizedRangeScan);
  53. // 2. localized range scan
  54. // create localized range scan
  55. pLocalizedRangeScan = new karto::LocalizedRangeScan(name, readings);
  56. pLocalizedRangeScan->SetOdometricPose(karto::Pose2(1.0, 0.0, 1.57));
  57. pLocalizedRangeScan->SetCorrectedPose(karto::Pose2(1.0, 0.0, 1.57));
  58. // Add the localized range scan to the mapper
  59. pMapper->Process(pLocalizedRangeScan);
  60. std::cout << "Pose: " << pLocalizedRangeScan->GetOdometricPose() << " Corrected Pose: " << pLocalizedRangeScan->GetCorrectedPose() << std::endl;
  61. // Add the localized range scan to the dataset
  62. pDataset->Add(pLocalizedRangeScan);
  63. // 3. localized range scan
  64. // create localized range scan
  65. pLocalizedRangeScan = new karto::LocalizedRangeScan(name, readings);
  66. pLocalizedRangeScan->SetOdometricPose(karto::Pose2(1.0, -1.0, 2.35619449));
  67. pLocalizedRangeScan->SetCorrectedPose(karto::Pose2(1.0, -1.0, 2.35619449));
  68. // Add the localized range scan to the mapper
  69. pMapper->Process(pLocalizedRangeScan);
  70. std::cout << "Pose: " << pLocalizedRangeScan->GetOdometricPose() << " Corrected Pose: " << pLocalizedRangeScan->GetCorrectedPose() << std::endl;
  71. // Add the localized range scan to the dataset
  72. pDataset->Add(pLocalizedRangeScan);
  73. return pDataset;
  74. }
  75. /**
  76. * Sample code to demonstrate basic occupancy grid creation and print occupancy grid.
  77. */
  78. karto::OccupancyGrid* CreateOccupancyGrid(karto::Mapper* pMapper, kt_double resolution)
  79. {
  80. std::cout << "Generating map..." << std::endl;
  81. // Create a map (occupancy grid) - time it
  82. karto::OccupancyGrid* pOccupancyGrid = karto::OccupancyGrid::CreateFromScans(pMapper->GetAllProcessedScans(), resolution);
  83. return pOccupancyGrid;
  84. }
  85. /**
  86. * Sample code to print a basic occupancy grid
  87. */
  88. void PrintOccupancyGrid(karto::OccupancyGrid* pOccupancyGrid)
  89. {
  90. if (pOccupancyGrid != NULL)
  91. {
  92. // Output ASCII representation of map
  93. kt_int32s width = pOccupancyGrid->GetWidth();
  94. kt_int32s height = pOccupancyGrid->GetHeight();
  95. karto::Vector2<kt_double> offset = pOccupancyGrid->GetCoordinateConverter()->GetOffset();
  96. std::cout << "width = " << width << ", height = " << height << ", scale = " << pOccupancyGrid->GetCoordinateConverter()->GetScale() << ", offset: " << offset.GetX() << ", " << offset.GetY() << std::endl;
  97. for (kt_int32s y=height-1; y>=0; y--)
  98. {
  99. for (kt_int32s x=0; x<width; x++)
  100. {
  101. // Getting the value at position x,y
  102. kt_int8u value = pOccupancyGrid->GetValue(karto::Vector2<kt_int32s>(x, y));
  103. switch (value)
  104. {
  105. case karto::GridStates_Unknown:
  106. std::cout << "*";
  107. break;
  108. case karto::GridStates_Occupied:
  109. std::cout << "X";
  110. break;
  111. case karto::GridStates_Free:
  112. std::cout << " ";
  113. break;
  114. default:
  115. std::cout << "?";
  116. }
  117. }
  118. std::cout << std::endl;
  119. }
  120. std::cout << std::endl;
  121. }
  122. }
  123. int main(int /*argc*/, char **/*argv*/)
  124. {
  125. // use try/catch to catch karto exceptions that might be thrown by the karto subsystem.
  126. /////////////////////////////////////
  127. // Get karto default mapper
  128. karto::Mapper* pMapper = new karto::Mapper();
  129. if (pMapper != NULL)
  130. {
  131. karto::OccupancyGrid* pOccupancyGrid = NULL;
  132. /////////////////////////////////////
  133. // sample code that creates a map from sample device and sample localized range scans
  134. std::cout << "Tutorial 1 ----------------" << std::endl << std::endl;
  135. // clear mapper
  136. pMapper->Reset();
  137. // create map from created dataset
  138. karto::Dataset* pDataset = CreateMap(pMapper);
  139. // create occupancy grid at 0.1 resolution and print grid
  140. pOccupancyGrid = CreateOccupancyGrid(pMapper, 0.1);
  141. PrintOccupancyGrid(pOccupancyGrid);
  142. delete pOccupancyGrid;
  143. // delete mapper
  144. delete pMapper;
  145. delete pDataset;
  146. }
  147. return 0;
  148. }