12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485868788899091929394959697989910010110210310410510610710810911011111211311411511611711811912012112212312412512612712812913013113213313413513613713813914014114214314414514614714814915015115215315415515615715815916016116216316416516616716816917017117217317417517617717817918018118218318418518618718818919019119219319419519619719819920020120220320420520620720820921021121221321421521621721821922022122222322422522622722822923023123223323423523623723823924024124224324424524624724824925025125225325425525625725825926026126226326426526626726826927027127227327427527627727827928028128228328428528628728828929029129229329429529629729829930030130230330430530630730830931031131231331431531631731831932032132232332432532632732832933033133233333433533633733833934034134234334434534634734834935035135235335435535635735835936036136236336436536636736836937037137237337437537637737837938038138238338438538638738838939039139239339439539639739839940040140240340440540640740840941041141241341441541641741841942042142242342442542642742842943043143243343443543643743843944044144244344444544644744844945045145245345445545645745845946046146246346446546646746846947047147247347447547647747847948048148248348448548648748848949049149249349449549649749849950050150250350450550650750850951051151251351451551651751851952052152252352452552652752852953053153253353453553653753853954054154254354454554654754854955055155255355455555655755855956056156256356456556656756856957057157257357457557657757857958058158258358458558658758858959059159259359459559659759859960060160260360460560660760860961061161261361461561661761861962062162262362462562662762862963063163263363463563663763863964064164264364464564664764864965065165265365465565665765865966066166266366466566666766866967067167267367467567667767867968068168268368468568668768868969069169269369469569669769869970070170270370470570670770870971071171271371471571671771871972072172272372472572672772872973073173273373473573673773873974074174274374474574674774874975075175275375475575675775875976076176276376476576676776876977077177277377477577677777877978078178278378478578678778878979079179279379479579679779879980080180280380480580680780880981081181281381481581681781881982082182282382482582682782882983083183283383483583683783883984084184284384484584684784884985085185285385485585685785885986086186286386486586686786886987087187287387487587687787887988088188288388488588688788888989089189289389489589689789889990090190290390490590690790890991091191291391491591691791891992092192292392492592692792892993093193293393493593693793893994094194294394494594694794894995095195295395495595695795895996096196296396496596696796896997097197297397497597697797897998098198298398498598698798898999099199299399499599699799899910001001100210031004100510061007100810091010101110121013101410151016101710181019102010211022102310241025102610271028102910301031103210331034103510361037103810391040104110421043104410451046104710481049105010511052105310541055105610571058105910601061106210631064106510661067106810691070107110721073107410751076107710781079108010811082108310841085108610871088108910901091109210931094109510961097109810991100110111021103110411051106110711081109111011111112111311141115111611171118111911201121112211231124112511261127112811291130113111321133113411351136113711381139114011411142114311441145114611471148114911501151115211531154115511561157115811591160116111621163116411651166116711681169117011711172117311741175117611771178117911801181118211831184118511861187118811891190119111921193119411951196119711981199120012011202120312041205120612071208120912101211121212131214121512161217121812191220122112221223122412251226122712281229123012311232123312341235123612371238123912401241124212431244124512461247124812491250125112521253125412551256125712581259126012611262126312641265126612671268126912701271127212731274127512761277127812791280128112821283128412851286128712881289129012911292129312941295129612971298129913001301130213031304130513061307130813091310131113121313131413151316131713181319132013211322132313241325132613271328132913301331133213331334133513361337133813391340134113421343134413451346134713481349135013511352135313541355135613571358135913601361136213631364136513661367136813691370137113721373137413751376137713781379138013811382138313841385138613871388138913901391139213931394139513961397139813991400140114021403140414051406140714081409141014111412141314141415141614171418141914201421142214231424142514261427142814291430143114321433143414351436143714381439144014411442144314441445144614471448144914501451145214531454145514561457145814591460146114621463146414651466146714681469147014711472147314741475147614771478147914801481148214831484148514861487148814891490149114921493149414951496149714981499150015011502150315041505150615071508150915101511151215131514151515161517151815191520152115221523152415251526152715281529153015311532153315341535153615371538153915401541154215431544154515461547154815491550155115521553155415551556155715581559156015611562156315641565156615671568156915701571157215731574157515761577157815791580158115821583158415851586158715881589159015911592159315941595159615971598159916001601160216031604160516061607160816091610161116121613161416151616161716181619162016211622162316241625162616271628162916301631163216331634163516361637163816391640164116421643164416451646164716481649165016511652165316541655165616571658165916601661166216631664166516661667166816691670167116721673167416751676167716781679168016811682168316841685168616871688168916901691169216931694169516961697169816991700170117021703170417051706170717081709171017111712171317141715171617171718171917201721172217231724172517261727172817291730173117321733173417351736173717381739174017411742174317441745174617471748174917501751175217531754175517561757175817591760176117621763176417651766176717681769177017711772177317741775177617771778177917801781178217831784178517861787178817891790179117921793179417951796179717981799180018011802180318041805180618071808180918101811181218131814181518161817181818191820182118221823182418251826182718281829183018311832183318341835183618371838183918401841184218431844184518461847184818491850185118521853185418551856185718581859186018611862186318641865186618671868186918701871187218731874187518761877187818791880188118821883188418851886188718881889189018911892189318941895189618971898189919001901190219031904190519061907190819091910191119121913191419151916191719181919192019211922192319241925192619271928192919301931193219331934193519361937193819391940194119421943194419451946194719481949195019511952195319541955195619571958195919601961196219631964196519661967196819691970197119721973197419751976197719781979198019811982198319841985198619871988198919901991199219931994199519961997199819992000200120022003200420052006200720082009201020112012201320142015201620172018201920202021202220232024202520262027202820292030203120322033203420352036203720382039204020412042204320442045204620472048204920502051205220532054205520562057205820592060206120622063206420652066206720682069207020712072207320742075207620772078207920802081208220832084208520862087208820892090209120922093209420952096209720982099210021012102210321042105210621072108210921102111211221132114211521162117211821192120212121222123212421252126212721282129213021312132213321342135213621372138213921402141214221432144214521462147214821492150215121522153215421552156215721582159216021612162216321642165216621672168216921702171217221732174217521762177217821792180218121822183218421852186218721882189219021912192219321942195219621972198219922002201220222032204220522062207220822092210221122122213221422152216221722182219222022212222222322242225222622272228222922302231223222332234223522362237223822392240224122422243224422452246224722482249225022512252225322542255225622572258225922602261226222632264226522662267226822692270227122722273227422752276227722782279228022812282228322842285228622872288228922902291229222932294229522962297229822992300230123022303230423052306230723082309231023112312231323142315231623172318231923202321232223232324232523262327232823292330233123322333233423352336233723382339234023412342234323442345234623472348234923502351235223532354235523562357235823592360236123622363236423652366236723682369237023712372237323742375237623772378237923802381238223832384238523862387238823892390239123922393239423952396239723982399240024012402240324042405240624072408240924102411241224132414241524162417241824192420242124222423242424252426242724282429243024312432243324342435243624372438243924402441244224432444244524462447244824492450245124522453245424552456245724582459246024612462246324642465246624672468246924702471247224732474247524762477247824792480248124822483248424852486248724882489249024912492249324942495249624972498249925002501250225032504250525062507250825092510251125122513251425152516251725182519252025212522252325242525252625272528252925302531253225332534253525362537253825392540254125422543254425452546254725482549255025512552255325542555255625572558255925602561256225632564256525662567256825692570257125722573257425752576257725782579258025812582258325842585258625872588258925902591259225932594259525962597259825992600260126022603260426052606260726082609261026112612261326142615261626172618261926202621262226232624262526262627262826292630263126322633263426352636263726382639264026412642264326442645264626472648264926502651265226532654265526562657265826592660266126622663266426652666266726682669267026712672267326742675267626772678267926802681268226832684268526862687268826892690269126922693269426952696269726982699270027012702270327042705270627072708270927102711271227132714271527162717271827192720272127222723272427252726272727282729273027312732273327342735273627372738273927402741274227432744274527462747274827492750275127522753275427552756275727582759276027612762276327642765276627672768276927702771277227732774277527762777277827792780278127822783278427852786278727882789279027912792279327942795279627972798279928002801280228032804280528062807280828092810281128122813281428152816281728182819282028212822282328242825282628272828282928302831283228332834283528362837283828392840284128422843284428452846284728482849285028512852285328542855285628572858285928602861286228632864286528662867286828692870287128722873287428752876287728782879288028812882288328842885288628872888288928902891289228932894289528962897289828992900290129022903290429052906290729082909291029112912291329142915291629172918291929202921292229232924292529262927292829292930293129322933293429352936293729382939294029412942294329442945294629472948294929502951295229532954295529562957295829592960296129622963296429652966296729682969297029712972297329742975297629772978297929802981298229832984298529862987298829892990299129922993299429952996299729982999300030013002300330043005300630073008300930103011301230133014301530163017301830193020302130223023302430253026302730283029303030313032303330343035303630373038303930403041304230433044304530463047304830493050305130523053305430553056305730583059306030613062306330643065306630673068306930703071307230733074307530763077307830793080308130823083308430853086308730883089309030913092309330943095309630973098309931003101310231033104310531063107310831093110311131123113311431153116311731183119312031213122312331243125312631273128312931303131313231333134313531363137313831393140314131423143314431453146314731483149315031513152315331543155315631573158315931603161316231633164316531663167316831693170317131723173317431753176317731783179318031813182318331843185318631873188318931903191319231933194319531963197319831993200320132023203320432053206320732083209321032113212321332143215321632173218321932203221322232233224322532263227322832293230323132323233323432353236323732383239324032413242324332443245324632473248324932503251325232533254325532563257325832593260326132623263326432653266326732683269327032713272327332743275327632773278327932803281328232833284328532863287328832893290329132923293329432953296329732983299330033013302330333043305330633073308330933103311331233133314331533163317331833193320332133223323332433253326332733283329333033313332333333343335333633373338333933403341334233433344334533463347334833493350335133523353335433553356335733583359336033613362336333643365336633673368336933703371337233733374337533763377337833793380338133823383338433853386338733883389339033913392339333943395339633973398339934003401340234033404340534063407340834093410341134123413341434153416341734183419342034213422342334243425342634273428342934303431343234333434343534363437343834393440344134423443344434453446344734483449345034513452345334543455345634573458345934603461346234633464346534663467346834693470347134723473347434753476347734783479348034813482348334843485348634873488348934903491349234933494349534963497349834993500350135023503350435053506350735083509351035113512351335143515351635173518351935203521352235233524352535263527352835293530353135323533353435353536353735383539354035413542354335443545354635473548354935503551355235533554355535563557355835593560356135623563356435653566356735683569357035713572357335743575357635773578357935803581358235833584358535863587358835893590359135923593359435953596359735983599360036013602360336043605360636073608360936103611361236133614361536163617361836193620362136223623362436253626362736283629363036313632363336343635363636373638363936403641364236433644364536463647364836493650365136523653365436553656365736583659366036613662366336643665366636673668366936703671367236733674367536763677367836793680368136823683368436853686368736883689369036913692369336943695369636973698369937003701370237033704370537063707370837093710371137123713371437153716371737183719372037213722372337243725372637273728372937303731373237333734373537363737373837393740374137423743374437453746374737483749375037513752375337543755375637573758375937603761376237633764376537663767376837693770377137723773377437753776377737783779378037813782378337843785378637873788378937903791379237933794379537963797379837993800380138023803380438053806380738083809381038113812381338143815381638173818381938203821382238233824382538263827382838293830383138323833383438353836383738383839384038413842384338443845384638473848384938503851385238533854385538563857385838593860386138623863386438653866386738683869387038713872387338743875387638773878387938803881388238833884388538863887388838893890389138923893389438953896389738983899390039013902390339043905390639073908390939103911391239133914391539163917391839193920392139223923392439253926392739283929393039313932393339343935393639373938393939403941394239433944394539463947394839493950395139523953395439553956395739583959396039613962396339643965396639673968396939703971397239733974397539763977397839793980398139823983398439853986398739883989399039913992399339943995399639973998399940004001400240034004400540064007400840094010401140124013401440154016401740184019402040214022402340244025402640274028402940304031403240334034403540364037403840394040404140424043404440454046404740484049405040514052405340544055405640574058405940604061406240634064406540664067406840694070407140724073407440754076407740784079408040814082408340844085408640874088408940904091409240934094409540964097409840994100410141024103410441054106410741084109411041114112411341144115411641174118411941204121412241234124412541264127412841294130413141324133413441354136413741384139414041414142414341444145414641474148414941504151415241534154415541564157415841594160416141624163416441654166416741684169417041714172417341744175417641774178417941804181418241834184418541864187418841894190419141924193419441954196419741984199420042014202420342044205420642074208420942104211421242134214421542164217421842194220422142224223422442254226422742284229423042314232423342344235423642374238423942404241424242434244424542464247424842494250425142524253425442554256425742584259426042614262426342644265426642674268426942704271427242734274427542764277427842794280428142824283428442854286428742884289429042914292429342944295429642974298429943004301430243034304430543064307430843094310431143124313431443154316431743184319432043214322432343244325432643274328432943304331433243334334433543364337433843394340434143424343434443454346434743484349435043514352435343544355435643574358435943604361436243634364436543664367436843694370437143724373437443754376437743784379438043814382438343844385438643874388438943904391439243934394439543964397439843994400440144024403440444054406440744084409441044114412441344144415441644174418441944204421442244234424442544264427442844294430443144324433443444354436443744384439444044414442444344444445444644474448444944504451445244534454445544564457445844594460446144624463446444654466446744684469447044714472447344744475447644774478447944804481448244834484448544864487448844894490449144924493449444954496449744984499450045014502450345044505450645074508450945104511451245134514451545164517451845194520452145224523452445254526452745284529453045314532453345344535453645374538453945404541454245434544454545464547454845494550455145524553455445554556455745584559456045614562456345644565456645674568456945704571457245734574457545764577457845794580458145824583458445854586458745884589459045914592459345944595459645974598459946004601460246034604460546064607460846094610461146124613461446154616461746184619462046214622462346244625462646274628462946304631463246334634463546364637463846394640464146424643464446454646464746484649465046514652465346544655465646574658465946604661466246634664466546664667466846694670467146724673467446754676467746784679468046814682468346844685468646874688468946904691469246934694469546964697469846994700470147024703470447054706470747084709471047114712471347144715471647174718471947204721472247234724472547264727472847294730473147324733473447354736473747384739474047414742474347444745474647474748474947504751475247534754475547564757475847594760476147624763476447654766476747684769477047714772477347744775477647774778477947804781478247834784478547864787478847894790479147924793479447954796479747984799480048014802480348044805480648074808480948104811481248134814481548164817481848194820482148224823482448254826482748284829483048314832483348344835483648374838483948404841484248434844484548464847484848494850485148524853485448554856485748584859486048614862486348644865486648674868486948704871487248734874487548764877487848794880488148824883488448854886488748884889489048914892489348944895489648974898489949004901490249034904490549064907490849094910491149124913491449154916491749184919492049214922492349244925492649274928492949304931493249334934493549364937493849394940494149424943494449454946494749484949495049514952495349544955495649574958495949604961496249634964496549664967496849694970497149724973497449754976497749784979498049814982498349844985498649874988498949904991499249934994499549964997499849995000500150025003500450055006500750085009501050115012501350145015501650175018501950205021502250235024502550265027502850295030503150325033503450355036503750385039504050415042504350445045504650475048504950505051505250535054505550565057505850595060506150625063506450655066506750685069507050715072507350745075507650775078507950805081508250835084508550865087508850895090509150925093509450955096509750985099510051015102510351045105510651075108510951105111511251135114511551165117511851195120512151225123512451255126512751285129513051315132513351345135513651375138513951405141514251435144514551465147514851495150515151525153515451555156515751585159516051615162516351645165516651675168516951705171517251735174517551765177517851795180518151825183518451855186518751885189519051915192519351945195519651975198519952005201520252035204520552065207520852095210521152125213521452155216521752185219522052215222522352245225522652275228522952305231523252335234523552365237523852395240524152425243524452455246524752485249525052515252525352545255525652575258525952605261526252635264526552665267526852695270527152725273527452755276527752785279528052815282528352845285528652875288528952905291529252935294529552965297529852995300530153025303530453055306530753085309531053115312531353145315531653175318531953205321532253235324532553265327532853295330533153325333533453355336533753385339534053415342534353445345534653475348534953505351535253535354535553565357535853595360536153625363536453655366536753685369537053715372537353745375537653775378537953805381538253835384538553865387538853895390539153925393539453955396539753985399540054015402540354045405540654075408540954105411541254135414541554165417541854195420542154225423542454255426542754285429543054315432543354345435543654375438543954405441544254435444544554465447544854495450545154525453545454555456545754585459546054615462546354645465546654675468546954705471547254735474547554765477547854795480548154825483548454855486548754885489549054915492549354945495549654975498549955005501550255035504550555065507550855095510551155125513551455155516551755185519552055215522552355245525552655275528552955305531553255335534553555365537553855395540554155425543554455455546554755485549555055515552555355545555555655575558555955605561556255635564556555665567556855695570557155725573557455755576557755785579558055815582558355845585558655875588558955905591559255935594559555965597559855995600560156025603560456055606560756085609561056115612561356145615561656175618561956205621562256235624562556265627562856295630563156325633563456355636563756385639564056415642564356445645564656475648564956505651565256535654565556565657565856595660566156625663566456655666566756685669567056715672567356745675567656775678567956805681568256835684568556865687568856895690569156925693569456955696569756985699570057015702570357045705570657075708570957105711571257135714571557165717571857195720572157225723572457255726572757285729573057315732573357345735573657375738573957405741574257435744574557465747574857495750575157525753575457555756575757585759576057615762576357645765576657675768576957705771577257735774577557765777577857795780578157825783578457855786578757885789579057915792579357945795579657975798579958005801580258035804580558065807580858095810581158125813581458155816581758185819582058215822582358245825582658275828582958305831583258335834583558365837583858395840584158425843584458455846584758485849585058515852585358545855585658575858585958605861586258635864586558665867586858695870587158725873587458755876587758785879588058815882588358845885588658875888588958905891589258935894589558965897589858995900590159025903590459055906590759085909591059115912591359145915591659175918591959205921592259235924592559265927592859295930593159325933593459355936593759385939594059415942594359445945594659475948594959505951595259535954595559565957595859595960596159625963596459655966596759685969597059715972597359745975597659775978597959805981598259835984598559865987598859895990599159925993599459955996599759985999600060016002600360046005600660076008600960106011601260136014601560166017601860196020602160226023602460256026602760286029603060316032603360346035603660376038603960406041604260436044604560466047604860496050605160526053605460556056605760586059606060616062606360646065606660676068606960706071607260736074607560766077607860796080608160826083608460856086608760886089609060916092609360946095609660976098609961006101610261036104610561066107610861096110611161126113611461156116611761186119612061216122612361246125612661276128612961306131613261336134613561366137613861396140614161426143614461456146614761486149615061516152615361546155615661576158615961606161616261636164616561666167616861696170617161726173617461756176617761786179618061816182618361846185618661876188618961906191619261936194619561966197619861996200620162026203620462056206620762086209621062116212621362146215621662176218621962206221622262236224622562266227622862296230623162326233623462356236623762386239624062416242624362446245624662476248624962506251625262536254625562566257625862596260626162626263626462656266626762686269627062716272627362746275627662776278627962806281628262836284628562866287628862896290629162926293629462956296629762986299630063016302630363046305630663076308630963106311631263136314631563166317631863196320632163226323632463256326632763286329633063316332633363346335633663376338633963406341634263436344634563466347634863496350635163526353635463556356635763586359636063616362636363646365636663676368636963706371637263736374637563766377637863796380638163826383638463856386638763886389639063916392639363946395639663976398639964006401640264036404640564066407640864096410641164126413641464156416641764186419642064216422642364246425642664276428642964306431643264336434643564366437643864396440644164426443644464456446644764486449645064516452645364546455645664576458645964606461646264636464646564666467646864696470647164726473647464756476647764786479648064816482648364846485648664876488648964906491649264936494649564966497649864996500650165026503650465056506650765086509651065116512651365146515651665176518651965206521652265236524652565266527652865296530653165326533653465356536653765386539654065416542654365446545654665476548654965506551655265536554655565566557655865596560656165626563656465656566656765686569657065716572657365746575657665776578657965806581658265836584658565866587658865896590659165926593659465956596659765986599660066016602660366046605660666076608660966106611661266136614661566166617661866196620662166226623662466256626662766286629663066316632663366346635663666376638 |
- /*
- * Copyright 2010 SRI International
- *
- * This program is free software: you can redistribute it and/or modify
- * it under the terms of the GNU Lesser General Public License as published by
- * the Free Software Foundation, either version 3 of the License, or
- * (at your option) any later version.
- *
- * This program is distributed in the hope that it will be useful,
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
- * GNU Lesser General Public License for more details.
- *
- * You should have received a copy of the GNU Lesser General Public License
- * along with this program. If not, see <http://www.gnu.org/licenses/>.
- */
- #ifndef OPEN_KARTO_KARTO_H
- #define OPEN_KARTO_KARTO_H
- #include <string>
- #include <fstream>
- #include <limits>
- #include <algorithm>
- #include <map>
- #include <vector>
- #include <iostream>
- #include <iomanip>
- #include <sstream>
- #include <stdexcept>
- #include <math.h>
- #include <float.h>
- #include <stdio.h>
- #include <assert.h>
- #include <string.h>
- #include <boost/thread.hpp>
- #ifdef USE_POCO
- #include <Poco/Mutex.h>
- #endif
- #include <open_karto/Math.h>
- #include <open_karto/Macros.h>
- #define KARTO_Object(name) \
- virtual const char* GetClassName() const { return #name; } \
- virtual kt_objecttype GetObjectType() const { return ObjectType_##name; }
- typedef kt_int32u kt_objecttype;
- const kt_objecttype ObjectType_None = 0x00000000;
- const kt_objecttype ObjectType_Sensor = 0x00001000;
- const kt_objecttype ObjectType_SensorData = 0x00002000;
- const kt_objecttype ObjectType_CustomData = 0x00004000;
- const kt_objecttype ObjectType_Misc = 0x10000000;
- const kt_objecttype ObjectType_Drive = ObjectType_Sensor | 0x01;
- const kt_objecttype ObjectType_LaserRangeFinder = ObjectType_Sensor | 0x02;
- const kt_objecttype ObjectType_Camera = ObjectType_Sensor | 0x04;
- const kt_objecttype ObjectType_DrivePose = ObjectType_SensorData | 0x01;
- const kt_objecttype ObjectType_LaserRangeScan = ObjectType_SensorData | 0x02;
- const kt_objecttype ObjectType_LocalizedRangeScan = ObjectType_SensorData | 0x04;
- const kt_objecttype ObjectType_CameraImage = ObjectType_SensorData | 0x08;
- const kt_objecttype ObjectType_LocalizedRangeScanWithPoints = ObjectType_SensorData | 0x16;
- const kt_objecttype ObjectType_Header = ObjectType_Misc | 0x01;
- const kt_objecttype ObjectType_Parameters = ObjectType_Misc | 0x02;
- const kt_objecttype ObjectType_DatasetInfo = ObjectType_Misc | 0x04;
- const kt_objecttype ObjectType_Module = ObjectType_Misc | 0x08;
- namespace karto
- {
- /**
- * \defgroup OpenKarto OpenKarto Module
- */
- /*@{*/
- /**
- * Exception class. All exceptions thrown from Karto will inherit from this class or be of this class
- */
- class KARTO_EXPORT Exception
- {
- public:
- /**
- * Constructor with exception message
- * @param rMessage exception message (default: "Karto Exception")
- * @param errorCode error code (default: 0)
- */
- Exception(const std::string& rMessage = "Karto Exception", kt_int32s errorCode = 0)
- : m_Message(rMessage)
- , m_ErrorCode(errorCode)
- {
- }
- /**
- * Copy constructor
- */
- Exception(const Exception& rException)
- : m_Message(rException.m_Message)
- , m_ErrorCode(rException.m_ErrorCode)
- {
- }
- /**
- * Destructor
- */
- virtual ~Exception()
- {
- }
- public:
- /**
- * Assignment operator
- */
- Exception& operator = (const Exception& rException)
- {
- m_Message = rException.m_Message;
- m_ErrorCode = rException.m_ErrorCode;
- return *this;
- }
- public:
- /**
- * Gets the exception message
- * @return error message as string
- */
- const std::string& GetErrorMessage() const
- {
- return m_Message;
- }
- /**
- * Gets error code
- * @return error code
- */
- kt_int32s GetErrorCode()
- {
- return m_ErrorCode;
- }
- public:
- /**
- * Write exception to output stream
- * @param rStream output stream
- * @param rException exception to write
- */
- friend KARTO_EXPORT std::ostream& operator << (std::ostream& rStream, Exception& rException);
- private:
- std::string m_Message;
- kt_int32s m_ErrorCode;
- }; // class Exception
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- /**
- * Subclass this class to make a non-copyable class (copy
- * constructor and assignment operator are private)
- */
- class KARTO_EXPORT NonCopyable
- {
- private:
- NonCopyable(const NonCopyable&);
- const NonCopyable& operator=(const NonCopyable&);
- protected:
- NonCopyable()
- {
- }
- virtual ~NonCopyable()
- {
- }
- }; // class NonCopyable
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- /**
- * Singleton class ensures only one instance of T is created
- */
- template <class T>
- class Singleton
- {
- public:
- /**
- * Constructor
- */
- Singleton()
- : m_pPointer(NULL)
- {
- }
- /**
- * Destructor
- */
- virtual ~Singleton()
- {
- delete m_pPointer;
- }
- /**
- * Gets the singleton
- * @return singleton
- */
- T* Get()
- {
- #ifdef USE_POCO
- Poco::FastMutex::ScopedLock lock(m_Mutex);
- #endif
- if (m_pPointer == NULL)
- {
- m_pPointer = new T;
- }
- return m_pPointer;
- }
- private:
- T* m_pPointer;
- #ifdef USE_POCO
- Poco::FastMutex m_Mutex;
- #endif
- private:
- Singleton(const Singleton&);
- const Singleton& operator=(const Singleton&);
- };
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- /**
- * Functor
- */
- class KARTO_EXPORT Functor
- {
- public:
- /**
- * Functor function
- */
- virtual void operator() (kt_int32u) {};
- }; // Functor
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- class AbstractParameter;
- /**
- * Type declaration of AbstractParameter vector
- */
- typedef std::vector<AbstractParameter*> ParameterVector;
- /**
- * Parameter manager.
- */
- class KARTO_EXPORT ParameterManager : public NonCopyable
- {
- public:
- /**
- * Default constructor
- */
- ParameterManager()
- {
- }
- /**
- * Destructor
- */
- virtual ~ParameterManager()
- {
- Clear();
- }
- public:
- /**
- * Adds the parameter to this manager
- * @param pParameter
- */
- void Add(AbstractParameter* pParameter);
- /**
- * Gets the parameter of the given name
- * @param rName
- * @return parameter of given name
- */
- AbstractParameter* Get(const std::string& rName)
- {
- if (m_ParameterLookup.find(rName) != m_ParameterLookup.end())
- {
- return m_ParameterLookup[rName];
- }
- std::cout << "Unknown parameter: " << rName << std::endl;
- return NULL;
- }
- /**
- * Clears the manager of all parameters
- */
- void Clear();
- /**
- * Gets all parameters
- * @return vector of all parameters
- */
- inline const ParameterVector& GetParameterVector() const
- {
- return m_Parameters;
- }
- public:
- /**
- * Gets the parameter with the given name
- * @param rName
- * @return parameter of given name
- */
- AbstractParameter* operator() (const std::string& rName)
- {
- return Get(rName);
- }
- private:
- ParameterManager(const ParameterManager&);
- const ParameterManager& operator=(const ParameterManager&);
- private:
- ParameterVector m_Parameters;
- std::map<std::string, AbstractParameter*> m_ParameterLookup;
- }; // ParameterManager
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- // valid names
- // 'Test' -- no scope
- // '/Test' -- no scope will be parsed to 'Test'
- // '/scope/Test' - 'scope' scope and 'Test' name
- // '/scope/name/Test' - 'scope/name' scope and 'Test' name
- //
- class Name
- {
- public:
- /**
- * Constructor
- */
- Name()
- {
- }
- /**
- * Constructor
- */
- Name(const std::string& rName)
- {
- Parse(rName);
- }
- /**
- * Constructor
- */
- Name(const Name& rOther)
- : m_Name(rOther.m_Name)
- , m_Scope(rOther.m_Scope)
- {
- }
- /**
- * Destructor
- */
- virtual ~Name()
- {
- }
- public:
- /**
- * Gets the name of this name
- * @return name
- */
- inline const std::string& GetName() const
- {
- return m_Name;
- }
- /**
- * Sets the name
- * @param rName name
- */
- inline void SetName(const std::string& rName)
- {
- std::string::size_type pos = rName.find_last_of('/');
- if (pos != 0 && pos != std::string::npos)
- {
- throw Exception("Name can't contain a scope!");
- }
- m_Name = rName;
- }
- /**
- * Gets the scope of this name
- * @return scope
- */
- inline const std::string& GetScope() const
- {
- return m_Scope;
- }
- /**
- * Sets the scope of this name
- * @param rScope scope
- */
- inline void SetScope(const std::string& rScope)
- {
- m_Scope = rScope;
- }
- /**
- * Returns a string representation of this name
- * @return string representation of this name
- */
- inline std::string ToString() const
- {
- if (m_Scope == "")
- {
- return m_Name;
- }
- else
- {
- std::string name;
- name.append("/");
- name.append(m_Scope);
- name.append("/");
- name.append(m_Name);
- return name;
- }
- }
- public:
- /**
- * Assignment operator.
- */
- Name& operator = (const Name& rOther)
- {
- if (&rOther != this)
- {
- m_Name = rOther.m_Name;
- m_Scope = rOther.m_Scope;
- }
- return *this;
- }
- /**
- * Equality operator.
- */
- kt_bool operator == (const Name& rOther) const
- {
- return (m_Name == rOther.m_Name) && (m_Scope == rOther.m_Scope);
- }
- /**
- * Inequality operator.
- */
- kt_bool operator != (const Name& rOther) const
- {
- return !(*this == rOther);
- }
- /**
- * Less than operator.
- */
- kt_bool operator < (const Name& rOther) const
- {
- return ToString() < rOther.ToString();
- }
- /**
- * Write Name onto output stream
- * @param rStream output stream
- * @param rName to write
- */
- friend inline std::ostream& operator << (std::ostream& rStream, const Name& rName)
- {
- rStream << rName.ToString();
- return rStream;
- }
- private:
- /**
- * Parse the given string into a Name object
- * @param rName name
- */
- void Parse(const std::string& rName)
- {
- std::string::size_type pos = rName.find_last_of('/');
- if (pos == std::string::npos)
- {
- m_Name = rName;
- }
- else
- {
- m_Scope = rName.substr(0, pos);
- m_Name = rName.substr(pos+1, rName.size());
- // remove '/' from m_Scope if first!!
- if (m_Scope.size() > 0 && m_Scope[0] == '/')
- {
- m_Scope = m_Scope.substr(1, m_Scope.size());
- }
- }
- }
- /**
- * Validates the given string as a Name
- * @param rName name
- */
- void Validate(const std::string& rName)
- {
- if (rName.empty())
- {
- return;
- }
- char c = rName[0];
- if (IsValidFirst(c))
- {
- for (size_t i = 1; i < rName.size(); ++i)
- {
- c = rName[i];
- if (!IsValid(c))
- {
- throw Exception("Invalid character in name. Valid characters must be within the ranges A-Z, a-z, 0-9, '/', '_' and '-'.");
- }
- }
- }
- else
- {
- throw Exception("Invalid first character in name. Valid characters must be within the ranges A-Z, a-z, and '/'.");
- }
- }
- /**
- * Whether the character is valid as a first character (alphanumeric or /)
- * @param c character
- * @return true if the character is a valid first character
- */
- inline kt_bool IsValidFirst(char c)
- {
- return (isalpha(c) || c == '/');
- }
- /**
- * Whether the character is a valid character (alphanumeric, /, _, or -)
- * @param c character
- * @return true if the character is valid
- */
- inline kt_bool IsValid(char c)
- {
- return (isalnum(c) || c == '/' || c == '_' || c == '-');
- }
- private:
- std::string m_Name;
- std::string m_Scope;
- };
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- /**
- * Abstract base class for Karto objects.
- */
- class KARTO_EXPORT Object : public NonCopyable
- {
- public:
- /**
- * Default constructor
- */
- Object();
- /**
- * Constructs an object with the given name
- * @param rName
- */
- Object(const Name& rName);
- /**
- * Default constructor
- */
- virtual ~Object();
- public:
- /**
- * Gets the name of this object
- * @return name
- */
- inline const Name& GetName() const
- {
- return m_Name;
- }
- /**
- * Gets the class name of this object
- * @return class name
- */
- virtual const char* GetClassName() const = 0;
- /**
- * Gets the type of this object
- * @return object type
- */
- virtual kt_objecttype GetObjectType() const = 0;
- /**
- * Gets the parameter manager of this dataset
- * @return parameter manager
- */
- virtual inline ParameterManager* GetParameterManager()
- {
- return m_pParameterManager;
- }
- /**
- * Gets the named parameter
- * @param rName name of parameter
- * @return parameter
- */
- inline AbstractParameter* GetParameter(const std::string& rName) const
- {
- return m_pParameterManager->Get(rName);
- }
- /**
- * Sets the parameter with the given name with the given value
- * @param rName name
- * @param value value
- */
- template<typename T>
- inline void SetParameter(const std::string& rName, T value);
- /**
- * Gets all parameters
- * @return parameters
- */
- inline const ParameterVector& GetParameters() const
- {
- return m_pParameterManager->GetParameterVector();
- }
- private:
- Object(const Object&);
- const Object& operator=(const Object&);
- private:
- Name m_Name;
- ParameterManager* m_pParameterManager;
- };
- /**
- * Type declaration of Object vector
- */
- typedef std::vector<Object*> ObjectVector;
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- /**
- * Whether the object is a sensor
- * @param pObject object
- * @return whether the object is a sensor
- */
- inline kt_bool IsSensor(Object* pObject)
- {
- return (pObject->GetObjectType() & ObjectType_Sensor) == ObjectType_Sensor;
- }
- /**
- * Whether the object is sensor data
- * @param pObject object
- * @return whether the object is sensor data
- */
- inline kt_bool IsSensorData(Object* pObject)
- {
- return (pObject->GetObjectType() & ObjectType_SensorData) == ObjectType_SensorData;
- }
- /**
- * Whether the object is a laser range finder
- * @param pObject object
- * @return whether the object is a laser range finder
- */
- inline kt_bool IsLaserRangeFinder(Object* pObject)
- {
- return (pObject->GetObjectType() & ObjectType_LaserRangeFinder) == ObjectType_LaserRangeFinder;
- }
- /**
- * Whether the object is a localized range scan
- * @param pObject object
- * @return whether the object is a localized range scan
- */
- inline kt_bool IsLocalizedRangeScan(Object* pObject)
- {
- return (pObject->GetObjectType() & ObjectType_LocalizedRangeScan) == ObjectType_LocalizedRangeScan;
- }
- /**
- * Whether the object is a localized range scan with points
- * @param pObject object
- * @return whether the object is a localized range scan with points
- */
- inline kt_bool IsLocalizedRangeScanWithPoints(Object* pObject)
- {
- return (pObject->GetObjectType() & ObjectType_LocalizedRangeScanWithPoints) == ObjectType_LocalizedRangeScanWithPoints;
- }
- /**
- * Whether the object is a Parameters object
- * @param pObject object
- * @return whether the object is a Parameters object
- */
- inline kt_bool IsParameters(Object* pObject)
- {
- return (pObject->GetObjectType() & ObjectType_Parameters) == ObjectType_Parameters;
- }
- /**
- * Whether the object is a DatasetInfo object
- * @param pObject object
- * @return whether the object is a DatasetInfo object
- */
- inline kt_bool IsDatasetInfo(Object* pObject)
- {
- return (pObject->GetObjectType() & ObjectType_DatasetInfo) == ObjectType_DatasetInfo;
- }
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- /**
- * Abstract base class for Karto modules.
- */
- class KARTO_EXPORT Module : public Object
- {
- public:
- // @cond EXCLUDE
- KARTO_Object(Module)
- // @endcond
- public:
- /**
- * Construct a Module
- * @param rName module name
- */
- Module(const std::string& rName);
- /**
- * Destructor
- */
- virtual ~Module();
- public:
- /**
- * Reset the module
- */
- virtual void Reset() = 0;
- /**
- * Process an Object
- */
- virtual kt_bool Process(karto::Object*)
- {
- return false;
- }
- private:
- Module(const Module&);
- const Module& operator=(const Module&);
- };
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- /**
- * Represents a size (width, height) in 2-dimensional real space.
- */
- template<typename T>
- class Size2
- {
- public:
- /**
- * Default constructor
- */
- Size2()
- : m_Width(0)
- , m_Height(0)
- {
- }
- /**
- * Constructor initializing point location
- * @param width
- * @param height
- */
- Size2(T width, T height)
- : m_Width(width)
- , m_Height(height)
- {
- }
- /**
- * Copy constructor
- * @param rOther
- */
- Size2(const Size2& rOther)
- : m_Width(rOther.m_Width)
- , m_Height(rOther.m_Height)
- {
- }
- public:
- /**
- * Gets the width
- * @return the width
- */
- inline const T GetWidth() const
- {
- return m_Width;
- }
- /**
- * Sets the width
- * @param width
- */
- inline void SetWidth(T width)
- {
- m_Width = width;
- }
- /**
- * Gets the height
- * @return the height
- */
- inline const T GetHeight() const
- {
- return m_Height;
- }
- /**
- * Sets the height
- * @param height
- */
- inline void SetHeight(T height)
- {
- m_Height = height;
- }
- /**
- * Assignment operator
- */
- inline Size2& operator = (const Size2& rOther)
- {
- m_Width = rOther.m_Width;
- m_Height = rOther.m_Height;
- return(*this);
- }
- /**
- * Equality operator
- */
- inline kt_bool operator == (const Size2& rOther) const
- {
- return (m_Width == rOther.m_Width && m_Height == rOther.m_Height);
- }
- /**
- * Inequality operator
- */
- inline kt_bool operator != (const Size2& rOther) const
- {
- return (m_Width != rOther.m_Width || m_Height != rOther.m_Height);
- }
- /**
- * Write Size2 onto output stream
- * @param rStream output stream
- * @param rSize to write
- */
- friend inline std::ostream& operator << (std::ostream& rStream, const Size2& rSize)
- {
- rStream << "(" << rSize.m_Width << ", " << rSize.m_Height << ")";
- return rStream;
- }
- private:
- T m_Width;
- T m_Height;
- }; // Size2<T>
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- /**
- * Represents a vector (x, y) in 2-dimensional real space.
- */
- template<typename T>
- class Vector2
- {
- public:
- /**
- * Default constructor
- */
- Vector2()
- {
- m_Values[0] = 0;
- m_Values[1] = 0;
- }
- /**
- * Constructor initializing vector location
- * @param x
- * @param y
- */
- Vector2(T x, T y)
- {
- m_Values[0] = x;
- m_Values[1] = y;
- }
- public:
- /**
- * Gets the x-coordinate of this vector2
- * @return the x-coordinate of the vector2
- */
- inline const T& GetX() const
- {
- return m_Values[0];
- }
- /**
- * Sets the x-coordinate of this vector2
- * @param x the x-coordinate of the vector2
- */
- inline void SetX(const T& x)
- {
- m_Values[0] = x;
- }
- /**
- * Gets the y-coordinate of this vector2
- * @return the y-coordinate of the vector2
- */
- inline const T& GetY() const
- {
- return m_Values[1];
- }
- /**
- * Sets the y-coordinate of this vector2
- * @param y the y-coordinate of the vector2
- */
- inline void SetY(const T& y)
- {
- m_Values[1] = y;
- }
- /**
- * Floor point operator
- * @param rOther
- */
- inline void MakeFloor(const Vector2& rOther)
- {
- if ( rOther.m_Values[0] < m_Values[0] ) m_Values[0] = rOther.m_Values[0];
- if ( rOther.m_Values[1] < m_Values[1] ) m_Values[1] = rOther.m_Values[1];
- }
- /**
- * Ceiling point operator
- * @param rOther
- */
- inline void MakeCeil(const Vector2& rOther)
- {
- if ( rOther.m_Values[0] > m_Values[0] ) m_Values[0] = rOther.m_Values[0];
- if ( rOther.m_Values[1] > m_Values[1] ) m_Values[1] = rOther.m_Values[1];
- }
- /**
- * Returns the square of the length of the vector
- * @return square of the length of the vector
- */
- inline kt_double SquaredLength() const
- {
- return math::Square(m_Values[0]) + math::Square(m_Values[1]);
- }
- /**
- * Returns the length of the vector (x and y).
- * @return length of the vector
- */
- inline kt_double Length() const
- {
- return sqrt(SquaredLength());
- }
- /**
- * Returns the square distance to the given vector
- * @returns square distance to the given vector
- */
- inline kt_double SquaredDistance(const Vector2& rOther) const
- {
- return (*this - rOther).SquaredLength();
- }
- /**
- * Gets the distance to the other vector2
- * @param rOther
- * @return distance to other vector2
- */
- inline kt_double Distance(const Vector2& rOther) const
- {
- return sqrt(SquaredDistance(rOther));
- }
- public:
- /**
- * In place Vector2 addition.
- */
- inline void operator += (const Vector2& rOther)
- {
- m_Values[0] += rOther.m_Values[0];
- m_Values[1] += rOther.m_Values[1];
- }
- /**
- * In place Vector2 subtraction.
- */
- inline void operator -= (const Vector2& rOther)
- {
- m_Values[0] -= rOther.m_Values[0];
- m_Values[1] -= rOther.m_Values[1];
- }
- /**
- * Addition operator
- * @param rOther
- * @return vector resulting from adding this vector with the given vector
- */
- inline const Vector2 operator + (const Vector2& rOther) const
- {
- return Vector2(m_Values[0] + rOther.m_Values[0], m_Values[1] + rOther.m_Values[1]);
- }
- /**
- * Subtraction operator
- * @param rOther
- * @return vector resulting from subtracting this vector from the given vector
- */
- inline const Vector2 operator - (const Vector2& rOther) const
- {
- return Vector2(m_Values[0] - rOther.m_Values[0], m_Values[1] - rOther.m_Values[1]);
- }
- /**
- * In place scalar division operator
- * @param scalar
- */
- inline void operator /= (T scalar)
- {
- m_Values[0] /= scalar;
- m_Values[1] /= scalar;
- }
- /**
- * Divides a Vector2
- * @param scalar
- * @return scalar product
- */
- inline const Vector2 operator / (T scalar) const
- {
- return Vector2(m_Values[0] / scalar, m_Values[1] / scalar);
- }
- /**
- * Computes the dot product between the two vectors
- * @param rOther
- * @return dot product
- */
- inline kt_double operator * (const Vector2& rOther) const
- {
- return m_Values[0] * rOther.m_Values[0] + m_Values[1] * rOther.m_Values[1];
- }
- /**
- * Scales the vector by the given scalar
- * @param scalar
- */
- inline const Vector2 operator * (T scalar) const
- {
- return Vector2(m_Values[0] * scalar, m_Values[1] * scalar);
- }
- /**
- * Subtract the vector by the given scalar
- * @param scalar
- */
- inline const Vector2 operator - (T scalar) const
- {
- return Vector2(m_Values[0] - scalar, m_Values[1] - scalar);
- }
- /**
- * In place scalar multiplication operator
- * @param scalar
- */
- inline void operator *= (T scalar)
- {
- m_Values[0] *= scalar;
- m_Values[1] *= scalar;
- }
- /**
- * Equality operator returns true if the corresponding x, y values of each Vector2 are the same values.
- * @param rOther
- */
- inline kt_bool operator == (const Vector2& rOther) const
- {
- return (m_Values[0] == rOther.m_Values[0] && m_Values[1] == rOther.m_Values[1]);
- }
- /**
- * Inequality operator returns true if any of the corresponding x, y values of each Vector2 not the same.
- * @param rOther
- */
- inline kt_bool operator != (const Vector2& rOther) const
- {
- return (m_Values[0] != rOther.m_Values[0] || m_Values[1] != rOther.m_Values[1]);
- }
- /**
- * Less than operator
- * @param rOther
- * @return true if left vector is less than right vector
- */
- inline kt_bool operator < (const Vector2& rOther) const
- {
- if (m_Values[0] < rOther.m_Values[0])
- return true;
- else if (m_Values[0] > rOther.m_Values[0])
- return false;
- else
- return (m_Values[1] < rOther.m_Values[1]);
- }
- /**
- * Write Vector2 onto output stream
- * @param rStream output stream
- * @param rVector to write
- */
- friend inline std::ostream& operator << (std::ostream& rStream, const Vector2& rVector)
- {
- rStream << rVector.GetX() << " " << rVector.GetY();
- return rStream;
- }
- /**
- * Read Vector2 from input stream
- * @param rStream input stream
- */
- friend inline std::istream& operator >> (std::istream& rStream, const Vector2& /*rVector*/)
- {
- // Implement me!! TODO(lucbettaieb): What the what? Do I need to implement this?
- return rStream;
- }
- private:
- T m_Values[2];
- }; // Vector2<T>
- /**
- * Type declaration of Vector2<kt_double> vector
- */
- typedef std::vector< Vector2<kt_double> > PointVectorDouble;
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- /**
- * Represents a vector (x, y, z) in 3-dimensional real space.
- */
- template<typename T>
- class Vector3
- {
- public:
- /**
- * Default constructor
- */
- Vector3()
- {
- m_Values[0] = 0;
- m_Values[1] = 0;
- m_Values[2] = 0;
- }
- /**
- * Constructor initializing point location
- * @param x
- * @param y
- * @param z
- */
- Vector3(T x, T y, T z)
- {
- m_Values[0] = x;
- m_Values[1] = y;
- m_Values[2] = z;
- }
- /**
- * Copy constructor
- * @param rOther
- */
- Vector3(const Vector3& rOther)
- {
- m_Values[0] = rOther.m_Values[0];
- m_Values[1] = rOther.m_Values[1];
- m_Values[2] = rOther.m_Values[2];
- }
- public:
- /**
- * Gets the x-component of this vector
- * @return x-component
- */
- inline const T& GetX() const
- {
- return m_Values[0];
- }
- /**
- * Sets the x-component of this vector
- * @param x
- */
- inline void SetX(const T& x)
- {
- m_Values[0] = x;
- }
- /**
- * Gets the y-component of this vector
- * @return y-component
- */
- inline const T& GetY() const
- {
- return m_Values[1];
- }
- /**
- * Sets the y-component of this vector
- * @param y
- */
- inline void SetY(const T& y)
- {
- m_Values[1] = y;
- }
- /**
- * Gets the z-component of this vector
- * @return z-component
- */
- inline const T& GetZ() const
- {
- return m_Values[2];
- }
- /**
- * Sets the z-component of this vector
- * @param z
- */
- inline void SetZ(const T& z)
- {
- m_Values[2] = z;
- }
- /**
- * Floor vector operator
- * @param rOther Vector3d
- */
- inline void MakeFloor(const Vector3& rOther)
- {
- if (rOther.m_Values[0] < m_Values[0]) m_Values[0] = rOther.m_Values[0];
- if (rOther.m_Values[1] < m_Values[1]) m_Values[1] = rOther.m_Values[1];
- if (rOther.m_Values[2] < m_Values[2]) m_Values[2] = rOther.m_Values[2];
- }
- /**
- * Ceiling vector operator
- * @param rOther Vector3d
- */
- inline void MakeCeil(const Vector3& rOther)
- {
- if (rOther.m_Values[0] > m_Values[0]) m_Values[0] = rOther.m_Values[0];
- if (rOther.m_Values[1] > m_Values[1]) m_Values[1] = rOther.m_Values[1];
- if (rOther.m_Values[2] > m_Values[2]) m_Values[2] = rOther.m_Values[2];
- }
- /**
- * Returns the square of the length of the vector
- * @return square of the length of the vector
- */
- inline kt_double SquaredLength() const
- {
- return math::Square(m_Values[0]) + math::Square(m_Values[1]) + math::Square(m_Values[2]);
- }
- /**
- * Returns the length of the vector.
- * @return Length of the vector
- */
- inline kt_double Length() const
- {
- return sqrt(SquaredLength());
- }
- /**
- * Returns a string representation of this vector
- * @return string representation of this vector
- */
- inline std::string ToString() const
- {
- std::stringstream converter;
- converter.precision(std::numeric_limits<double>::digits10);
- converter << GetX() << " " << GetY() << " " << GetZ();
- return converter.str();
- }
- public:
- /**
- * Assignment operator
- */
- inline Vector3& operator = (const Vector3& rOther)
- {
- m_Values[0] = rOther.m_Values[0];
- m_Values[1] = rOther.m_Values[1];
- m_Values[2] = rOther.m_Values[2];
- return *this;
- }
- /**
- * Binary vector add.
- * @param rOther
- * @return vector sum
- */
- inline const Vector3 operator + (const Vector3& rOther) const
- {
- return Vector3(m_Values[0] + rOther.m_Values[0],
- m_Values[1] + rOther.m_Values[1],
- m_Values[2] + rOther.m_Values[2]);
- }
- /**
- * Binary vector add.
- * @param scalar
- * @return sum
- */
- inline const Vector3 operator + (kt_double scalar) const
- {
- return Vector3(m_Values[0] + scalar,
- m_Values[1] + scalar,
- m_Values[2] + scalar);
- }
- /**
- * Binary vector subtract.
- * @param rOther
- * @return vector difference
- */
- inline const Vector3 operator - (const Vector3& rOther) const
- {
- return Vector3(m_Values[0] - rOther.m_Values[0],
- m_Values[1] - rOther.m_Values[1],
- m_Values[2] - rOther.m_Values[2]);
- }
- /**
- * Binary vector subtract.
- * @param scalar
- * @return difference
- */
- inline const Vector3 operator - (kt_double scalar) const
- {
- return Vector3(m_Values[0] - scalar, m_Values[1] - scalar, m_Values[2] - scalar);
- }
- /**
- * Scales the vector by the given scalar
- * @param scalar
- */
- inline const Vector3 operator * (T scalar) const
- {
- return Vector3(m_Values[0] * scalar, m_Values[1] * scalar, m_Values[2] * scalar);
- }
- /**
- * Equality operator returns true if the corresponding x, y, z values of each Vector3 are the same values.
- * @param rOther
- */
- inline kt_bool operator == (const Vector3& rOther) const
- {
- return (m_Values[0] == rOther.m_Values[0] &&
- m_Values[1] == rOther.m_Values[1] &&
- m_Values[2] == rOther.m_Values[2]);
- }
- /**
- * Inequality operator returns true if any of the corresponding x, y, z values of each Vector3 not the same.
- * @param rOther
- */
- inline kt_bool operator != (const Vector3& rOther) const
- {
- return (m_Values[0] != rOther.m_Values[0] ||
- m_Values[1] != rOther.m_Values[1] ||
- m_Values[2] != rOther.m_Values[2]);
- }
- /**
- * Write Vector3 onto output stream
- * @param rStream output stream
- * @param rVector to write
- */
- friend inline std::ostream& operator << (std::ostream& rStream, const Vector3& rVector)
- {
- rStream << rVector.ToString();
- return rStream;
- }
- /**
- * Read Vector3 from input stream
- * @param rStream input stream
- */
- friend inline std::istream& operator >> (std::istream& rStream, const Vector3& /*rVector*/)
- {
- // Implement me!!
- return rStream;
- }
- private:
- T m_Values[3];
- }; // Vector3
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- /**
- * Defines an orientation as a quaternion rotation using the positive Z axis as the zero reference.
- * <BR>
- * Q = w + ix + jy + kz <BR>
- * w = c_1 * c_2 * c_3 - s_1 * s_2 * s_3 <BR>
- * x = s_1 * s_2 * c_3 + c_1 * c_2 * s_3 <BR>
- * y = s_1 * c_2 * c_3 + c_1 * s_2 * s_3 <BR>
- * z = c_1 * s_2 * c_3 - s_1 * c_2 * s_3 <BR>
- * where <BR>
- * c_1 = cos(theta/2) <BR>
- * c_2 = cos(phi/2) <BR>
- * c_3 = cos(psi/2) <BR>
- * s_1 = sin(theta/2) <BR>
- * s_2 = sin(phi/2) <BR>
- * s_3 = sin(psi/2) <BR>
- * and <BR>
- * theta is the angle of rotation about the Y axis measured from the Z axis. <BR>
- * phi is the angle of rotation about the Z axis measured from the X axis. <BR>
- * psi is the angle of rotation about the X axis measured from the Y axis. <BR>
- * (All angles are right-handed.)
- */
- class Quaternion
- {
- public:
- /**
- * Create a quaternion with default (x=0, y=0, z=0, w=1) values
- */
- inline Quaternion()
- {
- m_Values[0] = 0.0;
- m_Values[1] = 0.0;
- m_Values[2] = 0.0;
- m_Values[3] = 1.0;
- }
- /**
- * Create a quaternion using x, y, z, w values.
- * @param x
- * @param y
- * @param z
- * @param w
- */
- inline Quaternion(kt_double x, kt_double y, kt_double z, kt_double w)
- {
- m_Values[0] = x;
- m_Values[1] = y;
- m_Values[2] = z;
- m_Values[3] = w;
- }
- /**
- * Copy constructor
- */
- inline Quaternion(const Quaternion& rQuaternion)
- {
- m_Values[0] = rQuaternion.m_Values[0];
- m_Values[1] = rQuaternion.m_Values[1];
- m_Values[2] = rQuaternion.m_Values[2];
- m_Values[3] = rQuaternion.m_Values[3];
- }
- public:
- /**
- * Returns the X-value
- * @return Return the X-value of the quaternion
- */
- inline kt_double GetX() const
- {
- return m_Values[0];
- }
- /**
- * Sets the X-value
- * @param x X-value of the quaternion
- */
- inline void SetX(kt_double x)
- {
- m_Values[0] = x;
- }
- /**
- * Returns the Y-value
- * @return Return the Y-value of the quaternion
- */
- inline kt_double GetY() const
- {
- return m_Values[1];
- }
- /**
- * Sets the Y-value
- * @param y Y-value of the quaternion
- */
- inline void SetY(kt_double y)
- {
- m_Values[1] = y;
- }
- /**
- * Returns the Z-value
- * @return Return the Z-value of the quaternion
- */
- inline kt_double GetZ() const
- {
- return m_Values[2];
- }
- /**
- * Sets the Z-value
- * @param z Z-value of the quaternion
- */
- inline void SetZ(kt_double z)
- {
- m_Values[2] = z;
- }
- /**
- * Returns the W-value
- * @return Return the W-value of the quaternion
- */
- inline kt_double GetW() const
- {
- return m_Values[3];
- }
- /**
- * Sets the W-value
- * @param w W-value of the quaternion
- */
- inline void SetW(kt_double w)
- {
- m_Values[3] = w;
- }
- /**
- * Converts this quaternion into Euler angles
- * Source: http://www.euclideanspace.com/maths/geometry/rotations/conversions/quaternionToEuler/index.htm
- * @param rYaw
- * @param rPitch
- * @param rRoll
- */
- void ToEulerAngles(kt_double& rYaw, kt_double& rPitch, kt_double& rRoll) const
- {
- kt_double test = m_Values[0] * m_Values[1] + m_Values[2] * m_Values[3];
- if (test > 0.499)
- {
- // singularity at north pole
- rYaw = 2 * atan2(m_Values[0], m_Values[3]);;
- rPitch = KT_PI_2;
- rRoll = 0;
- }
- else if (test < -0.499)
- {
- // singularity at south pole
- rYaw = -2 * atan2(m_Values[0], m_Values[3]);
- rPitch = -KT_PI_2;
- rRoll = 0;
- }
- else
- {
- kt_double sqx = m_Values[0] * m_Values[0];
- kt_double sqy = m_Values[1] * m_Values[1];
- kt_double sqz = m_Values[2] * m_Values[2];
- rYaw = atan2(2 * m_Values[1] * m_Values[3] - 2 * m_Values[0] * m_Values[2], 1 - 2 * sqy - 2 * sqz);
- rPitch = asin(2 * test);
- rRoll = atan2(2 * m_Values[0] * m_Values[3] - 2 * m_Values[1] * m_Values[2], 1 - 2 * sqx - 2 * sqz);
- }
- }
- /**
- * Set x,y,z,w values of the quaternion based on Euler angles.
- * Source: http://www.euclideanspace.com/maths/geometry/rotations/conversions/eulerToQuaternion/index.htm
- * @param yaw
- * @param pitch
- * @param roll
- */
- void FromEulerAngles(kt_double yaw, kt_double pitch, kt_double roll)
- {
- kt_double angle;
- angle = yaw * 0.5;
- kt_double cYaw = cos(angle);
- kt_double sYaw = sin(angle);
- angle = pitch * 0.5;
- kt_double cPitch = cos(angle);
- kt_double sPitch = sin(angle);
- angle = roll * 0.5;
- kt_double cRoll = cos(angle);
- kt_double sRoll = sin(angle);
- m_Values[0] = sYaw * sPitch * cRoll + cYaw * cPitch * sRoll;
- m_Values[1] = sYaw * cPitch * cRoll + cYaw * sPitch * sRoll;
- m_Values[2] = cYaw * sPitch * cRoll - sYaw * cPitch * sRoll;
- m_Values[3] = cYaw * cPitch * cRoll - sYaw * sPitch * sRoll;
- }
- /**
- * Assignment operator
- * @param rQuaternion
- */
- inline Quaternion& operator = (const Quaternion& rQuaternion)
- {
- m_Values[0] = rQuaternion.m_Values[0];
- m_Values[1] = rQuaternion.m_Values[1];
- m_Values[2] = rQuaternion.m_Values[2];
- m_Values[3] = rQuaternion.m_Values[3];
- return(*this);
- }
- /**
- * Equality operator returns true if the corresponding x, y, z, w values of each quaternion are the same values.
- * @param rOther
- */
- inline kt_bool operator == (const Quaternion& rOther) const
- {
- return (m_Values[0] == rOther.m_Values[0] &&
- m_Values[1] == rOther.m_Values[1] &&
- m_Values[2] == rOther.m_Values[2] &&
- m_Values[3] == rOther.m_Values[3]);
- }
- /**
- * Inequality operator returns true if any of the corresponding x, y, z, w values of each quaternion not the same.
- * @param rOther
- */
- inline kt_bool operator != (const Quaternion& rOther) const
- {
- return (m_Values[0] != rOther.m_Values[0] ||
- m_Values[1] != rOther.m_Values[1] ||
- m_Values[2] != rOther.m_Values[2] ||
- m_Values[3] != rOther.m_Values[3]);
- }
- /**
- * Write this quaternion onto output stream
- * @param rStream output stream
- * @param rQuaternion
- */
- friend inline std::ostream& operator << (std::ostream& rStream, const Quaternion& rQuaternion)
- {
- rStream << rQuaternion.m_Values[0] << " "
- << rQuaternion.m_Values[1] << " "
- << rQuaternion.m_Values[2] << " "
- << rQuaternion.m_Values[3];
- return rStream;
- }
- private:
- kt_double m_Values[4];
- };
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- /**
- * Stores x, y, width and height that represents the location and size of a rectangle
- * (x, y) is at bottom left in mapper!
- */
- template<typename T>
- class Rectangle2
- {
- public:
- /**
- * Default constructor
- */
- Rectangle2()
- {
- }
- /**
- * Constructor initializing rectangle parameters
- * @param x x-coordinate of left edge of rectangle
- * @param y y-coordinate of bottom edge of rectangle
- * @param width width of rectangle
- * @param height height of rectangle
- */
- Rectangle2(T x, T y, T width, T height)
- : m_Position(x, y)
- , m_Size(width, height)
- {
- }
- /**
- * Constructor initializing rectangle parameters
- * @param rPosition (x,y)-coordinate of rectangle
- * @param rSize Size of the rectangle
- */
- Rectangle2(const Vector2<T>& rPosition, const Size2<T>& rSize)
- : m_Position(rPosition)
- , m_Size(rSize)
- {
- }
- /**
- * Copy constructor
- */
- Rectangle2(const Rectangle2& rOther)
- : m_Position(rOther.m_Position)
- , m_Size(rOther.m_Size)
- {
- }
- public:
- /**
- * Gets the x-coordinate of the left edge of this rectangle
- * @return the x-coordinate of the left edge of this rectangle
- */
- inline T GetX() const
- {
- return m_Position.GetX();
- }
- /**
- * Sets the x-coordinate of the left edge of this rectangle
- * @param x the x-coordinate of the left edge of this rectangle
- */
- inline void SetX(T x)
- {
- m_Position.SetX(x);
- }
- /**
- * Gets the y-coordinate of the bottom edge of this rectangle
- * @return the y-coordinate of the bottom edge of this rectangle
- */
- inline T GetY() const
- {
- return m_Position.GetY();
- }
- /**
- * Sets the y-coordinate of the bottom edge of this rectangle
- * @param y the y-coordinate of the bottom edge of this rectangle
- */
- inline void SetY(T y)
- {
- m_Position.SetY(y);
- }
- /**
- * Gets the width of this rectangle
- * @return the width of this rectangle
- */
- inline T GetWidth() const
- {
- return m_Size.GetWidth();
- }
- /**
- * Sets the width of this rectangle
- * @param width the width of this rectangle
- */
- inline void SetWidth(T width)
- {
- m_Size.SetWidth(width);
- }
- /**
- * Gets the height of this rectangle
- * @return the height of this rectangle
- */
- inline T GetHeight() const
- {
- return m_Size.GetHeight();
- }
- /**
- * Sets the height of this rectangle
- * @param height the height of this rectangle
- */
- inline void SetHeight(T height)
- {
- m_Size.SetHeight(height);
- }
- /**
- * Gets the position of this rectangle
- * @return the position of this rectangle
- */
- inline const Vector2<T>& GetPosition() const
- {
- return m_Position;
- }
- /**
- * Sets the position of this rectangle
- * @param rX x
- * @param rY y
- */
- inline void SetPosition(const T& rX, const T& rY)
- {
- m_Position = Vector2<T>(rX, rY);
- }
- /**
- * Sets the position of this rectangle
- * @param rPosition position
- */
- inline void SetPosition(const Vector2<T>& rPosition)
- {
- m_Position = rPosition;
- }
- /**
- * Gets the size of this rectangle
- * @return the size of this rectangle
- */
- inline const Size2<T>& GetSize() const
- {
- return m_Size;
- }
- /**
- * Sets the size of this rectangle
- * @param rSize size
- */
- inline void SetSize(const Size2<T>& rSize)
- {
- m_Size = rSize;
- }
- /**
- * Gets the center of this rectangle
- * @return the center of this rectangle
- */
- inline const Vector2<T> GetCenter() const
- {
- return Vector2<T>(m_Position.GetX() + m_Size.GetWidth() * 0.5, m_Position.GetY() + m_Size.GetHeight() * 0.5);
- }
- public:
- /**
- * Assignment operator
- */
- Rectangle2& operator = (const Rectangle2& rOther)
- {
- m_Position = rOther.m_Position;
- m_Size = rOther.m_Size;
- return *this;
- }
- /**
- * Equality operator
- */
- inline kt_bool operator == (const Rectangle2& rOther) const
- {
- return (m_Position == rOther.m_Position && m_Size == rOther.m_Size);
- }
- /**
- * Inequality operator
- */
- inline kt_bool operator != (const Rectangle2& rOther) const
- {
- return (m_Position != rOther.m_Position || m_Size != rOther.m_Size);
- }
- private:
- Vector2<T> m_Position;
- Size2<T> m_Size;
- }; // Rectangle2
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- class Pose3;
- /**
- * Defines a position (x, y) in 2-dimensional space and heading.
- */
- class Pose2
- {
- public:
- /**
- * Default Constructor
- */
- Pose2()
- : m_Heading(0.0)
- {
- }
- /**
- * Constructor initializing pose parameters
- * @param rPosition position
- * @param heading heading
- **/
- Pose2(const Vector2<kt_double>& rPosition, kt_double heading)
- : m_Position(rPosition)
- , m_Heading(heading)
- {
- }
- /**
- * Constructor initializing pose parameters
- * @param x x-coordinate
- * @param y y-coordinate
- * @param heading heading
- **/
- Pose2(kt_double x, kt_double y, kt_double heading)
- : m_Position(x, y)
- , m_Heading(heading)
- {
- }
- /**
- * Constructs a Pose2 object from a Pose3.
- */
- Pose2(const Pose3& rPose);
- /**
- * Copy constructor
- */
- Pose2(const Pose2& rOther)
- : m_Position(rOther.m_Position)
- , m_Heading(rOther.m_Heading)
- {
- }
- public:
- /**
- * Returns the x-coordinate
- * @return the x-coordinate of the pose
- */
- inline kt_double GetX() const
- {
- return m_Position.GetX();
- }
- /**
- * Sets the x-coordinate
- * @param x the x-coordinate of the pose
- */
- inline void SetX(kt_double x)
- {
- m_Position.SetX(x);
- }
- /**
- * Returns the y-coordinate
- * @return the y-coordinate of the pose
- */
- inline kt_double GetY() const
- {
- return m_Position.GetY();
- }
- /**
- * Sets the y-coordinate
- * @param y the y-coordinate of the pose
- */
- inline void SetY(kt_double y)
- {
- m_Position.SetY(y);
- }
- /**
- * Returns the position
- * @return the position of the pose
- */
- inline const Vector2<kt_double>& GetPosition() const
- {
- return m_Position;
- }
- /**
- * Sets the position
- * @param rPosition of the pose
- */
- inline void SetPosition(const Vector2<kt_double>& rPosition)
- {
- m_Position = rPosition;
- }
- /**
- * Returns the heading of the pose (in radians)
- * @return the heading of the pose
- */
- inline kt_double GetHeading() const
- {
- return m_Heading;
- }
- /**
- * Sets the heading
- * @param heading of the pose
- */
- inline void SetHeading(kt_double heading)
- {
- m_Heading = heading;
- }
- /**
- * Return the squared distance between two Pose2
- * @return squared distance
- */
- inline kt_double SquaredDistance(const Pose2& rOther) const
- {
- return m_Position.SquaredDistance(rOther.m_Position);
- }
- public:
- /**
- * Assignment operator
- */
- inline Pose2& operator = (const Pose2& rOther)
- {
- m_Position = rOther.m_Position;
- m_Heading = rOther.m_Heading;
- return *this;
- }
- /**
- * Equality operator
- */
- inline kt_bool operator == (const Pose2& rOther) const
- {
- return (m_Position == rOther.m_Position && m_Heading == rOther.m_Heading);
- }
- /**
- * Inequality operator
- */
- inline kt_bool operator != (const Pose2& rOther) const
- {
- return (m_Position != rOther.m_Position || m_Heading != rOther.m_Heading);
- }
- /**
- * In place Pose2 add.
- */
- inline void operator += (const Pose2& rOther)
- {
- m_Position += rOther.m_Position;
- m_Heading = math::NormalizeAngle(m_Heading + rOther.m_Heading);
- }
- /**
- * Binary Pose2 add
- * @param rOther
- * @return Pose2 sum
- */
- inline Pose2 operator + (const Pose2& rOther) const
- {
- return Pose2(m_Position + rOther.m_Position, math::NormalizeAngle(m_Heading + rOther.m_Heading));
- }
- /**
- * Binary Pose2 subtract
- * @param rOther
- * @return Pose2 difference
- */
- inline Pose2 operator - (const Pose2& rOther) const
- {
- return Pose2(m_Position - rOther.m_Position, math::NormalizeAngle(m_Heading - rOther.m_Heading));
- }
- /**
- * Read pose from input stream
- * @param rStream input stream
- */
- friend inline std::istream& operator >> (std::istream& rStream, const Pose2& /*rPose*/)
- {
- // Implement me!!
- return rStream;
- }
- /**
- * Write this pose onto output stream
- * @param rStream output stream
- * @param rPose to read
- */
- friend inline std::ostream& operator << (std::ostream& rStream, const Pose2& rPose)
- {
- rStream << rPose.m_Position.GetX() << " " << rPose.m_Position.GetY() << " " << rPose.m_Heading;
- return rStream;
- }
- private:
- Vector2<kt_double> m_Position;
- kt_double m_Heading;
- }; // Pose2
- /**
- * Type declaration of Pose2 vector
- */
- typedef std::vector< Pose2 > Pose2Vector;
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- /**
- * Defines a position and orientation in 3-dimensional space.
- * Karto uses a right-handed coordinate system with X, Y as the 2-D ground plane and X is forward and Y is left.
- * Values in Vector3 used to define position must have units of meters.
- * The value of angle when defining orientation in two dimensions must be in units of radians.
- * The definition of orientation in three dimensions uses quaternions.
- */
- class Pose3
- {
- public:
- /**
- * Default constructor
- */
- Pose3()
- {
- }
- /**
- * Create a new Pose3 object from the given position.
- * @param rPosition position vector in three space.
- */
- Pose3(const Vector3<kt_double>& rPosition)
- : m_Position(rPosition)
- {
- }
- /**
- * Create a new Pose3 object from the given position and orientation.
- * @param rPosition position vector in three space.
- * @param rOrientation quaternion orientation in three space.
- */
- Pose3(const Vector3<kt_double>& rPosition, const karto::Quaternion& rOrientation)
- : m_Position(rPosition)
- , m_Orientation(rOrientation)
- {
- }
- /**
- * Copy constructor
- */
- Pose3(const Pose3& rOther)
- : m_Position(rOther.m_Position)
- , m_Orientation(rOther.m_Orientation)
- {
- }
- /**
- * Constructs a Pose3 object from a Pose2.
- */
- Pose3(const Pose2& rPose)
- {
- m_Position = Vector3<kt_double>(rPose.GetX(), rPose.GetY(), 0.0);
- m_Orientation.FromEulerAngles(rPose.GetHeading(), 0.0, 0.0);
- }
- public:
- /**
- * Get the position of the pose as a 3D vector as const. Values have units of meters.
- * @return 3-dimensional position vector as const
- */
- inline const Vector3<kt_double>& GetPosition() const
- {
- return m_Position;
- }
- /**
- * Set the position of the pose as a 3D vector. Values have units of meters.
- * @return 3-dimensional position vector
- */
- inline void SetPosition(const Vector3<kt_double>& rPosition)
- {
- m_Position = rPosition;
- }
- /**
- * Get the orientation quaternion of the pose as const.
- * @return orientation quaternion as const
- */
- inline const Quaternion& GetOrientation() const
- {
- return m_Orientation;
- }
- /**
- * Get the orientation quaternion of the pose.
- * @return orientation quaternion
- */
- inline void SetOrientation(const Quaternion& rOrientation)
- {
- m_Orientation = rOrientation;
- }
- /**
- * Returns a string representation of this pose
- * @return string representation of this pose
- */
- inline std::string ToString()
- {
- std::stringstream converter;
- converter.precision(std::numeric_limits<double>::digits10);
- converter << GetPosition() << " " << GetOrientation();
- return converter.str();
- }
- public:
- /**
- * Assignment operator
- */
- inline Pose3& operator = (const Pose3& rOther)
- {
- m_Position = rOther.m_Position;
- m_Orientation = rOther.m_Orientation;
- return *this;
- }
- /**
- * Equality operator
- */
- inline kt_bool operator == (const Pose3& rOther) const
- {
- return (m_Position == rOther.m_Position && m_Orientation == rOther.m_Orientation);
- }
- /**
- * Inequality operator
- */
- inline kt_bool operator != (const Pose3& rOther) const
- {
- return (m_Position != rOther.m_Position || m_Orientation != rOther.m_Orientation);
- }
- /**
- * Write Pose3 onto output stream
- * @param rStream output stream
- * @param rPose to write
- */
- friend inline std::ostream& operator << (std::ostream& rStream, const Pose3& rPose)
- {
- rStream << rPose.GetPosition() << ", " << rPose.GetOrientation();
- return rStream;
- }
- /**
- * Read Pose3 from input stream
- * @param rStream input stream
- */
- friend inline std::istream& operator >> (std::istream& rStream, const Pose3& /*rPose*/)
- {
- // Implement me!!
- return rStream;
- }
- private:
- Vector3<kt_double> m_Position;
- Quaternion m_Orientation;
- }; // Pose3
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- /**
- * Defines a Matrix 3 x 3 class.
- */
- class Matrix3
- {
- public:
- /**
- * Default constructor
- */
- Matrix3()
- {
- Clear();
- }
- /**
- * Copy constructor
- */
- inline Matrix3(const Matrix3& rOther)
- {
- memcpy(m_Matrix, rOther.m_Matrix, 9*sizeof(kt_double));
- }
- public:
- /**
- * Sets this matrix to identity matrix
- */
- void SetToIdentity()
- {
- memset(m_Matrix, 0, 9*sizeof(kt_double));
- for (kt_int32s i = 0; i < 3; i++)
- {
- m_Matrix[i][i] = 1.0;
- }
- }
- /**
- * Sets this matrix to zero matrix
- */
- void Clear()
- {
- memset(m_Matrix, 0, 9*sizeof(kt_double));
- }
- /**
- * Sets this matrix to be the rotation matrix of rotation around given axis
- * @param x x-coordinate of axis
- * @param y y-coordinate of axis
- * @param z z-coordinate of axis
- * @param radians amount of rotation
- */
- void FromAxisAngle(kt_double x, kt_double y, kt_double z, const kt_double radians)
- {
- kt_double cosRadians = cos(radians);
- kt_double sinRadians = sin(radians);
- kt_double oneMinusCos = 1.0 - cosRadians;
- kt_double xx = x * x;
- kt_double yy = y * y;
- kt_double zz = z * z;
- kt_double xyMCos = x * y * oneMinusCos;
- kt_double xzMCos = x * z * oneMinusCos;
- kt_double yzMCos = y * z * oneMinusCos;
- kt_double xSin = x * sinRadians;
- kt_double ySin = y * sinRadians;
- kt_double zSin = z * sinRadians;
- m_Matrix[0][0] = xx * oneMinusCos + cosRadians;
- m_Matrix[0][1] = xyMCos - zSin;
- m_Matrix[0][2] = xzMCos + ySin;
- m_Matrix[1][0] = xyMCos + zSin;
- m_Matrix[1][1] = yy * oneMinusCos + cosRadians;
- m_Matrix[1][2] = yzMCos - xSin;
- m_Matrix[2][0] = xzMCos - ySin;
- m_Matrix[2][1] = yzMCos + xSin;
- m_Matrix[2][2] = zz * oneMinusCos + cosRadians;
- }
- /**
- * Returns transposed version of this matrix
- * @return transposed matrix
- */
- Matrix3 Transpose() const
- {
- Matrix3 transpose;
- for (kt_int32u row = 0; row < 3; row++)
- {
- for (kt_int32u col = 0; col < 3; col++)
- {
- transpose.m_Matrix[row][col] = m_Matrix[col][row];
- }
- }
- return transpose;
- }
- /**
- * Returns the inverse of the matrix
- */
- Matrix3 Inverse() const
- {
- Matrix3 kInverse = *this;
- kt_bool haveInverse = InverseFast(kInverse, 1e-14);
- if (haveInverse == false)
- {
- assert(false);
- }
- return kInverse;
- }
- /**
- * Internal helper method for inverse matrix calculation
- * This code is lifted from the OgreMatrix3 class!!
- */
- kt_bool InverseFast(Matrix3& rkInverse, kt_double fTolerance = KT_TOLERANCE) const
- {
- // Invert a 3x3 using cofactors. This is about 8 times faster than
- // the Numerical Recipes code which uses Gaussian elimination.
- rkInverse.m_Matrix[0][0] = m_Matrix[1][1]*m_Matrix[2][2] - m_Matrix[1][2]*m_Matrix[2][1];
- rkInverse.m_Matrix[0][1] = m_Matrix[0][2]*m_Matrix[2][1] - m_Matrix[0][1]*m_Matrix[2][2];
- rkInverse.m_Matrix[0][2] = m_Matrix[0][1]*m_Matrix[1][2] - m_Matrix[0][2]*m_Matrix[1][1];
- rkInverse.m_Matrix[1][0] = m_Matrix[1][2]*m_Matrix[2][0] - m_Matrix[1][0]*m_Matrix[2][2];
- rkInverse.m_Matrix[1][1] = m_Matrix[0][0]*m_Matrix[2][2] - m_Matrix[0][2]*m_Matrix[2][0];
- rkInverse.m_Matrix[1][2] = m_Matrix[0][2]*m_Matrix[1][0] - m_Matrix[0][0]*m_Matrix[1][2];
- rkInverse.m_Matrix[2][0] = m_Matrix[1][0]*m_Matrix[2][1] - m_Matrix[1][1]*m_Matrix[2][0];
- rkInverse.m_Matrix[2][1] = m_Matrix[0][1]*m_Matrix[2][0] - m_Matrix[0][0]*m_Matrix[2][1];
- rkInverse.m_Matrix[2][2] = m_Matrix[0][0]*m_Matrix[1][1] - m_Matrix[0][1]*m_Matrix[1][0];
- kt_double fDet = m_Matrix[0][0]*rkInverse.m_Matrix[0][0] +
- m_Matrix[0][1]*rkInverse.m_Matrix[1][0] +
- m_Matrix[0][2]*rkInverse.m_Matrix[2][0];
- if (fabs(fDet) <= fTolerance)
- {
- return false;
- }
- kt_double fInvDet = 1.0/fDet;
- for (size_t row = 0; row < 3; row++)
- {
- for (size_t col = 0; col < 3; col++)
- {
- rkInverse.m_Matrix[row][col] *= fInvDet;
- }
- }
- return true;
- }
- /**
- * Returns a string representation of this matrix
- * @return string representation of this matrix
- */
- inline std::string ToString() const
- {
- std::stringstream converter;
- converter.precision(std::numeric_limits<double>::digits10);
- for (int row = 0; row < 3; row++)
- {
- for (int col = 0; col < 3; col++)
- {
- converter << m_Matrix[row][col] << " ";
- }
- }
- return converter.str();
- }
- public:
- /**
- * Assignment operator
- */
- inline Matrix3& operator = (const Matrix3& rOther)
- {
- memcpy(m_Matrix, rOther.m_Matrix, 9*sizeof(kt_double));
- return *this;
- }
- /**
- * Matrix element access, allows use of construct mat(r, c)
- * @param row
- * @param column
- * @return reference to mat(r,c)
- */
- inline kt_double& operator()(kt_int32u row, kt_int32u column)
- {
- return m_Matrix[row][column];
- }
- /**
- * Read-only matrix element access, allows use of construct mat(r, c)
- * @param row
- * @param column
- * @return mat(r,c)
- */
- inline kt_double operator()(kt_int32u row, kt_int32u column) const
- {
- return m_Matrix[row][column];
- }
- /**
- * Binary Matrix3 multiplication.
- * @param rOther
- * @return Matrix3 product
- */
- Matrix3 operator * (const Matrix3& rOther) const
- {
- Matrix3 product;
- for (size_t row = 0; row < 3; row++)
- {
- for (size_t col = 0; col < 3; col++)
- {
- product.m_Matrix[row][col] = m_Matrix[row][0]*rOther.m_Matrix[0][col] +
- m_Matrix[row][1]*rOther.m_Matrix[1][col] +
- m_Matrix[row][2]*rOther.m_Matrix[2][col];
- }
- }
- return product;
- }
- /**
- * Matrix3 and Pose2 multiplication - matrix * pose [3x3 * 3x1 = 3x1]
- * @param rPose2
- * @return Pose2 product
- */
- inline Pose2 operator * (const Pose2& rPose2) const
- {
- Pose2 pose2;
- pose2.SetX(m_Matrix[0][0] * rPose2.GetX() + m_Matrix[0][1] *
- rPose2.GetY() + m_Matrix[0][2] * rPose2.GetHeading());
- pose2.SetY(m_Matrix[1][0] * rPose2.GetX() + m_Matrix[1][1] *
- rPose2.GetY() + m_Matrix[1][2] * rPose2.GetHeading());
- pose2.SetHeading(m_Matrix[2][0] * rPose2.GetX() + m_Matrix[2][1] *
- rPose2.GetY() + m_Matrix[2][2] * rPose2.GetHeading());
- return pose2;
- }
- /**
- * In place Matrix3 add.
- * @param rkMatrix
- */
- inline void operator += (const Matrix3& rkMatrix)
- {
- for (kt_int32u row = 0; row < 3; row++)
- {
- for (kt_int32u col = 0; col < 3; col++)
- {
- m_Matrix[row][col] += rkMatrix.m_Matrix[row][col];
- }
- }
- }
- /**
- * Write Matrix3 onto output stream
- * @param rStream output stream
- * @param rMatrix to write
- */
- friend inline std::ostream& operator << (std::ostream& rStream, const Matrix3& rMatrix)
- {
- rStream << rMatrix.ToString();
- return rStream;
- }
- private:
- kt_double m_Matrix[3][3];
- }; // Matrix3
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- /**
- * Defines a general Matrix class.
- */
- class Matrix
- {
- public:
- /**
- * Constructs a matrix of size rows x columns
- */
- Matrix(kt_int32u rows, kt_int32u columns)
- : m_Rows(rows)
- , m_Columns(columns)
- , m_pData(NULL)
- {
- Allocate();
- Clear();
- }
- /**
- * Destructor
- */
- virtual ~Matrix()
- {
- delete [] m_pData;
- }
- public:
- /**
- * Set all entries to 0
- */
- void Clear()
- {
- if (m_pData != NULL)
- {
- memset(m_pData, 0, sizeof(kt_double) * m_Rows * m_Columns);
- }
- }
- /**
- * Gets the number of rows of the matrix
- * @return nubmer of rows
- */
- inline kt_int32u GetRows() const
- {
- return m_Rows;
- }
- /**
- * Gets the number of columns of the matrix
- * @return nubmer of columns
- */
- inline kt_int32u GetColumns() const
- {
- return m_Columns;
- }
- /**
- * Returns a reference to the entry at (row,column)
- * @param row
- * @param column
- * @return reference to entry at (row,column)
- */
- inline kt_double& operator()(kt_int32u row, kt_int32u column)
- {
- RangeCheck(row, column);
- return m_pData[row + column * m_Rows];
- }
- /**
- * Returns a const reference to the entry at (row,column)
- * @param row
- * @param column
- * @return const reference to entry at (row,column)
- */
- inline const kt_double& operator()(kt_int32u row, kt_int32u column) const
- {
- RangeCheck(row, column);
- return m_pData[row + column * m_Rows];
- }
- private:
- /**
- * Allocate space for the matrix
- */
- void Allocate()
- {
- try
- {
- if (m_pData != NULL)
- {
- delete[] m_pData;
- }
- m_pData = new kt_double[m_Rows * m_Columns];
- }
- catch (const std::bad_alloc& ex)
- {
- throw Exception("Matrix allocation error");
- }
- if (m_pData == NULL)
- {
- throw Exception("Matrix allocation error");
- }
- }
- /**
- * Checks if (row,column) is a valid entry into the matrix
- * @param row
- * @param column
- */
- inline void RangeCheck(kt_int32u row, kt_int32u column) const
- {
- if (math::IsUpTo(row, m_Rows) == false)
- {
- throw Exception("Matrix - RangeCheck ERROR!!!!");
- }
- if (math::IsUpTo(column, m_Columns) == false)
- {
- throw Exception("Matrix - RangeCheck ERROR!!!!");
- }
- }
- private:
- kt_int32u m_Rows;
- kt_int32u m_Columns;
- kt_double* m_pData;
- }; // Matrix
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- /**
- * Defines a bounding box in 2-dimensional real space.
- */
- class BoundingBox2
- {
- public:
- /*
- * Default constructor
- */
- BoundingBox2()
- : m_Minimum(999999999999999999.99999, 999999999999999999.99999)
- , m_Maximum(-999999999999999999.99999, -999999999999999999.99999)
- {
- }
- public:
- /**
- * Get bounding box minimum
- */
- inline const Vector2<kt_double>& GetMinimum() const
- {
- return m_Minimum;
- }
- /**
- * Set bounding box minimum
- */
- inline void SetMinimum(const Vector2<kt_double>& mMinimum)
- {
- m_Minimum = mMinimum;
- }
- /**
- * Get bounding box maximum
- */
- inline const Vector2<kt_double>& GetMaximum() const
- {
- return m_Maximum;
- }
- /**
- * Set bounding box maximum
- */
- inline void SetMaximum(const Vector2<kt_double>& rMaximum)
- {
- m_Maximum = rMaximum;
- }
- /**
- * Get the size of the bounding box
- */
- inline Size2<kt_double> GetSize() const
- {
- Vector2<kt_double> size = m_Maximum - m_Minimum;
- return Size2<kt_double>(size.GetX(), size.GetY());
- }
- /**
- * Add vector to bounding box
- */
- inline void Add(const Vector2<kt_double>& rPoint)
- {
- m_Minimum.MakeFloor(rPoint);
- m_Maximum.MakeCeil(rPoint);
- }
- /**
- * Add other bounding box to bounding box
- */
- inline void Add(const BoundingBox2& rBoundingBox)
- {
- Add(rBoundingBox.GetMinimum());
- Add(rBoundingBox.GetMaximum());
- }
- /**
- * Whether the given point is in the bounds of this box
- * @param rPoint
- * @return in bounds?
- */
- inline kt_bool IsInBounds(const Vector2<kt_double>& rPoint) const
- {
- return (math::InRange(rPoint.GetX(), m_Minimum.GetX(), m_Maximum.GetX()) &&
- math::InRange(rPoint.GetY(), m_Minimum.GetY(), m_Maximum.GetY()));
- }
- private:
- Vector2<kt_double> m_Minimum;
- Vector2<kt_double> m_Maximum;
- }; // BoundingBox2
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- /**
- * Implementation of a Pose2 transform
- */
- class Transform
- {
- public:
- /**
- * Constructs a transformation from the origin to the given pose
- * @param rPose pose
- */
- Transform(const Pose2& rPose)
- {
- SetTransform(Pose2(), rPose);
- }
- /**
- * Constructs a transformation from the first pose to the second pose
- * @param rPose1 first pose
- * @param rPose2 second pose
- */
- Transform(const Pose2& rPose1, const Pose2& rPose2)
- {
- SetTransform(rPose1, rPose2);
- }
- public:
- /**
- * Transforms the pose according to this transform
- * @param rSourcePose pose to transform from
- * @return transformed pose
- */
- inline Pose2 TransformPose(const Pose2& rSourcePose)
- {
- Pose2 newPosition = m_Transform + m_Rotation * rSourcePose;
- kt_double angle = math::NormalizeAngle(rSourcePose.GetHeading() + m_Transform.GetHeading());
- return Pose2(newPosition.GetPosition(), angle);
- }
- /**
- * Inverse transformation of the pose according to this transform
- * @param rSourcePose pose to transform from
- * @return transformed pose
- */
- inline Pose2 InverseTransformPose(const Pose2& rSourcePose)
- {
- Pose2 newPosition = m_InverseRotation * (rSourcePose - m_Transform);
- kt_double angle = math::NormalizeAngle(rSourcePose.GetHeading() - m_Transform.GetHeading());
- // components of transform
- return Pose2(newPosition.GetPosition(), angle);
- }
- private:
- /**
- * Sets this to be the transformation from the first pose to the second pose
- * @param rPose1 first pose
- * @param rPose2 second pose
- */
- void SetTransform(const Pose2& rPose1, const Pose2& rPose2)
- {
- if (rPose1 == rPose2)
- {
- m_Rotation.SetToIdentity();
- m_InverseRotation.SetToIdentity();
- m_Transform = Pose2();
- return;
- }
- // heading transformation
- m_Rotation.FromAxisAngle(0, 0, 1, rPose2.GetHeading() - rPose1.GetHeading());
- m_InverseRotation.FromAxisAngle(0, 0, 1, rPose1.GetHeading() - rPose2.GetHeading());
- // position transformation
- Pose2 newPosition;
- if (rPose1.GetX() != 0.0 || rPose1.GetY() != 0.0)
- {
- newPosition = rPose2 - m_Rotation * rPose1;
- }
- else
- {
- newPosition = rPose2;
- }
- m_Transform = Pose2(newPosition.GetPosition(), rPose2.GetHeading() - rPose1.GetHeading());
- }
- private:
- // pose transformation
- Pose2 m_Transform;
- Matrix3 m_Rotation;
- Matrix3 m_InverseRotation;
- }; // Transform
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- /**
- * Enumerated type for valid LaserRangeFinder types
- */
- typedef enum
- {
- LaserRangeFinder_Custom = 0,
- LaserRangeFinder_Sick_LMS100 = 1,
- LaserRangeFinder_Sick_LMS200 = 2,
- LaserRangeFinder_Sick_LMS291 = 3,
- LaserRangeFinder_Hokuyo_UTM_30LX = 4,
- LaserRangeFinder_Hokuyo_URG_04LX = 5
- } LaserRangeFinderType;
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- /**
- * Abstract base class for Parameters
- */
- class AbstractParameter
- {
- public:
- /**
- * Constructs a parameter with the given name
- * @param rName
- * @param pParameterManger
- */
- AbstractParameter(const std::string& rName, ParameterManager* pParameterManger = NULL)
- : m_Name(rName)
- {
- // if parameter manager is provided add myself to it!
- if (pParameterManger != NULL)
- {
- pParameterManger->Add(this);
- }
- }
- /**
- * Constructs a parameter with the given name and description
- * @param rName
- * @param rDescription
- * @param pParameterManger
- */
- AbstractParameter(const std::string& rName,
- const std::string& rDescription,
- ParameterManager* pParameterManger = NULL)
- : m_Name(rName)
- , m_Description(rDescription)
- {
- // if parameter manager is provided add myself to it!
- if (pParameterManger != NULL)
- {
- pParameterManger->Add(this);
- }
- }
- /**
- * Destructor
- */
- virtual ~AbstractParameter()
- {
- }
- public:
- /**
- * Gets the name of this object
- * @return name
- */
- inline const std::string& GetName() const
- {
- return m_Name;
- }
- /**
- * Returns the parameter description
- * @return parameter description
- */
- inline const std::string& GetDescription() const
- {
- return m_Description;
- }
- /**
- * Get parameter value as string.
- * @return value as string
- */
- virtual const std::string GetValueAsString() const = 0;
- /**
- * Set parameter value from string.
- * @param rStringValue value as string
- */
- virtual void SetValueFromString(const std::string& rStringValue) = 0;
- /**
- * Clones the parameter
- * @return clone
- */
- virtual AbstractParameter* Clone() = 0;
- public:
- /**
- * Write this parameter onto output stream
- * @param rStream output stream
- * @param rParameter
- */
- friend std::ostream& operator << (std::ostream& rStream, const AbstractParameter& rParameter)
- {
- rStream.precision(6);
- rStream.flags(std::ios::fixed);
- rStream << rParameter.GetName() << " = " << rParameter.GetValueAsString();
- return rStream;
- }
- private:
- std::string m_Name;
- std::string m_Description;
- }; // AbstractParameter
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- /**
- * Parameter class
- */
- template<typename T>
- class Parameter : public AbstractParameter
- {
- public:
- /**
- * Parameter with given name and value
- * @param rName
- * @param value
- * @param pParameterManger
- */
- Parameter(const std::string& rName, T value, ParameterManager* pParameterManger = NULL)
- : AbstractParameter(rName, pParameterManger)
- , m_Value(value)
- {
- }
- /**
- * Parameter with given name, description and value
- * @param rName
- * @param rDescription
- * @param value
- * @param pParameterManger
- */
- Parameter(const std::string& rName,
- const std::string& rDescription,
- T value,
- ParameterManager* pParameterManger = NULL)
- : AbstractParameter(rName, rDescription, pParameterManger)
- , m_Value(value)
- {
- }
- /**
- * Destructor
- */
- virtual ~Parameter()
- {
- }
- public:
- /**
- * Gets value of parameter
- * @return parameter value
- */
- inline const T& GetValue() const
- {
- return m_Value;
- }
- /**
- * Sets value of parameter
- * @param rValue
- */
- inline void SetValue(const T& rValue)
- {
- m_Value = rValue;
- }
- /**
- * Gets value of parameter as string
- * @return string version of value
- */
- virtual const std::string GetValueAsString() const
- {
- std::stringstream converter;
- converter << m_Value;
- return converter.str();
- }
- /**
- * Sets value of parameter from string
- * @param rStringValue
- */
- virtual void SetValueFromString(const std::string& rStringValue)
- {
- std::stringstream converter;
- converter.str(rStringValue);
- converter >> m_Value;
- }
- /**
- * Clone this parameter
- * @return clone of this parameter
- */
- virtual Parameter* Clone()
- {
- return new Parameter(GetName(), GetDescription(), GetValue());
- }
- public:
- /**
- * Assignment operator
- */
- Parameter& operator = (const Parameter& rOther)
- {
- m_Value = rOther.m_Value;
- return *this;
- }
- /**
- * Sets the value of this parameter to given value
- */
- T operator = (T value)
- {
- m_Value = value;
- return m_Value;
- }
- protected:
- /**
- * Parameter value
- */
- T m_Value;
- }; // Parameter
- template<>
- inline void Parameter<kt_double>::SetValueFromString(const std::string& rStringValue)
- {
- int precision = std::numeric_limits<double>::digits10;
- std::stringstream converter;
- converter.precision(precision);
- converter.str(rStringValue);
- m_Value = 0.0;
- converter >> m_Value;
- }
- template<>
- inline const std::string Parameter<kt_double>::GetValueAsString() const
- {
- std::stringstream converter;
- converter.precision(std::numeric_limits<double>::digits10);
- converter << m_Value;
- return converter.str();
- }
- template<>
- inline void Parameter<kt_bool>::SetValueFromString(const std::string& rStringValue)
- {
- if (rStringValue == "true" || rStringValue == "TRUE")
- {
- m_Value = true;
- }
- else
- {
- m_Value = false;
- }
- }
- template<>
- inline const std::string Parameter<kt_bool>::GetValueAsString() const
- {
- if (m_Value == true)
- {
- return "true";
- }
- return "false";
- }
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- /**
- * Parameter enum class
- */
- class ParameterEnum : public Parameter<kt_int32s>
- {
- typedef std::map<std::string, kt_int32s> EnumMap;
- public:
- /**
- * Construct a Parameter object with name and value
- * @param rName parameter name
- * @param value of parameter
- * @param pParameterManger
- */
- ParameterEnum(const std::string& rName, kt_int32s value, ParameterManager* pParameterManger = NULL)
- : Parameter<kt_int32s>(rName, value, pParameterManger)
- {
- }
- /**
- * Destructor
- */
- virtual ~ParameterEnum()
- {
- }
- public:
- /**
- * Return a clone of this instance
- * @return clone
- */
- virtual Parameter<kt_int32s>* Clone()
- {
- ParameterEnum* pEnum = new ParameterEnum(GetName(), GetValue());
- pEnum->m_EnumDefines = m_EnumDefines;
- return pEnum;
- }
- /**
- * Set parameter value from string.
- * @param rStringValue value as string
- */
- virtual void SetValueFromString(const std::string& rStringValue)
- {
- if (m_EnumDefines.find(rStringValue) != m_EnumDefines.end())
- {
- m_Value = m_EnumDefines[rStringValue];
- }
- else
- {
- std::string validValues;
- const_forEach(EnumMap, &m_EnumDefines)
- {
- validValues += iter->first + ", ";
- }
- throw Exception("Unable to set enum: " + rStringValue + ". Valid values are: " + validValues);
- }
- }
- /**
- * Get parameter value as string.
- * @return value as string
- */
- virtual const std::string GetValueAsString() const
- {
- const_forEach(EnumMap, &m_EnumDefines)
- {
- if (iter->second == m_Value)
- {
- return iter->first;
- }
- }
- throw Exception("Unable to lookup enum");
- }
- /**
- * Defines the enum with the given name as having the given value
- * @param value
- * @param rName
- */
- void DefineEnumValue(kt_int32s value, const std::string& rName)
- {
- if (m_EnumDefines.find(rName) == m_EnumDefines.end())
- {
- m_EnumDefines[rName] = value;
- }
- else
- {
- std::cerr << "Overriding enum value: " << m_EnumDefines[rName] << " with " << value << std::endl;
- m_EnumDefines[rName] = value;
- assert(false);
- }
- }
- public:
- /**
- * Assignment operator
- */
- ParameterEnum& operator = (const ParameterEnum& rOther)
- {
- SetValue(rOther.GetValue());
- return *this;
- }
- /**
- * Assignment operator
- */
- kt_int32s operator = (kt_int32s value)
- {
- SetValue(value);
- return m_Value;
- }
- private:
- EnumMap m_EnumDefines;
- }; // ParameterEnum
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- /**
- * Set of parameters
- */
- class Parameters : public Object
- {
- public:
- // @cond EXCLUDE
- KARTO_Object(Parameters)
- // @endcond
- public:
- /**
- * Parameters
- * @param rName
- */
- Parameters(const std::string& rName)
- : Object(rName)
- {
- }
- /**
- * Destructor
- */
- virtual ~Parameters()
- {
- }
- private:
- Parameters(const Parameters&);
- const Parameters& operator=(const Parameters&);
- }; // Parameters
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- class SensorData;
- /**
- * Abstract Sensor base class
- */
- class KARTO_EXPORT Sensor : public Object
- {
- public:
- // @cond EXCLUDE
- KARTO_Object(Sensor)
- // @endcond
- protected:
- /**
- * Construct a Sensor
- * @param rName sensor name
- */
- Sensor(const Name& rName);
- public:
- /**
- * Destructor
- */
- virtual ~Sensor();
- public:
- /**
- * Gets this range finder sensor's offset
- * @return offset pose
- */
- inline const Pose2& GetOffsetPose() const
- {
- return m_pOffsetPose->GetValue();
- }
- /**
- * Sets this range finder sensor's offset
- * @param rPose
- */
- inline void SetOffsetPose(const Pose2& rPose)
- {
- m_pOffsetPose->SetValue(rPose);
- }
- /**
- * Validates sensor
- * @return true if valid
- */
- virtual kt_bool Validate() = 0;
- /**
- * Validates sensor data
- * @param pSensorData sensor data
- * @return true if valid
- */
- virtual kt_bool Validate(SensorData* pSensorData) = 0;
- private:
- /**
- * Restrict the copy constructor
- */
- Sensor(const Sensor&);
- /**
- * Restrict the assignment operator
- */
- const Sensor& operator=(const Sensor&);
- private:
- /**
- * Sensor offset pose
- */
- Parameter<Pose2>* m_pOffsetPose;
- }; // Sensor
- /**
- * Type declaration of Sensor vector
- */
- typedef std::vector<Sensor*> SensorVector;
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- /**
- * Type declaration of <Name, Sensor*> map
- */
- typedef std::map<Name, Sensor*> SensorManagerMap;
- /**
- * Manages sensors
- */
- class KARTO_EXPORT SensorManager
- {
- public:
- /**
- * Constructor
- */
- SensorManager()
- {
- }
- /**
- * Destructor
- */
- virtual ~SensorManager()
- {
- }
- public:
- /**
- * Get singleton instance of SensorManager
- */
- static SensorManager* GetInstance();
- public:
- /**
- * Registers a sensor by it's name. The Sensor name must be unique, if not sensor is not registered
- * unless override is set to true
- * @param pSensor sensor to register
- * @param override
- * @return true if sensor is registered with SensorManager, false if Sensor name is not unique
- */
- void RegisterSensor(Sensor* pSensor, kt_bool override = false)
- {
- Validate(pSensor);
- if ((m_Sensors.find(pSensor->GetName()) != m_Sensors.end()) && !override)
- {
- throw Exception("Cannot register sensor: already registered: [" +
- pSensor->GetName().ToString() +
- "] (Consider setting 'override' to true)");
- }
- std::cout << "Registering sensor: [" << pSensor->GetName().ToString() << "]" << std::endl;
- m_Sensors[pSensor->GetName()] = pSensor;
- }
- /**
- * Unregisters the given sensor
- * @param pSensor sensor to unregister
- */
- void UnregisterSensor(Sensor* pSensor)
- {
- Validate(pSensor);
- if (m_Sensors.find(pSensor->GetName()) != m_Sensors.end())
- {
- std::cout << "Unregistering sensor: " << pSensor->GetName().ToString() << std::endl;
- m_Sensors.erase(pSensor->GetName());
- }
- else
- {
- throw Exception("Cannot unregister sensor: not registered: [" + pSensor->GetName().ToString() + "]");
- }
- }
- /**
- * Gets the sensor with the given name
- * @param rName name of sensor
- * @return sensor
- */
- Sensor* GetSensorByName(const Name& rName)
- {
- if (m_Sensors.find(rName) != m_Sensors.end())
- {
- return m_Sensors[rName];
- }
- throw Exception("Sensor not registered: [" + rName.ToString() + "] (Did you add the sensor to the Dataset?)");
- }
- /**
- * Gets the sensor with the given name
- * @param rName name of sensor
- * @return sensor
- */
- template<class T>
- T* GetSensorByName(const Name& rName)
- {
- Sensor* pSensor = GetSensorByName(rName);
- return dynamic_cast<T*>(pSensor);
- }
- /**
- * Gets all registered sensors
- * @return vector of all registered sensors
- */
- SensorVector GetAllSensors()
- {
- SensorVector sensors;
- forEach(SensorManagerMap, &m_Sensors)
- {
- sensors.push_back(iter->second);
- }
- return sensors;
- }
- protected:
- /**
- * Checks that given sensor is not NULL and has non-empty name
- * @param pSensor sensor to validate
- */
- static void Validate(Sensor* pSensor)
- {
- if (pSensor == NULL)
- {
- throw Exception("Invalid sensor: NULL");
- }
- else if (pSensor->GetName().ToString() == "")
- {
- throw Exception("Invalid sensor: nameless");
- }
- }
- protected:
- /**
- * Sensor map
- */
- SensorManagerMap m_Sensors;
- };
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- /**
- * Sensor that provides pose information relative to world coordinates.
- *
- * The user can set the offset pose of the drive sensor. If no value is provided by the user the default is no offset,
- * i.e, the sensor is initially at the world origin, oriented along the positive z axis.
- */
- class Drive : public Sensor
- {
- public:
- // @cond EXCLUDE
- KARTO_Object(Drive)
- // @endcond
- public:
- /**
- * Constructs a Drive object
- */
- Drive(const std::string& rName)
- : Sensor(rName)
- {
- }
- /**
- * Destructor
- */
- virtual ~Drive()
- {
- }
- public:
- virtual kt_bool Validate()
- {
- return true;
- }
- virtual kt_bool Validate(SensorData* pSensorData)
- {
- if (pSensorData == NULL)
- {
- return false;
- }
- return true;
- }
- private:
- Drive(const Drive&);
- const Drive& operator=(const Drive&);
- }; // class Drive
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- class LocalizedRangeScan;
- class CoordinateConverter;
- /**
- * The LaserRangeFinder defines a laser sensor that provides the pose offset position of a localized range scan relative to the robot.
- * The user can set an offset pose for the sensor relative to the robot coordinate system. If no value is provided
- * by the user, the sensor is set to be at the origin of the robot coordinate system.
- * The LaserRangeFinder contains parameters for physical laser sensor used by the mapper for scan matching
- * Also contains information about the maximum range of the sensor and provides a threshold
- * for limiting the range of readings.
- * The optimal value for the range threshold depends on the angular resolution of the scan and
- * the desired map resolution. RangeThreshold should be set as large as possible while still
- * providing "solid" coverage between consecutive range readings. The diagram below illustrates
- * the relationship between map resolution and the range threshold.
- */
- class KARTO_EXPORT LaserRangeFinder : public Sensor
- {
- public:
- // @cond EXCLUDE
- KARTO_Object(LaserRangeFinder)
- // @endcond
- public:
- /**
- * Destructor
- */
- virtual ~LaserRangeFinder()
- {
- }
- public:
- /**
- * Gets this range finder sensor's minimum range
- * @return minimum range
- */
- inline kt_double GetMinimumRange() const
- {
- return m_pMinimumRange->GetValue();
- }
- /**
- * Sets this range finder sensor's minimum range
- * @param minimumRange
- */
- inline void SetMinimumRange(kt_double minimumRange)
- {
- m_pMinimumRange->SetValue(minimumRange);
- SetRangeThreshold(GetRangeThreshold());
- }
- /**
- * Gets this range finder sensor's maximum range
- * @return maximum range
- */
- inline kt_double GetMaximumRange() const
- {
- return m_pMaximumRange->GetValue();
- }
- /**
- * Sets this range finder sensor's maximum range
- * @param maximumRange
- */
- inline void SetMaximumRange(kt_double maximumRange)
- {
- m_pMaximumRange->SetValue(maximumRange);
- SetRangeThreshold(GetRangeThreshold());
- }
- /**
- * Gets the range threshold
- * @return range threshold
- */
- inline kt_double GetRangeThreshold() const
- {
- return m_pRangeThreshold->GetValue();
- }
- /**
- * Sets the range threshold
- * @param rangeThreshold
- */
- inline void SetRangeThreshold(kt_double rangeThreshold)
- {
- // make sure rangeThreshold is within laser range finder range
- m_pRangeThreshold->SetValue(math::Clip(rangeThreshold, GetMinimumRange(), GetMaximumRange()));
- if (math::DoubleEqual(GetRangeThreshold(), rangeThreshold) == false)
- {
- std::cout << "Info: clipped range threshold to be within minimum and maximum range!" << std::endl;
- }
- }
- /**
- * Gets this range finder sensor's minimum angle
- * @return minimum angle
- */
- inline kt_double GetMinimumAngle() const
- {
- return m_pMinimumAngle->GetValue();
- }
- /**
- * Sets this range finder sensor's minimum angle
- * @param minimumAngle
- */
- inline void SetMinimumAngle(kt_double minimumAngle)
- {
- m_pMinimumAngle->SetValue(minimumAngle);
- Update();
- }
- /**
- * Gets this range finder sensor's maximum angle
- * @return maximum angle
- */
- inline kt_double GetMaximumAngle() const
- {
- return m_pMaximumAngle->GetValue();
- }
- /**
- * Sets this range finder sensor's maximum angle
- * @param maximumAngle
- */
- inline void SetMaximumAngle(kt_double maximumAngle)
- {
- m_pMaximumAngle->SetValue(maximumAngle);
- Update();
- }
- /**
- * Gets this range finder sensor's angular resolution
- * @return angular resolution
- */
- inline kt_double GetAngularResolution() const
- {
- return m_pAngularResolution->GetValue();
- }
- /**
- * Sets this range finder sensor's angular resolution
- * @param angularResolution
- */
- inline void SetAngularResolution(kt_double angularResolution)
- {
- if (m_pType->GetValue() == LaserRangeFinder_Custom)
- {
- m_pAngularResolution->SetValue(angularResolution);
- }
- else if (m_pType->GetValue() == LaserRangeFinder_Sick_LMS100)
- {
- if (math::DoubleEqual(angularResolution, math::DegreesToRadians(0.25)))
- {
- m_pAngularResolution->SetValue(math::DegreesToRadians(0.25));
- }
- else if (math::DoubleEqual(angularResolution, math::DegreesToRadians(0.50)))
- {
- m_pAngularResolution->SetValue(math::DegreesToRadians(0.50));
- }
- else
- {
- std::stringstream stream;
- stream << "Invalid resolution for Sick LMS100: ";
- stream << angularResolution;
- throw Exception(stream.str());
- }
- }
- else if (m_pType->GetValue() == LaserRangeFinder_Sick_LMS200 ||
- m_pType->GetValue() == LaserRangeFinder_Sick_LMS291)
- {
- if (math::DoubleEqual(angularResolution, math::DegreesToRadians(0.25)))
- {
- m_pAngularResolution->SetValue(math::DegreesToRadians(0.25));
- }
- else if (math::DoubleEqual(angularResolution, math::DegreesToRadians(0.50)))
- {
- m_pAngularResolution->SetValue(math::DegreesToRadians(0.50));
- }
- else if (math::DoubleEqual(angularResolution, math::DegreesToRadians(1.00)))
- {
- m_pAngularResolution->SetValue(math::DegreesToRadians(1.00));
- }
- else
- {
- std::stringstream stream;
- stream << "Invalid resolution for Sick LMS291: ";
- stream << angularResolution;
- throw Exception(stream.str());
- }
- }
- else if (m_pType->GetValue() == LaserRangeFinder_Hokuyo_UTM_30LX)
- {
- if (math::DoubleEqual(angularResolution, math::DegreesToRadians(0.25)))
- {
- m_pAngularResolution->SetValue(math::DegreesToRadians(0.25));
- }
- else
- {
- std::stringstream stream;
- stream << "Invalid resolution for Hokuyo_UTM_30LX: ";
- stream << angularResolution;
- throw Exception(stream.str());
- }
- }
- else if (m_pType->GetValue() == LaserRangeFinder_Hokuyo_URG_04LX)
- {
- if (math::DoubleEqual(angularResolution, math::DegreesToRadians(0.352)))
- {
- m_pAngularResolution->SetValue(math::DegreesToRadians(0.352));
- }
- else
- {
- std::stringstream stream;
- stream << "Invalid resolution for Hokuyo_URG_04LX: ";
- stream << angularResolution;
- throw Exception(stream.str());
- }
- }
- else
- {
- throw Exception("Can't set angular resolution, please create a LaserRangeFinder of type Custom");
- }
- Update();
- }
- /**
- * Return Laser type
- */
- inline kt_int32s GetType()
- {
- return m_pType->GetValue();
- }
- /**
- * Gets the number of range readings each localized range scan must contain to be a valid scan.
- * @return number of range readings
- */
- inline kt_int32u GetNumberOfRangeReadings() const
- {
- return m_NumberOfRangeReadings;
- }
- virtual kt_bool Validate()
- {
- Update();
- if (math::InRange(GetRangeThreshold(), GetMinimumRange(), GetMaximumRange()) == false)
- {
- std::cout << "Please set range threshold to a value between ["
- << GetMinimumRange() << ";" << GetMaximumRange() << "]" << std::endl;
- return false;
- }
- return true;
- }
- virtual kt_bool Validate(SensorData* pSensorData);
- /**
- * Get point readings (potentially scale readings if given coordinate converter is not null)
- * @param pLocalizedRangeScan
- * @param pCoordinateConverter
- * @param ignoreThresholdPoints
- * @param flipY
- */
- const PointVectorDouble GetPointReadings(LocalizedRangeScan* pLocalizedRangeScan,
- CoordinateConverter* pCoordinateConverter,
- kt_bool ignoreThresholdPoints = true,
- kt_bool flipY = false) const;
- public:
- /**
- * Create a laser range finder of the given type and ID
- * @param type
- * @param rName name of sensor - if no name is specified default name will be assigned
- * @return laser range finder
- */
- static LaserRangeFinder* CreateLaserRangeFinder(LaserRangeFinderType type, const Name& rName)
- {
- LaserRangeFinder* pLrf = NULL;
- switch (type)
- {
- // see http://www.hizook.com/files/publications/SICK_LMS100.pdf
- // set range threshold to 18m
- case LaserRangeFinder_Sick_LMS100:
- {
- pLrf = new LaserRangeFinder((rName.GetName() != "") ? rName : Name("Sick LMS 100"));
- // Sensing range is 18 meters (at 10% reflectivity, max range of 20 meters), with an error of about 20mm
- pLrf->m_pMinimumRange->SetValue(0.0);
- pLrf->m_pMaximumRange->SetValue(20.0);
- // 270 degree range, 50 Hz
- pLrf->m_pMinimumAngle->SetValue(math::DegreesToRadians(-135));
- pLrf->m_pMaximumAngle->SetValue(math::DegreesToRadians(135));
- // 0.25 degree angular resolution
- pLrf->m_pAngularResolution->SetValue(math::DegreesToRadians(0.25));
- pLrf->m_NumberOfRangeReadings = 1081;
- }
- break;
- // see http://www.hizook.com/files/publications/SICK_LMS200-291_Tech_Info.pdf
- // set range threshold to 10m
- case LaserRangeFinder_Sick_LMS200:
- {
- pLrf = new LaserRangeFinder((rName.GetName() != "") ? rName : Name("Sick LMS 200"));
- // Sensing range is 80 meters
- pLrf->m_pMinimumRange->SetValue(0.0);
- pLrf->m_pMaximumRange->SetValue(80.0);
- // 180 degree range, 75 Hz
- pLrf->m_pMinimumAngle->SetValue(math::DegreesToRadians(-90));
- pLrf->m_pMaximumAngle->SetValue(math::DegreesToRadians(90));
- // 0.5 degree angular resolution
- pLrf->m_pAngularResolution->SetValue(math::DegreesToRadians(0.5));
- pLrf->m_NumberOfRangeReadings = 361;
- }
- break;
- // see http://www.hizook.com/files/publications/SICK_LMS200-291_Tech_Info.pdf
- // set range threshold to 30m
- case LaserRangeFinder_Sick_LMS291:
- {
- pLrf = new LaserRangeFinder((rName.GetName() != "") ? rName : Name("Sick LMS 291"));
- // Sensing range is 80 meters
- pLrf->m_pMinimumRange->SetValue(0.0);
- pLrf->m_pMaximumRange->SetValue(80.0);
- // 180 degree range, 75 Hz
- pLrf->m_pMinimumAngle->SetValue(math::DegreesToRadians(-90));
- pLrf->m_pMaximumAngle->SetValue(math::DegreesToRadians(90));
- // 0.5 degree angular resolution
- pLrf->m_pAngularResolution->SetValue(math::DegreesToRadians(0.5));
- pLrf->m_NumberOfRangeReadings = 361;
- }
- break;
- // see http://www.hizook.com/files/publications/Hokuyo_UTM_LaserRangeFinder_LIDAR.pdf
- // set range threshold to 30m
- case LaserRangeFinder_Hokuyo_UTM_30LX:
- {
- pLrf = new LaserRangeFinder((rName.GetName() != "") ? rName : Name("Hokuyo UTM-30LX"));
- // Sensing range is 30 meters
- pLrf->m_pMinimumRange->SetValue(0.1);
- pLrf->m_pMaximumRange->SetValue(30.0);
- // 270 degree range, 40 Hz
- pLrf->m_pMinimumAngle->SetValue(math::DegreesToRadians(-135));
- pLrf->m_pMaximumAngle->SetValue(math::DegreesToRadians(135));
- // 0.25 degree angular resolution
- pLrf->m_pAngularResolution->SetValue(math::DegreesToRadians(0.25));
- pLrf->m_NumberOfRangeReadings = 1081;
- }
- break;
- // see http://www.hizook.com/files/publications/HokuyoURG_Datasheet.pdf
- // set range threshold to 3.5m
- case LaserRangeFinder_Hokuyo_URG_04LX:
- {
- pLrf = new LaserRangeFinder((rName.GetName() != "") ? rName : Name("Hokuyo URG-04LX"));
- // Sensing range is 4 meters. It has detection problems when
- // scanning absorptive surfaces (such as black trimming).
- pLrf->m_pMinimumRange->SetValue(0.02);
- pLrf->m_pMaximumRange->SetValue(4.0);
- // 240 degree range, 10 Hz
- pLrf->m_pMinimumAngle->SetValue(math::DegreesToRadians(-120));
- pLrf->m_pMaximumAngle->SetValue(math::DegreesToRadians(120));
- // 0.352 degree angular resolution
- pLrf->m_pAngularResolution->SetValue(math::DegreesToRadians(0.352));
- pLrf->m_NumberOfRangeReadings = 751;
- }
- break;
- case LaserRangeFinder_Custom:
- {
- pLrf = new LaserRangeFinder((rName.GetName() != "") ? rName : Name("User-Defined LaserRangeFinder"));
- // Sensing range is 80 meters.
- pLrf->m_pMinimumRange->SetValue(0.0);
- pLrf->m_pMaximumRange->SetValue(80.0);
- // 180 degree range
- pLrf->m_pMinimumAngle->SetValue(math::DegreesToRadians(-90));
- pLrf->m_pMaximumAngle->SetValue(math::DegreesToRadians(90));
- // 1.0 degree angular resolution
- pLrf->m_pAngularResolution->SetValue(math::DegreesToRadians(1.0));
- pLrf->m_NumberOfRangeReadings = 181;
- }
- break;
- }
- if (pLrf != NULL)
- {
- pLrf->m_pType->SetValue(type);
- Pose2 defaultOffset;
- pLrf->SetOffsetPose(defaultOffset);
- }
- return pLrf;
- }
- private:
- /**
- * Constructs a LaserRangeFinder object with given ID
- */
- LaserRangeFinder(const Name& rName)
- : Sensor(rName)
- , m_NumberOfRangeReadings(0)
- {
- m_pMinimumRange = new Parameter<kt_double>("MinimumRange", 0.0, GetParameterManager());
- m_pMaximumRange = new Parameter<kt_double>("MaximumRange", 80.0, GetParameterManager());
- m_pMinimumAngle = new Parameter<kt_double>("MinimumAngle", -KT_PI_2, GetParameterManager());
- m_pMaximumAngle = new Parameter<kt_double>("MaximumAngle", KT_PI_2, GetParameterManager());
- m_pAngularResolution = new Parameter<kt_double>("AngularResolution",
- math::DegreesToRadians(1),
- GetParameterManager());
- m_pRangeThreshold = new Parameter<kt_double>("RangeThreshold", 12.0, GetParameterManager());
- m_pType = new ParameterEnum("Type", LaserRangeFinder_Custom, GetParameterManager());
- m_pType->DefineEnumValue(LaserRangeFinder_Custom, "Custom");
- m_pType->DefineEnumValue(LaserRangeFinder_Sick_LMS100, "Sick_LMS100");
- m_pType->DefineEnumValue(LaserRangeFinder_Sick_LMS200, "Sick_LMS200");
- m_pType->DefineEnumValue(LaserRangeFinder_Sick_LMS291, "Sick_LMS291");
- m_pType->DefineEnumValue(LaserRangeFinder_Hokuyo_UTM_30LX, "Hokuyo_UTM_30LX");
- m_pType->DefineEnumValue(LaserRangeFinder_Hokuyo_URG_04LX, "Hokuyo_URG_04LX");
- }
- /**
- * Set the number of range readings based on the minimum and
- * maximum angles of the sensor and the angular resolution
- */
- void Update()
- {
- m_NumberOfRangeReadings = static_cast<kt_int32u>(math::Round((GetMaximumAngle() -
- GetMinimumAngle())
- / GetAngularResolution()) + 1);
- }
- private:
- LaserRangeFinder(const LaserRangeFinder&);
- const LaserRangeFinder& operator=(const LaserRangeFinder&);
- private:
- // sensor m_Parameters
- Parameter<kt_double>* m_pMinimumAngle;
- Parameter<kt_double>* m_pMaximumAngle;
- Parameter<kt_double>* m_pAngularResolution;
- Parameter<kt_double>* m_pMinimumRange;
- Parameter<kt_double>* m_pMaximumRange;
- Parameter<kt_double>* m_pRangeThreshold;
- ParameterEnum* m_pType;
- kt_int32u m_NumberOfRangeReadings;
- // static std::string LaserRangeFinderTypeNames[6];
- }; // LaserRangeFinder
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- /**
- * Enumerated type for valid grid cell states
- */
- typedef enum
- {
- GridStates_Unknown = 0,
- GridStates_Occupied = 100,
- GridStates_Free = 255
- } GridStates;
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- /**
- * The CoordinateConverter class is used to convert coordinates between world and grid coordinates
- * In world coordinates 1.0 = 1 meter where 1 in grid coordinates = 1 pixel!
- * Default scale for coordinate converter is 20 that converters to 1 pixel = 0.05 meter
- */
- class CoordinateConverter
- {
- public:
- /**
- * Default constructor
- */
- CoordinateConverter()
- : m_Scale(20.0)
- {
- }
- public:
- /**
- * Scales the value
- * @param value
- * @return scaled value
- */
- inline kt_double Transform(kt_double value)
- {
- return value * m_Scale;
- }
- /**
- * Converts the point from world coordinates to grid coordinates
- * @param rWorld world coordinate
- * @param flipY
- * @return grid coordinate
- */
- inline Vector2<kt_int32s> WorldToGrid(const Vector2<kt_double>& rWorld, kt_bool flipY = false) const
- {
- kt_double gridX = (rWorld.GetX() - m_Offset.GetX()) * m_Scale;
- kt_double gridY = 0.0;
- if (flipY == false)
- {
- gridY = (rWorld.GetY() - m_Offset.GetY()) * m_Scale;
- }
- else
- {
- gridY = (m_Size.GetHeight() / m_Scale - rWorld.GetY() + m_Offset.GetY()) * m_Scale;
- }
- return Vector2<kt_int32s>(static_cast<kt_int32s>(math::Round(gridX)), static_cast<kt_int32s>(math::Round(gridY)));
- }
- /**
- * Converts the point from grid coordinates to world coordinates
- * @param rGrid world coordinate
- * @param flipY
- * @return world coordinate
- */
- inline Vector2<kt_double> GridToWorld(const Vector2<kt_int32s>& rGrid, kt_bool flipY = false) const
- {
- kt_double worldX = m_Offset.GetX() + rGrid.GetX() / m_Scale;
- kt_double worldY = 0.0;
- if (flipY == false)
- {
- worldY = m_Offset.GetY() + rGrid.GetY() / m_Scale;
- }
- else
- {
- worldY = m_Offset.GetY() + (m_Size.GetHeight() - rGrid.GetY()) / m_Scale;
- }
- return Vector2<kt_double>(worldX, worldY);
- }
- /**
- * Gets the scale
- * @return scale
- */
- inline kt_double GetScale() const
- {
- return m_Scale;
- }
- /**
- * Sets the scale
- * @param scale
- */
- inline void SetScale(kt_double scale)
- {
- m_Scale = scale;
- }
- /**
- * Gets the offset
- * @return offset
- */
- inline const Vector2<kt_double>& GetOffset() const
- {
- return m_Offset;
- }
- /**
- * Sets the offset
- * @param rOffset
- */
- inline void SetOffset(const Vector2<kt_double>& rOffset)
- {
- m_Offset = rOffset;
- }
- /**
- * Sets the size
- * @param rSize
- */
- inline void SetSize(const Size2<kt_int32s>& rSize)
- {
- m_Size = rSize;
- }
- /**
- * Gets the size
- * @return size
- */
- inline const Size2<kt_int32s>& GetSize() const
- {
- return m_Size;
- }
- /**
- * Gets the resolution
- * @return resolution
- */
- inline kt_double GetResolution() const
- {
- return 1.0 / m_Scale;
- }
- /**
- * Sets the resolution
- * @param resolution
- */
- inline void SetResolution(kt_double resolution)
- {
- m_Scale = 1.0 / resolution;
- }
- /**
- * Gets the bounding box
- * @return bounding box
- */
- inline BoundingBox2 GetBoundingBox() const
- {
- BoundingBox2 box;
- kt_double minX = GetOffset().GetX();
- kt_double minY = GetOffset().GetY();
- kt_double maxX = minX + GetSize().GetWidth() * GetResolution();
- kt_double maxY = minY + GetSize().GetHeight() * GetResolution();
- box.SetMinimum(GetOffset());
- box.SetMaximum(Vector2<kt_double>(maxX, maxY));
- return box;
- }
- private:
- Size2<kt_int32s> m_Size;
- kt_double m_Scale;
- Vector2<kt_double> m_Offset;
- }; // CoordinateConverter
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- /**
- * Defines a grid class
- */
- template<typename T>
- class Grid
- {
- public:
- /**
- * Creates a grid of given size and resolution
- * @param width
- * @param height
- * @param resolution
- * @return grid pointer
- */
- static Grid* CreateGrid(kt_int32s width, kt_int32s height, kt_double resolution)
- {
- Grid* pGrid = new Grid(width, height);
- pGrid->GetCoordinateConverter()->SetScale(1.0 / resolution);
- return pGrid;
- }
- /**
- * Destructor
- */
- virtual ~Grid()
- {
- delete [] m_pData;
- delete m_pCoordinateConverter;
- }
- public:
- /**
- * Clear out the grid data
- */
- void Clear()
- {
- memset(m_pData, 0, GetDataSize() * sizeof(T));
- }
- /**
- * Returns a clone of this grid
- * @return grid clone
- */
- Grid* Clone()
- {
- Grid* pGrid = CreateGrid(GetWidth(), GetHeight(), GetResolution());
- pGrid->GetCoordinateConverter()->SetOffset(GetCoordinateConverter()->GetOffset());
- memcpy(pGrid->GetDataPointer(), GetDataPointer(), GetDataSize());
- return pGrid;
- }
- /**
- * Resizes the grid (deletes all old data)
- * @param width
- * @param height
- */
- virtual void Resize(kt_int32s width, kt_int32s height)
- {
- m_Width = width;
- m_Height = height;
- m_WidthStep = math::AlignValue<kt_int32s>(width, 8);
- if (m_pData != NULL)
- {
- delete[] m_pData;
- m_pData = NULL;
- }
- try
- {
- m_pData = new T[GetDataSize()];
- if (m_pCoordinateConverter == NULL)
- {
- m_pCoordinateConverter = new CoordinateConverter();
- }
- m_pCoordinateConverter->SetSize(Size2<kt_int32s>(width, height));
- }
- catch(...)
- {
- m_pData = NULL;
- m_Width = 0;
- m_Height = 0;
- m_WidthStep = 0;
- }
- Clear();
- }
- /**
- * Checks whether the given coordinates are valid grid indices
- * @param rGrid
- */
- inline kt_bool IsValidGridIndex(const Vector2<kt_int32s>& rGrid) const
- {
- return (math::IsUpTo(rGrid.GetX(), m_Width) && math::IsUpTo(rGrid.GetY(), m_Height));
- }
- /**
- * Gets the index into the data pointer of the given grid coordinate
- * @param rGrid
- * @param boundaryCheck default value is true
- * @return grid index
- */
- virtual kt_int32s GridIndex(const Vector2<kt_int32s>& rGrid, kt_bool boundaryCheck = true) const
- {
- if (boundaryCheck == true)
- {
- if (IsValidGridIndex(rGrid) == false)
- {
- std::stringstream error;
- error << "Index " << rGrid << " out of range. Index must be between [0; "
- << m_Width << ") and [0; " << m_Height << ")";
- throw Exception(error.str());
- }
- }
- kt_int32s index = rGrid.GetX() + (rGrid.GetY() * m_WidthStep);
- if (boundaryCheck == true)
- {
- assert(math::IsUpTo(index, GetDataSize()));
- }
- return index;
- }
- /**
- * Gets the grid coordinate from an index
- * @param index
- * @return grid coordinate
- */
- Vector2<kt_int32s> IndexToGrid(kt_int32s index) const
- {
- Vector2<kt_int32s> grid;
- grid.SetY(index / m_WidthStep);
- grid.SetX(index - grid.GetY() * m_WidthStep);
- return grid;
- }
- /**
- * Converts the point from world coordinates to grid coordinates
- * @param rWorld world coordinate
- * @param flipY
- * @return grid coordinate
- */
- inline Vector2<kt_int32s> WorldToGrid(const Vector2<kt_double>& rWorld, kt_bool flipY = false) const
- {
- return GetCoordinateConverter()->WorldToGrid(rWorld, flipY);
- }
- /**
- * Converts the point from grid coordinates to world coordinates
- * @param rGrid world coordinate
- * @param flipY
- * @return world coordinate
- */
- inline Vector2<kt_double> GridToWorld(const Vector2<kt_int32s>& rGrid, kt_bool flipY = false) const
- {
- return GetCoordinateConverter()->GridToWorld(rGrid, flipY);
- }
- /**
- * Gets pointer to data at given grid coordinate
- * @param rGrid grid coordinate
- * @return grid point
- */
- T* GetDataPointer(const Vector2<kt_int32s>& rGrid)
- {
- kt_int32s index = GridIndex(rGrid, true);
- return m_pData + index;
- }
- /**
- * Gets pointer to data at given grid coordinate
- * @param rGrid grid coordinate
- * @return grid point
- */
- T* GetDataPointer(const Vector2<kt_int32s>& rGrid) const
- {
- kt_int32s index = GridIndex(rGrid, true);
- return m_pData + index;
- }
- /**
- * Gets the width of the grid
- * @return width of the grid
- */
- inline kt_int32s GetWidth() const
- {
- return m_Width;
- };
- /**
- * Gets the height of the grid
- * @return height of the grid
- */
- inline kt_int32s GetHeight() const
- {
- return m_Height;
- };
- /**
- * Get the size as a Size2<kt_int32s>
- * @return size of the grid
- */
- inline const Size2<kt_int32s> GetSize() const
- {
- return Size2<kt_int32s>(m_Width, m_Height);
- }
- /**
- * Gets the width step in bytes
- * @return width step
- */
- inline kt_int32s GetWidthStep() const
- {
- return m_WidthStep;
- }
- /**
- * Gets the grid data pointer
- * @return data pointer
- */
- inline T* GetDataPointer()
- {
- return m_pData;
- }
- /**
- * Gets const grid data pointer
- * @return data pointer
- */
- inline T* GetDataPointer() const
- {
- return m_pData;
- }
- /**
- * Gets the allocated grid size in bytes
- * @return data size
- */
- inline kt_int32s GetDataSize() const
- {
- return m_WidthStep * m_Height;
- }
- /**
- * Get value at given grid coordinate
- * @param rGrid grid coordinate
- * @return value
- */
- inline T GetValue(const Vector2<kt_int32s>& rGrid) const
- {
- kt_int32s index = GridIndex(rGrid);
- return m_pData[index];
- }
- /**
- * Gets the coordinate converter for this grid
- * @return coordinate converter
- */
- inline CoordinateConverter* GetCoordinateConverter() const
- {
- return m_pCoordinateConverter;
- }
- /**
- * Gets the resolution
- * @return resolution
- */
- inline kt_double GetResolution() const
- {
- return GetCoordinateConverter()->GetResolution();
- }
- /**
- * Gets the grids bounding box
- * @return bounding box
- */
- inline BoundingBox2 GetBoundingBox() const
- {
- return GetCoordinateConverter()->GetBoundingBox();
- }
- /**
- * Increments all the grid cells from (x0, y0) to (x1, y1);
- * if applicable, apply f to each cell traced
- * @param x0
- * @param y0
- * @param x1
- * @param y1
- * @param f
- */
- void TraceLine(kt_int32s x0, kt_int32s y0, kt_int32s x1, kt_int32s y1, Functor* f = NULL)
- {
- kt_bool steep = abs(y1 - y0) > abs(x1 - x0);
- if (steep)
- {
- std::swap(x0, y0);
- std::swap(x1, y1);
- }
- if (x0 > x1)
- {
- std::swap(x0, x1);
- std::swap(y0, y1);
- }
- kt_int32s deltaX = x1 - x0;
- kt_int32s deltaY = abs(y1 - y0);
- kt_int32s error = 0;
- kt_int32s ystep;
- kt_int32s y = y0;
- if (y0 < y1)
- {
- ystep = 1;
- }
- else
- {
- ystep = -1;
- }
- kt_int32s pointX;
- kt_int32s pointY;
- for (kt_int32s x = x0; x <= x1; x++)
- {
- if (steep)
- {
- pointX = y;
- pointY = x;
- }
- else
- {
- pointX = x;
- pointY = y;
- }
- error += deltaY;
- if (2 * error >= deltaX)
- {
- y += ystep;
- error -= deltaX;
- }
- Vector2<kt_int32s> gridIndex(pointX, pointY);
- if (IsValidGridIndex(gridIndex))
- {
- kt_int32s index = GridIndex(gridIndex, false);
- T* pGridPointer = GetDataPointer();
- pGridPointer[index]++;
- if (f != NULL)
- {
- (*f)(index);
- }
- }
- }
- }
- protected:
- /**
- * Constructs grid of given size
- * @param width
- * @param height
- */
- Grid(kt_int32s width, kt_int32s height)
- : m_pData(NULL)
- , m_pCoordinateConverter(NULL)
- {
- Resize(width, height);
- }
- private:
- kt_int32s m_Width; // width of grid
- kt_int32s m_Height; // height of grid
- kt_int32s m_WidthStep; // 8 bit aligned width of grid
- T* m_pData; // grid data
- // coordinate converter to convert between world coordinates and grid coordinates
- CoordinateConverter* m_pCoordinateConverter;
- }; // Grid
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- /**
- * For making custom data
- */
- class CustomData : public Object
- {
- public:
- // @cond EXCLUDE
- KARTO_Object(CustomData)
- // @endcond
- public:
- /**
- * Constructor
- */
- CustomData()
- : Object()
- {
- }
- /**
- * Destructor
- */
- virtual ~CustomData()
- {
- }
- public:
- /**
- * Write out this custom data as a string
- * @return string representation of this data object
- */
- virtual const std::string Write() const = 0;
- /**
- * Read in this custom data from a string
- * @param rValue string representation of this data object
- */
- virtual void Read(const std::string& rValue) = 0;
- private:
- CustomData(const CustomData&);
- const CustomData& operator=(const CustomData&);
- };
- /**
- * Type declaration of CustomData vector
- */
- typedef std::vector<CustomData*> CustomDataVector;
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- /**
- * SensorData is a base class for all sensor data
- */
- class KARTO_EXPORT SensorData : public Object
- {
- public:
- // @cond EXCLUDE
- KARTO_Object(SensorData)
- // @endcond
- public:
- /**
- * Destructor
- */
- virtual ~SensorData();
- public:
- /**
- * Gets sensor data id
- * @return sensor id
- */
- inline kt_int32s GetStateId() const
- {
- return m_StateId;
- }
- /**
- * Sets sensor data id
- * @param stateId id
- */
- inline void SetStateId(kt_int32s stateId)
- {
- m_StateId = stateId;
- }
- /**
- * Gets sensor unique id
- * @return unique id
- */
- inline kt_int32s GetUniqueId() const
- {
- return m_UniqueId;
- }
- /**
- * Sets sensor unique id
- * @param uniqueId
- */
- inline void SetUniqueId(kt_int32u uniqueId)
- {
- m_UniqueId = uniqueId;
- }
- /**
- * Gets sensor data time
- * @return time
- */
- inline kt_double GetTime() const
- {
- return m_Time;
- }
- /**
- * Sets sensor data time
- * @param time
- */
- inline void SetTime(kt_double time)
- {
- m_Time = time;
- }
- /**
- * Get the sensor that created this sensor data
- * @return sensor
- */
- inline const Name& GetSensorName() const
- {
- return m_SensorName;
- }
- /**
- * Add a CustomData object to sensor data
- * @param pCustomData
- */
- inline void AddCustomData(CustomData* pCustomData)
- {
- m_CustomData.push_back(pCustomData);
- }
- /**
- * Get all custom data objects assigned to sensor data
- * @return CustomDataVector&
- */
- inline const CustomDataVector& GetCustomData() const
- {
- return m_CustomData;
- }
- protected:
- /**
- * Construct a SensorData object with a sensor name
- */
- SensorData(const Name& rSensorName);
- private:
- /**
- * Restrict the copy constructor
- */
- SensorData(const SensorData&);
- /**
- * Restrict the assignment operator
- */
- const SensorData& operator=(const SensorData&);
- private:
- /**
- * ID unique to individual sensor
- */
- kt_int32s m_StateId;
- /**
- * ID unique across all sensor data
- */
- kt_int32s m_UniqueId;
- /**
- * Sensor that created this sensor data
- */
- Name m_SensorName;
- /**
- * Time the sensor data was created
- */
- kt_double m_Time;
- CustomDataVector m_CustomData;
- };
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- /**
- * Type declaration of range readings vector
- */
- typedef std::vector<kt_double> RangeReadingsVector;
- /**
- * LaserRangeScan representing the range readings from a laser range finder sensor.
- */
- class LaserRangeScan : public SensorData
- {
- public:
- // @cond EXCLUDE
- KARTO_Object(LaserRangeScan)
- // @endcond
- public:
- /**
- * Constructs a scan from the given sensor with the given readings
- * @param rSensorName
- */
- LaserRangeScan(const Name& rSensorName)
- : SensorData(rSensorName)
- , m_pRangeReadings(NULL)
- , m_NumberOfRangeReadings(0)
- {
- }
- /**
- * Constructs a scan from the given sensor with the given readings
- * @param rSensorName
- * @param rRangeReadings
- */
- LaserRangeScan(const Name& rSensorName, const RangeReadingsVector& rRangeReadings)
- : SensorData(rSensorName)
- , m_pRangeReadings(NULL)
- , m_NumberOfRangeReadings(0)
- {
- assert(rSensorName.ToString() != "");
- SetRangeReadings(rRangeReadings);
- }
- /**
- * Destructor
- */
- virtual ~LaserRangeScan()
- {
- delete [] m_pRangeReadings;
- }
- public:
- /**
- * Gets the range readings of this scan
- * @return range readings of this scan
- */
- inline kt_double* GetRangeReadings() const
- {
- return m_pRangeReadings;
- }
- inline RangeReadingsVector GetRangeReadingsVector() const
- {
- return RangeReadingsVector(m_pRangeReadings, m_pRangeReadings + m_NumberOfRangeReadings);
- }
- /**
- * Sets the range readings for this scan
- * @param rRangeReadings
- */
- inline void SetRangeReadings(const RangeReadingsVector& rRangeReadings)
- {
- // ignore for now! XXXMAE BUGUBUG 05/21/2010 << TODO(lucbettaieb): What the heck is this??
- // if (rRangeReadings.size() != GetNumberOfRangeReadings())
- // {
- // std::stringstream error;
- // error << "Given number of readings (" << rRangeReadings.size()
- // << ") does not match expected number of range finder (" << GetNumberOfRangeReadings() << ")";
- // throw Exception(error.str());
- // }
- if (!rRangeReadings.empty())
- {
- if (rRangeReadings.size() != m_NumberOfRangeReadings)
- {
- // delete old readings
- delete [] m_pRangeReadings;
- // store size of array!
- m_NumberOfRangeReadings = static_cast<kt_int32u>(rRangeReadings.size());
- // allocate range readings
- m_pRangeReadings = new kt_double[m_NumberOfRangeReadings];
- }
- // copy readings
- kt_int32u index = 0;
- const_forEach(RangeReadingsVector, &rRangeReadings)
- {
- m_pRangeReadings[index++] = *iter;
- }
- }
- else
- {
- delete [] m_pRangeReadings;
- m_pRangeReadings = NULL;
- }
- }
- /**
- * Gets the laser range finder sensor that generated this scan
- * @return laser range finder sensor of this scan
- */
- inline LaserRangeFinder* GetLaserRangeFinder() const
- {
- return SensorManager::GetInstance()->GetSensorByName<LaserRangeFinder>(GetSensorName());
- }
- /**
- * Gets the number of range readings
- * @return number of range readings
- */
- inline kt_int32u GetNumberOfRangeReadings() const
- {
- return m_NumberOfRangeReadings;
- }
- private:
- LaserRangeScan(const LaserRangeScan&);
- const LaserRangeScan& operator=(const LaserRangeScan&);
- private:
- kt_double* m_pRangeReadings;
- kt_int32u m_NumberOfRangeReadings;
- }; // LaserRangeScan
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- /**
- * DrivePose representing the pose value of a drive sensor.
- */
- class DrivePose : public SensorData
- {
- public:
- // @cond EXCLUDE
- KARTO_Object(DrivePose)
- // @endcond
- public:
- /**
- * Constructs a pose of the given drive sensor
- * @param rSensorName
- */
- DrivePose(const Name& rSensorName)
- : SensorData(rSensorName)
- {
- }
- /**
- * Destructor
- */
- virtual ~DrivePose()
- {
- }
- public:
- /**
- * Gets the odometric pose of this scan
- * @return odometric pose of this scan
- */
- inline const Pose3& GetOdometricPose() const
- {
- return m_OdometricPose;
- }
- /**
- * Sets the odometric pose of this scan
- * @param rPose
- */
- inline void SetOdometricPose(const Pose3& rPose)
- {
- m_OdometricPose = rPose;
- }
- private:
- DrivePose(const DrivePose&);
- const DrivePose& operator=(const DrivePose&);
- private:
- /**
- * Odometric pose of robot
- */
- Pose3 m_OdometricPose;
- }; // class DrivePose
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- /**
- * The LocalizedRangeScan contains range data from a single sweep of a laser range finder sensor
- * in a two-dimensional space and position information. The odometer position is the position
- * reported by the robot when the range data was recorded. The corrected position is the position
- * calculated by the mapper (or localizer)
- * LocalizedRangeScan包含二维空间中激光测距仪传感器单次扫描的距离数据和位置信息。
- * 里程表位置是记录里程数据时机器人报告的位置。校正后的位置是由映射器(或定位器)计算的位置
- */
- class LocalizedRangeScan : public LaserRangeScan
- {
- public:
- // @cond EXCLUDE
- KARTO_Object(LocalizedRangeScan)
- // @endcond
- public:
- /**
- * Constructs a range scan from the given range finder with the given readings
- */
- LocalizedRangeScan(const Name& rSensorName, const RangeReadingsVector& rReadings)
- : LaserRangeScan(rSensorName, rReadings)
- , m_IsDirty(true)
- {
- }
- /**
- * Destructor
- */
- virtual ~LocalizedRangeScan()
- {
- }
- private:
- mutable boost::shared_mutex m_Lock;
- public:
- /**
- * Gets the odometric pose of this scan
- * @return odometric pose of this scan
- */
- inline const Pose2& GetOdometricPose() const
- {
- return m_OdometricPose;
- }
- /**
- * Sets the odometric pose of this scan
- * @param rPose
- */
- inline void SetOdometricPose(const Pose2& rPose)
- {
- m_OdometricPose = rPose;
- }
- /**
- * Gets the (possibly corrected) robot pose at which this scan was taken. The corrected robot pose of the scan
- * is usually set by an external module such as a localization or mapping module when it is determined
- * that the original pose was incorrect. The external module will set the correct pose based on
- * additional sensor data and any context information it has. If the pose has not been corrected,
- * a call to this method returns the same pose as GetOdometricPose().
- * @return corrected pose
- */
- inline const Pose2& GetCorrectedPose() const
- {
- return m_CorrectedPose;
- }
- /**
- * Moves the scan by moving the robot pose to the given location.
- * @param rPose new pose of the robot of this scan
- */
- inline void SetCorrectedPose(const Pose2& rPose)
- {
- m_CorrectedPose = rPose;
- m_IsDirty = true;
- }
- /**
- * Gets barycenter of point readings
- */
- inline const Pose2& GetBarycenterPose() const
- {
- boost::shared_lock<boost::shared_mutex> lock(m_Lock);
- if (m_IsDirty)
- {
- // throw away constness and do an update!
- lock.unlock();
- boost::unique_lock<boost::shared_mutex> uniqueLock(m_Lock);
- const_cast<LocalizedRangeScan*>(this)->Update();
- }
- return m_BarycenterPose;
- }
- /**
- * Gets barycenter if the given parameter is true, otherwise returns the scanner pose
- * @param useBarycenter
- * @return barycenter if parameter is true, otherwise scanner pose
- */
- inline Pose2 GetReferencePose(kt_bool useBarycenter) const
- {
- boost::shared_lock<boost::shared_mutex> lock(m_Lock);
- if (m_IsDirty)
- {
- // throw away constness and do an update!
- lock.unlock();
- boost::unique_lock<boost::shared_mutex> uniqueLock(m_Lock);
- const_cast<LocalizedRangeScan*>(this)->Update();
- }
- return useBarycenter ? GetBarycenterPose() : GetSensorPose();
- }
- /**
- * Computes the position of the sensor
- * @return scan pose
- */
- inline Pose2 GetSensorPose() const
- {
- return GetSensorAt(m_CorrectedPose);
- }
- /**
- * Computes the robot pose given the corrected scan pose
- * @param rScanPose pose of the sensor
- */
- void SetSensorPose(const Pose2& rScanPose)
- {
- Pose2 deviceOffsetPose2 = GetLaserRangeFinder()->GetOffsetPose();
- kt_double offsetLength = deviceOffsetPose2.GetPosition().Length();
- kt_double offsetHeading = deviceOffsetPose2.GetHeading();
- kt_double angleoffset = atan2(deviceOffsetPose2.GetY(), deviceOffsetPose2.GetX());
- kt_double correctedHeading = math::NormalizeAngle(rScanPose.GetHeading());
- Pose2 worldSensorOffset = Pose2(offsetLength * cos(correctedHeading + angleoffset - offsetHeading),
- offsetLength * sin(correctedHeading + angleoffset - offsetHeading),
- offsetHeading);
- m_CorrectedPose = rScanPose - worldSensorOffset;
- Update();
- }
- /**
- * Computes the position of the sensor if the robot were at the given pose
- * @param rPose
- * @return sensor pose
- */
- inline Pose2 GetSensorAt(const Pose2& rPose) const
- {
- return Transform(rPose).TransformPose(GetLaserRangeFinder()->GetOffsetPose());
- }
- /**
- * Gets the bounding box of this scan
- * @return bounding box of this scan
- */
- inline const BoundingBox2& GetBoundingBox() const
- {
- boost::shared_lock<boost::shared_mutex> lock(m_Lock);
- if (m_IsDirty)
- {
- // throw away constness and do an update!
- lock.unlock();
- boost::unique_lock<boost::shared_mutex> uniqueLock(m_Lock);
- const_cast<LocalizedRangeScan*>(this)->Update();
- }
- return m_BoundingBox;
- }
- /**
- * Get point readings in local coordinates
- */
- inline const PointVectorDouble& GetPointReadings(kt_bool wantFiltered = false) const
- {
- boost::shared_lock<boost::shared_mutex> lock(m_Lock);
- if (m_IsDirty)
- {
- // throw away constness and do an update!
- lock.unlock();
- boost::unique_lock<boost::shared_mutex> uniqueLock(m_Lock);
- const_cast<LocalizedRangeScan*>(this)->Update();
- }
- if (wantFiltered == true)
- {
- return m_PointReadings;
- }
- else
- {
- return m_UnfilteredPointReadings;
- }
- }
- private:
- /**
- * Compute point readings based on range readings
- * Only range readings within [minimum range; range threshold] are returned
- */
- virtual void Update()
- {
- LaserRangeFinder* pLaserRangeFinder = GetLaserRangeFinder();
- if (pLaserRangeFinder != NULL)
- {
- m_PointReadings.clear();
- m_UnfilteredPointReadings.clear();
- kt_double rangeThreshold = pLaserRangeFinder->GetRangeThreshold();
- kt_double minimumAngle = pLaserRangeFinder->GetMinimumAngle();
- kt_double angularResolution = pLaserRangeFinder->GetAngularResolution();
- Pose2 scanPose = GetSensorPose();
- // compute point readings
- Vector2<kt_double> rangePointsSum;
- kt_int32u beamNum = 0;
- for (kt_int32u i = 0; i < pLaserRangeFinder->GetNumberOfRangeReadings(); i++, beamNum++)
- {
- kt_double rangeReading = GetRangeReadings()[i];
- if (!math::InRange(rangeReading, pLaserRangeFinder->GetMinimumRange(), rangeThreshold))
- {
- kt_double angle = scanPose.GetHeading() + minimumAngle + beamNum * angularResolution;
- Vector2<kt_double> point;
- point.SetX(scanPose.GetX() + (rangeReading * cos(angle)));
- point.SetY(scanPose.GetY() + (rangeReading * sin(angle)));
- m_UnfilteredPointReadings.push_back(point);
- continue;
- }
- kt_double angle = scanPose.GetHeading() + minimumAngle + beamNum * angularResolution;
- Vector2<kt_double> point;
- point.SetX(scanPose.GetX() + (rangeReading * cos(angle)));
- point.SetY(scanPose.GetY() + (rangeReading * sin(angle)));
- m_PointReadings.push_back(point);
- m_UnfilteredPointReadings.push_back(point);
- rangePointsSum += point;
- }
- // compute barycenter
- kt_double nPoints = static_cast<kt_double>(m_PointReadings.size());
- if (nPoints != 0.0)
- {
- Vector2<kt_double> averagePosition = Vector2<kt_double>(rangePointsSum / nPoints);
- m_BarycenterPose = Pose2(averagePosition, 0.0);
- }
- else
- {
- m_BarycenterPose = scanPose;
- }
- // calculate bounding box of scan
- m_BoundingBox = BoundingBox2();
- m_BoundingBox.Add(scanPose.GetPosition());
- forEach(PointVectorDouble, &m_PointReadings)
- {
- m_BoundingBox.Add(*iter);
- }
- }
- m_IsDirty = false;
- }
- private:
- LocalizedRangeScan(const LocalizedRangeScan&);
- const LocalizedRangeScan& operator=(const LocalizedRangeScan&);
- private:
- /**
- * Odometric pose of robot
- */
- Pose2 m_OdometricPose;
- /**
- * Corrected pose of robot calculated by mapper (or localizer)
- */
- Pose2 m_CorrectedPose;
- protected:
- /**
- * Average of all the point readings
- */
- Pose2 m_BarycenterPose;
- /**
- * Vector of point readings
- */
- PointVectorDouble m_PointReadings;
- /**
- * Vector of unfiltered point readings
- */
- PointVectorDouble m_UnfilteredPointReadings;
- /**
- * Bounding box of localized range scan
- */
- BoundingBox2 m_BoundingBox;
- /**
- * Internal flag used to update point readings, barycenter and bounding box
- */
- kt_bool m_IsDirty;
- }; // LocalizedRangeScan
- /**
- * Type declaration of LocalizedRangeScan vector
- */
- typedef std::vector<LocalizedRangeScan*> LocalizedRangeScanVector;
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- /**
- * The LocalizedRangeScanWithPoints is an extension of the LocalizedRangeScan with precomputed points.
- */
- class LocalizedRangeScanWithPoints : public LocalizedRangeScan
- {
- public:
- // @cond EXCLUDE
- KARTO_Object(LocalizedRangeScanWithPoints)
- // @endcond
- public:
- /**
- * Constructs a range scan from the given range finder with the given readings. Precomptued points should be
- * in the robot frame.
- */
- LocalizedRangeScanWithPoints(const Name& rSensorName, const RangeReadingsVector& rReadings,
- const PointVectorDouble& rPoints)
- : LocalizedRangeScan(rSensorName, rReadings),
- m_Points(rPoints)
- {
- }
- /**
- * Destructor
- */
- virtual ~LocalizedRangeScanWithPoints()
- {
- }
- private:
- /**
- * Update the points based on the latest sensor pose.
- */
- void Update()
- {
- m_PointReadings.clear();
- m_UnfilteredPointReadings.clear();
- Pose2 scanPose = GetSensorPose();
- Pose2 robotPose = GetCorrectedPose();
- // update point readings
- Vector2<kt_double> rangePointsSum;
- for (kt_int32u i = 0; i < m_Points.size(); i++)
- {
- // check if this has a NaN
- if (!std::isfinite(m_Points[i].GetX()) || !std::isfinite(m_Points[i].GetY()))
- {
- Vector2<kt_double> point(m_Points[i].GetX(), m_Points[i].GetY());
- m_UnfilteredPointReadings.push_back(point);
- continue;
- }
- // transform into world coords
- Pose2 pointPose(m_Points[i].GetX(), m_Points[i].GetY(), 0);
- Pose2 result = Transform(robotPose).TransformPose(pointPose);
- Vector2<kt_double> point(result.GetX(), result.GetY());
- m_PointReadings.push_back(point);
- m_UnfilteredPointReadings.push_back(point);
- rangePointsSum += point;
- }
- // compute barycenter
- kt_double nPoints = static_cast<kt_double>(m_PointReadings.size());
- if (nPoints != 0.0)
- {
- Vector2<kt_double> averagePosition = Vector2<kt_double>(rangePointsSum / nPoints);
- m_BarycenterPose = Pose2(averagePosition, 0.0);
- }
- else
- {
- m_BarycenterPose = scanPose;
- }
- // calculate bounding box of scan
- m_BoundingBox = BoundingBox2();
- m_BoundingBox.Add(scanPose.GetPosition());
- forEach(PointVectorDouble, &m_PointReadings)
- {
- m_BoundingBox.Add(*iter);
- }
- m_IsDirty = false;
- }
- private:
- LocalizedRangeScanWithPoints(const LocalizedRangeScanWithPoints&);
- const LocalizedRangeScanWithPoints& operator=(const LocalizedRangeScanWithPoints&);
- private:
- const PointVectorDouble m_Points;
- }; // LocalizedRangeScanWithPoints
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- class OccupancyGrid;
- class KARTO_EXPORT CellUpdater : public Functor
- {
- public:
- CellUpdater(OccupancyGrid* pGrid)
- : m_pOccupancyGrid(pGrid)
- {
- }
- /**
- * Destructor
- */
- virtual ~CellUpdater() {}
- /**
- * Updates the cell at the given index based on the grid's hits and pass counters
- * @param index
- */
- virtual void operator() (kt_int32u index);
- private:
- OccupancyGrid* m_pOccupancyGrid;
- }; // CellUpdater
- /**
- * Occupancy grid definition. See GridStates for possible grid values.
- */
- class OccupancyGrid : public Grid<kt_int8u>
- {
- friend class CellUpdater;
- friend class IncrementalOccupancyGrid;
- public:
- /**
- * Constructs an occupancy grid of given size
- * @param width
- * @param height
- * @param rOffset
- * @param resolution
- */
- OccupancyGrid(kt_int32s width, kt_int32s height, const Vector2<kt_double>& rOffset, kt_double resolution)
- : Grid<kt_int8u>(width, height)
- , m_pCellPassCnt(Grid<kt_int32u>::CreateGrid(0, 0, resolution))
- , m_pCellHitsCnt(Grid<kt_int32u>::CreateGrid(0, 0, resolution))
- , m_pCellUpdater(NULL)
- {
- m_pCellUpdater = new CellUpdater(this);
- if (karto::math::DoubleEqual(resolution, 0.0))
- {
- throw Exception("Resolution cannot be 0");
- }
- m_pMinPassThrough = new Parameter<kt_int32u>("MinPassThrough", 2);
- m_pOccupancyThreshold = new Parameter<kt_double>("OccupancyThreshold", 0.1);
- GetCoordinateConverter()->SetScale(1.0 / resolution);
- GetCoordinateConverter()->SetOffset(rOffset);
- }
- /**
- * Destructor
- */
- virtual ~OccupancyGrid()
- {
- delete m_pCellUpdater;
- delete m_pCellPassCnt;
- delete m_pCellHitsCnt;
- delete m_pMinPassThrough;
- delete m_pOccupancyThreshold;
- }
- public:
- /**
- * Create an occupancy grid from the given scans using the given resolution
- * @param rScans
- * @param resolution
- */
- static OccupancyGrid* CreateFromScans(const LocalizedRangeScanVector& rScans, kt_double resolution)
- {
- if (rScans.empty())
- {
- return NULL;
- }
- kt_int32s width, height;
- Vector2<kt_double> offset;
- ComputeDimensions(rScans, resolution, width, height, offset);
- OccupancyGrid* pOccupancyGrid = new OccupancyGrid(width, height, offset, resolution);
- pOccupancyGrid->CreateFromScans(rScans);
- return pOccupancyGrid;
- }
- /**
- * Make a clone
- * @return occupancy grid clone
- */
- OccupancyGrid* Clone() const
- {
- OccupancyGrid* pOccupancyGrid = new OccupancyGrid(GetWidth(),
- GetHeight(),
- GetCoordinateConverter()->GetOffset(),
- 1.0 / GetCoordinateConverter()->GetScale());
- memcpy(pOccupancyGrid->GetDataPointer(), GetDataPointer(), GetDataSize());
- pOccupancyGrid->GetCoordinateConverter()->SetSize(GetCoordinateConverter()->GetSize());
- pOccupancyGrid->m_pCellPassCnt = m_pCellPassCnt->Clone();
- pOccupancyGrid->m_pCellHitsCnt = m_pCellHitsCnt->Clone();
- return pOccupancyGrid;
- }
- /**
- * Check if grid point is free
- * @param rPose
- * @return whether the cell at the given point is free space
- */
- virtual kt_bool IsFree(const Vector2<kt_int32s>& rPose) const
- {
- kt_int8u* pOffsets = reinterpret_cast<kt_int8u*>(GetDataPointer(rPose));
- if (*pOffsets == GridStates_Free)
- {
- return true;
- }
- return false;
- }
- /**
- * Casts a ray from the given point (up to the given max range)
- * and returns the distance to the closest obstacle
- * @param rPose2
- * @param maxRange
- * @return distance to closest obstacle
- */
- virtual kt_double RayCast(const Pose2& rPose2, kt_double maxRange) const
- {
- double scale = GetCoordinateConverter()->GetScale();
- kt_double x = rPose2.GetX();
- kt_double y = rPose2.GetY();
- kt_double theta = rPose2.GetHeading();
- kt_double sinTheta = sin(theta);
- kt_double cosTheta = cos(theta);
- kt_double xStop = x + maxRange * cosTheta;
- kt_double xSteps = 1 + fabs(xStop - x) * scale;
- kt_double yStop = y + maxRange * sinTheta;
- kt_double ySteps = 1 + fabs(yStop - y) * scale;
- kt_double steps = math::Maximum(xSteps, ySteps);
- kt_double delta = maxRange / steps;
- kt_double distance = delta;
- for (kt_int32u i = 1; i < steps; i++)
- {
- kt_double x1 = x + distance * cosTheta;
- kt_double y1 = y + distance * sinTheta;
- Vector2<kt_int32s> gridIndex = WorldToGrid(Vector2<kt_double>(x1, y1));
- if (IsValidGridIndex(gridIndex) && IsFree(gridIndex))
- {
- distance = (i + 1) * delta;
- }
- else
- {
- break;
- }
- }
- return (distance < maxRange)? distance : maxRange;
- }
- /**
- * Sets the minimum number of beams that must pass through a cell before it
- * will be considered to be occupied or unoccupied.
- * This prevents stray beams from messing up the map.
- */
- void SetMinPassThrough(kt_int32u count)
- {
- m_pMinPassThrough->SetValue(count);
- }
- /**
- * Sets the minimum ratio of beams hitting cell to beams passing through
- * cell for cell to be marked as occupied.
- */
- void SetOccupancyThreshold(kt_double thresh)
- {
- m_pOccupancyThreshold->SetValue(thresh);
- }
- protected:
- /**
- * Get cell hit grid
- * @return Grid<kt_int32u>*
- */
- virtual Grid<kt_int32u>* GetCellHitsCounts()
- {
- return m_pCellHitsCnt;
- }
- /**
- * Get cell pass grid
- * @return Grid<kt_int32u>*
- */
- virtual Grid<kt_int32u>* GetCellPassCounts()
- {
- return m_pCellPassCnt;
- }
- protected:
- /**
- * Calculate grid dimensions from localized range scans
- * @param rScans
- * @param resolution
- * @param rWidth
- * @param rHeight
- * @param rOffset
- */
- static void ComputeDimensions(const LocalizedRangeScanVector& rScans,
- kt_double resolution,
- kt_int32s& rWidth,
- kt_int32s& rHeight,
- Vector2<kt_double>& rOffset)
- {
- BoundingBox2 boundingBox;
- const_forEach(LocalizedRangeScanVector, &rScans)
- {
- boundingBox.Add((*iter)->GetBoundingBox());
- }
- kt_double scale = 1.0 / resolution;
- Size2<kt_double> size = boundingBox.GetSize();
- rWidth = static_cast<kt_int32s>(math::Round(size.GetWidth() * scale));
- rHeight = static_cast<kt_int32s>(math::Round(size.GetHeight() * scale));
- rOffset = boundingBox.GetMinimum();
- }
- /**
- * Create grid using scans
- * @param rScans
- */
- virtual void CreateFromScans(const LocalizedRangeScanVector& rScans)
- {
- m_pCellPassCnt->Resize(GetWidth(), GetHeight());
- m_pCellPassCnt->GetCoordinateConverter()->SetOffset(GetCoordinateConverter()->GetOffset());
- m_pCellHitsCnt->Resize(GetWidth(), GetHeight());
- m_pCellHitsCnt->GetCoordinateConverter()->SetOffset(GetCoordinateConverter()->GetOffset());
- const_forEach(LocalizedRangeScanVector, &rScans)
- {
- LocalizedRangeScan* pScan = *iter;
- AddScan(pScan);
- }
- Update();
- }
- /**
- * Adds the scan's information to this grid's counters (optionally
- * update the grid's cells' occupancy status)
- * @param pScan
- * @param doUpdate whether to update the grid's cell's occupancy status
- * @return returns false if an endpoint fell off the grid, otherwise true
- */
- virtual kt_bool AddScan(LocalizedRangeScan* pScan, kt_bool doUpdate = false)
- {
- kt_double rangeThreshold = pScan->GetLaserRangeFinder()->GetRangeThreshold();
- kt_double maxRange = pScan->GetLaserRangeFinder()->GetMaximumRange();
- kt_double minRange = pScan->GetLaserRangeFinder()->GetMinimumRange();
- Vector2<kt_double> scanPosition = pScan->GetSensorPose().GetPosition();
- // get scan point readings
- const PointVectorDouble& rPointReadings = pScan->GetPointReadings(false);
- kt_bool isAllInMap = true;
- // draw lines from scan position to all point readings
- int pointIndex = 0;
- const_forEachAs(PointVectorDouble, &rPointReadings, pointsIter)
- {
- Vector2<kt_double> point = *pointsIter;
- kt_double rangeReading = pScan->GetRangeReadings()[pointIndex];
- kt_bool isEndPointValid = rangeReading < (rangeThreshold - KT_TOLERANCE);
- if (rangeReading <= minRange || rangeReading >= maxRange || std::isnan(rangeReading))
- {
- // ignore these readings
- pointIndex++;
- continue;
- }
- else if (rangeReading >= rangeThreshold)
- {
- // trace up to range reading
- kt_double ratio = rangeThreshold / rangeReading;
- kt_double dx = point.GetX() - scanPosition.GetX();
- kt_double dy = point.GetY() - scanPosition.GetY();
- point.SetX(scanPosition.GetX() + ratio * dx);
- point.SetY(scanPosition.GetY() + ratio * dy);
- }
- kt_bool isInMap = RayTrace(scanPosition, point, isEndPointValid, doUpdate);
- if (!isInMap)
- {
- isAllInMap = false;
- }
- pointIndex++;
- }
- return isAllInMap;
- }
- /**
- * Traces a beam from the start position to the end position marking
- * the bookkeeping arrays accordingly.
- * @param rWorldFrom start position of beam
- * @param rWorldTo end position of beam
- * @param isEndPointValid is the reading within the range threshold?
- * @param doUpdate whether to update the cells' occupancy status immediately
- * @return returns false if an endpoint fell off the grid, otherwise true
- */
- virtual kt_bool RayTrace(const Vector2<kt_double>& rWorldFrom,
- const Vector2<kt_double>& rWorldTo,
- kt_bool isEndPointValid,
- kt_bool doUpdate = false)
- {
- assert(m_pCellPassCnt != NULL && m_pCellHitsCnt != NULL);
- Vector2<kt_int32s> gridFrom = m_pCellPassCnt->WorldToGrid(rWorldFrom);
- Vector2<kt_int32s> gridTo = m_pCellPassCnt->WorldToGrid(rWorldTo);
- CellUpdater* pCellUpdater = doUpdate ? m_pCellUpdater : NULL;
- m_pCellPassCnt->TraceLine(gridFrom.GetX(), gridFrom.GetY(), gridTo.GetX(), gridTo.GetY(), pCellUpdater);
- // for the end point
- if (isEndPointValid)
- {
- if (m_pCellPassCnt->IsValidGridIndex(gridTo))
- {
- kt_int32s index = m_pCellPassCnt->GridIndex(gridTo, false);
- kt_int32u* pCellPassCntPtr = m_pCellPassCnt->GetDataPointer();
- kt_int32u* pCellHitCntPtr = m_pCellHitsCnt->GetDataPointer();
- // increment cell pass through and hit count
- pCellPassCntPtr[index]++;
- pCellHitCntPtr[index]++;
- if (doUpdate)
- {
- (*m_pCellUpdater)(index);
- }
- }
- }
- return m_pCellPassCnt->IsValidGridIndex(gridTo);
- }
- /**
- * Updates a single cell's value based on the given counters
- * @param pCell
- * @param cellPassCnt
- * @param cellHitCnt
- */
- virtual void UpdateCell(kt_int8u* pCell, kt_int32u cellPassCnt, kt_int32u cellHitCnt)
- {
- if (cellPassCnt > m_pMinPassThrough->GetValue())
- {
- kt_double hitRatio = static_cast<kt_double>(cellHitCnt) / static_cast<kt_double>(cellPassCnt);
- if (hitRatio > m_pOccupancyThreshold->GetValue())
- {
- *pCell = GridStates_Occupied;
- }
- else
- {
- *pCell = GridStates_Free;
- }
- }
- }
- /**
- * Update the grid based on the values in m_pCellHitsCnt and m_pCellPassCnt
- */
- virtual void Update()
- {
- assert(m_pCellPassCnt != NULL && m_pCellHitsCnt != NULL);
- // clear grid
- Clear();
- // set occupancy status of cells
- kt_int8u* pDataPtr = GetDataPointer();
- kt_int32u* pCellPassCntPtr = m_pCellPassCnt->GetDataPointer();
- kt_int32u* pCellHitCntPtr = m_pCellHitsCnt->GetDataPointer();
- kt_int32u nBytes = GetDataSize();
- for (kt_int32u i = 0; i < nBytes; i++, pDataPtr++, pCellPassCntPtr++, pCellHitCntPtr++)
- {
- UpdateCell(pDataPtr, *pCellPassCntPtr, *pCellHitCntPtr);
- }
- }
- /**
- * Resizes the grid (deletes all old data)
- * @param width
- * @param height
- */
- virtual void Resize(kt_int32s width, kt_int32s height)
- {
- Grid<kt_int8u>::Resize(width, height);
- m_pCellPassCnt->Resize(width, height);
- m_pCellHitsCnt->Resize(width, height);
- }
- protected:
- /**
- * Counters of number of times a beam passed through a cell
- */
- Grid<kt_int32u>* m_pCellPassCnt;
- /**
- * Counters of number of times a beam ended at a cell
- */
- Grid<kt_int32u>* m_pCellHitsCnt;
- private:
- /**
- * Restrict the copy constructor
- */
- OccupancyGrid(const OccupancyGrid&);
- /**
- * Restrict the assignment operator
- */
- const OccupancyGrid& operator=(const OccupancyGrid&);
- private:
- CellUpdater* m_pCellUpdater;
- ////////////////////////////////////////////////////////////
- // NOTE: These two values are dependent on the resolution. If the resolution is too small,
- // then not many beams will hit the cell!
- // Number of beams that must pass through a cell before it will be considered to be occupied
- // or unoccupied. This prevents stray beams from messing up the map.
- Parameter<kt_int32u>* m_pMinPassThrough;
- // Minimum ratio of beams hitting cell to beams passing through cell for cell to be marked as occupied
- Parameter<kt_double>* m_pOccupancyThreshold;
- }; // OccupancyGrid
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- /**
- * Dataset info
- * Contains title, author and other information about the dataset
- */
- class DatasetInfo : public Object
- {
- public:
- // @cond EXCLUDE
- KARTO_Object(DatasetInfo)
- // @endcond
- public:
- DatasetInfo()
- : Object()
- {
- m_pTitle = new Parameter<std::string>("Title", "", GetParameterManager());
- m_pAuthor = new Parameter<std::string>("Author", "", GetParameterManager());
- m_pDescription = new Parameter<std::string>("Description", "", GetParameterManager());
- m_pCopyright = new Parameter<std::string>("Copyright", "", GetParameterManager());
- }
- virtual ~DatasetInfo()
- {
- }
- public:
- /**
- * Dataset title
- */
- const std::string& GetTitle() const
- {
- return m_pTitle->GetValue();
- }
- /**
- * Dataset author(s)
- */
- const std::string& GetAuthor() const
- {
- return m_pAuthor->GetValue();
- }
- /**
- * Dataset description
- */
- const std::string& GetDescription() const
- {
- return m_pDescription->GetValue();
- }
- /**
- * Dataset copyrights
- */
- const std::string& GetCopyright() const
- {
- return m_pCopyright->GetValue();
- }
- private:
- DatasetInfo(const DatasetInfo&);
- const DatasetInfo& operator=(const DatasetInfo&);
- private:
- Parameter<std::string>* m_pTitle;
- Parameter<std::string>* m_pAuthor;
- Parameter<std::string>* m_pDescription;
- Parameter<std::string>* m_pCopyright;
- }; // class DatasetInfo
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- /**
- * Karto dataset. Stores LaserRangeFinders and LocalizedRangeScans and manages memory of allocated LaserRangeFinders
- * and LocalizedRangeScans
- */
- class Dataset
- {
- public:
- /**
- * Default constructor
- */
- Dataset()
- : m_pDatasetInfo(NULL)
- {
- }
- /**
- * Destructor
- */
- virtual ~Dataset()
- {
- Clear();
- }
- public:
- /**
- * Adds object to this dataset
- * @param pObject
- */
- void Add(Object* pObject)
- {
- if (pObject != NULL)
- {
- if (dynamic_cast<Sensor*>(pObject))
- {
- Sensor* pSensor = dynamic_cast<Sensor*>(pObject);
- if (pSensor != NULL)
- {
- m_SensorNameLookup[pSensor->GetName()] = pSensor;
- karto::SensorManager::GetInstance()->RegisterSensor(pSensor);
- }
- m_Objects.push_back(pObject);
- }
- else if (dynamic_cast<SensorData*>(pObject))
- {
- SensorData* pSensorData = dynamic_cast<SensorData*>(pObject);
- m_Objects.push_back(pSensorData);
- }
- else if (dynamic_cast<DatasetInfo*>(pObject))
- {
- m_pDatasetInfo = dynamic_cast<DatasetInfo*>(pObject);
- }
- else
- {
- m_Objects.push_back(pObject);
- }
- }
- }
- /**
- * Get sensor states
- * @return sensor state
- */
- inline const ObjectVector& GetObjects() const
- {
- return m_Objects;
- }
- /**
- * Get dataset info
- * @return dataset info
- */
- inline DatasetInfo* GetDatasetInfo()
- {
- return m_pDatasetInfo;
- }
- /**
- * Delete all stored data
- */
- virtual void Clear()
- {
- for (std::map<Name, Sensor*>::iterator iter = m_SensorNameLookup.begin(); iter != m_SensorNameLookup.end(); ++iter)
- {
- karto::SensorManager::GetInstance()->UnregisterSensor(iter->second);
- }
- forEach(ObjectVector, &m_Objects)
- {
- delete *iter;
- }
- m_Objects.clear();
- if (m_pDatasetInfo != NULL)
- {
- delete m_pDatasetInfo;
- m_pDatasetInfo = NULL;
- }
- }
- private:
- std::map<Name, Sensor*> m_SensorNameLookup;
- ObjectVector m_Objects;
- DatasetInfo* m_pDatasetInfo;
- }; // Dataset
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- /**
- * An array that can be resized as long as the size
- * does not exceed the initial capacity
- */
- class LookupArray
- {
- public:
- /**
- * Constructs lookup array
- */
- LookupArray()
- : m_pArray(NULL)
- , m_Capacity(0)
- , m_Size(0)
- {
- }
- /**
- * Destructor
- */
- virtual ~LookupArray()
- {
- assert(m_pArray != NULL);
- delete[] m_pArray;
- m_pArray = NULL;
- }
- public:
- /**
- * Clear array
- */
- void Clear()
- {
- memset(m_pArray, 0, sizeof(kt_int32s) * m_Capacity);
- }
- /**
- * Gets size of array
- * @return array size
- */
- kt_int32u GetSize() const
- {
- return m_Size;
- }
- /**
- * Sets size of array (resize if not big enough)
- * @param size
- */
- void SetSize(kt_int32u size)
- {
- assert(size != 0);
- if (size > m_Capacity)
- {
- if (m_pArray != NULL)
- {
- delete [] m_pArray;
- }
- m_Capacity = size;
- m_pArray = new kt_int32s[m_Capacity];
- }
- m_Size = size;
- }
- /**
- * Gets reference to value at given index
- * @param index
- * @return reference to value at index
- */
- inline kt_int32s& operator [] (kt_int32u index)
- {
- assert(index < m_Size);
- return m_pArray[index];
- }
- /**
- * Gets value at given index
- * @param index
- * @return value at index
- */
- inline kt_int32s operator [] (kt_int32u index) const
- {
- assert(index < m_Size);
- return m_pArray[index];
- }
- /**
- * Gets array pointer
- * @return array pointer
- */
- inline kt_int32s* GetArrayPointer()
- {
- return m_pArray;
- }
- /**
- * Gets array pointer
- * @return array pointer
- */
- inline kt_int32s* GetArrayPointer() const
- {
- return m_pArray;
- }
- private:
- kt_int32s* m_pArray;
- kt_int32u m_Capacity;
- kt_int32u m_Size;
- }; // LookupArray
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- /**
- * Create lookup tables for point readings at varying angles in grid.
- * For each angle, grid indexes are calculated for each range reading.
- * This is to speed up finding best angle/position for a localized range scan
- *
- * Used heavily in mapper and localizer.
- *
- * In the localizer, this is a huge speed up for calculating possible position. For each particle,
- * a probability is calculated. The range scan is the same, but all grid indexes at all possible angles are
- * calculated. So when calculating the particle probability at a specific angle, the index table is used
- * to look up probability in probability grid!
- *
- */
- template<typename T>
- class GridIndexLookup
- {
- public:
- /**
- * Construct a GridIndexLookup with a grid
- * @param pGrid
- */
- GridIndexLookup(Grid<T>* pGrid)
- : m_pGrid(pGrid)
- , m_Capacity(0)
- , m_Size(0)
- , m_ppLookupArray(NULL)
- {
- }
- /**
- * Destructor
- */
- virtual ~GridIndexLookup()
- {
- DestroyArrays();
- }
- public:
- /**
- * Gets the lookup array for a particular angle index
- * @param index
- * @return lookup array
- */
- const LookupArray* GetLookupArray(kt_int32u index) const
- {
- assert(math::IsUpTo(index, m_Size));
- return m_ppLookupArray[index];
- }
- /**
- * Get angles
- * @return std::vector<kt_double>& angles
- */
- const std::vector<kt_double>& GetAngles() const
- {
- return m_Angles;
- }
- /**
- * Compute lookup table of the points of the given scan for the given angular space
- * @param pScan the scan
- * @param angleCenter
- * @param angleOffset computes lookup arrays for the angles within this offset around angleStart
- * @param angleResolution how fine a granularity to compute lookup arrays in the angular space
- */
- void ComputeOffsets(LocalizedRangeScan* pScan,
- kt_double angleCenter,
- kt_double angleOffset,
- kt_double angleResolution)
- {
- assert(angleOffset != 0.0);
- assert(angleResolution != 0.0);
- kt_int32u nAngles = static_cast<kt_int32u>(math::Round(angleOffset * 2.0 / angleResolution) + 1);
- SetSize(nAngles);
- //////////////////////////////////////////////////////
- // convert points into local coordinates of scan pose
- const PointVectorDouble& rPointReadings = pScan->GetPointReadings();
- // compute transform to scan pose
- Transform transform(pScan->GetSensorPose());
- Pose2Vector localPoints;
- const_forEach(PointVectorDouble, &rPointReadings)
- {
- // do inverse transform to get points in local coordinates
- Pose2 vec = transform.InverseTransformPose(Pose2(*iter, 0.0));
- localPoints.push_back(vec);
- }
- //////////////////////////////////////////////////////
- // create lookup array for different angles
- kt_double angle = 0.0;
- kt_double startAngle = angleCenter - angleOffset;
- for (kt_int32u angleIndex = 0; angleIndex < nAngles; angleIndex++)
- {
- angle = startAngle + angleIndex * angleResolution;
- ComputeOffsets(angleIndex, angle, localPoints, pScan);
- }
- // assert(math::DoubleEqual(angle, angleCenter + angleOffset));
- }
- private:
- /**
- * Compute lookup value of points for given angle
- * @param angleIndex
- * @param angle
- * @param rLocalPoints
- */
- void ComputeOffsets(kt_int32u angleIndex, kt_double angle, const Pose2Vector& rLocalPoints, LocalizedRangeScan* pScan)
- {
- m_ppLookupArray[angleIndex]->SetSize(static_cast<kt_int32u>(rLocalPoints.size()));
- m_Angles.at(angleIndex) = angle;
- // set up point array by computing relative offsets to points readings
- // when rotated by given angle
- const Vector2<kt_double>& rGridOffset = m_pGrid->GetCoordinateConverter()->GetOffset();
- kt_double cosine = cos(angle);
- kt_double sine = sin(angle);
- kt_int32u readingIndex = 0;
- kt_int32s* pAngleIndexPointer = m_ppLookupArray[angleIndex]->GetArrayPointer();
- kt_double maxRange = pScan->GetLaserRangeFinder()->GetMaximumRange();
- const_forEach(Pose2Vector, &rLocalPoints)
- {
- const Vector2<kt_double>& rPosition = iter->GetPosition();
- if (std::isnan(pScan->GetRangeReadings()[readingIndex]) || std::isinf(pScan->GetRangeReadings()[readingIndex]))
- {
- pAngleIndexPointer[readingIndex] = INVALID_SCAN;
- readingIndex++;
- continue;
- }
- // counterclockwise rotation and that rotation is about the origin (0, 0).
- Vector2<kt_double> offset;
- offset.SetX(cosine * rPosition.GetX() - sine * rPosition.GetY());
- offset.SetY(sine * rPosition.GetX() + cosine * rPosition.GetY());
- // have to compensate for the grid offset when getting the grid index
- Vector2<kt_int32s> gridPoint = m_pGrid->WorldToGrid(offset + rGridOffset);
- // use base GridIndex to ignore ROI
- kt_int32s lookupIndex = m_pGrid->Grid<T>::GridIndex(gridPoint, false);
- pAngleIndexPointer[readingIndex] = lookupIndex;
- readingIndex++;
- }
- assert(readingIndex == rLocalPoints.size());
- }
- /**
- * Sets size of lookup table (resize if not big enough)
- * @param size
- */
- void SetSize(kt_int32u size)
- {
- assert(size != 0);
- if (size > m_Capacity)
- {
- if (m_ppLookupArray != NULL)
- {
- DestroyArrays();
- }
- m_Capacity = size;
- m_ppLookupArray = new LookupArray*[m_Capacity];
- for (kt_int32u i = 0; i < m_Capacity; i++)
- {
- m_ppLookupArray[i] = new LookupArray();
- }
- }
- m_Size = size;
- m_Angles.resize(size);
- }
- /**
- * Delete the arrays
- */
- void DestroyArrays()
- {
- for (kt_int32u i = 0; i < m_Capacity; i++)
- {
- delete m_ppLookupArray[i];
- }
- delete[] m_ppLookupArray;
- m_ppLookupArray = NULL;
- }
- private:
- Grid<T>* m_pGrid;
- kt_int32u m_Capacity;
- kt_int32u m_Size;
- LookupArray **m_ppLookupArray;
- // for sanity check
- std::vector<kt_double> m_Angles;
- }; // class GridIndexLookup
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- inline Pose2::Pose2(const Pose3& rPose)
- : m_Position(rPose.GetPosition().GetX(), rPose.GetPosition().GetY())
- {
- kt_double t1, t2;
- // calculates heading from orientation
- rPose.GetOrientation().ToEulerAngles(m_Heading, t1, t2);
- }
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////
- // @cond EXCLUDE
- template<typename T>
- inline void Object::SetParameter(const std::string& rName, T value)
- {
- AbstractParameter* pParameter = GetParameter(rName);
- if (pParameter != NULL)
- {
- std::stringstream stream;
- stream << value;
- pParameter->SetValueFromString(stream.str());
- }
- else
- {
- throw Exception("Parameter does not exist: " + rName);
- }
- }
- template<>
- inline void Object::SetParameter(const std::string& rName, kt_bool value)
- {
- AbstractParameter* pParameter = GetParameter(rName);
- if (pParameter != NULL)
- {
- pParameter->SetValueFromString(value ? "true" : "false");
- }
- else
- {
- throw Exception("Parameter does not exist: " + rName);
- }
- }
- // @endcond
- /*@}*/
- } // namespace karto
- #endif // OPEN_KARTO_KARTO_H
|