Mapper.cpp 77 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485868788899091929394959697989910010110210310410510610710810911011111211311411511611711811912012112212312412512612712812913013113213313413513613713813914014114214314414514614714814915015115215315415515615715815916016116216316416516616716816917017117217317417517617717817918018118218318418518618718818919019119219319419519619719819920020120220320420520620720820921021121221321421521621721821922022122222322422522622722822923023123223323423523623723823924024124224324424524624724824925025125225325425525625725825926026126226326426526626726826927027127227327427527627727827928028128228328428528628728828929029129229329429529629729829930030130230330430530630730830931031131231331431531631731831932032132232332432532632732832933033133233333433533633733833934034134234334434534634734834935035135235335435535635735835936036136236336436536636736836937037137237337437537637737837938038138238338438538638738838939039139239339439539639739839940040140240340440540640740840941041141241341441541641741841942042142242342442542642742842943043143243343443543643743843944044144244344444544644744844945045145245345445545645745845946046146246346446546646746846947047147247347447547647747847948048148248348448548648748848949049149249349449549649749849950050150250350450550650750850951051151251351451551651751851952052152252352452552652752852953053153253353453553653753853954054154254354454554654754854955055155255355455555655755855956056156256356456556656756856957057157257357457557657757857958058158258358458558658758858959059159259359459559659759859960060160260360460560660760860961061161261361461561661761861962062162262362462562662762862963063163263363463563663763863964064164264364464564664764864965065165265365465565665765865966066166266366466566666766866967067167267367467567667767867968068168268368468568668768868969069169269369469569669769869970070170270370470570670770870971071171271371471571671771871972072172272372472572672772872973073173273373473573673773873974074174274374474574674774874975075175275375475575675775875976076176276376476576676776876977077177277377477577677777877978078178278378478578678778878979079179279379479579679779879980080180280380480580680780880981081181281381481581681781881982082182282382482582682782882983083183283383483583683783883984084184284384484584684784884985085185285385485585685785885986086186286386486586686786886987087187287387487587687787887988088188288388488588688788888989089189289389489589689789889990090190290390490590690790890991091191291391491591691791891992092192292392492592692792892993093193293393493593693793893994094194294394494594694794894995095195295395495595695795895996096196296396496596696796896997097197297397497597697797897998098198298398498598698798898999099199299399499599699799899910001001100210031004100510061007100810091010101110121013101410151016101710181019102010211022102310241025102610271028102910301031103210331034103510361037103810391040104110421043104410451046104710481049105010511052105310541055105610571058105910601061106210631064106510661067106810691070107110721073107410751076107710781079108010811082108310841085108610871088108910901091109210931094109510961097109810991100110111021103110411051106110711081109111011111112111311141115111611171118111911201121112211231124112511261127112811291130113111321133113411351136113711381139114011411142114311441145114611471148114911501151115211531154115511561157115811591160116111621163116411651166116711681169117011711172117311741175117611771178117911801181118211831184118511861187118811891190119111921193119411951196119711981199120012011202120312041205120612071208120912101211121212131214121512161217121812191220122112221223122412251226122712281229123012311232123312341235123612371238123912401241124212431244124512461247124812491250125112521253125412551256125712581259126012611262126312641265126612671268126912701271127212731274127512761277127812791280128112821283128412851286128712881289129012911292129312941295129612971298129913001301130213031304130513061307130813091310131113121313131413151316131713181319132013211322132313241325132613271328132913301331133213331334133513361337133813391340134113421343134413451346134713481349135013511352135313541355135613571358135913601361136213631364136513661367136813691370137113721373137413751376137713781379138013811382138313841385138613871388138913901391139213931394139513961397139813991400140114021403140414051406140714081409141014111412141314141415141614171418141914201421142214231424142514261427142814291430143114321433143414351436143714381439144014411442144314441445144614471448144914501451145214531454145514561457145814591460146114621463146414651466146714681469147014711472147314741475147614771478147914801481148214831484148514861487148814891490149114921493149414951496149714981499150015011502150315041505150615071508150915101511151215131514151515161517151815191520152115221523152415251526152715281529153015311532153315341535153615371538153915401541154215431544154515461547154815491550155115521553155415551556155715581559156015611562156315641565156615671568156915701571157215731574157515761577157815791580158115821583158415851586158715881589159015911592159315941595159615971598159916001601160216031604160516061607160816091610161116121613161416151616161716181619162016211622162316241625162616271628162916301631163216331634163516361637163816391640164116421643164416451646164716481649165016511652165316541655165616571658165916601661166216631664166516661667166816691670167116721673167416751676167716781679168016811682168316841685168616871688168916901691169216931694169516961697169816991700170117021703170417051706170717081709171017111712171317141715171617171718171917201721172217231724172517261727172817291730173117321733173417351736173717381739174017411742174317441745174617471748174917501751175217531754175517561757175817591760176117621763176417651766176717681769177017711772177317741775177617771778177917801781178217831784178517861787178817891790179117921793179417951796179717981799180018011802180318041805180618071808180918101811181218131814181518161817181818191820182118221823182418251826182718281829183018311832183318341835183618371838183918401841184218431844184518461847184818491850185118521853185418551856185718581859186018611862186318641865186618671868186918701871187218731874187518761877187818791880188118821883188418851886188718881889189018911892189318941895189618971898189919001901190219031904190519061907190819091910191119121913191419151916191719181919192019211922192319241925192619271928192919301931193219331934193519361937193819391940194119421943194419451946194719481949195019511952195319541955195619571958195919601961196219631964196519661967196819691970197119721973197419751976197719781979198019811982198319841985198619871988198919901991199219931994199519961997199819992000200120022003200420052006200720082009201020112012201320142015201620172018201920202021202220232024202520262027202820292030203120322033203420352036203720382039204020412042204320442045204620472048204920502051205220532054205520562057205820592060206120622063206420652066206720682069207020712072207320742075207620772078207920802081208220832084208520862087208820892090209120922093209420952096209720982099210021012102210321042105210621072108210921102111211221132114211521162117211821192120212121222123212421252126212721282129213021312132213321342135213621372138213921402141214221432144214521462147214821492150215121522153215421552156215721582159216021612162216321642165216621672168216921702171217221732174217521762177217821792180218121822183218421852186
  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 <sstream>
  18. #include <fstream>
  19. #include <stdexcept>
  20. #include <set>
  21. #include <list>
  22. #include <iterator>
  23. #include <math.h>
  24. #include <assert.h>
  25. #include "open_karto/Mapper.h"
  26. namespace karto
  27. {
  28. // enable this for verbose debug information
  29. // #define KARTO_DEBUG
  30. #define MAX_VARIANCE 500.0
  31. #define DISTANCE_PENALTY_GAIN 0.2
  32. #define ANGLE_PENALTY_GAIN 0.2
  33. ////////////////////////////////////////////////////////////////////////////////////////
  34. ////////////////////////////////////////////////////////////////////////////////////////
  35. ////////////////////////////////////////////////////////////////////////////////////////
  36. // 注册一个新的传感器,为该传感器创建一个新的 ScanManager 。
  37. void MapperSensorManager::RegisterSensor(const Name &rSensorName)
  38. {
  39. if (GetScanManager(rSensorName) == NULL)
  40. {
  41. m_ScanManagers[rSensorName] = new ScanManager(m_RunningBufferMaximumSize, m_RunningBufferMaximumDistance);
  42. }
  43. }
  44. /**
  45. * Gets scan from given device with given ID 根据传感器名称和扫描索引获取特定的扫描数据
  46. * @param rSensorName
  47. * @param scanNum
  48. * @return localized range scan
  49. */
  50. LocalizedRangeScan *MapperSensorManager::GetScan(const Name &rSensorName, kt_int32s scanIndex)
  51. {
  52. ScanManager *pScanManager = GetScanManager(rSensorName);
  53. if (pScanManager != NULL)
  54. {
  55. return pScanManager->GetScans().at(scanIndex);
  56. }
  57. assert(false);
  58. return NULL;
  59. }
  60. /**
  61. * Adds scan to scan vector of device that recorded scan
  62. * 向传感器的扫描向量中添加一个新的扫描,并更新全局扫描列表和下一个扫描ID
  63. * @param pScan
  64. */
  65. void MapperSensorManager::AddScan(LocalizedRangeScan *pScan)
  66. {
  67. GetScanManager(pScan)->AddScan(pScan, m_NextScanId);
  68. m_Scans.push_back(pScan);
  69. m_NextScanId++;
  70. }
  71. /**
  72. * Gets all scans of all devices 获取所有设备的所有扫描数据
  73. * @return all scans of all devices
  74. */
  75. LocalizedRangeScanVector MapperSensorManager::GetAllScans()
  76. {
  77. LocalizedRangeScanVector scans;
  78. forEach(ScanManagerMap, &m_ScanManagers)
  79. {
  80. LocalizedRangeScanVector &rScans = iter->second->GetScans();
  81. scans.insert(scans.end(), rScans.begin(), rScans.end());
  82. }
  83. return scans;
  84. }
  85. /**
  86. * Deletes all scan managers of all devices
  87. * 删除所有扫描管理器并清除扫描列表
  88. */
  89. void MapperSensorManager::Clear()
  90. {
  91. // SensorManager::Clear();
  92. forEach(ScanManagerMap, &m_ScanManagers)
  93. {
  94. delete iter->second;
  95. }
  96. m_ScanManagers.clear();
  97. }
  98. ////////////////////////////////////////////////////////////////////////////////////////
  99. ////////////////////////////////////////////////////////////////////////////////////////
  100. ////////////////////////////////////////////////////////////////////////////////////////
  101. // 析构函数
  102. ScanMatcher::~ScanMatcher()
  103. {
  104. delete m_pCorrelationGrid;
  105. delete m_pSearchSpaceProbs;
  106. delete m_pGridLookup;
  107. }
  108. // 创建一个新的ScanMatcher实例
  109. ScanMatcher *ScanMatcher::Create(Mapper *pMapper, kt_double searchSize, kt_double resolution,
  110. kt_double smearDeviation, kt_double rangeThreshold)
  111. {
  112. // invalid parameters
  113. if (resolution <= 0)
  114. {
  115. return NULL;
  116. }
  117. if (searchSize <= 0)
  118. {
  119. return NULL;
  120. }
  121. if (smearDeviation < 0)
  122. {
  123. return NULL;
  124. }
  125. if (rangeThreshold <= 0)
  126. {
  127. return NULL;
  128. }
  129. assert(math::DoubleEqual(math::Round(searchSize / resolution), (searchSize / resolution)));
  130. // calculate search space in grid coordinates
  131. kt_int32u searchSpaceSideSize = static_cast<kt_int32u>(math::Round(searchSize / resolution) + 1);
  132. // compute requisite size of correlation grid (pad grid so that scan points can't fall off the grid
  133. // if a scan is on the border of the search space)
  134. kt_int32u pointReadingMargin = static_cast<kt_int32u>(ceil(rangeThreshold / resolution));
  135. kt_int32s gridSize = searchSpaceSideSize + 2 * pointReadingMargin;
  136. // create correlation grid
  137. assert(gridSize % 2 == 1);
  138. CorrelationGrid *pCorrelationGrid = CorrelationGrid::CreateGrid(gridSize, gridSize, resolution, smearDeviation);
  139. // create search space probabilities
  140. Grid<kt_double> *pSearchSpaceProbs = Grid<kt_double>::CreateGrid(searchSpaceSideSize,
  141. searchSpaceSideSize, resolution);
  142. ScanMatcher *pScanMatcher = new ScanMatcher(pMapper);
  143. pScanMatcher->m_pCorrelationGrid = pCorrelationGrid;
  144. pScanMatcher->m_pSearchSpaceProbs = pSearchSpaceProbs;
  145. pScanMatcher->m_pGridLookup = new GridIndexLookup<kt_int8u>(pCorrelationGrid);
  146. return pScanMatcher;
  147. }
  148. /**
  149. * 将给定的扫描与一组基扫描进行匹配,并输出最佳姿态和协方差
  150. * Match given scan against set of scans
  151. * @param pScan scan being scan-matched
  152. * @param rBaseScans set of scans whose points will mark cells in grid as being occupied
  153. * @param rMean output parameter of mean (best pose) of match
  154. * @param rCovariance output parameter of covariance of match
  155. * @param doPenalize whether to penalize matches further from the search center
  156. * @param doRefineMatch whether to do finer-grained matching if coarse match is good (default is true)
  157. * @return strength of response
  158. */
  159. kt_double ScanMatcher::MatchScan(LocalizedRangeScan *pScan, // 给定的用来匹配的点云
  160. const LocalizedRangeScanVector &rBaseScans, // 已知的地图点云
  161. Pose2 &rMean, // 匹配平均(最佳姿态)输出参数
  162. Matrix3 &rCovariance, // 匹配协方差输出参数
  163. kt_bool doPenalize, // 是否对距离搜索中心更远的匹配进行处罚
  164. kt_bool doRefineMatch) // 是否进一步惩罚搜索中心的匹配,如果粗略匹配良好,是否进行更细粒度的匹配(默认为true)
  165. {
  166. ///////////////////////////////////////
  167. // set scan pose to be center of grid
  168. // 1. get scan position
  169. Pose2 scanPose = pScan->GetSensorPose();
  170. // scan has no readings; cannot do scan matching
  171. // best guess of pose is based off of adjusted odometer reading 姿势的最佳猜测是基于调整后的里程表读数
  172. if (pScan->GetNumberOfRangeReadings() == 0)
  173. {
  174. // 扫描没有读数;无法进行扫描匹配
  175. rMean = scanPose;
  176. // maximum covariance
  177. rCovariance(0, 0) = MAX_VARIANCE; // XX
  178. rCovariance(1, 1) = MAX_VARIANCE; // YY
  179. rCovariance(2, 2) = 4 * math::Square(m_pMapper->m_pCoarseAngleResolution->GetValue()); // TH*TH
  180. return 0.0;
  181. }
  182. // 2. get size of grid
  183. Rectangle2<kt_int32s> roi = m_pCorrelationGrid->GetROI(); // 获得感兴趣的区域
  184. // 3. compute offset (in meters - lower left corner) 计算偏移量(单位:米-左下角)
  185. Vector2<kt_double> offset;
  186. offset.SetX(scanPose.GetX() - (0.5 * (roi.GetWidth() - 1) * m_pCorrelationGrid->GetResolution()));
  187. offset.SetY(scanPose.GetY() - (0.5 * (roi.GetHeight() - 1) * m_pCorrelationGrid->GetResolution()));
  188. // 4. set offset 设置偏移量
  189. m_pCorrelationGrid->GetCoordinateConverter()->SetOffset(offset);
  190. ///////////////////////////////////////
  191. // set up correlation grid 设置相关栅格
  192. AddScans(rBaseScans, scanPose.GetPosition());
  193. // compute how far to search in each direction 计算在每个方向上搜索的距离
  194. Vector2<kt_double> searchDimensions(m_pSearchSpaceProbs->GetWidth(), m_pSearchSpaceProbs->GetHeight());
  195. Vector2<kt_double> coarseSearchOffset(0.5 * (searchDimensions.GetX() - 1) * m_pCorrelationGrid->GetResolution(),
  196. 0.5 * (searchDimensions.GetY() - 1) * m_pCorrelationGrid->GetResolution());
  197. // a coarse search only checks half the cells in each dimension
  198. // 粗略搜索只检查每个维度中的一半单元格
  199. Vector2<kt_double> coarseSearchResolution(2 * m_pCorrelationGrid->GetResolution(),
  200. 2 * m_pCorrelationGrid->GetResolution());
  201. // actual scan-matching 实际扫描匹配
  202. kt_double bestResponse = CorrelateScan(pScan, scanPose, coarseSearchOffset, coarseSearchResolution,
  203. m_pMapper->m_pCoarseSearchAngleOffset->GetValue(),
  204. m_pMapper->m_pCoarseAngleResolution->GetValue(),
  205. doPenalize, rMean, rCovariance, false);
  206. if (m_pMapper->m_pUseResponseExpansion->GetValue() == true)
  207. {
  208. if (math::DoubleEqual(bestResponse, 0.0))
  209. {
  210. // #ifdef KARTO_DEBUG
  211. // std::cout << "Mapper Info: Expanding response search space!" << std::endl;
  212. // #endif
  213. // try and increase search angle offset with 20 degrees and do another match
  214. kt_double newSearchAngleOffset = m_pMapper->m_pCoarseSearchAngleOffset->GetValue();
  215. for (kt_int32u i = 0; i < 3; i++)
  216. {
  217. newSearchAngleOffset += math::DegreesToRadians(20);
  218. bestResponse = CorrelateScan(pScan, scanPose, coarseSearchOffset, coarseSearchResolution,
  219. newSearchAngleOffset, m_pMapper->m_pCoarseAngleResolution->GetValue(),
  220. doPenalize, rMean, rCovariance, false);
  221. if (math::DoubleEqual(bestResponse, 0.0) == false)
  222. {
  223. break;
  224. }
  225. }
  226. // #ifdef KARTO_DEBUG
  227. // if (math::DoubleEqual(bestResponse, 0.0))
  228. // {
  229. // std::cout << "Mapper Warning: Unable to calculate response!" << std::endl;
  230. // }
  231. // #endif
  232. }
  233. }
  234. if (doRefineMatch)
  235. {
  236. Vector2<kt_double> fineSearchOffset(coarseSearchResolution * 0.5);
  237. Vector2<kt_double> fineSearchResolution(m_pCorrelationGrid->GetResolution(), m_pCorrelationGrid->GetResolution());
  238. bestResponse = CorrelateScan(pScan, rMean, fineSearchOffset, fineSearchResolution,
  239. 0.5 * m_pMapper->m_pCoarseAngleResolution->GetValue(),
  240. m_pMapper->m_pFineSearchAngleOffset->GetValue(),
  241. doPenalize, rMean, rCovariance, true);
  242. }
  243. // #ifdef KARTO_DEBUG
  244. // std::cout << " BEST POSE = " << rMean << " BEST RESPONSE = " << bestResponse << ", VARIANCE = "
  245. // << rCovariance(0, 0) << ", " << rCovariance(1, 1) << std::endl;
  246. // #endif
  247. assert(math::InRange(rMean.GetHeading(), -KT_PI, KT_PI));
  248. return bestResponse;
  249. }
  250. /**
  251. * 在给定的搜索空间内,找到与扫描中心最匹配的姿态。 !!! 核心函数 !!!
  252. * Finds the best pose for the scan centering the search in the correlation grid
  253. * at the given pose and search in the space by the vector and angular offsets
  254. * in increments of the given resolutions
  255. * @param pScan scan to match against correlation grid
  256. * @param rSearchCenter the center of the search space
  257. * @param rSearchSpaceOffset searches poses in the area offset by this vector around search center
  258. * @param rSearchSpaceResolution how fine a granularity to search in the search space
  259. * @param searchAngleOffset searches poses in the angles offset by this angle around search center
  260. * @param searchAngleResolution how fine a granularity to search in the angular search space
  261. * @param doPenalize whether to penalize matches further from the search center
  262. * @param rMean output parameter of mean (best pose) of match
  263. * @param rCovariance output parameter of covariance of match
  264. * @param doingFineMatch whether to do a finer search after coarse search
  265. * @return strength of response
  266. *
  267. * @param pScan 扫描以匹配相关网格
  268. * @param rSearchCenter 搜索空间的中心
  269. * @param rSearchSpaceOffset 在搜索中心周围由该矢量偏移的区域中搜索姿势
  270. * @param rSearchSpaceResolution 在搜索空间中搜索的分辨率
  271. * @param searchAngleOffset 在搜索中心周围偏移此角度的角度内搜索姿势
  272. * @param searchAngleResolution 在角搜索空间中搜索的分辨率
  273. * @param doPenalize 是否对距离搜索中心更远的匹配进行处罚
  274. * @param rMean 匹配平均(最佳姿态)输出参数
  275. * @param rCovariance 匹配协方差输出参数
  276. * @param doingFineMatch 是否在粗略搜索后进行更精细的搜索
  277. * @return 反应强度
  278. */
  279. kt_double ScanMatcher::CorrelateScan(LocalizedRangeScan *pScan, const Pose2 &rSearchCenter,
  280. const Vector2<kt_double> &rSearchSpaceOffset,
  281. const Vector2<kt_double> &rSearchSpaceResolution,
  282. kt_double searchAngleOffset, kt_double searchAngleResolution,
  283. kt_bool doPenalize, Pose2 &rMean, Matrix3 &rCovariance, kt_bool doingFineMatch)
  284. {
  285. assert(searchAngleResolution != 0.0);
  286. // setup lookup arrays 建立查询数组
  287. m_pGridLookup->ComputeOffsets(pScan, rSearchCenter.GetHeading(), searchAngleOffset, searchAngleResolution);
  288. // only initialize probability grid if computing positional covariance (during coarse match)
  289. // 仅在计算位置协方差时初始化概率网格(在粗略匹配期间)
  290. if (!doingFineMatch) // doingFineMatch == true,
  291. {
  292. m_pSearchSpaceProbs->Clear();
  293. // position search grid - finds lower left corner of search grid
  294. Vector2<kt_double> offset(rSearchCenter.GetPosition() - rSearchSpaceOffset);
  295. m_pSearchSpaceProbs->GetCoordinateConverter()->SetOffset(offset);
  296. }
  297. // calculate position arrays 计算位置数组
  298. std::vector<kt_double> xPoses;
  299. kt_int32u nX = static_cast<kt_int32u>(math::Round(rSearchSpaceOffset.GetX() *
  300. 2.0 / rSearchSpaceResolution.GetX()) +
  301. 1);
  302. kt_double startX = -rSearchSpaceOffset.GetX();
  303. for (kt_int32u xIndex = 0; xIndex < nX; xIndex++)
  304. {
  305. xPoses.push_back(startX + xIndex * rSearchSpaceResolution.GetX());
  306. }
  307. assert(math::DoubleEqual(xPoses.back(), -startX));
  308. std::vector<kt_double> yPoses;
  309. kt_int32u nY = static_cast<kt_int32u>(math::Round(rSearchSpaceOffset.GetY() *
  310. 2.0 / rSearchSpaceResolution.GetY()) +
  311. 1);
  312. kt_double startY = -rSearchSpaceOffset.GetY();
  313. for (kt_int32u yIndex = 0; yIndex < nY; yIndex++)
  314. {
  315. yPoses.push_back(startY + yIndex * rSearchSpaceResolution.GetY());
  316. }
  317. assert(math::DoubleEqual(yPoses.back(), -startY));
  318. // calculate pose response array size 计算姿态响应阵列大小
  319. kt_int32u nAngles = static_cast<kt_int32u>(math::Round(searchAngleOffset * 2.0 / searchAngleResolution) + 1);
  320. kt_int32u poseResponseSize = static_cast<kt_int32u>(xPoses.size() * yPoses.size() * nAngles);
  321. // allocate array 分配数组
  322. std::pair<kt_double, Pose2> *pPoseResponse = new std::pair<kt_double, Pose2>[poseResponseSize];
  323. Vector2<kt_int32s> startGridPoint = m_pCorrelationGrid->WorldToGrid(Vector2<kt_double>(rSearchCenter.GetX() + startX, rSearchCenter.GetY() + startY));
  324. kt_int32u poseResponseCounter = 0;
  325. forEachAs(std::vector<kt_double>, &yPoses, yIter) // 遍历Y
  326. {
  327. kt_double y = *yIter;
  328. kt_double newPositionY = rSearchCenter.GetY() + y;
  329. kt_double squareY = math::Square(y);
  330. forEachAs(std::vector<kt_double>, &xPoses, xIter) // 遍历X
  331. {
  332. kt_double x = *xIter;
  333. kt_double newPositionX = rSearchCenter.GetX() + x;
  334. kt_double squareX = math::Square(x);
  335. Vector2<kt_int32s> gridPoint = m_pCorrelationGrid->WorldToGrid(Vector2<kt_double>(newPositionX, newPositionY));
  336. kt_int32s gridIndex = m_pCorrelationGrid->GridIndex(gridPoint);
  337. assert(gridIndex >= 0);
  338. kt_double angle = 0.0;
  339. kt_double startAngle = rSearchCenter.GetHeading() - searchAngleOffset;
  340. for (kt_int32u angleIndex = 0; angleIndex < nAngles; angleIndex++) // 遍历角度
  341. {
  342. angle = startAngle + angleIndex * searchAngleResolution;
  343. kt_double response = GetResponse(angleIndex, gridIndex); // 获取当前角度下的匹配响应值
  344. if (doPenalize && (math::DoubleEqual(response, 0.0) == false))
  345. {
  346. // simple model (approximate Gaussian) to take odometry into account
  347. kt_double squaredDistance = squareX + squareY;
  348. kt_double distancePenalty = 1.0 - (DISTANCE_PENALTY_GAIN *
  349. squaredDistance / m_pMapper->m_pDistanceVariancePenalty->GetValue());
  350. distancePenalty = math::Maximum(distancePenalty, m_pMapper->m_pMinimumDistancePenalty->GetValue());
  351. kt_double squaredAngleDistance = math::Square(angle - rSearchCenter.GetHeading());
  352. kt_double anglePenalty = 1.0 - (ANGLE_PENALTY_GAIN *
  353. squaredAngleDistance / m_pMapper->m_pAngleVariancePenalty->GetValue());
  354. anglePenalty = math::Maximum(anglePenalty, m_pMapper->m_pMinimumAnglePenalty->GetValue());
  355. response *= (distancePenalty * anglePenalty);
  356. }
  357. // store response and pose
  358. pPoseResponse[poseResponseCounter] = std::pair<kt_double, Pose2>(response, Pose2(newPositionX, newPositionY,
  359. math::NormalizeAngle(angle)));
  360. poseResponseCounter++;
  361. }
  362. assert(math::DoubleEqual(angle, rSearchCenter.GetHeading() + searchAngleOffset));
  363. }
  364. }
  365. assert(poseResponseSize == poseResponseCounter);
  366. // find value of best response (in [0; 1])
  367. kt_double bestResponse = -1;
  368. for (kt_int32u i = 0; i < poseResponseSize; i++)
  369. {
  370. bestResponse = math::Maximum(bestResponse, pPoseResponse[i].first);
  371. // will compute positional covariance, save best relative probability for each cell
  372. if (!doingFineMatch)
  373. {
  374. const Pose2 &rPose = pPoseResponse[i].second;
  375. Vector2<kt_int32s> grid = m_pSearchSpaceProbs->WorldToGrid(rPose.GetPosition());
  376. // Changed (kt_double*) to the reinterpret_cast - Luc
  377. kt_double *ptr = reinterpret_cast<kt_double *>(m_pSearchSpaceProbs->GetDataPointer(grid));
  378. if (ptr == NULL)
  379. {
  380. throw std::runtime_error("Mapper FATAL ERROR - Index out of range in probability search!");
  381. }
  382. *ptr = math::Maximum(pPoseResponse[i].first, *ptr);
  383. }
  384. }
  385. // average all poses with same highest response
  386. Vector2<kt_double> averagePosition;
  387. kt_double thetaX = 0.0;
  388. kt_double thetaY = 0.0;
  389. kt_int32s averagePoseCount = 0;
  390. for (kt_int32u i = 0; i < poseResponseSize; i++)
  391. {
  392. if (math::DoubleEqual(pPoseResponse[i].first, bestResponse))
  393. {
  394. averagePosition += pPoseResponse[i].second.GetPosition();
  395. kt_double heading = pPoseResponse[i].second.GetHeading();
  396. thetaX += cos(heading);
  397. thetaY += sin(heading);
  398. averagePoseCount++;
  399. }
  400. }
  401. Pose2 averagePose;
  402. if (averagePoseCount > 0)
  403. {
  404. averagePosition /= averagePoseCount;
  405. thetaX /= averagePoseCount;
  406. thetaY /= averagePoseCount;
  407. averagePose = Pose2(averagePosition, atan2(thetaY, thetaX));
  408. }
  409. else
  410. {
  411. throw std::runtime_error("Mapper FATAL ERROR - Unable to find best position");
  412. }
  413. // delete pose response array
  414. delete[] pPoseResponse;
  415. // #ifdef KARTO_DEBUG
  416. // std::cout << "bestPose: " << averagePose << std::endl;
  417. // std::cout << "bestResponse: " << bestResponse << std::endl;
  418. // #endif
  419. if (!doingFineMatch)
  420. {
  421. ComputePositionalCovariance(averagePose, bestResponse, rSearchCenter, rSearchSpaceOffset,
  422. rSearchSpaceResolution, searchAngleResolution, rCovariance);
  423. }
  424. else
  425. {
  426. ComputeAngularCovariance(averagePose, bestResponse, rSearchCenter,
  427. searchAngleOffset, searchAngleResolution, rCovariance);
  428. }
  429. rMean = averagePose;
  430. // #ifdef KARTO_DEBUG
  431. // std::cout << "bestPose: " << averagePose << std::endl;
  432. // #endif
  433. if (bestResponse > 1.0)
  434. {
  435. bestResponse = 1.0;
  436. }
  437. assert(math::InRange(bestResponse, 0.0, 1.0));
  438. assert(math::InRange(rMean.GetHeading(), -KT_PI, KT_PI));
  439. return bestResponse;
  440. }
  441. /**
  442. * 计算最佳姿态的位置协方差
  443. * Computes the positional covariance of the best pose
  444. * @param rBestPose
  445. * @param bestResponse
  446. * @param rSearchCenter
  447. * @param rSearchSpaceOffset
  448. * @param rSearchSpaceResolution
  449. * @param searchAngleResolution
  450. * @param rCovariance
  451. */
  452. void ScanMatcher::ComputePositionalCovariance(const Pose2 &rBestPose, kt_double bestResponse,
  453. const Pose2 &rSearchCenter,
  454. const Vector2<kt_double> &rSearchSpaceOffset,
  455. const Vector2<kt_double> &rSearchSpaceResolution,
  456. kt_double searchAngleResolution, Matrix3 &rCovariance)
  457. {
  458. // reset covariance to identity matrix
  459. rCovariance.SetToIdentity();
  460. // if best response is vary small return max variance
  461. if (bestResponse < KT_TOLERANCE)
  462. {
  463. rCovariance(0, 0) = MAX_VARIANCE; // XX
  464. rCovariance(1, 1) = MAX_VARIANCE; // YY
  465. rCovariance(2, 2) = 4 * math::Square(searchAngleResolution); // TH*TH
  466. return;
  467. }
  468. kt_double accumulatedVarianceXX = 0;
  469. kt_double accumulatedVarianceXY = 0;
  470. kt_double accumulatedVarianceYY = 0;
  471. kt_double norm = 0;
  472. kt_double dx = rBestPose.GetX() - rSearchCenter.GetX();
  473. kt_double dy = rBestPose.GetY() - rSearchCenter.GetY();
  474. kt_double offsetX = rSearchSpaceOffset.GetX();
  475. kt_double offsetY = rSearchSpaceOffset.GetY();
  476. kt_int32u nX = static_cast<kt_int32u>(math::Round(offsetX * 2.0 / rSearchSpaceResolution.GetX()) + 1);
  477. kt_double startX = -offsetX;
  478. assert(math::DoubleEqual(startX + (nX - 1) * rSearchSpaceResolution.GetX(), -startX));
  479. kt_int32u nY = static_cast<kt_int32u>(math::Round(offsetY * 2.0 / rSearchSpaceResolution.GetY()) + 1);
  480. kt_double startY = -offsetY;
  481. assert(math::DoubleEqual(startY + (nY - 1) * rSearchSpaceResolution.GetY(), -startY));
  482. for (kt_int32u yIndex = 0; yIndex < nY; yIndex++)
  483. {
  484. kt_double y = startY + yIndex * rSearchSpaceResolution.GetY();
  485. for (kt_int32u xIndex = 0; xIndex < nX; xIndex++)
  486. {
  487. kt_double x = startX + xIndex * rSearchSpaceResolution.GetX();
  488. Vector2<kt_int32s> gridPoint = m_pSearchSpaceProbs->WorldToGrid(Vector2<kt_double>(rSearchCenter.GetX() + x,
  489. rSearchCenter.GetY() + y));
  490. kt_double response = *(m_pSearchSpaceProbs->GetDataPointer(gridPoint));
  491. // response is not a low response
  492. if (response >= (bestResponse - 0.1))
  493. {
  494. norm += response;
  495. accumulatedVarianceXX += (math::Square(x - dx) * response);
  496. accumulatedVarianceXY += ((x - dx) * (y - dy) * response);
  497. accumulatedVarianceYY += (math::Square(y - dy) * response);
  498. }
  499. }
  500. }
  501. if (norm > KT_TOLERANCE)
  502. {
  503. kt_double varianceXX = accumulatedVarianceXX / norm;
  504. kt_double varianceXY = accumulatedVarianceXY / norm;
  505. kt_double varianceYY = accumulatedVarianceYY / norm;
  506. kt_double varianceTHTH = 4 * math::Square(searchAngleResolution);
  507. // lower-bound variances so that they are not too small;
  508. // ensures that links are not too tight
  509. kt_double minVarianceXX = 0.1 * math::Square(rSearchSpaceResolution.GetX());
  510. kt_double minVarianceYY = 0.1 * math::Square(rSearchSpaceResolution.GetY());
  511. varianceXX = math::Maximum(varianceXX, minVarianceXX);
  512. varianceYY = math::Maximum(varianceYY, minVarianceYY);
  513. // increase variance for poorer responses
  514. kt_double multiplier = 1.0 / bestResponse;
  515. rCovariance(0, 0) = varianceXX * multiplier;
  516. rCovariance(0, 1) = varianceXY * multiplier;
  517. rCovariance(1, 0) = varianceXY * multiplier;
  518. rCovariance(1, 1) = varianceYY * multiplier;
  519. rCovariance(2, 2) = varianceTHTH; // this value will be set in ComputeAngularCovariance
  520. }
  521. // if values are 0, set to MAX_VARIANCE
  522. // values might be 0 if points are too sparse and thus don't hit other points
  523. if (math::DoubleEqual(rCovariance(0, 0), 0.0))
  524. {
  525. rCovariance(0, 0) = MAX_VARIANCE;
  526. }
  527. if (math::DoubleEqual(rCovariance(1, 1), 0.0))
  528. {
  529. rCovariance(1, 1) = MAX_VARIANCE;
  530. }
  531. }
  532. /**
  533. * 计算最佳姿态的角度协方差
  534. * Computes the angular covariance of the best pose
  535. * @param rBestPose
  536. * @param bestResponse
  537. * @param rSearchCenter
  538. * @param rSearchAngleOffset
  539. * @param searchAngleResolution
  540. * @param rCovariance
  541. */
  542. void ScanMatcher::ComputeAngularCovariance(const Pose2 &rBestPose,
  543. kt_double bestResponse,
  544. const Pose2 &rSearchCenter,
  545. kt_double searchAngleOffset,
  546. kt_double searchAngleResolution,
  547. Matrix3 &rCovariance)
  548. {
  549. // NOTE: do not reset covariance matrix
  550. // normalize angle difference
  551. kt_double bestAngle = math::NormalizeAngleDifference(rBestPose.GetHeading(), rSearchCenter.GetHeading());
  552. Vector2<kt_int32s> gridPoint = m_pCorrelationGrid->WorldToGrid(rBestPose.GetPosition());
  553. kt_int32s gridIndex = m_pCorrelationGrid->GridIndex(gridPoint);
  554. kt_int32u nAngles = static_cast<kt_int32u>(math::Round(searchAngleOffset * 2 / searchAngleResolution) + 1);
  555. kt_double angle = 0.0;
  556. kt_double startAngle = rSearchCenter.GetHeading() - searchAngleOffset;
  557. kt_double norm = 0.0;
  558. kt_double accumulatedVarianceThTh = 0.0;
  559. for (kt_int32u angleIndex = 0; angleIndex < nAngles; angleIndex++)
  560. {
  561. angle = startAngle + angleIndex * searchAngleResolution;
  562. kt_double response = GetResponse(angleIndex, gridIndex);
  563. // response is not a low response
  564. if (response >= (bestResponse - 0.1))
  565. {
  566. norm += response;
  567. accumulatedVarianceThTh += (math::Square(angle - bestAngle) * response);
  568. }
  569. }
  570. assert(math::DoubleEqual(angle, rSearchCenter.GetHeading() + searchAngleOffset));
  571. if (norm > KT_TOLERANCE)
  572. {
  573. if (accumulatedVarianceThTh < KT_TOLERANCE)
  574. {
  575. accumulatedVarianceThTh = math::Square(searchAngleResolution);
  576. }
  577. accumulatedVarianceThTh /= norm;
  578. }
  579. else
  580. {
  581. accumulatedVarianceThTh = 1000 * math::Square(searchAngleResolution);
  582. }
  583. rCovariance(2, 2) = accumulatedVarianceThTh;
  584. }
  585. /**
  586. * 将扫描的点标记为占用在相关网格中
  587. * Marks cells where scans' points hit as being occupied
  588. * @param rScans scans whose points will mark cells in grid as being occupied
  589. * @param viewPoint do not add points that belong to scans "opposite" the view point
  590. */
  591. void ScanMatcher::AddScans(const LocalizedRangeScanVector &rScans, Vector2<kt_double> viewPoint)
  592. {
  593. m_pCorrelationGrid->Clear();
  594. // add all scans to grid
  595. const_forEach(LocalizedRangeScanVector, &rScans)
  596. {
  597. AddScan(*iter, viewPoint);
  598. }
  599. }
  600. /**
  601. * 将单个扫描的点标记为占用在相关网格中,可以选择是否模糊点
  602. * Marks cells where scans' points hit as being occupied. Can smear points as they are added.
  603. * @param pScan scan whose points will mark cells in grid as being occupied
  604. * @param viewPoint do not add points that belong to scans "opposite" the view point
  605. * @param doSmear whether the points will be smeared
  606. */
  607. void ScanMatcher::AddScan(LocalizedRangeScan *pScan, const Vector2<kt_double> &rViewPoint, kt_bool doSmear)
  608. {
  609. PointVectorDouble validPoints = FindValidPoints(pScan, rViewPoint);
  610. // put in all valid points
  611. const_forEach(PointVectorDouble, &validPoints)
  612. {
  613. Vector2<kt_int32s> gridPoint = m_pCorrelationGrid->WorldToGrid(*iter);
  614. if (!math::IsUpTo(gridPoint.GetX(), m_pCorrelationGrid->GetROI().GetWidth()) ||
  615. !math::IsUpTo(gridPoint.GetY(), m_pCorrelationGrid->GetROI().GetHeight()))
  616. {
  617. // point not in grid
  618. continue;
  619. }
  620. int gridIndex = m_pCorrelationGrid->GridIndex(gridPoint);
  621. // set grid cell as occupied
  622. if (m_pCorrelationGrid->GetDataPointer()[gridIndex] == GridStates_Occupied)
  623. {
  624. // value already set
  625. continue;
  626. }
  627. m_pCorrelationGrid->GetDataPointer()[gridIndex] = GridStates_Occupied;
  628. // smear grid
  629. if (doSmear == true)
  630. {
  631. m_pCorrelationGrid->SmearPoint(gridPoint);
  632. }
  633. }
  634. }
  635. /**
  636. * 计算扫描中与给定视点在同一侧的点
  637. * Compute which points in a scan are on the same side as the given viewpoint
  638. * @param pScan
  639. * @param rViewPoint
  640. * @return points on the same side
  641. */
  642. PointVectorDouble ScanMatcher::FindValidPoints(LocalizedRangeScan *pScan, const Vector2<kt_double> &rViewPoint) const
  643. {
  644. const PointVectorDouble &rPointReadings = pScan->GetPointReadings();
  645. // points must be at least 10 cm away when making comparisons of inside/outside of viewpoint
  646. const kt_double minSquareDistance = math::Square(0.1); // in m^2
  647. // this iterator lags from the main iterator adding points only when the points are on
  648. // the same side as the viewpoint
  649. PointVectorDouble::const_iterator trailingPointIter = rPointReadings.begin();
  650. PointVectorDouble validPoints;
  651. Vector2<kt_double> firstPoint;
  652. kt_bool firstTime = true;
  653. const_forEach(PointVectorDouble, &rPointReadings)
  654. {
  655. Vector2<kt_double> currentPoint = *iter;
  656. if (firstTime && !std::isnan(currentPoint.GetX()) && !std::isnan(currentPoint.GetY()))
  657. {
  658. firstPoint = currentPoint;
  659. firstTime = false;
  660. }
  661. Vector2<kt_double> delta = firstPoint - currentPoint;
  662. if (delta.SquaredLength() > minSquareDistance)
  663. {
  664. // This compute the Determinant (viewPoint FirstPoint, viewPoint currentPoint)
  665. // Which computes the direction of rotation, if the rotation is counterclock
  666. // wise then we are looking at data we should keep. If it's negative rotation
  667. // we should not included in in the matching
  668. // have enough distance, check viewpoint
  669. double a = rViewPoint.GetY() - firstPoint.GetY();
  670. double b = firstPoint.GetX() - rViewPoint.GetX();
  671. double c = firstPoint.GetY() * rViewPoint.GetX() - firstPoint.GetX() * rViewPoint.GetY();
  672. double ss = currentPoint.GetX() * a + currentPoint.GetY() * b + c;
  673. // reset beginning point
  674. firstPoint = currentPoint;
  675. if (ss < 0.0) // wrong side, skip and keep going
  676. {
  677. trailingPointIter = iter;
  678. }
  679. else
  680. {
  681. for (; trailingPointIter != iter; ++trailingPointIter)
  682. {
  683. validPoints.push_back(*trailingPointIter);
  684. }
  685. }
  686. }
  687. }
  688. return validPoints;
  689. }
  690. /**
  691. * 获取在给定位置和旋转下的响应值
  692. * Get response at given position for given rotation (only look up valid points)
  693. * @param angleIndex 角度索引,表示当前的旋转角度在查找数组中的位置
  694. * @param gridPositionIndex 当前位置在网格数组中的索引
  695. * @return response 当前位置和角度的匹配响应值,范围为 [0,1]
  696. */
  697. kt_double ScanMatcher::GetResponse(kt_int32u angleIndex, kt_int32s gridPositionIndex) const
  698. {
  699. kt_double response = 0.0;
  700. // add up value for each point 将每个点的值相加
  701. kt_int8u *pByte = m_pCorrelationGrid->GetDataPointer() + gridPositionIndex;
  702. const LookupArray *pOffsets = m_pGridLookup->GetLookupArray(angleIndex);
  703. assert(pOffsets != NULL);
  704. // get number of points in offset list 获取偏移列表中的点数
  705. kt_int32u nPoints = pOffsets->GetSize();
  706. if (nPoints == 0)
  707. {
  708. return response;
  709. }
  710. // calculate response 计算 response
  711. kt_int32s *pAngleIndexPointer = pOffsets->GetArrayPointer();
  712. for (kt_int32u i = 0; i < nPoints; i++)
  713. {
  714. // ignore points that fall off the grid 忽略不在网格上的点
  715. kt_int32s pointGridIndex = gridPositionIndex + pAngleIndexPointer[i];
  716. if (!math::IsUpTo(pointGridIndex, m_pCorrelationGrid->GetDataSize()) || pAngleIndexPointer[i] == INVALID_SCAN)
  717. {
  718. continue;
  719. }
  720. // uses index offsets to efficiently find location of point in the grid
  721. // 使用索引偏移来有效地找到网格中点的位置
  722. response += pByte[pAngleIndexPointer[i]];
  723. }
  724. // normalize response
  725. response /= (nPoints * GridStates_Occupied);
  726. assert(fabs(response) <= 1.0);
  727. return response;
  728. }
  729. ////////////////////////////////////////////////////////////////////////////////////////
  730. ////////////////////////////////////////////////////////////////////////////////////////
  731. ////////////////////////////////////////////////////////////////////////////////////////
  732. MapperGraph::MapperGraph(Mapper *pMapper, kt_double rangeThreshold)
  733. : m_pMapper(pMapper)
  734. {
  735. m_pLoopScanMatcher = ScanMatcher::Create(pMapper, m_pMapper->m_pLoopSearchSpaceDimension->GetValue(),
  736. m_pMapper->m_pLoopSearchSpaceResolution->GetValue(),
  737. m_pMapper->m_pLoopSearchSpaceSmearDeviation->GetValue(), rangeThreshold);
  738. assert(m_pLoopScanMatcher);
  739. m_pTraversal = new BreadthFirstTraversal<LocalizedRangeScan>(this);
  740. }
  741. MapperGraph::~MapperGraph()
  742. {
  743. delete m_pLoopScanMatcher;
  744. m_pLoopScanMatcher = NULL;
  745. delete m_pTraversal;
  746. m_pTraversal = NULL;
  747. }
  748. void MapperGraph::AddVertex(LocalizedRangeScan *pScan)
  749. {
  750. assert(pScan);
  751. if (pScan != NULL)
  752. {
  753. Vertex<LocalizedRangeScan> *pVertex = new Vertex<LocalizedRangeScan>(pScan);
  754. Graph<LocalizedRangeScan>::AddVertex(pScan->GetSensorName(), pVertex);
  755. if (m_pMapper->m_pScanOptimizer != NULL)
  756. {
  757. m_pMapper->m_pScanOptimizer->AddNode(pVertex);
  758. }
  759. }
  760. }
  761. void MapperGraph::AddEdges(LocalizedRangeScan *pScan, const Matrix3 &rCovariance)
  762. {
  763. MapperSensorManager *pSensorManager = m_pMapper->m_pMapperSensorManager;
  764. const Name &rSensorName = pScan->GetSensorName();
  765. // link to previous scan
  766. kt_int32s previousScanNum = pScan->GetStateId() - 1;
  767. if (pSensorManager->GetLastScan(rSensorName) != NULL)
  768. {
  769. assert(previousScanNum >= 0);
  770. LinkScans(pSensorManager->GetScan(rSensorName, previousScanNum), pScan, pScan->GetSensorPose(), rCovariance);
  771. }
  772. Pose2Vector means;
  773. std::vector<Matrix3> covariances;
  774. // first scan (link to first scan of other robots)
  775. if (pSensorManager->GetLastScan(rSensorName) == NULL)
  776. {
  777. assert(pSensorManager->GetScans(rSensorName).size() == 1);
  778. std::vector<Name> deviceNames = pSensorManager->GetSensorNames();
  779. forEach(std::vector<Name>, &deviceNames)
  780. {
  781. const Name &rCandidateSensorName = *iter;
  782. // skip if candidate device is the same or other device has no scans
  783. if ((rCandidateSensorName == rSensorName) || (pSensorManager->GetScans(rCandidateSensorName).empty()))
  784. {
  785. continue;
  786. }
  787. Pose2 bestPose;
  788. Matrix3 covariance;
  789. kt_double response = m_pMapper->m_pSequentialScanMatcher->MatchScan(pScan,
  790. pSensorManager->GetScans(rCandidateSensorName),
  791. bestPose, covariance);
  792. LinkScans(pSensorManager->GetScan(rCandidateSensorName, 0), pScan, bestPose, covariance);
  793. // only add to means and covariances if response was high "enough"
  794. if (response > m_pMapper->m_pLinkMatchMinimumResponseFine->GetValue())
  795. {
  796. means.push_back(bestPose);
  797. covariances.push_back(covariance);
  798. }
  799. }
  800. }
  801. else
  802. {
  803. // link to running scans
  804. Pose2 scanPose = pScan->GetSensorPose();
  805. means.push_back(scanPose);
  806. covariances.push_back(rCovariance);
  807. LinkChainToScan(pSensorManager->GetRunningScans(rSensorName), pScan, scanPose, rCovariance);
  808. }
  809. // link to other near chains (chains that include new scan are invalid)
  810. LinkNearChains(pScan, means, covariances);
  811. if (!means.empty())
  812. {
  813. pScan->SetSensorPose(ComputeWeightedMean(means, covariances));
  814. }
  815. }
  816. kt_bool MapperGraph::TryCloseLoop(LocalizedRangeScan *pScan, const Name &rSensorName)
  817. {
  818. kt_bool loopClosed = false;
  819. kt_int32u scanIndex = 0;
  820. LocalizedRangeScanVector candidateChain = FindPossibleLoopClosure(pScan, rSensorName, scanIndex);
  821. while (!candidateChain.empty())
  822. {
  823. Pose2 bestPose;
  824. Matrix3 covariance;
  825. kt_double coarseResponse = m_pLoopScanMatcher->MatchScan(pScan, candidateChain,
  826. bestPose, covariance, false, false);
  827. std::stringstream stream;
  828. stream << "COARSE RESPONSE: " << coarseResponse
  829. << " (> " << m_pMapper->m_pLoopMatchMinimumResponseCoarse->GetValue() << ")"
  830. << std::endl;
  831. stream << " var: " << covariance(0, 0) << ", " << covariance(1, 1)
  832. << " (< " << m_pMapper->m_pLoopMatchMaximumVarianceCoarse->GetValue() << ")";
  833. m_pMapper->FireLoopClosureCheck(stream.str());
  834. if ((coarseResponse > m_pMapper->m_pLoopMatchMinimumResponseCoarse->GetValue()) &&
  835. (covariance(0, 0) < m_pMapper->m_pLoopMatchMaximumVarianceCoarse->GetValue()) &&
  836. (covariance(1, 1) < m_pMapper->m_pLoopMatchMaximumVarianceCoarse->GetValue()))
  837. {
  838. LocalizedRangeScan tmpScan(pScan->GetSensorName(), pScan->GetRangeReadingsVector());
  839. tmpScan.SetUniqueId(pScan->GetUniqueId());
  840. tmpScan.SetTime(pScan->GetTime());
  841. tmpScan.SetStateId(pScan->GetStateId());
  842. tmpScan.SetCorrectedPose(pScan->GetCorrectedPose());
  843. tmpScan.SetSensorPose(bestPose); // This also updates OdometricPose.
  844. kt_double fineResponse = m_pMapper->m_pSequentialScanMatcher->MatchScan(&tmpScan, candidateChain,
  845. bestPose, covariance, false);
  846. std::stringstream stream1;
  847. stream1 << "FINE RESPONSE: " << fineResponse << " (>"
  848. << m_pMapper->m_pLoopMatchMinimumResponseFine->GetValue() << ")" << std::endl;
  849. m_pMapper->FireLoopClosureCheck(stream1.str());
  850. if (fineResponse < m_pMapper->m_pLoopMatchMinimumResponseFine->GetValue())
  851. {
  852. m_pMapper->FireLoopClosureCheck("REJECTED!");
  853. }
  854. else
  855. {
  856. m_pMapper->FireBeginLoopClosure("Closing loop...");
  857. pScan->SetSensorPose(bestPose);
  858. LinkChainToScan(candidateChain, pScan, bestPose, covariance);
  859. CorrectPoses();
  860. m_pMapper->FireEndLoopClosure("Loop closed!");
  861. loopClosed = true;
  862. }
  863. }
  864. candidateChain = FindPossibleLoopClosure(pScan, rSensorName, scanIndex);
  865. }
  866. return loopClosed;
  867. }
  868. LocalizedRangeScan *MapperGraph::GetClosestScanToPose(const LocalizedRangeScanVector &rScans,
  869. const Pose2 &rPose) const
  870. {
  871. LocalizedRangeScan *pClosestScan = NULL;
  872. kt_double bestSquaredDistance = DBL_MAX;
  873. const_forEach(LocalizedRangeScanVector, &rScans)
  874. {
  875. Pose2 scanPose = (*iter)->GetReferencePose(m_pMapper->m_pUseScanBarycenter->GetValue());
  876. kt_double squaredDistance = rPose.GetPosition().SquaredDistance(scanPose.GetPosition());
  877. if (squaredDistance < bestSquaredDistance)
  878. {
  879. bestSquaredDistance = squaredDistance;
  880. pClosestScan = *iter;
  881. }
  882. }
  883. return pClosestScan;
  884. }
  885. Edge<LocalizedRangeScan> *MapperGraph::AddEdge(LocalizedRangeScan *pSourceScan,
  886. LocalizedRangeScan *pTargetScan, kt_bool &rIsNewEdge)
  887. {
  888. // check that vertex exists
  889. assert(pSourceScan->GetStateId() < (kt_int32s)m_Vertices[pSourceScan->GetSensorName()].size());
  890. assert(pTargetScan->GetStateId() < (kt_int32s)m_Vertices[pTargetScan->GetSensorName()].size());
  891. Vertex<LocalizedRangeScan> *v1 = m_Vertices[pSourceScan->GetSensorName()][pSourceScan->GetStateId()];
  892. Vertex<LocalizedRangeScan> *v2 = m_Vertices[pTargetScan->GetSensorName()][pTargetScan->GetStateId()];
  893. // see if edge already exists
  894. const_forEach(std::vector<Edge<LocalizedRangeScan> *>, &(v1->GetEdges()))
  895. {
  896. Edge<LocalizedRangeScan> *pEdge = *iter;
  897. if (pEdge->GetTarget() == v2)
  898. {
  899. rIsNewEdge = false;
  900. return pEdge;
  901. }
  902. }
  903. Edge<LocalizedRangeScan> *pEdge = new Edge<LocalizedRangeScan>(v1, v2);
  904. Graph<LocalizedRangeScan>::AddEdge(pEdge);
  905. rIsNewEdge = true;
  906. return pEdge;
  907. }
  908. void MapperGraph::LinkScans(LocalizedRangeScan *pFromScan, LocalizedRangeScan *pToScan,
  909. const Pose2 &rMean, const Matrix3 &rCovariance)
  910. {
  911. kt_bool isNewEdge = true;
  912. Edge<LocalizedRangeScan> *pEdge = AddEdge(pFromScan, pToScan, isNewEdge);
  913. // only attach link information if the edge is new
  914. if (isNewEdge == true)
  915. {
  916. pEdge->SetLabel(new LinkInfo(pFromScan->GetSensorPose(), rMean, rCovariance));
  917. if (m_pMapper->m_pScanOptimizer != NULL)
  918. {
  919. m_pMapper->m_pScanOptimizer->AddConstraint(pEdge);
  920. }
  921. }
  922. }
  923. void MapperGraph::LinkNearChains(LocalizedRangeScan *pScan, Pose2Vector &rMeans, std::vector<Matrix3> &rCovariances)
  924. {
  925. const std::vector<LocalizedRangeScanVector> nearChains = FindNearChains(pScan);
  926. const_forEach(std::vector<LocalizedRangeScanVector>, &nearChains)
  927. {
  928. if (iter->size() < m_pMapper->m_pLoopMatchMinimumChainSize->GetValue())
  929. {
  930. continue;
  931. }
  932. Pose2 mean;
  933. Matrix3 covariance;
  934. // match scan against "near" chain
  935. kt_double response = m_pMapper->m_pSequentialScanMatcher->MatchScan(pScan, *iter, mean, covariance, false);
  936. if (response > m_pMapper->m_pLinkMatchMinimumResponseFine->GetValue() - KT_TOLERANCE)
  937. {
  938. rMeans.push_back(mean);
  939. rCovariances.push_back(covariance);
  940. LinkChainToScan(*iter, pScan, mean, covariance);
  941. }
  942. }
  943. }
  944. void MapperGraph::LinkChainToScan(const LocalizedRangeScanVector &rChain, LocalizedRangeScan *pScan,
  945. const Pose2 &rMean, const Matrix3 &rCovariance)
  946. {
  947. Pose2 pose = pScan->GetReferencePose(m_pMapper->m_pUseScanBarycenter->GetValue());
  948. LocalizedRangeScan *pClosestScan = GetClosestScanToPose(rChain, pose);
  949. assert(pClosestScan != NULL);
  950. Pose2 closestScanPose = pClosestScan->GetReferencePose(m_pMapper->m_pUseScanBarycenter->GetValue());
  951. kt_double squaredDistance = pose.GetPosition().SquaredDistance(closestScanPose.GetPosition());
  952. if (squaredDistance < math::Square(m_pMapper->m_pLinkScanMaximumDistance->GetValue()) + KT_TOLERANCE)
  953. {
  954. LinkScans(pClosestScan, pScan, rMean, rCovariance);
  955. }
  956. }
  957. std::vector<LocalizedRangeScanVector> MapperGraph::FindNearChains(LocalizedRangeScan *pScan)
  958. {
  959. std::vector<LocalizedRangeScanVector> nearChains;
  960. Pose2 scanPose = pScan->GetReferencePose(m_pMapper->m_pUseScanBarycenter->GetValue());
  961. // to keep track of which scans have been added to a chain
  962. LocalizedRangeScanVector processed;
  963. const LocalizedRangeScanVector nearLinkedScans = FindNearLinkedScans(pScan,
  964. m_pMapper->m_pLinkScanMaximumDistance->GetValue());
  965. const_forEach(LocalizedRangeScanVector, &nearLinkedScans)
  966. {
  967. LocalizedRangeScan *pNearScan = *iter;
  968. if (pNearScan == pScan)
  969. {
  970. continue;
  971. }
  972. // scan has already been processed, skip
  973. if (find(processed.begin(), processed.end(), pNearScan) != processed.end())
  974. {
  975. continue;
  976. }
  977. processed.push_back(pNearScan);
  978. // build up chain
  979. kt_bool isValidChain = true;
  980. std::list<LocalizedRangeScan *> chain;
  981. // add scans before current scan being processed
  982. for (kt_int32s candidateScanNum = pNearScan->GetStateId() - 1; candidateScanNum >= 0; candidateScanNum--)
  983. {
  984. LocalizedRangeScan *pCandidateScan = m_pMapper->m_pMapperSensorManager->GetScan(pNearScan->GetSensorName(),
  985. candidateScanNum);
  986. // chain is invalid--contains scan being added
  987. if (pCandidateScan == pScan)
  988. {
  989. isValidChain = false;
  990. }
  991. Pose2 candidatePose = pCandidateScan->GetReferencePose(m_pMapper->m_pUseScanBarycenter->GetValue());
  992. kt_double squaredDistance = scanPose.GetPosition().SquaredDistance(candidatePose.GetPosition());
  993. if (squaredDistance < math::Square(m_pMapper->m_pLinkScanMaximumDistance->GetValue()) + KT_TOLERANCE)
  994. {
  995. chain.push_front(pCandidateScan);
  996. processed.push_back(pCandidateScan);
  997. }
  998. else
  999. {
  1000. break;
  1001. }
  1002. }
  1003. chain.push_back(pNearScan);
  1004. // add scans after current scan being processed
  1005. kt_int32u end = static_cast<kt_int32u>(m_pMapper->m_pMapperSensorManager->GetScans(pNearScan->GetSensorName()).size());
  1006. for (kt_int32u candidateScanNum = pNearScan->GetStateId() + 1; candidateScanNum < end; candidateScanNum++)
  1007. {
  1008. LocalizedRangeScan *pCandidateScan = m_pMapper->m_pMapperSensorManager->GetScan(pNearScan->GetSensorName(),
  1009. candidateScanNum);
  1010. if (pCandidateScan == pScan)
  1011. {
  1012. isValidChain = false;
  1013. }
  1014. Pose2 candidatePose = pCandidateScan->GetReferencePose(m_pMapper->m_pUseScanBarycenter->GetValue());
  1015. ;
  1016. kt_double squaredDistance = scanPose.GetPosition().SquaredDistance(candidatePose.GetPosition());
  1017. if (squaredDistance < math::Square(m_pMapper->m_pLinkScanMaximumDistance->GetValue()) + KT_TOLERANCE)
  1018. {
  1019. chain.push_back(pCandidateScan);
  1020. processed.push_back(pCandidateScan);
  1021. }
  1022. else
  1023. {
  1024. break;
  1025. }
  1026. }
  1027. if (isValidChain)
  1028. {
  1029. // change list to vector
  1030. LocalizedRangeScanVector tempChain;
  1031. std::copy(chain.begin(), chain.end(), std::inserter(tempChain, tempChain.begin()));
  1032. // add chain to collection
  1033. nearChains.push_back(tempChain);
  1034. }
  1035. }
  1036. return nearChains;
  1037. }
  1038. LocalizedRangeScanVector MapperGraph::FindNearLinkedScans(LocalizedRangeScan *pScan, kt_double maxDistance)
  1039. {
  1040. NearScanVisitor *pVisitor = new NearScanVisitor(pScan, maxDistance, m_pMapper->m_pUseScanBarycenter->GetValue());
  1041. LocalizedRangeScanVector nearLinkedScans = m_pTraversal->Traverse(GetVertex(pScan), pVisitor);
  1042. delete pVisitor;
  1043. return nearLinkedScans;
  1044. }
  1045. Pose2 MapperGraph::ComputeWeightedMean(const Pose2Vector &rMeans, const std::vector<Matrix3> &rCovariances) const
  1046. {
  1047. assert(rMeans.size() == rCovariances.size());
  1048. // compute sum of inverses and create inverse list
  1049. std::vector<Matrix3> inverses;
  1050. inverses.reserve(rCovariances.size());
  1051. Matrix3 sumOfInverses;
  1052. const_forEach(std::vector<Matrix3>, &rCovariances)
  1053. {
  1054. Matrix3 inverse = iter->Inverse();
  1055. inverses.push_back(inverse);
  1056. sumOfInverses += inverse;
  1057. }
  1058. Matrix3 inverseOfSumOfInverses = sumOfInverses.Inverse();
  1059. // compute weighted mean
  1060. Pose2 accumulatedPose;
  1061. kt_double thetaX = 0.0;
  1062. kt_double thetaY = 0.0;
  1063. Pose2Vector::const_iterator meansIter = rMeans.begin();
  1064. const_forEach(std::vector<Matrix3>, &inverses)
  1065. {
  1066. Pose2 pose = *meansIter;
  1067. kt_double angle = pose.GetHeading();
  1068. thetaX += cos(angle);
  1069. thetaY += sin(angle);
  1070. Matrix3 weight = inverseOfSumOfInverses * (*iter);
  1071. accumulatedPose += weight * pose;
  1072. ++meansIter;
  1073. }
  1074. thetaX /= rMeans.size();
  1075. thetaY /= rMeans.size();
  1076. accumulatedPose.SetHeading(atan2(thetaY, thetaX));
  1077. return accumulatedPose;
  1078. }
  1079. LocalizedRangeScanVector MapperGraph::FindPossibleLoopClosure(LocalizedRangeScan *pScan,
  1080. const Name &rSensorName,
  1081. kt_int32u &rStartNum)
  1082. {
  1083. LocalizedRangeScanVector chain; // return value
  1084. Pose2 pose = pScan->GetReferencePose(m_pMapper->m_pUseScanBarycenter->GetValue());
  1085. // possible loop closure chain should not include close scans that have a
  1086. // path of links to the scan of interest
  1087. const LocalizedRangeScanVector nearLinkedScans =
  1088. FindNearLinkedScans(pScan, m_pMapper->m_pLoopSearchMaximumDistance->GetValue());
  1089. kt_int32u nScans = static_cast<kt_int32u>(m_pMapper->m_pMapperSensorManager->GetScans(rSensorName).size());
  1090. for (; rStartNum < nScans; rStartNum++)
  1091. {
  1092. LocalizedRangeScan *pCandidateScan = m_pMapper->m_pMapperSensorManager->GetScan(rSensorName, rStartNum);
  1093. Pose2 candidateScanPose = pCandidateScan->GetReferencePose(m_pMapper->m_pUseScanBarycenter->GetValue());
  1094. kt_double squaredDistance = candidateScanPose.GetPosition().SquaredDistance(pose.GetPosition());
  1095. if (squaredDistance < math::Square(m_pMapper->m_pLoopSearchMaximumDistance->GetValue()) + KT_TOLERANCE)
  1096. {
  1097. // a linked scan cannot be in the chain
  1098. if (find(nearLinkedScans.begin(), nearLinkedScans.end(), pCandidateScan) != nearLinkedScans.end())
  1099. {
  1100. chain.clear();
  1101. }
  1102. else
  1103. {
  1104. chain.push_back(pCandidateScan);
  1105. }
  1106. }
  1107. else
  1108. {
  1109. // return chain if it is long "enough"
  1110. if (chain.size() >= m_pMapper->m_pLoopMatchMinimumChainSize->GetValue())
  1111. {
  1112. return chain;
  1113. }
  1114. else
  1115. {
  1116. chain.clear();
  1117. }
  1118. }
  1119. }
  1120. return chain;
  1121. }
  1122. void MapperGraph::CorrectPoses()
  1123. {
  1124. // optimize scans!
  1125. ScanSolver *pSolver = m_pMapper->m_pScanOptimizer;
  1126. if (pSolver != NULL)
  1127. {
  1128. pSolver->Compute();
  1129. const_forEach(ScanSolver::IdPoseVector, &pSolver->GetCorrections())
  1130. {
  1131. m_pMapper->m_pMapperSensorManager->GetScan(iter->first)->SetSensorPose(iter->second);
  1132. }
  1133. pSolver->Clear();
  1134. }
  1135. }
  1136. ////////////////////////////////////////////////////////////////////////////////////////
  1137. ////////////////////////////////////////////////////////////////////////////////////////
  1138. ////////////////////////////////////////////////////////////////////////////////////////
  1139. /**
  1140. * Default constructor
  1141. */
  1142. Mapper::Mapper()
  1143. : Module("Mapper"), m_Initialized(false), m_pSequentialScanMatcher(NULL), m_pMapperSensorManager(NULL), m_pGraph(NULL), m_pScanOptimizer(NULL)
  1144. {
  1145. InitializeParameters();
  1146. }
  1147. /**
  1148. * Default constructor
  1149. */
  1150. Mapper::Mapper(const std::string &rName)
  1151. : Module(rName), m_Initialized(false), m_pSequentialScanMatcher(NULL), m_pMapperSensorManager(NULL), m_pGraph(NULL), m_pScanOptimizer(NULL)
  1152. {
  1153. InitializeParameters();
  1154. }
  1155. /**
  1156. * Destructor
  1157. */
  1158. Mapper::~Mapper()
  1159. {
  1160. Reset();
  1161. delete m_pMapperSensorManager;
  1162. }
  1163. void Mapper::InitializeParameters()
  1164. {
  1165. m_pUseScanMatching = new Parameter<kt_bool>(
  1166. "UseScanMatching",
  1167. "When set to true, the mapper will use a scan matching algorithm. "
  1168. "In most real-world situations this should be set to true so that the "
  1169. "mapper algorithm can correct for noise and errors in odometry and "
  1170. "scan data. In some simulator environments where the simulated scan "
  1171. "and odometry data are very accurate, the scan matching algorithm can "
  1172. "produce worse results. In those cases set this to false to improve "
  1173. "results.",
  1174. true,
  1175. GetParameterManager());
  1176. m_pUseScanBarycenter = new Parameter<kt_bool>(
  1177. "UseScanBarycenter",
  1178. "Use the barycenter of scan endpoints to define distances between "
  1179. "scans.",
  1180. true, GetParameterManager());
  1181. m_pMinimumTimeInterval = new Parameter<kt_double>(
  1182. "MinimumTimeInterval",
  1183. "Sets the minimum time between scans. If a new scan's time stamp is "
  1184. "longer than MinimumTimeInterval from the previously processed scan, "
  1185. "the mapper will use the data from the new scan. Otherwise, it will "
  1186. "discard the new scan if it also does not meet the minimum travel "
  1187. "distance and heading requirements. For performance reasons, it is "
  1188. "generally it is a good idea to only process scans if a reasonable "
  1189. "amount of time has passed. This parameter is particularly useful "
  1190. "when there is a need to process scans while the robot is stationary.",
  1191. 3600, GetParameterManager());
  1192. m_pMinimumTravelDistance = new Parameter<kt_double>(
  1193. "MinimumTravelDistance",
  1194. "Sets the minimum travel between scans. If a new scan's position is "
  1195. "more than minimumTravelDistance from the previous scan, the mapper "
  1196. "will use the data from the new scan. Otherwise, it will discard the "
  1197. "new scan if it also does not meet the minimum change in heading "
  1198. "requirement. For performance reasons, generally it is a good idea to "
  1199. "only process scans if the robot has moved a reasonable amount.",
  1200. 0.2, GetParameterManager());
  1201. m_pMinimumTravelHeading = new Parameter<kt_double>(
  1202. "MinimumTravelHeading",
  1203. "Sets the minimum heading change between scans. If a new scan's "
  1204. "heading is more than MinimumTravelHeading from the previous scan, the "
  1205. "mapper will use the data from the new scan. Otherwise, it will "
  1206. "discard the new scan if it also does not meet the minimum travel "
  1207. "distance requirement. For performance reasons, generally it is a good "
  1208. "idea to only process scans if the robot has moved a reasonable "
  1209. "amount.",
  1210. math::DegreesToRadians(10), GetParameterManager());
  1211. m_pScanBufferSize = new Parameter<kt_int32u>(
  1212. "ScanBufferSize",
  1213. "Scan buffer size is the length of the scan chain stored for scan "
  1214. "matching. \"ScanBufferSize\" should be set to approximately "
  1215. "\"ScanBufferMaximumScanDistance\" / \"MinimumTravelDistance\". The "
  1216. "idea is to get an area approximately 20 meters long for scan "
  1217. "matching. For example, if we add scans every MinimumTravelDistance == "
  1218. "0.3 meters, then \"scanBufferSize\" should be 20 / 0.3 = 67.)",
  1219. 70, GetParameterManager());
  1220. m_pScanBufferMaximumScanDistance = new Parameter<kt_double>(
  1221. "ScanBufferMaximumScanDistance",
  1222. "Scan buffer maximum scan distance is the maximum distance between the "
  1223. "first and last scans in the scan chain stored for matching.",
  1224. 20.0, GetParameterManager());
  1225. m_pLinkMatchMinimumResponseFine = new Parameter<kt_double>(
  1226. "LinkMatchMinimumResponseFine",
  1227. "Scans are linked only if the correlation response value is greater "
  1228. "than this value.",
  1229. 0.8, GetParameterManager());
  1230. m_pLinkScanMaximumDistance = new Parameter<kt_double>(
  1231. "LinkScanMaximumDistance",
  1232. "Maximum distance between linked scans. Scans that are farther apart "
  1233. "will not be linked regardless of the correlation response value.",
  1234. 10.0, GetParameterManager());
  1235. m_pLoopSearchMaximumDistance = new Parameter<kt_double>(
  1236. "LoopSearchMaximumDistance",
  1237. "Scans less than this distance from the current position will be "
  1238. "considered for a match in loop closure.",
  1239. 4.0, GetParameterManager());
  1240. m_pDoLoopClosing = new Parameter<kt_bool>(
  1241. "DoLoopClosing",
  1242. "Enable/disable loop closure.",
  1243. true, GetParameterManager());
  1244. m_pLoopMatchMinimumChainSize = new Parameter<kt_int32u>(
  1245. "LoopMatchMinimumChainSize",
  1246. "When the loop closure detection finds a candidate it must be part of "
  1247. "a large set of linked scans. If the chain of scans is less than this "
  1248. "value we do not attempt to close the loop.",
  1249. 10, GetParameterManager());
  1250. m_pLoopMatchMaximumVarianceCoarse = new Parameter<kt_double>(
  1251. "LoopMatchMaximumVarianceCoarse",
  1252. "The co-variance values for a possible loop closure have to be less "
  1253. "than this value to consider a viable solution. This applies to the "
  1254. "coarse search.",
  1255. math::Square(0.4), GetParameterManager());
  1256. m_pLoopMatchMinimumResponseCoarse = new Parameter<kt_double>(
  1257. "LoopMatchMinimumResponseCoarse",
  1258. "If response is larger then this, then initiate loop closure search at "
  1259. "the coarse resolution.",
  1260. 0.8, GetParameterManager());
  1261. m_pLoopMatchMinimumResponseFine = new Parameter<kt_double>(
  1262. "LoopMatchMinimumResponseFine",
  1263. "If response is larger then this, then initiate loop closure search at "
  1264. "the fine resolution.",
  1265. 0.8, GetParameterManager());
  1266. //////////////////////////////////////////////////////////////////////////////
  1267. // CorrelationParameters correlationParameters;
  1268. m_pCorrelationSearchSpaceDimension = new Parameter<kt_double>(
  1269. "CorrelationSearchSpaceDimension",
  1270. "The size of the search grid used by the matcher. The search grid will "
  1271. "have the size CorrelationSearchSpaceDimension * "
  1272. "CorrelationSearchSpaceDimension",
  1273. 0.3, GetParameterManager());
  1274. m_pCorrelationSearchSpaceResolution = new Parameter<kt_double>(
  1275. "CorrelationSearchSpaceResolution",
  1276. "The resolution (size of a grid cell) of the correlation grid.",
  1277. 0.01, GetParameterManager());
  1278. m_pCorrelationSearchSpaceSmearDeviation = new Parameter<kt_double>(
  1279. "CorrelationSearchSpaceSmearDeviation",
  1280. "The point readings are smeared by this value in X and Y to create a "
  1281. "smoother response.",
  1282. 0.03, GetParameterManager());
  1283. //////////////////////////////////////////////////////////////////////////////
  1284. // CorrelationParameters loopCorrelationParameters;
  1285. m_pLoopSearchSpaceDimension = new Parameter<kt_double>(
  1286. "LoopSearchSpaceDimension",
  1287. "The size of the search grid used by the matcher.",
  1288. 8.0, GetParameterManager());
  1289. m_pLoopSearchSpaceResolution = new Parameter<kt_double>(
  1290. "LoopSearchSpaceResolution",
  1291. "The resolution (size of a grid cell) of the correlation grid.",
  1292. 0.05, GetParameterManager());
  1293. m_pLoopSearchSpaceSmearDeviation = new Parameter<kt_double>(
  1294. "LoopSearchSpaceSmearDeviation",
  1295. "The point readings are smeared by this value in X and Y to create a "
  1296. "smoother response.",
  1297. 0.03, GetParameterManager());
  1298. //////////////////////////////////////////////////////////////////////////////
  1299. // ScanMatcherParameters;
  1300. m_pDistanceVariancePenalty = new Parameter<kt_double>(
  1301. "DistanceVariancePenalty",
  1302. "Variance of penalty for deviating from odometry when scan-matching. "
  1303. "The penalty is a multiplier (less than 1.0) is a function of the "
  1304. "delta of the scan position being tested and the odometric pose.",
  1305. math::Square(0.3), GetParameterManager());
  1306. m_pAngleVariancePenalty = new Parameter<kt_double>(
  1307. "AngleVariancePenalty",
  1308. "See DistanceVariancePenalty.",
  1309. math::Square(math::DegreesToRadians(20)), GetParameterManager());
  1310. m_pFineSearchAngleOffset = new Parameter<kt_double>(
  1311. "FineSearchAngleOffset",
  1312. "The range of angles to search during a fine search.",
  1313. math::DegreesToRadians(0.2), GetParameterManager());
  1314. m_pCoarseSearchAngleOffset = new Parameter<kt_double>(
  1315. "CoarseSearchAngleOffset",
  1316. "The range of angles to search during a coarse search.",
  1317. math::DegreesToRadians(20), GetParameterManager());
  1318. m_pCoarseAngleResolution = new Parameter<kt_double>(
  1319. "CoarseAngleResolution",
  1320. "Resolution of angles to search during a coarse search.",
  1321. math::DegreesToRadians(2), GetParameterManager());
  1322. m_pMinimumAnglePenalty = new Parameter<kt_double>(
  1323. "MinimumAnglePenalty",
  1324. "Minimum value of the angle penalty multiplier so scores do not become "
  1325. "too small.",
  1326. 0.9, GetParameterManager());
  1327. m_pMinimumDistancePenalty = new Parameter<kt_double>(
  1328. "MinimumDistancePenalty",
  1329. "Minimum value of the distance penalty multiplier so scores do not "
  1330. "become too small.",
  1331. 0.5, GetParameterManager());
  1332. m_pUseResponseExpansion = new Parameter<kt_bool>(
  1333. "UseResponseExpansion",
  1334. "Whether to increase the search space if no good matches are initially "
  1335. "found.",
  1336. false, GetParameterManager());
  1337. }
  1338. /* Adding in getters and setters here for easy parameter access */
  1339. // General Parameters
  1340. bool Mapper::getParamUseScanMatching()
  1341. {
  1342. return static_cast<bool>(m_pUseScanMatching->GetValue());
  1343. }
  1344. bool Mapper::getParamUseScanBarycenter()
  1345. {
  1346. return static_cast<bool>(m_pUseScanBarycenter->GetValue());
  1347. }
  1348. double Mapper::getParamMinimumTimeInterval()
  1349. {
  1350. return static_cast<double>(m_pMinimumTimeInterval->GetValue());
  1351. }
  1352. double Mapper::getParamMinimumTravelDistance()
  1353. {
  1354. return static_cast<double>(m_pMinimumTravelDistance->GetValue());
  1355. }
  1356. double Mapper::getParamMinimumTravelHeading()
  1357. {
  1358. return math::RadiansToDegrees(static_cast<double>(m_pMinimumTravelHeading->GetValue()));
  1359. }
  1360. int Mapper::getParamScanBufferSize()
  1361. {
  1362. return static_cast<int>(m_pScanBufferSize->GetValue());
  1363. }
  1364. double Mapper::getParamScanBufferMaximumScanDistance()
  1365. {
  1366. return static_cast<double>(m_pScanBufferMaximumScanDistance->GetValue());
  1367. }
  1368. double Mapper::getParamLinkMatchMinimumResponseFine()
  1369. {
  1370. return static_cast<double>(m_pLinkMatchMinimumResponseFine->GetValue());
  1371. }
  1372. double Mapper::getParamLinkScanMaximumDistance()
  1373. {
  1374. return static_cast<double>(m_pLinkScanMaximumDistance->GetValue());
  1375. }
  1376. double Mapper::getParamLoopSearchMaximumDistance()
  1377. {
  1378. return static_cast<double>(m_pLoopSearchMaximumDistance->GetValue());
  1379. }
  1380. bool Mapper::getParamDoLoopClosing()
  1381. {
  1382. return static_cast<bool>(m_pDoLoopClosing->GetValue());
  1383. }
  1384. int Mapper::getParamLoopMatchMinimumChainSize()
  1385. {
  1386. return static_cast<int>(m_pLoopMatchMinimumChainSize->GetValue());
  1387. }
  1388. double Mapper::getParamLoopMatchMaximumVarianceCoarse()
  1389. {
  1390. return static_cast<double>(std::sqrt(m_pLoopMatchMaximumVarianceCoarse->GetValue()));
  1391. }
  1392. double Mapper::getParamLoopMatchMinimumResponseCoarse()
  1393. {
  1394. return static_cast<double>(m_pLoopMatchMinimumResponseCoarse->GetValue());
  1395. }
  1396. double Mapper::getParamLoopMatchMinimumResponseFine()
  1397. {
  1398. return static_cast<double>(m_pLoopMatchMinimumResponseFine->GetValue());
  1399. }
  1400. // Correlation Parameters - Correlation Parameters
  1401. double Mapper::getParamCorrelationSearchSpaceDimension()
  1402. {
  1403. return static_cast<double>(m_pCorrelationSearchSpaceDimension->GetValue());
  1404. }
  1405. double Mapper::getParamCorrelationSearchSpaceResolution()
  1406. {
  1407. return static_cast<double>(m_pCorrelationSearchSpaceResolution->GetValue());
  1408. }
  1409. double Mapper::getParamCorrelationSearchSpaceSmearDeviation()
  1410. {
  1411. return static_cast<double>(m_pCorrelationSearchSpaceSmearDeviation->GetValue());
  1412. }
  1413. // Correlation Parameters - Loop Correlation Parameters
  1414. double Mapper::getParamLoopSearchSpaceDimension()
  1415. {
  1416. return static_cast<double>(m_pLoopSearchSpaceDimension->GetValue());
  1417. }
  1418. double Mapper::getParamLoopSearchSpaceResolution()
  1419. {
  1420. return static_cast<double>(m_pLoopSearchSpaceResolution->GetValue());
  1421. }
  1422. double Mapper::getParamLoopSearchSpaceSmearDeviation()
  1423. {
  1424. return static_cast<double>(m_pLoopSearchSpaceSmearDeviation->GetValue());
  1425. }
  1426. // ScanMatcher Parameters
  1427. double Mapper::getParamDistanceVariancePenalty()
  1428. {
  1429. return std::sqrt(static_cast<double>(m_pDistanceVariancePenalty->GetValue()));
  1430. }
  1431. double Mapper::getParamAngleVariancePenalty()
  1432. {
  1433. return std::sqrt(static_cast<double>(m_pAngleVariancePenalty->GetValue()));
  1434. }
  1435. double Mapper::getParamFineSearchAngleOffset()
  1436. {
  1437. return static_cast<double>(m_pFineSearchAngleOffset->GetValue());
  1438. }
  1439. double Mapper::getParamCoarseSearchAngleOffset()
  1440. {
  1441. return static_cast<double>(m_pCoarseSearchAngleOffset->GetValue());
  1442. }
  1443. double Mapper::getParamCoarseAngleResolution()
  1444. {
  1445. return static_cast<double>(m_pCoarseAngleResolution->GetValue());
  1446. }
  1447. double Mapper::getParamMinimumAnglePenalty()
  1448. {
  1449. return static_cast<double>(m_pMinimumAnglePenalty->GetValue());
  1450. }
  1451. double Mapper::getParamMinimumDistancePenalty()
  1452. {
  1453. return static_cast<double>(m_pMinimumDistancePenalty->GetValue());
  1454. }
  1455. bool Mapper::getParamUseResponseExpansion()
  1456. {
  1457. return static_cast<bool>(m_pUseResponseExpansion->GetValue());
  1458. }
  1459. /* Setters for parameters */
  1460. // General Parameters
  1461. void Mapper::setParamUseScanMatching(bool b)
  1462. {
  1463. m_pUseScanMatching->SetValue((kt_bool)b);
  1464. }
  1465. void Mapper::setParamUseScanBarycenter(bool b)
  1466. {
  1467. m_pUseScanBarycenter->SetValue((kt_bool)b);
  1468. }
  1469. void Mapper::setParamMinimumTimeInterval(double d)
  1470. {
  1471. m_pMinimumTimeInterval->SetValue((kt_double)d);
  1472. }
  1473. void Mapper::setParamMinimumTravelDistance(double d)
  1474. {
  1475. m_pMinimumTravelDistance->SetValue((kt_double)d);
  1476. }
  1477. void Mapper::setParamMinimumTravelHeading(double d)
  1478. {
  1479. m_pMinimumTravelHeading->SetValue((kt_double)d);
  1480. }
  1481. void Mapper::setParamScanBufferSize(int i)
  1482. {
  1483. m_pScanBufferSize->SetValue((kt_int32u)i);
  1484. }
  1485. void Mapper::setParamScanBufferMaximumScanDistance(double d)
  1486. {
  1487. m_pScanBufferMaximumScanDistance->SetValue((kt_double)d);
  1488. }
  1489. void Mapper::setParamLinkMatchMinimumResponseFine(double d)
  1490. {
  1491. m_pLinkMatchMinimumResponseFine->SetValue((kt_double)d);
  1492. }
  1493. void Mapper::setParamLinkScanMaximumDistance(double d)
  1494. {
  1495. m_pLinkScanMaximumDistance->SetValue((kt_double)d);
  1496. }
  1497. void Mapper::setParamLoopSearchMaximumDistance(double d)
  1498. {
  1499. m_pLoopSearchMaximumDistance->SetValue((kt_double)d);
  1500. }
  1501. void Mapper::setParamDoLoopClosing(bool b)
  1502. {
  1503. m_pDoLoopClosing->SetValue((kt_bool)b);
  1504. }
  1505. void Mapper::setParamLoopMatchMinimumChainSize(int i)
  1506. {
  1507. m_pLoopMatchMinimumChainSize->SetValue((kt_int32u)i);
  1508. }
  1509. void Mapper::setParamLoopMatchMaximumVarianceCoarse(double d)
  1510. {
  1511. m_pLoopMatchMaximumVarianceCoarse->SetValue((kt_double)math::Square(d));
  1512. }
  1513. void Mapper::setParamLoopMatchMinimumResponseCoarse(double d)
  1514. {
  1515. m_pLoopMatchMinimumResponseCoarse->SetValue((kt_double)d);
  1516. }
  1517. void Mapper::setParamLoopMatchMinimumResponseFine(double d)
  1518. {
  1519. m_pLoopMatchMinimumResponseFine->SetValue((kt_double)d);
  1520. }
  1521. // Correlation Parameters - Correlation Parameters
  1522. void Mapper::setParamCorrelationSearchSpaceDimension(double d)
  1523. {
  1524. m_pCorrelationSearchSpaceDimension->SetValue((kt_double)d);
  1525. }
  1526. void Mapper::setParamCorrelationSearchSpaceResolution(double d)
  1527. {
  1528. m_pCorrelationSearchSpaceResolution->SetValue((kt_double)d);
  1529. }
  1530. void Mapper::setParamCorrelationSearchSpaceSmearDeviation(double d)
  1531. {
  1532. m_pCorrelationSearchSpaceSmearDeviation->SetValue((kt_double)d);
  1533. }
  1534. // Correlation Parameters - Loop Closure Parameters
  1535. void Mapper::setParamLoopSearchSpaceDimension(double d)
  1536. {
  1537. m_pLoopSearchSpaceDimension->SetValue((kt_double)d);
  1538. }
  1539. void Mapper::setParamLoopSearchSpaceResolution(double d)
  1540. {
  1541. m_pLoopSearchSpaceResolution->SetValue((kt_double)d);
  1542. }
  1543. void Mapper::setParamLoopSearchSpaceSmearDeviation(double d)
  1544. {
  1545. m_pLoopSearchSpaceSmearDeviation->SetValue((kt_double)d);
  1546. }
  1547. // Scan Matcher Parameters
  1548. void Mapper::setParamDistanceVariancePenalty(double d)
  1549. {
  1550. m_pDistanceVariancePenalty->SetValue((kt_double)math::Square(d));
  1551. }
  1552. void Mapper::setParamAngleVariancePenalty(double d)
  1553. {
  1554. m_pAngleVariancePenalty->SetValue((kt_double)math::Square(d));
  1555. }
  1556. void Mapper::setParamFineSearchAngleOffset(double d)
  1557. {
  1558. m_pFineSearchAngleOffset->SetValue((kt_double)d);
  1559. }
  1560. void Mapper::setParamCoarseSearchAngleOffset(double d)
  1561. {
  1562. m_pCoarseSearchAngleOffset->SetValue((kt_double)d);
  1563. }
  1564. void Mapper::setParamCoarseAngleResolution(double d)
  1565. {
  1566. m_pCoarseAngleResolution->SetValue((kt_double)d);
  1567. }
  1568. void Mapper::setParamMinimumAnglePenalty(double d)
  1569. {
  1570. m_pMinimumAnglePenalty->SetValue((kt_double)d);
  1571. }
  1572. void Mapper::setParamMinimumDistancePenalty(double d)
  1573. {
  1574. m_pMinimumDistancePenalty->SetValue((kt_double)d);
  1575. }
  1576. void Mapper::setParamUseResponseExpansion(bool b)
  1577. {
  1578. m_pUseResponseExpansion->SetValue((kt_bool)b);
  1579. }
  1580. void Mapper::Initialize(kt_double rangeThreshold)
  1581. {
  1582. if (m_Initialized == false)
  1583. {
  1584. // create sequential scan and loop matcher
  1585. m_pSequentialScanMatcher = ScanMatcher::Create(this,
  1586. m_pCorrelationSearchSpaceDimension->GetValue(),
  1587. m_pCorrelationSearchSpaceResolution->GetValue(),
  1588. m_pCorrelationSearchSpaceSmearDeviation->GetValue(),
  1589. rangeThreshold);
  1590. assert(m_pSequentialScanMatcher);
  1591. m_pMapperSensorManager = new MapperSensorManager(m_pScanBufferSize->GetValue(),
  1592. m_pScanBufferMaximumScanDistance->GetValue());
  1593. m_pGraph = new MapperGraph(this, rangeThreshold);
  1594. m_Initialized = true;
  1595. }
  1596. }
  1597. void Mapper::Reset()
  1598. {
  1599. delete m_pSequentialScanMatcher;
  1600. m_pSequentialScanMatcher = NULL;
  1601. delete m_pGraph;
  1602. m_pGraph = NULL;
  1603. delete m_pMapperSensorManager;
  1604. m_pMapperSensorManager = NULL;
  1605. m_Initialized = false;
  1606. }
  1607. kt_bool Mapper::Process(Object * /*pObject*/)
  1608. {
  1609. return true;
  1610. }
  1611. kt_bool Mapper::Process(LocalizedRangeScan *pScan)
  1612. {
  1613. if (pScan != NULL)
  1614. {
  1615. karto::LaserRangeFinder *pLaserRangeFinder = pScan->GetLaserRangeFinder();
  1616. // validate scan
  1617. if (pLaserRangeFinder == NULL || pScan == NULL || pLaserRangeFinder->Validate(pScan) == false)
  1618. {
  1619. // std::cout << "validate scan false !!" << std::endl;
  1620. return false;
  1621. }
  1622. if (m_Initialized == false)
  1623. {
  1624. // initialize mapper with range threshold from device
  1625. Initialize(pLaserRangeFinder->GetRangeThreshold());
  1626. }
  1627. // get last scan
  1628. LocalizedRangeScan *pLastScan = m_pMapperSensorManager->GetLastScan(pScan->GetSensorName());
  1629. // update scans corrected pose based on last correction
  1630. if (pLastScan != NULL)
  1631. {
  1632. Transform lastTransform(pLastScan->GetOdometricPose(), pLastScan->GetCorrectedPose());
  1633. pScan->SetCorrectedPose(lastTransform.TransformPose(pScan->GetOdometricPose()));
  1634. }
  1635. // test if scan is outside minimum boundary or if heading is larger then minimum heading
  1636. if (!HasMovedEnough(pScan, pLastScan))
  1637. {
  1638. // std::cout << "!HasMovedEnough !! return false" << std::endl;
  1639. return false;
  1640. }
  1641. Matrix3 covariance;
  1642. covariance.SetToIdentity();
  1643. // correct scan (if not first scan)
  1644. if (m_pUseScanMatching->GetValue() && pLastScan != NULL)
  1645. {
  1646. Pose2 bestPose;
  1647. m_pSequentialScanMatcher->MatchScan(pScan,
  1648. m_pMapperSensorManager->GetRunningScans(pScan->GetSensorName()),
  1649. bestPose,
  1650. covariance);
  1651. pScan->SetSensorPose(bestPose);
  1652. }
  1653. // add scan to buffer and assign id
  1654. m_pMapperSensorManager->AddScan(pScan);
  1655. if (m_pUseScanMatching->GetValue())
  1656. {
  1657. // add to graph
  1658. m_pGraph->AddVertex(pScan);
  1659. m_pGraph->AddEdges(pScan, covariance);
  1660. m_pMapperSensorManager->AddRunningScan(pScan);
  1661. if (m_pDoLoopClosing->GetValue())
  1662. {
  1663. std::vector<Name> deviceNames = m_pMapperSensorManager->GetSensorNames();
  1664. const_forEach(std::vector<Name>, &deviceNames)
  1665. {
  1666. m_pGraph->TryCloseLoop(pScan, *iter);
  1667. }
  1668. }
  1669. }
  1670. m_pMapperSensorManager->SetLastScan(pScan);
  1671. return true;
  1672. }
  1673. return false;
  1674. }
  1675. /**
  1676. * Is the scan sufficiently far from the last scan?
  1677. * @param pScan
  1678. * @param pLastScan
  1679. * @return true if the scans are sufficiently far
  1680. */
  1681. kt_bool Mapper::HasMovedEnough(LocalizedRangeScan *pScan, LocalizedRangeScan *pLastScan) const
  1682. {
  1683. // test if first scan
  1684. if (pLastScan == NULL)
  1685. {
  1686. return true;
  1687. }
  1688. // test if enough time has passed
  1689. kt_double timeInterval = pScan->GetTime() - pLastScan->GetTime();
  1690. if (timeInterval >= m_pMinimumTimeInterval->GetValue())
  1691. {
  1692. return true;
  1693. }
  1694. Pose2 lastScannerPose = pLastScan->GetSensorAt(pLastScan->GetOdometricPose());
  1695. Pose2 scannerPose = pScan->GetSensorAt(pScan->GetOdometricPose());
  1696. // test if we have turned enough
  1697. kt_double deltaHeading = math::NormalizeAngle(scannerPose.GetHeading() - lastScannerPose.GetHeading());
  1698. if (fabs(deltaHeading) >= m_pMinimumTravelHeading->GetValue())
  1699. {
  1700. return true;
  1701. }
  1702. // test if we have moved enough
  1703. kt_double squaredTravelDistance = lastScannerPose.GetPosition().SquaredDistance(scannerPose.GetPosition());
  1704. if (squaredTravelDistance >= math::Square(m_pMinimumTravelDistance->GetValue()) - KT_TOLERANCE)
  1705. {
  1706. return true;
  1707. }
  1708. // std::cout << " deltaHeading = " << deltaHeading << std::endl;
  1709. // std::cout << "squaredTravelDistance = " << squaredTravelDistance << std::endl;
  1710. return false;
  1711. }
  1712. /**
  1713. * Gets all the processed scans
  1714. * @return all scans
  1715. */
  1716. const LocalizedRangeScanVector Mapper::GetAllProcessedScans() const
  1717. {
  1718. LocalizedRangeScanVector allScans;
  1719. if (m_pMapperSensorManager != NULL)
  1720. {
  1721. allScans = m_pMapperSensorManager->GetAllScans();
  1722. }
  1723. return allScans;
  1724. }
  1725. /**
  1726. * Adds a listener
  1727. * @param pListener
  1728. */
  1729. void Mapper::AddListener(MapperListener *pListener)
  1730. {
  1731. m_Listeners.push_back(pListener);
  1732. }
  1733. /**
  1734. * Removes a listener
  1735. * @param pListener
  1736. */
  1737. void Mapper::RemoveListener(MapperListener *pListener)
  1738. {
  1739. std::vector<MapperListener *>::iterator iter = std::find(m_Listeners.begin(), m_Listeners.end(), pListener);
  1740. if (iter != m_Listeners.end())
  1741. {
  1742. m_Listeners.erase(iter);
  1743. }
  1744. }
  1745. void Mapper::FireInfo(const std::string &rInfo) const
  1746. {
  1747. const_forEach(std::vector<MapperListener *>, &m_Listeners)
  1748. {
  1749. (*iter)->Info(rInfo);
  1750. }
  1751. }
  1752. void Mapper::FireDebug(const std::string &rInfo) const
  1753. {
  1754. const_forEach(std::vector<MapperListener *>, &m_Listeners)
  1755. {
  1756. MapperDebugListener *pListener = dynamic_cast<MapperDebugListener *>(*iter);
  1757. if (pListener != NULL)
  1758. {
  1759. pListener->Debug(rInfo);
  1760. }
  1761. }
  1762. }
  1763. void Mapper::FireLoopClosureCheck(const std::string &rInfo) const
  1764. {
  1765. const_forEach(std::vector<MapperListener *>, &m_Listeners)
  1766. {
  1767. MapperLoopClosureListener *pListener = dynamic_cast<MapperLoopClosureListener *>(*iter);
  1768. if (pListener != NULL)
  1769. {
  1770. pListener->LoopClosureCheck(rInfo);
  1771. }
  1772. }
  1773. }
  1774. void Mapper::FireBeginLoopClosure(const std::string &rInfo) const
  1775. {
  1776. const_forEach(std::vector<MapperListener *>, &m_Listeners)
  1777. {
  1778. MapperLoopClosureListener *pListener = dynamic_cast<MapperLoopClosureListener *>(*iter);
  1779. if (pListener != NULL)
  1780. {
  1781. pListener->BeginLoopClosure(rInfo);
  1782. }
  1783. }
  1784. }
  1785. void Mapper::FireEndLoopClosure(const std::string &rInfo) const
  1786. {
  1787. const_forEach(std::vector<MapperListener *>, &m_Listeners)
  1788. {
  1789. MapperLoopClosureListener *pListener = dynamic_cast<MapperLoopClosureListener *>(*iter);
  1790. if (pListener != NULL)
  1791. {
  1792. pListener->EndLoopClosure(rInfo);
  1793. }
  1794. }
  1795. }
  1796. void Mapper::SetScanSolver(ScanSolver *pScanOptimizer)
  1797. {
  1798. m_pScanOptimizer = pScanOptimizer;
  1799. }
  1800. MapperGraph *Mapper::GetGraph() const
  1801. {
  1802. return m_pGraph;
  1803. }
  1804. ScanMatcher *Mapper::GetSequentialScanMatcher() const
  1805. {
  1806. return m_pSequentialScanMatcher;
  1807. }
  1808. ScanMatcher *Mapper::GetLoopScanMatcher() const
  1809. {
  1810. return m_pGraph->GetLoopScanMatcher();
  1811. }
  1812. } // namespace karto