Karto.h 166 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485868788899091929394959697989910010110210310410510610710810911011111211311411511611711811912012112212312412512612712812913013113213313413513613713813914014114214314414514614714814915015115215315415515615715815916016116216316416516616716816917017117217317417517617717817918018118218318418518618718818919019119219319419519619719819920020120220320420520620720820921021121221321421521621721821922022122222322422522622722822923023123223323423523623723823924024124224324424524624724824925025125225325425525625725825926026126226326426526626726826927027127227327427527627727827928028128228328428528628728828929029129229329429529629729829930030130230330430530630730830931031131231331431531631731831932032132232332432532632732832933033133233333433533633733833934034134234334434534634734834935035135235335435535635735835936036136236336436536636736836937037137237337437537637737837938038138238338438538638738838939039139239339439539639739839940040140240340440540640740840941041141241341441541641741841942042142242342442542642742842943043143243343443543643743843944044144244344444544644744844945045145245345445545645745845946046146246346446546646746846947047147247347447547647747847948048148248348448548648748848949049149249349449549649749849950050150250350450550650750850951051151251351451551651751851952052152252352452552652752852953053153253353453553653753853954054154254354454554654754854955055155255355455555655755855956056156256356456556656756856957057157257357457557657757857958058158258358458558658758858959059159259359459559659759859960060160260360460560660760860961061161261361461561661761861962062162262362462562662762862963063163263363463563663763863964064164264364464564664764864965065165265365465565665765865966066166266366466566666766866967067167267367467567667767867968068168268368468568668768868969069169269369469569669769869970070170270370470570670770870971071171271371471571671771871972072172272372472572672772872973073173273373473573673773873974074174274374474574674774874975075175275375475575675775875976076176276376476576676776876977077177277377477577677777877978078178278378478578678778878979079179279379479579679779879980080180280380480580680780880981081181281381481581681781881982082182282382482582682782882983083183283383483583683783883984084184284384484584684784884985085185285385485585685785885986086186286386486586686786886987087187287387487587687787887988088188288388488588688788888989089189289389489589689789889990090190290390490590690790890991091191291391491591691791891992092192292392492592692792892993093193293393493593693793893994094194294394494594694794894995095195295395495595695795895996096196296396496596696796896997097197297397497597697797897998098198298398498598698798898999099199299399499599699799899910001001100210031004100510061007100810091010101110121013101410151016101710181019102010211022102310241025102610271028102910301031103210331034103510361037103810391040104110421043104410451046104710481049105010511052105310541055105610571058105910601061106210631064106510661067106810691070107110721073107410751076107710781079108010811082108310841085108610871088108910901091109210931094109510961097109810991100110111021103110411051106110711081109111011111112111311141115111611171118111911201121112211231124112511261127112811291130113111321133113411351136113711381139114011411142114311441145114611471148114911501151115211531154115511561157115811591160116111621163116411651166116711681169117011711172117311741175117611771178117911801181118211831184118511861187118811891190119111921193119411951196119711981199120012011202120312041205120612071208120912101211121212131214121512161217121812191220122112221223122412251226122712281229123012311232123312341235123612371238123912401241124212431244124512461247124812491250125112521253125412551256125712581259126012611262126312641265126612671268126912701271127212731274127512761277127812791280128112821283128412851286128712881289129012911292129312941295129612971298129913001301130213031304130513061307130813091310131113121313131413151316131713181319132013211322132313241325132613271328132913301331133213331334133513361337133813391340134113421343134413451346134713481349135013511352135313541355135613571358135913601361136213631364136513661367136813691370137113721373137413751376137713781379138013811382138313841385138613871388138913901391139213931394139513961397139813991400140114021403140414051406140714081409141014111412141314141415141614171418141914201421142214231424142514261427142814291430143114321433143414351436143714381439144014411442144314441445144614471448144914501451145214531454145514561457145814591460146114621463146414651466146714681469147014711472147314741475147614771478147914801481148214831484148514861487148814891490149114921493149414951496149714981499150015011502150315041505150615071508150915101511151215131514151515161517151815191520152115221523152415251526152715281529153015311532153315341535153615371538153915401541154215431544154515461547154815491550155115521553155415551556155715581559156015611562156315641565156615671568156915701571157215731574157515761577157815791580158115821583158415851586158715881589159015911592159315941595159615971598159916001601160216031604160516061607160816091610161116121613161416151616161716181619162016211622162316241625162616271628162916301631163216331634163516361637163816391640164116421643164416451646164716481649165016511652165316541655165616571658165916601661166216631664166516661667166816691670167116721673167416751676167716781679168016811682168316841685168616871688168916901691169216931694169516961697169816991700170117021703170417051706170717081709171017111712171317141715171617171718171917201721172217231724172517261727172817291730173117321733173417351736173717381739174017411742174317441745174617471748174917501751175217531754175517561757175817591760176117621763176417651766176717681769177017711772177317741775177617771778177917801781178217831784178517861787178817891790179117921793179417951796179717981799180018011802180318041805180618071808180918101811181218131814181518161817181818191820182118221823182418251826182718281829183018311832183318341835183618371838183918401841184218431844184518461847184818491850185118521853185418551856185718581859186018611862186318641865186618671868186918701871187218731874187518761877187818791880188118821883188418851886188718881889189018911892189318941895189618971898189919001901190219031904190519061907190819091910191119121913191419151916191719181919192019211922192319241925192619271928192919301931193219331934193519361937193819391940194119421943194419451946194719481949195019511952195319541955195619571958195919601961196219631964196519661967196819691970197119721973197419751976197719781979198019811982198319841985198619871988198919901991199219931994199519961997199819992000200120022003200420052006200720082009201020112012201320142015201620172018201920202021202220232024202520262027202820292030203120322033203420352036203720382039204020412042204320442045204620472048204920502051205220532054205520562057205820592060206120622063206420652066206720682069207020712072207320742075207620772078207920802081208220832084208520862087208820892090209120922093209420952096209720982099210021012102210321042105210621072108210921102111211221132114211521162117211821192120212121222123212421252126212721282129213021312132213321342135213621372138213921402141214221432144214521462147214821492150215121522153215421552156215721582159216021612162216321642165216621672168216921702171217221732174217521762177217821792180218121822183218421852186218721882189219021912192219321942195219621972198219922002201220222032204220522062207220822092210221122122213221422152216221722182219222022212222222322242225222622272228222922302231223222332234223522362237223822392240224122422243224422452246224722482249225022512252225322542255225622572258225922602261226222632264226522662267226822692270227122722273227422752276227722782279228022812282228322842285228622872288228922902291229222932294229522962297229822992300230123022303230423052306230723082309231023112312231323142315231623172318231923202321232223232324232523262327232823292330233123322333233423352336233723382339234023412342234323442345234623472348234923502351235223532354235523562357235823592360236123622363236423652366236723682369237023712372237323742375237623772378237923802381238223832384238523862387238823892390239123922393239423952396239723982399240024012402240324042405240624072408240924102411241224132414241524162417241824192420242124222423242424252426242724282429243024312432243324342435243624372438243924402441244224432444244524462447244824492450245124522453245424552456245724582459246024612462246324642465246624672468246924702471247224732474247524762477247824792480248124822483248424852486248724882489249024912492249324942495249624972498249925002501250225032504250525062507250825092510251125122513251425152516251725182519252025212522252325242525252625272528252925302531253225332534253525362537253825392540254125422543254425452546254725482549255025512552255325542555255625572558255925602561256225632564256525662567256825692570257125722573257425752576257725782579258025812582258325842585258625872588258925902591259225932594259525962597259825992600260126022603260426052606260726082609261026112612261326142615261626172618261926202621262226232624262526262627262826292630263126322633263426352636263726382639264026412642264326442645264626472648264926502651265226532654265526562657265826592660266126622663266426652666266726682669267026712672267326742675267626772678267926802681268226832684268526862687268826892690269126922693269426952696269726982699270027012702270327042705270627072708270927102711271227132714271527162717271827192720272127222723272427252726272727282729273027312732273327342735273627372738273927402741274227432744274527462747274827492750275127522753275427552756275727582759276027612762276327642765276627672768276927702771277227732774277527762777277827792780278127822783278427852786278727882789279027912792279327942795279627972798279928002801280228032804280528062807280828092810281128122813281428152816281728182819282028212822282328242825282628272828282928302831283228332834283528362837283828392840284128422843284428452846284728482849285028512852285328542855285628572858285928602861286228632864286528662867286828692870287128722873287428752876287728782879288028812882288328842885288628872888288928902891289228932894289528962897289828992900290129022903290429052906290729082909291029112912291329142915291629172918291929202921292229232924292529262927292829292930293129322933293429352936293729382939294029412942294329442945294629472948294929502951295229532954295529562957295829592960296129622963296429652966296729682969297029712972297329742975297629772978297929802981298229832984298529862987298829892990299129922993299429952996299729982999300030013002300330043005300630073008300930103011301230133014301530163017301830193020302130223023302430253026302730283029303030313032303330343035303630373038303930403041304230433044304530463047304830493050305130523053305430553056305730583059306030613062306330643065306630673068306930703071307230733074307530763077307830793080308130823083308430853086308730883089309030913092309330943095309630973098309931003101310231033104310531063107310831093110311131123113311431153116311731183119312031213122312331243125312631273128312931303131313231333134313531363137313831393140314131423143314431453146314731483149315031513152315331543155315631573158315931603161316231633164316531663167316831693170317131723173317431753176317731783179318031813182318331843185318631873188318931903191319231933194319531963197319831993200320132023203320432053206320732083209321032113212321332143215321632173218321932203221322232233224322532263227322832293230323132323233323432353236323732383239324032413242324332443245324632473248324932503251325232533254325532563257325832593260326132623263326432653266326732683269327032713272327332743275327632773278327932803281328232833284328532863287328832893290329132923293329432953296329732983299330033013302330333043305330633073308330933103311331233133314331533163317331833193320332133223323332433253326332733283329333033313332333333343335333633373338333933403341334233433344334533463347334833493350335133523353335433553356335733583359336033613362336333643365336633673368336933703371337233733374337533763377337833793380338133823383338433853386338733883389339033913392339333943395339633973398339934003401340234033404340534063407340834093410341134123413341434153416341734183419342034213422342334243425342634273428342934303431343234333434343534363437343834393440344134423443344434453446344734483449345034513452345334543455345634573458345934603461346234633464346534663467346834693470347134723473347434753476347734783479348034813482348334843485348634873488348934903491349234933494349534963497349834993500350135023503350435053506350735083509351035113512351335143515351635173518351935203521352235233524352535263527352835293530353135323533353435353536353735383539354035413542354335443545354635473548354935503551355235533554355535563557355835593560356135623563356435653566356735683569357035713572357335743575357635773578357935803581358235833584358535863587358835893590359135923593359435953596359735983599360036013602360336043605360636073608360936103611361236133614361536163617361836193620362136223623362436253626362736283629363036313632363336343635363636373638363936403641364236433644364536463647364836493650365136523653365436553656365736583659366036613662366336643665366636673668366936703671367236733674367536763677367836793680368136823683368436853686368736883689369036913692369336943695369636973698369937003701370237033704370537063707370837093710371137123713371437153716371737183719372037213722372337243725372637273728372937303731373237333734373537363737373837393740374137423743374437453746374737483749375037513752375337543755375637573758375937603761376237633764376537663767376837693770377137723773377437753776377737783779378037813782378337843785378637873788378937903791379237933794379537963797379837993800380138023803380438053806380738083809381038113812381338143815381638173818381938203821382238233824382538263827382838293830383138323833383438353836383738383839384038413842384338443845384638473848384938503851385238533854385538563857385838593860386138623863386438653866386738683869387038713872387338743875387638773878387938803881388238833884388538863887388838893890389138923893389438953896389738983899390039013902390339043905390639073908390939103911391239133914391539163917391839193920392139223923392439253926392739283929393039313932393339343935393639373938393939403941394239433944394539463947394839493950395139523953395439553956395739583959396039613962396339643965396639673968396939703971397239733974397539763977397839793980398139823983398439853986398739883989399039913992399339943995399639973998399940004001400240034004400540064007400840094010401140124013401440154016401740184019402040214022402340244025402640274028402940304031403240334034403540364037403840394040404140424043404440454046404740484049405040514052405340544055405640574058405940604061406240634064406540664067406840694070407140724073407440754076407740784079408040814082408340844085408640874088408940904091409240934094409540964097409840994100410141024103410441054106410741084109411041114112411341144115411641174118411941204121412241234124412541264127412841294130413141324133413441354136413741384139414041414142414341444145414641474148414941504151415241534154415541564157415841594160416141624163416441654166416741684169417041714172417341744175417641774178417941804181418241834184418541864187418841894190419141924193419441954196419741984199420042014202420342044205420642074208420942104211421242134214421542164217421842194220422142224223422442254226422742284229423042314232423342344235423642374238423942404241424242434244424542464247424842494250425142524253425442554256425742584259426042614262426342644265426642674268426942704271427242734274427542764277427842794280428142824283428442854286428742884289429042914292429342944295429642974298429943004301430243034304430543064307430843094310431143124313431443154316431743184319432043214322432343244325432643274328432943304331433243334334433543364337433843394340434143424343434443454346434743484349435043514352435343544355435643574358435943604361436243634364436543664367436843694370437143724373437443754376437743784379438043814382438343844385438643874388438943904391439243934394439543964397439843994400440144024403440444054406440744084409441044114412441344144415441644174418441944204421442244234424442544264427442844294430443144324433443444354436443744384439444044414442444344444445444644474448444944504451445244534454445544564457445844594460446144624463446444654466446744684469447044714472447344744475447644774478447944804481448244834484448544864487448844894490449144924493449444954496449744984499450045014502450345044505450645074508450945104511451245134514451545164517451845194520452145224523452445254526452745284529453045314532453345344535453645374538453945404541454245434544454545464547454845494550455145524553455445554556455745584559456045614562456345644565456645674568456945704571457245734574457545764577457845794580458145824583458445854586458745884589459045914592459345944595459645974598459946004601460246034604460546064607460846094610461146124613461446154616461746184619462046214622462346244625462646274628462946304631463246334634463546364637463846394640464146424643464446454646464746484649465046514652465346544655465646574658465946604661466246634664466546664667466846694670467146724673467446754676467746784679468046814682468346844685468646874688468946904691469246934694469546964697469846994700470147024703470447054706470747084709471047114712471347144715471647174718471947204721472247234724472547264727472847294730473147324733473447354736473747384739474047414742474347444745474647474748474947504751475247534754475547564757475847594760476147624763476447654766476747684769477047714772477347744775477647774778477947804781478247834784478547864787478847894790479147924793479447954796479747984799480048014802480348044805480648074808480948104811481248134814481548164817481848194820482148224823482448254826482748284829483048314832483348344835483648374838483948404841484248434844484548464847484848494850485148524853485448554856485748584859486048614862486348644865486648674868486948704871487248734874487548764877487848794880488148824883488448854886488748884889489048914892489348944895489648974898489949004901490249034904490549064907490849094910491149124913491449154916491749184919492049214922492349244925492649274928492949304931493249334934493549364937493849394940494149424943494449454946494749484949495049514952495349544955495649574958495949604961496249634964496549664967496849694970497149724973497449754976497749784979498049814982498349844985498649874988498949904991499249934994499549964997499849995000500150025003500450055006500750085009501050115012501350145015501650175018501950205021502250235024502550265027502850295030503150325033503450355036503750385039504050415042504350445045504650475048504950505051505250535054505550565057505850595060506150625063506450655066506750685069507050715072507350745075507650775078507950805081508250835084508550865087508850895090509150925093509450955096509750985099510051015102510351045105510651075108510951105111511251135114511551165117511851195120512151225123512451255126512751285129513051315132513351345135513651375138513951405141514251435144514551465147514851495150515151525153515451555156515751585159516051615162516351645165516651675168516951705171517251735174517551765177517851795180518151825183518451855186518751885189519051915192519351945195519651975198519952005201520252035204520552065207520852095210521152125213521452155216521752185219522052215222522352245225522652275228522952305231523252335234523552365237523852395240524152425243524452455246524752485249525052515252525352545255525652575258525952605261526252635264526552665267526852695270527152725273527452755276527752785279528052815282528352845285528652875288528952905291529252935294529552965297529852995300530153025303530453055306530753085309531053115312531353145315531653175318531953205321532253235324532553265327532853295330533153325333533453355336533753385339534053415342534353445345534653475348534953505351535253535354535553565357535853595360536153625363536453655366536753685369537053715372537353745375537653775378537953805381538253835384538553865387538853895390539153925393539453955396539753985399540054015402540354045405540654075408540954105411541254135414541554165417541854195420542154225423542454255426542754285429543054315432543354345435543654375438543954405441544254435444544554465447544854495450545154525453545454555456545754585459546054615462546354645465546654675468546954705471547254735474547554765477547854795480548154825483548454855486548754885489549054915492549354945495549654975498549955005501550255035504550555065507550855095510551155125513551455155516551755185519552055215522552355245525552655275528552955305531553255335534553555365537553855395540554155425543554455455546554755485549555055515552555355545555555655575558555955605561556255635564556555665567556855695570557155725573557455755576557755785579558055815582558355845585558655875588558955905591559255935594559555965597559855995600560156025603560456055606560756085609561056115612561356145615561656175618561956205621562256235624562556265627562856295630563156325633563456355636563756385639564056415642564356445645564656475648564956505651565256535654565556565657565856595660566156625663566456655666566756685669567056715672567356745675567656775678567956805681568256835684568556865687568856895690569156925693569456955696569756985699570057015702570357045705570657075708570957105711571257135714571557165717571857195720572157225723572457255726572757285729573057315732573357345735573657375738573957405741574257435744574557465747574857495750575157525753575457555756575757585759576057615762576357645765576657675768576957705771577257735774577557765777577857795780578157825783578457855786578757885789579057915792579357945795579657975798579958005801580258035804580558065807580858095810581158125813581458155816581758185819582058215822582358245825582658275828582958305831583258335834583558365837583858395840584158425843584458455846584758485849585058515852585358545855585658575858585958605861586258635864586558665867586858695870587158725873587458755876587758785879588058815882588358845885588658875888588958905891589258935894589558965897589858995900590159025903590459055906590759085909591059115912591359145915591659175918591959205921592259235924592559265927592859295930593159325933593459355936593759385939594059415942594359445945594659475948594959505951595259535954595559565957595859595960596159625963596459655966596759685969597059715972597359745975597659775978597959805981598259835984598559865987598859895990599159925993599459955996599759985999600060016002600360046005600660076008600960106011601260136014601560166017601860196020602160226023602460256026602760286029603060316032603360346035603660376038603960406041604260436044604560466047604860496050605160526053605460556056605760586059606060616062606360646065606660676068606960706071607260736074607560766077607860796080608160826083608460856086608760886089609060916092609360946095609660976098609961006101610261036104610561066107610861096110611161126113611461156116611761186119612061216122612361246125612661276128612961306131613261336134613561366137613861396140614161426143614461456146614761486149615061516152615361546155615661576158615961606161616261636164616561666167616861696170617161726173617461756176617761786179618061816182618361846185618661876188618961906191619261936194619561966197619861996200620162026203620462056206620762086209621062116212621362146215621662176218621962206221622262236224622562266227622862296230623162326233623462356236623762386239624062416242624362446245624662476248624962506251625262536254625562566257625862596260626162626263626462656266626762686269627062716272627362746275627662776278627962806281628262836284628562866287628862896290629162926293629462956296629762986299630063016302630363046305630663076308630963106311631263136314631563166317631863196320632163226323632463256326632763286329633063316332633363346335633663376338633963406341634263436344634563466347634863496350635163526353635463556356635763586359636063616362636363646365636663676368636963706371637263736374637563766377637863796380638163826383638463856386638763886389639063916392639363946395639663976398639964006401640264036404640564066407640864096410641164126413641464156416641764186419642064216422642364246425642664276428642964306431643264336434643564366437643864396440644164426443644464456446644764486449645064516452645364546455645664576458645964606461646264636464646564666467646864696470647164726473647464756476647764786479648064816482648364846485648664876488648964906491649264936494649564966497649864996500650165026503650465056506650765086509651065116512651365146515651665176518651965206521652265236524652565266527652865296530653165326533653465356536653765386539654065416542654365446545654665476548654965506551655265536554655565566557655865596560656165626563656465656566656765686569657065716572657365746575657665776578657965806581658265836584658565866587658865896590659165926593659465956596659765986599660066016602660366046605660666076608660966106611661266136614661566166617661866196620662166226623662466256626662766286629663066316632663366346635663666376638
  1. /*
  2. * Copyright 2010 SRI International
  3. *
  4. * This program is free software: you can redistribute it and/or modify
  5. * it under the terms of the GNU Lesser General Public License as published by
  6. * the Free Software Foundation, either version 3 of the License, or
  7. * (at your option) any later version.
  8. *
  9. * This program is distributed in the hope that it will be useful,
  10. * but WITHOUT ANY WARRANTY; without even the implied warranty of
  11. * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  12. * GNU Lesser General Public License for more details.
  13. *
  14. * You should have received a copy of the GNU Lesser General Public License
  15. * along with this program. If not, see <http://www.gnu.org/licenses/>.
  16. */
  17. #ifndef OPEN_KARTO_KARTO_H
  18. #define OPEN_KARTO_KARTO_H
  19. #include <string>
  20. #include <fstream>
  21. #include <limits>
  22. #include <algorithm>
  23. #include <map>
  24. #include <vector>
  25. #include <iostream>
  26. #include <iomanip>
  27. #include <sstream>
  28. #include <stdexcept>
  29. #include <math.h>
  30. #include <float.h>
  31. #include <stdio.h>
  32. #include <assert.h>
  33. #include <string.h>
  34. #include <boost/thread.hpp>
  35. #ifdef USE_POCO
  36. #include <Poco/Mutex.h>
  37. #endif
  38. #include <open_karto/Math.h>
  39. #include <open_karto/Macros.h>
  40. #define KARTO_Object(name) \
  41. virtual const char* GetClassName() const { return #name; } \
  42. virtual kt_objecttype GetObjectType() const { return ObjectType_##name; }
  43. typedef kt_int32u kt_objecttype;
  44. const kt_objecttype ObjectType_None = 0x00000000;
  45. const kt_objecttype ObjectType_Sensor = 0x00001000;
  46. const kt_objecttype ObjectType_SensorData = 0x00002000;
  47. const kt_objecttype ObjectType_CustomData = 0x00004000;
  48. const kt_objecttype ObjectType_Misc = 0x10000000;
  49. const kt_objecttype ObjectType_Drive = ObjectType_Sensor | 0x01;
  50. const kt_objecttype ObjectType_LaserRangeFinder = ObjectType_Sensor | 0x02;
  51. const kt_objecttype ObjectType_Camera = ObjectType_Sensor | 0x04;
  52. const kt_objecttype ObjectType_DrivePose = ObjectType_SensorData | 0x01;
  53. const kt_objecttype ObjectType_LaserRangeScan = ObjectType_SensorData | 0x02;
  54. const kt_objecttype ObjectType_LocalizedRangeScan = ObjectType_SensorData | 0x04;
  55. const kt_objecttype ObjectType_CameraImage = ObjectType_SensorData | 0x08;
  56. const kt_objecttype ObjectType_LocalizedRangeScanWithPoints = ObjectType_SensorData | 0x16;
  57. const kt_objecttype ObjectType_Header = ObjectType_Misc | 0x01;
  58. const kt_objecttype ObjectType_Parameters = ObjectType_Misc | 0x02;
  59. const kt_objecttype ObjectType_DatasetInfo = ObjectType_Misc | 0x04;
  60. const kt_objecttype ObjectType_Module = ObjectType_Misc | 0x08;
  61. namespace karto
  62. {
  63. /**
  64. * \defgroup OpenKarto OpenKarto Module
  65. */
  66. /*@{*/
  67. /**
  68. * Exception class. All exceptions thrown from Karto will inherit from this class or be of this class
  69. */
  70. class KARTO_EXPORT Exception
  71. {
  72. public:
  73. /**
  74. * Constructor with exception message
  75. * @param rMessage exception message (default: "Karto Exception")
  76. * @param errorCode error code (default: 0)
  77. */
  78. Exception(const std::string& rMessage = "Karto Exception", kt_int32s errorCode = 0)
  79. : m_Message(rMessage)
  80. , m_ErrorCode(errorCode)
  81. {
  82. }
  83. /**
  84. * Copy constructor
  85. */
  86. Exception(const Exception& rException)
  87. : m_Message(rException.m_Message)
  88. , m_ErrorCode(rException.m_ErrorCode)
  89. {
  90. }
  91. /**
  92. * Destructor
  93. */
  94. virtual ~Exception()
  95. {
  96. }
  97. public:
  98. /**
  99. * Assignment operator
  100. */
  101. Exception& operator = (const Exception& rException)
  102. {
  103. m_Message = rException.m_Message;
  104. m_ErrorCode = rException.m_ErrorCode;
  105. return *this;
  106. }
  107. public:
  108. /**
  109. * Gets the exception message
  110. * @return error message as string
  111. */
  112. const std::string& GetErrorMessage() const
  113. {
  114. return m_Message;
  115. }
  116. /**
  117. * Gets error code
  118. * @return error code
  119. */
  120. kt_int32s GetErrorCode()
  121. {
  122. return m_ErrorCode;
  123. }
  124. public:
  125. /**
  126. * Write exception to output stream
  127. * @param rStream output stream
  128. * @param rException exception to write
  129. */
  130. friend KARTO_EXPORT std::ostream& operator << (std::ostream& rStream, Exception& rException);
  131. private:
  132. std::string m_Message;
  133. kt_int32s m_ErrorCode;
  134. }; // class Exception
  135. ////////////////////////////////////////////////////////////////////////////////////////
  136. ////////////////////////////////////////////////////////////////////////////////////////
  137. ////////////////////////////////////////////////////////////////////////////////////////
  138. /**
  139. * Subclass this class to make a non-copyable class (copy
  140. * constructor and assignment operator are private)
  141. */
  142. class KARTO_EXPORT NonCopyable
  143. {
  144. private:
  145. NonCopyable(const NonCopyable&);
  146. const NonCopyable& operator=(const NonCopyable&);
  147. protected:
  148. NonCopyable()
  149. {
  150. }
  151. virtual ~NonCopyable()
  152. {
  153. }
  154. }; // class NonCopyable
  155. ////////////////////////////////////////////////////////////////////////////////////////
  156. ////////////////////////////////////////////////////////////////////////////////////////
  157. ////////////////////////////////////////////////////////////////////////////////////////
  158. /**
  159. * Singleton class ensures only one instance of T is created
  160. */
  161. template <class T>
  162. class Singleton
  163. {
  164. public:
  165. /**
  166. * Constructor
  167. */
  168. Singleton()
  169. : m_pPointer(NULL)
  170. {
  171. }
  172. /**
  173. * Destructor
  174. */
  175. virtual ~Singleton()
  176. {
  177. delete m_pPointer;
  178. }
  179. /**
  180. * Gets the singleton
  181. * @return singleton
  182. */
  183. T* Get()
  184. {
  185. #ifdef USE_POCO
  186. Poco::FastMutex::ScopedLock lock(m_Mutex);
  187. #endif
  188. if (m_pPointer == NULL)
  189. {
  190. m_pPointer = new T;
  191. }
  192. return m_pPointer;
  193. }
  194. private:
  195. T* m_pPointer;
  196. #ifdef USE_POCO
  197. Poco::FastMutex m_Mutex;
  198. #endif
  199. private:
  200. Singleton(const Singleton&);
  201. const Singleton& operator=(const Singleton&);
  202. };
  203. ////////////////////////////////////////////////////////////////////////////////////////
  204. ////////////////////////////////////////////////////////////////////////////////////////
  205. ////////////////////////////////////////////////////////////////////////////////////////
  206. /**
  207. * Functor
  208. */
  209. class KARTO_EXPORT Functor
  210. {
  211. public:
  212. /**
  213. * Functor function
  214. */
  215. virtual void operator() (kt_int32u) {};
  216. }; // Functor
  217. ////////////////////////////////////////////////////////////////////////////////////////
  218. ////////////////////////////////////////////////////////////////////////////////////////
  219. ////////////////////////////////////////////////////////////////////////////////////////
  220. class AbstractParameter;
  221. /**
  222. * Type declaration of AbstractParameter vector
  223. */
  224. typedef std::vector<AbstractParameter*> ParameterVector;
  225. /**
  226. * Parameter manager.
  227. */
  228. class KARTO_EXPORT ParameterManager : public NonCopyable
  229. {
  230. public:
  231. /**
  232. * Default constructor
  233. */
  234. ParameterManager()
  235. {
  236. }
  237. /**
  238. * Destructor
  239. */
  240. virtual ~ParameterManager()
  241. {
  242. Clear();
  243. }
  244. public:
  245. /**
  246. * Adds the parameter to this manager
  247. * @param pParameter
  248. */
  249. void Add(AbstractParameter* pParameter);
  250. /**
  251. * Gets the parameter of the given name
  252. * @param rName
  253. * @return parameter of given name
  254. */
  255. AbstractParameter* Get(const std::string& rName)
  256. {
  257. if (m_ParameterLookup.find(rName) != m_ParameterLookup.end())
  258. {
  259. return m_ParameterLookup[rName];
  260. }
  261. std::cout << "Unknown parameter: " << rName << std::endl;
  262. return NULL;
  263. }
  264. /**
  265. * Clears the manager of all parameters
  266. */
  267. void Clear();
  268. /**
  269. * Gets all parameters
  270. * @return vector of all parameters
  271. */
  272. inline const ParameterVector& GetParameterVector() const
  273. {
  274. return m_Parameters;
  275. }
  276. public:
  277. /**
  278. * Gets the parameter with the given name
  279. * @param rName
  280. * @return parameter of given name
  281. */
  282. AbstractParameter* operator() (const std::string& rName)
  283. {
  284. return Get(rName);
  285. }
  286. private:
  287. ParameterManager(const ParameterManager&);
  288. const ParameterManager& operator=(const ParameterManager&);
  289. private:
  290. ParameterVector m_Parameters;
  291. std::map<std::string, AbstractParameter*> m_ParameterLookup;
  292. }; // ParameterManager
  293. ////////////////////////////////////////////////////////////////////////////////////////
  294. ////////////////////////////////////////////////////////////////////////////////////////
  295. ////////////////////////////////////////////////////////////////////////////////////////
  296. // valid names
  297. // 'Test' -- no scope
  298. // '/Test' -- no scope will be parsed to 'Test'
  299. // '/scope/Test' - 'scope' scope and 'Test' name
  300. // '/scope/name/Test' - 'scope/name' scope and 'Test' name
  301. //
  302. class Name
  303. {
  304. public:
  305. /**
  306. * Constructor
  307. */
  308. Name()
  309. {
  310. }
  311. /**
  312. * Constructor
  313. */
  314. Name(const std::string& rName)
  315. {
  316. Parse(rName);
  317. }
  318. /**
  319. * Constructor
  320. */
  321. Name(const Name& rOther)
  322. : m_Name(rOther.m_Name)
  323. , m_Scope(rOther.m_Scope)
  324. {
  325. }
  326. /**
  327. * Destructor
  328. */
  329. virtual ~Name()
  330. {
  331. }
  332. public:
  333. /**
  334. * Gets the name of this name
  335. * @return name
  336. */
  337. inline const std::string& GetName() const
  338. {
  339. return m_Name;
  340. }
  341. /**
  342. * Sets the name
  343. * @param rName name
  344. */
  345. inline void SetName(const std::string& rName)
  346. {
  347. std::string::size_type pos = rName.find_last_of('/');
  348. if (pos != 0 && pos != std::string::npos)
  349. {
  350. throw Exception("Name can't contain a scope!");
  351. }
  352. m_Name = rName;
  353. }
  354. /**
  355. * Gets the scope of this name
  356. * @return scope
  357. */
  358. inline const std::string& GetScope() const
  359. {
  360. return m_Scope;
  361. }
  362. /**
  363. * Sets the scope of this name
  364. * @param rScope scope
  365. */
  366. inline void SetScope(const std::string& rScope)
  367. {
  368. m_Scope = rScope;
  369. }
  370. /**
  371. * Returns a string representation of this name
  372. * @return string representation of this name
  373. */
  374. inline std::string ToString() const
  375. {
  376. if (m_Scope == "")
  377. {
  378. return m_Name;
  379. }
  380. else
  381. {
  382. std::string name;
  383. name.append("/");
  384. name.append(m_Scope);
  385. name.append("/");
  386. name.append(m_Name);
  387. return name;
  388. }
  389. }
  390. public:
  391. /**
  392. * Assignment operator.
  393. */
  394. Name& operator = (const Name& rOther)
  395. {
  396. if (&rOther != this)
  397. {
  398. m_Name = rOther.m_Name;
  399. m_Scope = rOther.m_Scope;
  400. }
  401. return *this;
  402. }
  403. /**
  404. * Equality operator.
  405. */
  406. kt_bool operator == (const Name& rOther) const
  407. {
  408. return (m_Name == rOther.m_Name) && (m_Scope == rOther.m_Scope);
  409. }
  410. /**
  411. * Inequality operator.
  412. */
  413. kt_bool operator != (const Name& rOther) const
  414. {
  415. return !(*this == rOther);
  416. }
  417. /**
  418. * Less than operator.
  419. */
  420. kt_bool operator < (const Name& rOther) const
  421. {
  422. return ToString() < rOther.ToString();
  423. }
  424. /**
  425. * Write Name onto output stream
  426. * @param rStream output stream
  427. * @param rName to write
  428. */
  429. friend inline std::ostream& operator << (std::ostream& rStream, const Name& rName)
  430. {
  431. rStream << rName.ToString();
  432. return rStream;
  433. }
  434. private:
  435. /**
  436. * Parse the given string into a Name object
  437. * @param rName name
  438. */
  439. void Parse(const std::string& rName)
  440. {
  441. std::string::size_type pos = rName.find_last_of('/');
  442. if (pos == std::string::npos)
  443. {
  444. m_Name = rName;
  445. }
  446. else
  447. {
  448. m_Scope = rName.substr(0, pos);
  449. m_Name = rName.substr(pos+1, rName.size());
  450. // remove '/' from m_Scope if first!!
  451. if (m_Scope.size() > 0 && m_Scope[0] == '/')
  452. {
  453. m_Scope = m_Scope.substr(1, m_Scope.size());
  454. }
  455. }
  456. }
  457. /**
  458. * Validates the given string as a Name
  459. * @param rName name
  460. */
  461. void Validate(const std::string& rName)
  462. {
  463. if (rName.empty())
  464. {
  465. return;
  466. }
  467. char c = rName[0];
  468. if (IsValidFirst(c))
  469. {
  470. for (size_t i = 1; i < rName.size(); ++i)
  471. {
  472. c = rName[i];
  473. if (!IsValid(c))
  474. {
  475. throw Exception("Invalid character in name. Valid characters must be within the ranges A-Z, a-z, 0-9, '/', '_' and '-'.");
  476. }
  477. }
  478. }
  479. else
  480. {
  481. throw Exception("Invalid first character in name. Valid characters must be within the ranges A-Z, a-z, and '/'.");
  482. }
  483. }
  484. /**
  485. * Whether the character is valid as a first character (alphanumeric or /)
  486. * @param c character
  487. * @return true if the character is a valid first character
  488. */
  489. inline kt_bool IsValidFirst(char c)
  490. {
  491. return (isalpha(c) || c == '/');
  492. }
  493. /**
  494. * Whether the character is a valid character (alphanumeric, /, _, or -)
  495. * @param c character
  496. * @return true if the character is valid
  497. */
  498. inline kt_bool IsValid(char c)
  499. {
  500. return (isalnum(c) || c == '/' || c == '_' || c == '-');
  501. }
  502. private:
  503. std::string m_Name;
  504. std::string m_Scope;
  505. };
  506. ////////////////////////////////////////////////////////////////////////////////////////
  507. ////////////////////////////////////////////////////////////////////////////////////////
  508. ////////////////////////////////////////////////////////////////////////////////////////
  509. /**
  510. * Abstract base class for Karto objects.
  511. */
  512. class KARTO_EXPORT Object : public NonCopyable
  513. {
  514. public:
  515. /**
  516. * Default constructor
  517. */
  518. Object();
  519. /**
  520. * Constructs an object with the given name
  521. * @param rName
  522. */
  523. Object(const Name& rName);
  524. /**
  525. * Default constructor
  526. */
  527. virtual ~Object();
  528. public:
  529. /**
  530. * Gets the name of this object
  531. * @return name
  532. */
  533. inline const Name& GetName() const
  534. {
  535. return m_Name;
  536. }
  537. /**
  538. * Gets the class name of this object
  539. * @return class name
  540. */
  541. virtual const char* GetClassName() const = 0;
  542. /**
  543. * Gets the type of this object
  544. * @return object type
  545. */
  546. virtual kt_objecttype GetObjectType() const = 0;
  547. /**
  548. * Gets the parameter manager of this dataset
  549. * @return parameter manager
  550. */
  551. virtual inline ParameterManager* GetParameterManager()
  552. {
  553. return m_pParameterManager;
  554. }
  555. /**
  556. * Gets the named parameter
  557. * @param rName name of parameter
  558. * @return parameter
  559. */
  560. inline AbstractParameter* GetParameter(const std::string& rName) const
  561. {
  562. return m_pParameterManager->Get(rName);
  563. }
  564. /**
  565. * Sets the parameter with the given name with the given value
  566. * @param rName name
  567. * @param value value
  568. */
  569. template<typename T>
  570. inline void SetParameter(const std::string& rName, T value);
  571. /**
  572. * Gets all parameters
  573. * @return parameters
  574. */
  575. inline const ParameterVector& GetParameters() const
  576. {
  577. return m_pParameterManager->GetParameterVector();
  578. }
  579. private:
  580. Object(const Object&);
  581. const Object& operator=(const Object&);
  582. private:
  583. Name m_Name;
  584. ParameterManager* m_pParameterManager;
  585. };
  586. /**
  587. * Type declaration of Object vector
  588. */
  589. typedef std::vector<Object*> ObjectVector;
  590. ////////////////////////////////////////////////////////////////////////////////////////
  591. ////////////////////////////////////////////////////////////////////////////////////////
  592. ////////////////////////////////////////////////////////////////////////////////////////
  593. /**
  594. * Whether the object is a sensor
  595. * @param pObject object
  596. * @return whether the object is a sensor
  597. */
  598. inline kt_bool IsSensor(Object* pObject)
  599. {
  600. return (pObject->GetObjectType() & ObjectType_Sensor) == ObjectType_Sensor;
  601. }
  602. /**
  603. * Whether the object is sensor data
  604. * @param pObject object
  605. * @return whether the object is sensor data
  606. */
  607. inline kt_bool IsSensorData(Object* pObject)
  608. {
  609. return (pObject->GetObjectType() & ObjectType_SensorData) == ObjectType_SensorData;
  610. }
  611. /**
  612. * Whether the object is a laser range finder
  613. * @param pObject object
  614. * @return whether the object is a laser range finder
  615. */
  616. inline kt_bool IsLaserRangeFinder(Object* pObject)
  617. {
  618. return (pObject->GetObjectType() & ObjectType_LaserRangeFinder) == ObjectType_LaserRangeFinder;
  619. }
  620. /**
  621. * Whether the object is a localized range scan
  622. * @param pObject object
  623. * @return whether the object is a localized range scan
  624. */
  625. inline kt_bool IsLocalizedRangeScan(Object* pObject)
  626. {
  627. return (pObject->GetObjectType() & ObjectType_LocalizedRangeScan) == ObjectType_LocalizedRangeScan;
  628. }
  629. /**
  630. * Whether the object is a localized range scan with points
  631. * @param pObject object
  632. * @return whether the object is a localized range scan with points
  633. */
  634. inline kt_bool IsLocalizedRangeScanWithPoints(Object* pObject)
  635. {
  636. return (pObject->GetObjectType() & ObjectType_LocalizedRangeScanWithPoints) == ObjectType_LocalizedRangeScanWithPoints;
  637. }
  638. /**
  639. * Whether the object is a Parameters object
  640. * @param pObject object
  641. * @return whether the object is a Parameters object
  642. */
  643. inline kt_bool IsParameters(Object* pObject)
  644. {
  645. return (pObject->GetObjectType() & ObjectType_Parameters) == ObjectType_Parameters;
  646. }
  647. /**
  648. * Whether the object is a DatasetInfo object
  649. * @param pObject object
  650. * @return whether the object is a DatasetInfo object
  651. */
  652. inline kt_bool IsDatasetInfo(Object* pObject)
  653. {
  654. return (pObject->GetObjectType() & ObjectType_DatasetInfo) == ObjectType_DatasetInfo;
  655. }
  656. ////////////////////////////////////////////////////////////////////////////////////////
  657. ////////////////////////////////////////////////////////////////////////////////////////
  658. ////////////////////////////////////////////////////////////////////////////////////////
  659. /**
  660. * Abstract base class for Karto modules.
  661. */
  662. class KARTO_EXPORT Module : public Object
  663. {
  664. public:
  665. // @cond EXCLUDE
  666. KARTO_Object(Module)
  667. // @endcond
  668. public:
  669. /**
  670. * Construct a Module
  671. * @param rName module name
  672. */
  673. Module(const std::string& rName);
  674. /**
  675. * Destructor
  676. */
  677. virtual ~Module();
  678. public:
  679. /**
  680. * Reset the module
  681. */
  682. virtual void Reset() = 0;
  683. /**
  684. * Process an Object
  685. */
  686. virtual kt_bool Process(karto::Object*)
  687. {
  688. return false;
  689. }
  690. private:
  691. Module(const Module&);
  692. const Module& operator=(const Module&);
  693. };
  694. ////////////////////////////////////////////////////////////////////////////////////////
  695. ////////////////////////////////////////////////////////////////////////////////////////
  696. ////////////////////////////////////////////////////////////////////////////////////////
  697. /**
  698. * Represents a size (width, height) in 2-dimensional real space.
  699. */
  700. template<typename T>
  701. class Size2
  702. {
  703. public:
  704. /**
  705. * Default constructor
  706. */
  707. Size2()
  708. : m_Width(0)
  709. , m_Height(0)
  710. {
  711. }
  712. /**
  713. * Constructor initializing point location
  714. * @param width
  715. * @param height
  716. */
  717. Size2(T width, T height)
  718. : m_Width(width)
  719. , m_Height(height)
  720. {
  721. }
  722. /**
  723. * Copy constructor
  724. * @param rOther
  725. */
  726. Size2(const Size2& rOther)
  727. : m_Width(rOther.m_Width)
  728. , m_Height(rOther.m_Height)
  729. {
  730. }
  731. public:
  732. /**
  733. * Gets the width
  734. * @return the width
  735. */
  736. inline const T GetWidth() const
  737. {
  738. return m_Width;
  739. }
  740. /**
  741. * Sets the width
  742. * @param width
  743. */
  744. inline void SetWidth(T width)
  745. {
  746. m_Width = width;
  747. }
  748. /**
  749. * Gets the height
  750. * @return the height
  751. */
  752. inline const T GetHeight() const
  753. {
  754. return m_Height;
  755. }
  756. /**
  757. * Sets the height
  758. * @param height
  759. */
  760. inline void SetHeight(T height)
  761. {
  762. m_Height = height;
  763. }
  764. /**
  765. * Assignment operator
  766. */
  767. inline Size2& operator = (const Size2& rOther)
  768. {
  769. m_Width = rOther.m_Width;
  770. m_Height = rOther.m_Height;
  771. return(*this);
  772. }
  773. /**
  774. * Equality operator
  775. */
  776. inline kt_bool operator == (const Size2& rOther) const
  777. {
  778. return (m_Width == rOther.m_Width && m_Height == rOther.m_Height);
  779. }
  780. /**
  781. * Inequality operator
  782. */
  783. inline kt_bool operator != (const Size2& rOther) const
  784. {
  785. return (m_Width != rOther.m_Width || m_Height != rOther.m_Height);
  786. }
  787. /**
  788. * Write Size2 onto output stream
  789. * @param rStream output stream
  790. * @param rSize to write
  791. */
  792. friend inline std::ostream& operator << (std::ostream& rStream, const Size2& rSize)
  793. {
  794. rStream << "(" << rSize.m_Width << ", " << rSize.m_Height << ")";
  795. return rStream;
  796. }
  797. private:
  798. T m_Width;
  799. T m_Height;
  800. }; // Size2<T>
  801. ////////////////////////////////////////////////////////////////////////////////////////
  802. ////////////////////////////////////////////////////////////////////////////////////////
  803. ////////////////////////////////////////////////////////////////////////////////////////
  804. /**
  805. * Represents a vector (x, y) in 2-dimensional real space.
  806. */
  807. template<typename T>
  808. class Vector2
  809. {
  810. public:
  811. /**
  812. * Default constructor
  813. */
  814. Vector2()
  815. {
  816. m_Values[0] = 0;
  817. m_Values[1] = 0;
  818. }
  819. /**
  820. * Constructor initializing vector location
  821. * @param x
  822. * @param y
  823. */
  824. Vector2(T x, T y)
  825. {
  826. m_Values[0] = x;
  827. m_Values[1] = y;
  828. }
  829. public:
  830. /**
  831. * Gets the x-coordinate of this vector2
  832. * @return the x-coordinate of the vector2
  833. */
  834. inline const T& GetX() const
  835. {
  836. return m_Values[0];
  837. }
  838. /**
  839. * Sets the x-coordinate of this vector2
  840. * @param x the x-coordinate of the vector2
  841. */
  842. inline void SetX(const T& x)
  843. {
  844. m_Values[0] = x;
  845. }
  846. /**
  847. * Gets the y-coordinate of this vector2
  848. * @return the y-coordinate of the vector2
  849. */
  850. inline const T& GetY() const
  851. {
  852. return m_Values[1];
  853. }
  854. /**
  855. * Sets the y-coordinate of this vector2
  856. * @param y the y-coordinate of the vector2
  857. */
  858. inline void SetY(const T& y)
  859. {
  860. m_Values[1] = y;
  861. }
  862. /**
  863. * Floor point operator
  864. * @param rOther
  865. */
  866. inline void MakeFloor(const Vector2& rOther)
  867. {
  868. if ( rOther.m_Values[0] < m_Values[0] ) m_Values[0] = rOther.m_Values[0];
  869. if ( rOther.m_Values[1] < m_Values[1] ) m_Values[1] = rOther.m_Values[1];
  870. }
  871. /**
  872. * Ceiling point operator
  873. * @param rOther
  874. */
  875. inline void MakeCeil(const Vector2& rOther)
  876. {
  877. if ( rOther.m_Values[0] > m_Values[0] ) m_Values[0] = rOther.m_Values[0];
  878. if ( rOther.m_Values[1] > m_Values[1] ) m_Values[1] = rOther.m_Values[1];
  879. }
  880. /**
  881. * Returns the square of the length of the vector
  882. * @return square of the length of the vector
  883. */
  884. inline kt_double SquaredLength() const
  885. {
  886. return math::Square(m_Values[0]) + math::Square(m_Values[1]);
  887. }
  888. /**
  889. * Returns the length of the vector (x and y).
  890. * @return length of the vector
  891. */
  892. inline kt_double Length() const
  893. {
  894. return sqrt(SquaredLength());
  895. }
  896. /**
  897. * Returns the square distance to the given vector
  898. * @returns square distance to the given vector
  899. */
  900. inline kt_double SquaredDistance(const Vector2& rOther) const
  901. {
  902. return (*this - rOther).SquaredLength();
  903. }
  904. /**
  905. * Gets the distance to the other vector2
  906. * @param rOther
  907. * @return distance to other vector2
  908. */
  909. inline kt_double Distance(const Vector2& rOther) const
  910. {
  911. return sqrt(SquaredDistance(rOther));
  912. }
  913. public:
  914. /**
  915. * In place Vector2 addition.
  916. */
  917. inline void operator += (const Vector2& rOther)
  918. {
  919. m_Values[0] += rOther.m_Values[0];
  920. m_Values[1] += rOther.m_Values[1];
  921. }
  922. /**
  923. * In place Vector2 subtraction.
  924. */
  925. inline void operator -= (const Vector2& rOther)
  926. {
  927. m_Values[0] -= rOther.m_Values[0];
  928. m_Values[1] -= rOther.m_Values[1];
  929. }
  930. /**
  931. * Addition operator
  932. * @param rOther
  933. * @return vector resulting from adding this vector with the given vector
  934. */
  935. inline const Vector2 operator + (const Vector2& rOther) const
  936. {
  937. return Vector2(m_Values[0] + rOther.m_Values[0], m_Values[1] + rOther.m_Values[1]);
  938. }
  939. /**
  940. * Subtraction operator
  941. * @param rOther
  942. * @return vector resulting from subtracting this vector from the given vector
  943. */
  944. inline const Vector2 operator - (const Vector2& rOther) const
  945. {
  946. return Vector2(m_Values[0] - rOther.m_Values[0], m_Values[1] - rOther.m_Values[1]);
  947. }
  948. /**
  949. * In place scalar division operator
  950. * @param scalar
  951. */
  952. inline void operator /= (T scalar)
  953. {
  954. m_Values[0] /= scalar;
  955. m_Values[1] /= scalar;
  956. }
  957. /**
  958. * Divides a Vector2
  959. * @param scalar
  960. * @return scalar product
  961. */
  962. inline const Vector2 operator / (T scalar) const
  963. {
  964. return Vector2(m_Values[0] / scalar, m_Values[1] / scalar);
  965. }
  966. /**
  967. * Computes the dot product between the two vectors
  968. * @param rOther
  969. * @return dot product
  970. */
  971. inline kt_double operator * (const Vector2& rOther) const
  972. {
  973. return m_Values[0] * rOther.m_Values[0] + m_Values[1] * rOther.m_Values[1];
  974. }
  975. /**
  976. * Scales the vector by the given scalar
  977. * @param scalar
  978. */
  979. inline const Vector2 operator * (T scalar) const
  980. {
  981. return Vector2(m_Values[0] * scalar, m_Values[1] * scalar);
  982. }
  983. /**
  984. * Subtract the vector by the given scalar
  985. * @param scalar
  986. */
  987. inline const Vector2 operator - (T scalar) const
  988. {
  989. return Vector2(m_Values[0] - scalar, m_Values[1] - scalar);
  990. }
  991. /**
  992. * In place scalar multiplication operator
  993. * @param scalar
  994. */
  995. inline void operator *= (T scalar)
  996. {
  997. m_Values[0] *= scalar;
  998. m_Values[1] *= scalar;
  999. }
  1000. /**
  1001. * Equality operator returns true if the corresponding x, y values of each Vector2 are the same values.
  1002. * @param rOther
  1003. */
  1004. inline kt_bool operator == (const Vector2& rOther) const
  1005. {
  1006. return (m_Values[0] == rOther.m_Values[0] && m_Values[1] == rOther.m_Values[1]);
  1007. }
  1008. /**
  1009. * Inequality operator returns true if any of the corresponding x, y values of each Vector2 not the same.
  1010. * @param rOther
  1011. */
  1012. inline kt_bool operator != (const Vector2& rOther) const
  1013. {
  1014. return (m_Values[0] != rOther.m_Values[0] || m_Values[1] != rOther.m_Values[1]);
  1015. }
  1016. /**
  1017. * Less than operator
  1018. * @param rOther
  1019. * @return true if left vector is less than right vector
  1020. */
  1021. inline kt_bool operator < (const Vector2& rOther) const
  1022. {
  1023. if (m_Values[0] < rOther.m_Values[0])
  1024. return true;
  1025. else if (m_Values[0] > rOther.m_Values[0])
  1026. return false;
  1027. else
  1028. return (m_Values[1] < rOther.m_Values[1]);
  1029. }
  1030. /**
  1031. * Write Vector2 onto output stream
  1032. * @param rStream output stream
  1033. * @param rVector to write
  1034. */
  1035. friend inline std::ostream& operator << (std::ostream& rStream, const Vector2& rVector)
  1036. {
  1037. rStream << rVector.GetX() << " " << rVector.GetY();
  1038. return rStream;
  1039. }
  1040. /**
  1041. * Read Vector2 from input stream
  1042. * @param rStream input stream
  1043. */
  1044. friend inline std::istream& operator >> (std::istream& rStream, const Vector2& /*rVector*/)
  1045. {
  1046. // Implement me!! TODO(lucbettaieb): What the what? Do I need to implement this?
  1047. return rStream;
  1048. }
  1049. private:
  1050. T m_Values[2];
  1051. }; // Vector2<T>
  1052. /**
  1053. * Type declaration of Vector2<kt_double> vector
  1054. */
  1055. typedef std::vector< Vector2<kt_double> > PointVectorDouble;
  1056. ////////////////////////////////////////////////////////////////////////////////////////
  1057. ////////////////////////////////////////////////////////////////////////////////////////
  1058. ////////////////////////////////////////////////////////////////////////////////////////
  1059. /**
  1060. * Represents a vector (x, y, z) in 3-dimensional real space.
  1061. */
  1062. template<typename T>
  1063. class Vector3
  1064. {
  1065. public:
  1066. /**
  1067. * Default constructor
  1068. */
  1069. Vector3()
  1070. {
  1071. m_Values[0] = 0;
  1072. m_Values[1] = 0;
  1073. m_Values[2] = 0;
  1074. }
  1075. /**
  1076. * Constructor initializing point location
  1077. * @param x
  1078. * @param y
  1079. * @param z
  1080. */
  1081. Vector3(T x, T y, T z)
  1082. {
  1083. m_Values[0] = x;
  1084. m_Values[1] = y;
  1085. m_Values[2] = z;
  1086. }
  1087. /**
  1088. * Copy constructor
  1089. * @param rOther
  1090. */
  1091. Vector3(const Vector3& rOther)
  1092. {
  1093. m_Values[0] = rOther.m_Values[0];
  1094. m_Values[1] = rOther.m_Values[1];
  1095. m_Values[2] = rOther.m_Values[2];
  1096. }
  1097. public:
  1098. /**
  1099. * Gets the x-component of this vector
  1100. * @return x-component
  1101. */
  1102. inline const T& GetX() const
  1103. {
  1104. return m_Values[0];
  1105. }
  1106. /**
  1107. * Sets the x-component of this vector
  1108. * @param x
  1109. */
  1110. inline void SetX(const T& x)
  1111. {
  1112. m_Values[0] = x;
  1113. }
  1114. /**
  1115. * Gets the y-component of this vector
  1116. * @return y-component
  1117. */
  1118. inline const T& GetY() const
  1119. {
  1120. return m_Values[1];
  1121. }
  1122. /**
  1123. * Sets the y-component of this vector
  1124. * @param y
  1125. */
  1126. inline void SetY(const T& y)
  1127. {
  1128. m_Values[1] = y;
  1129. }
  1130. /**
  1131. * Gets the z-component of this vector
  1132. * @return z-component
  1133. */
  1134. inline const T& GetZ() const
  1135. {
  1136. return m_Values[2];
  1137. }
  1138. /**
  1139. * Sets the z-component of this vector
  1140. * @param z
  1141. */
  1142. inline void SetZ(const T& z)
  1143. {
  1144. m_Values[2] = z;
  1145. }
  1146. /**
  1147. * Floor vector operator
  1148. * @param rOther Vector3d
  1149. */
  1150. inline void MakeFloor(const Vector3& rOther)
  1151. {
  1152. if (rOther.m_Values[0] < m_Values[0]) m_Values[0] = rOther.m_Values[0];
  1153. if (rOther.m_Values[1] < m_Values[1]) m_Values[1] = rOther.m_Values[1];
  1154. if (rOther.m_Values[2] < m_Values[2]) m_Values[2] = rOther.m_Values[2];
  1155. }
  1156. /**
  1157. * Ceiling vector operator
  1158. * @param rOther Vector3d
  1159. */
  1160. inline void MakeCeil(const Vector3& rOther)
  1161. {
  1162. if (rOther.m_Values[0] > m_Values[0]) m_Values[0] = rOther.m_Values[0];
  1163. if (rOther.m_Values[1] > m_Values[1]) m_Values[1] = rOther.m_Values[1];
  1164. if (rOther.m_Values[2] > m_Values[2]) m_Values[2] = rOther.m_Values[2];
  1165. }
  1166. /**
  1167. * Returns the square of the length of the vector
  1168. * @return square of the length of the vector
  1169. */
  1170. inline kt_double SquaredLength() const
  1171. {
  1172. return math::Square(m_Values[0]) + math::Square(m_Values[1]) + math::Square(m_Values[2]);
  1173. }
  1174. /**
  1175. * Returns the length of the vector.
  1176. * @return Length of the vector
  1177. */
  1178. inline kt_double Length() const
  1179. {
  1180. return sqrt(SquaredLength());
  1181. }
  1182. /**
  1183. * Returns a string representation of this vector
  1184. * @return string representation of this vector
  1185. */
  1186. inline std::string ToString() const
  1187. {
  1188. std::stringstream converter;
  1189. converter.precision(std::numeric_limits<double>::digits10);
  1190. converter << GetX() << " " << GetY() << " " << GetZ();
  1191. return converter.str();
  1192. }
  1193. public:
  1194. /**
  1195. * Assignment operator
  1196. */
  1197. inline Vector3& operator = (const Vector3& rOther)
  1198. {
  1199. m_Values[0] = rOther.m_Values[0];
  1200. m_Values[1] = rOther.m_Values[1];
  1201. m_Values[2] = rOther.m_Values[2];
  1202. return *this;
  1203. }
  1204. /**
  1205. * Binary vector add.
  1206. * @param rOther
  1207. * @return vector sum
  1208. */
  1209. inline const Vector3 operator + (const Vector3& rOther) const
  1210. {
  1211. return Vector3(m_Values[0] + rOther.m_Values[0],
  1212. m_Values[1] + rOther.m_Values[1],
  1213. m_Values[2] + rOther.m_Values[2]);
  1214. }
  1215. /**
  1216. * Binary vector add.
  1217. * @param scalar
  1218. * @return sum
  1219. */
  1220. inline const Vector3 operator + (kt_double scalar) const
  1221. {
  1222. return Vector3(m_Values[0] + scalar,
  1223. m_Values[1] + scalar,
  1224. m_Values[2] + scalar);
  1225. }
  1226. /**
  1227. * Binary vector subtract.
  1228. * @param rOther
  1229. * @return vector difference
  1230. */
  1231. inline const Vector3 operator - (const Vector3& rOther) const
  1232. {
  1233. return Vector3(m_Values[0] - rOther.m_Values[0],
  1234. m_Values[1] - rOther.m_Values[1],
  1235. m_Values[2] - rOther.m_Values[2]);
  1236. }
  1237. /**
  1238. * Binary vector subtract.
  1239. * @param scalar
  1240. * @return difference
  1241. */
  1242. inline const Vector3 operator - (kt_double scalar) const
  1243. {
  1244. return Vector3(m_Values[0] - scalar, m_Values[1] - scalar, m_Values[2] - scalar);
  1245. }
  1246. /**
  1247. * Scales the vector by the given scalar
  1248. * @param scalar
  1249. */
  1250. inline const Vector3 operator * (T scalar) const
  1251. {
  1252. return Vector3(m_Values[0] * scalar, m_Values[1] * scalar, m_Values[2] * scalar);
  1253. }
  1254. /**
  1255. * Equality operator returns true if the corresponding x, y, z values of each Vector3 are the same values.
  1256. * @param rOther
  1257. */
  1258. inline kt_bool operator == (const Vector3& rOther) const
  1259. {
  1260. return (m_Values[0] == rOther.m_Values[0] &&
  1261. m_Values[1] == rOther.m_Values[1] &&
  1262. m_Values[2] == rOther.m_Values[2]);
  1263. }
  1264. /**
  1265. * Inequality operator returns true if any of the corresponding x, y, z values of each Vector3 not the same.
  1266. * @param rOther
  1267. */
  1268. inline kt_bool operator != (const Vector3& rOther) const
  1269. {
  1270. return (m_Values[0] != rOther.m_Values[0] ||
  1271. m_Values[1] != rOther.m_Values[1] ||
  1272. m_Values[2] != rOther.m_Values[2]);
  1273. }
  1274. /**
  1275. * Write Vector3 onto output stream
  1276. * @param rStream output stream
  1277. * @param rVector to write
  1278. */
  1279. friend inline std::ostream& operator << (std::ostream& rStream, const Vector3& rVector)
  1280. {
  1281. rStream << rVector.ToString();
  1282. return rStream;
  1283. }
  1284. /**
  1285. * Read Vector3 from input stream
  1286. * @param rStream input stream
  1287. */
  1288. friend inline std::istream& operator >> (std::istream& rStream, const Vector3& /*rVector*/)
  1289. {
  1290. // Implement me!!
  1291. return rStream;
  1292. }
  1293. private:
  1294. T m_Values[3];
  1295. }; // Vector3
  1296. ////////////////////////////////////////////////////////////////////////////////////////
  1297. ////////////////////////////////////////////////////////////////////////////////////////
  1298. ////////////////////////////////////////////////////////////////////////////////////////
  1299. /**
  1300. * Defines an orientation as a quaternion rotation using the positive Z axis as the zero reference.
  1301. * <BR>
  1302. * Q = w + ix + jy + kz <BR>
  1303. * w = c_1 * c_2 * c_3 - s_1 * s_2 * s_3 <BR>
  1304. * x = s_1 * s_2 * c_3 + c_1 * c_2 * s_3 <BR>
  1305. * y = s_1 * c_2 * c_3 + c_1 * s_2 * s_3 <BR>
  1306. * z = c_1 * s_2 * c_3 - s_1 * c_2 * s_3 <BR>
  1307. * where <BR>
  1308. * c_1 = cos(theta/2) <BR>
  1309. * c_2 = cos(phi/2) <BR>
  1310. * c_3 = cos(psi/2) <BR>
  1311. * s_1 = sin(theta/2) <BR>
  1312. * s_2 = sin(phi/2) <BR>
  1313. * s_3 = sin(psi/2) <BR>
  1314. * and <BR>
  1315. * theta is the angle of rotation about the Y axis measured from the Z axis. <BR>
  1316. * phi is the angle of rotation about the Z axis measured from the X axis. <BR>
  1317. * psi is the angle of rotation about the X axis measured from the Y axis. <BR>
  1318. * (All angles are right-handed.)
  1319. */
  1320. class Quaternion
  1321. {
  1322. public:
  1323. /**
  1324. * Create a quaternion with default (x=0, y=0, z=0, w=1) values
  1325. */
  1326. inline Quaternion()
  1327. {
  1328. m_Values[0] = 0.0;
  1329. m_Values[1] = 0.0;
  1330. m_Values[2] = 0.0;
  1331. m_Values[3] = 1.0;
  1332. }
  1333. /**
  1334. * Create a quaternion using x, y, z, w values.
  1335. * @param x
  1336. * @param y
  1337. * @param z
  1338. * @param w
  1339. */
  1340. inline Quaternion(kt_double x, kt_double y, kt_double z, kt_double w)
  1341. {
  1342. m_Values[0] = x;
  1343. m_Values[1] = y;
  1344. m_Values[2] = z;
  1345. m_Values[3] = w;
  1346. }
  1347. /**
  1348. * Copy constructor
  1349. */
  1350. inline Quaternion(const Quaternion& rQuaternion)
  1351. {
  1352. m_Values[0] = rQuaternion.m_Values[0];
  1353. m_Values[1] = rQuaternion.m_Values[1];
  1354. m_Values[2] = rQuaternion.m_Values[2];
  1355. m_Values[3] = rQuaternion.m_Values[3];
  1356. }
  1357. public:
  1358. /**
  1359. * Returns the X-value
  1360. * @return Return the X-value of the quaternion
  1361. */
  1362. inline kt_double GetX() const
  1363. {
  1364. return m_Values[0];
  1365. }
  1366. /**
  1367. * Sets the X-value
  1368. * @param x X-value of the quaternion
  1369. */
  1370. inline void SetX(kt_double x)
  1371. {
  1372. m_Values[0] = x;
  1373. }
  1374. /**
  1375. * Returns the Y-value
  1376. * @return Return the Y-value of the quaternion
  1377. */
  1378. inline kt_double GetY() const
  1379. {
  1380. return m_Values[1];
  1381. }
  1382. /**
  1383. * Sets the Y-value
  1384. * @param y Y-value of the quaternion
  1385. */
  1386. inline void SetY(kt_double y)
  1387. {
  1388. m_Values[1] = y;
  1389. }
  1390. /**
  1391. * Returns the Z-value
  1392. * @return Return the Z-value of the quaternion
  1393. */
  1394. inline kt_double GetZ() const
  1395. {
  1396. return m_Values[2];
  1397. }
  1398. /**
  1399. * Sets the Z-value
  1400. * @param z Z-value of the quaternion
  1401. */
  1402. inline void SetZ(kt_double z)
  1403. {
  1404. m_Values[2] = z;
  1405. }
  1406. /**
  1407. * Returns the W-value
  1408. * @return Return the W-value of the quaternion
  1409. */
  1410. inline kt_double GetW() const
  1411. {
  1412. return m_Values[3];
  1413. }
  1414. /**
  1415. * Sets the W-value
  1416. * @param w W-value of the quaternion
  1417. */
  1418. inline void SetW(kt_double w)
  1419. {
  1420. m_Values[3] = w;
  1421. }
  1422. /**
  1423. * Converts this quaternion into Euler angles
  1424. * Source: http://www.euclideanspace.com/maths/geometry/rotations/conversions/quaternionToEuler/index.htm
  1425. * @param rYaw
  1426. * @param rPitch
  1427. * @param rRoll
  1428. */
  1429. void ToEulerAngles(kt_double& rYaw, kt_double& rPitch, kt_double& rRoll) const
  1430. {
  1431. kt_double test = m_Values[0] * m_Values[1] + m_Values[2] * m_Values[3];
  1432. if (test > 0.499)
  1433. {
  1434. // singularity at north pole
  1435. rYaw = 2 * atan2(m_Values[0], m_Values[3]);;
  1436. rPitch = KT_PI_2;
  1437. rRoll = 0;
  1438. }
  1439. else if (test < -0.499)
  1440. {
  1441. // singularity at south pole
  1442. rYaw = -2 * atan2(m_Values[0], m_Values[3]);
  1443. rPitch = -KT_PI_2;
  1444. rRoll = 0;
  1445. }
  1446. else
  1447. {
  1448. kt_double sqx = m_Values[0] * m_Values[0];
  1449. kt_double sqy = m_Values[1] * m_Values[1];
  1450. kt_double sqz = m_Values[2] * m_Values[2];
  1451. rYaw = atan2(2 * m_Values[1] * m_Values[3] - 2 * m_Values[0] * m_Values[2], 1 - 2 * sqy - 2 * sqz);
  1452. rPitch = asin(2 * test);
  1453. rRoll = atan2(2 * m_Values[0] * m_Values[3] - 2 * m_Values[1] * m_Values[2], 1 - 2 * sqx - 2 * sqz);
  1454. }
  1455. }
  1456. /**
  1457. * Set x,y,z,w values of the quaternion based on Euler angles.
  1458. * Source: http://www.euclideanspace.com/maths/geometry/rotations/conversions/eulerToQuaternion/index.htm
  1459. * @param yaw
  1460. * @param pitch
  1461. * @param roll
  1462. */
  1463. void FromEulerAngles(kt_double yaw, kt_double pitch, kt_double roll)
  1464. {
  1465. kt_double angle;
  1466. angle = yaw * 0.5;
  1467. kt_double cYaw = cos(angle);
  1468. kt_double sYaw = sin(angle);
  1469. angle = pitch * 0.5;
  1470. kt_double cPitch = cos(angle);
  1471. kt_double sPitch = sin(angle);
  1472. angle = roll * 0.5;
  1473. kt_double cRoll = cos(angle);
  1474. kt_double sRoll = sin(angle);
  1475. m_Values[0] = sYaw * sPitch * cRoll + cYaw * cPitch * sRoll;
  1476. m_Values[1] = sYaw * cPitch * cRoll + cYaw * sPitch * sRoll;
  1477. m_Values[2] = cYaw * sPitch * cRoll - sYaw * cPitch * sRoll;
  1478. m_Values[3] = cYaw * cPitch * cRoll - sYaw * sPitch * sRoll;
  1479. }
  1480. /**
  1481. * Assignment operator
  1482. * @param rQuaternion
  1483. */
  1484. inline Quaternion& operator = (const Quaternion& rQuaternion)
  1485. {
  1486. m_Values[0] = rQuaternion.m_Values[0];
  1487. m_Values[1] = rQuaternion.m_Values[1];
  1488. m_Values[2] = rQuaternion.m_Values[2];
  1489. m_Values[3] = rQuaternion.m_Values[3];
  1490. return(*this);
  1491. }
  1492. /**
  1493. * Equality operator returns true if the corresponding x, y, z, w values of each quaternion are the same values.
  1494. * @param rOther
  1495. */
  1496. inline kt_bool operator == (const Quaternion& rOther) const
  1497. {
  1498. return (m_Values[0] == rOther.m_Values[0] &&
  1499. m_Values[1] == rOther.m_Values[1] &&
  1500. m_Values[2] == rOther.m_Values[2] &&
  1501. m_Values[3] == rOther.m_Values[3]);
  1502. }
  1503. /**
  1504. * Inequality operator returns true if any of the corresponding x, y, z, w values of each quaternion not the same.
  1505. * @param rOther
  1506. */
  1507. inline kt_bool operator != (const Quaternion& rOther) const
  1508. {
  1509. return (m_Values[0] != rOther.m_Values[0] ||
  1510. m_Values[1] != rOther.m_Values[1] ||
  1511. m_Values[2] != rOther.m_Values[2] ||
  1512. m_Values[3] != rOther.m_Values[3]);
  1513. }
  1514. /**
  1515. * Write this quaternion onto output stream
  1516. * @param rStream output stream
  1517. * @param rQuaternion
  1518. */
  1519. friend inline std::ostream& operator << (std::ostream& rStream, const Quaternion& rQuaternion)
  1520. {
  1521. rStream << rQuaternion.m_Values[0] << " "
  1522. << rQuaternion.m_Values[1] << " "
  1523. << rQuaternion.m_Values[2] << " "
  1524. << rQuaternion.m_Values[3];
  1525. return rStream;
  1526. }
  1527. private:
  1528. kt_double m_Values[4];
  1529. };
  1530. ////////////////////////////////////////////////////////////////////////////////////////
  1531. ////////////////////////////////////////////////////////////////////////////////////////
  1532. ////////////////////////////////////////////////////////////////////////////////////////
  1533. /**
  1534. * Stores x, y, width and height that represents the location and size of a rectangle
  1535. * (x, y) is at bottom left in mapper!
  1536. */
  1537. template<typename T>
  1538. class Rectangle2
  1539. {
  1540. public:
  1541. /**
  1542. * Default constructor
  1543. */
  1544. Rectangle2()
  1545. {
  1546. }
  1547. /**
  1548. * Constructor initializing rectangle parameters
  1549. * @param x x-coordinate of left edge of rectangle
  1550. * @param y y-coordinate of bottom edge of rectangle
  1551. * @param width width of rectangle
  1552. * @param height height of rectangle
  1553. */
  1554. Rectangle2(T x, T y, T width, T height)
  1555. : m_Position(x, y)
  1556. , m_Size(width, height)
  1557. {
  1558. }
  1559. /**
  1560. * Constructor initializing rectangle parameters
  1561. * @param rPosition (x,y)-coordinate of rectangle
  1562. * @param rSize Size of the rectangle
  1563. */
  1564. Rectangle2(const Vector2<T>& rPosition, const Size2<T>& rSize)
  1565. : m_Position(rPosition)
  1566. , m_Size(rSize)
  1567. {
  1568. }
  1569. /**
  1570. * Copy constructor
  1571. */
  1572. Rectangle2(const Rectangle2& rOther)
  1573. : m_Position(rOther.m_Position)
  1574. , m_Size(rOther.m_Size)
  1575. {
  1576. }
  1577. public:
  1578. /**
  1579. * Gets the x-coordinate of the left edge of this rectangle
  1580. * @return the x-coordinate of the left edge of this rectangle
  1581. */
  1582. inline T GetX() const
  1583. {
  1584. return m_Position.GetX();
  1585. }
  1586. /**
  1587. * Sets the x-coordinate of the left edge of this rectangle
  1588. * @param x the x-coordinate of the left edge of this rectangle
  1589. */
  1590. inline void SetX(T x)
  1591. {
  1592. m_Position.SetX(x);
  1593. }
  1594. /**
  1595. * Gets the y-coordinate of the bottom edge of this rectangle
  1596. * @return the y-coordinate of the bottom edge of this rectangle
  1597. */
  1598. inline T GetY() const
  1599. {
  1600. return m_Position.GetY();
  1601. }
  1602. /**
  1603. * Sets the y-coordinate of the bottom edge of this rectangle
  1604. * @param y the y-coordinate of the bottom edge of this rectangle
  1605. */
  1606. inline void SetY(T y)
  1607. {
  1608. m_Position.SetY(y);
  1609. }
  1610. /**
  1611. * Gets the width of this rectangle
  1612. * @return the width of this rectangle
  1613. */
  1614. inline T GetWidth() const
  1615. {
  1616. return m_Size.GetWidth();
  1617. }
  1618. /**
  1619. * Sets the width of this rectangle
  1620. * @param width the width of this rectangle
  1621. */
  1622. inline void SetWidth(T width)
  1623. {
  1624. m_Size.SetWidth(width);
  1625. }
  1626. /**
  1627. * Gets the height of this rectangle
  1628. * @return the height of this rectangle
  1629. */
  1630. inline T GetHeight() const
  1631. {
  1632. return m_Size.GetHeight();
  1633. }
  1634. /**
  1635. * Sets the height of this rectangle
  1636. * @param height the height of this rectangle
  1637. */
  1638. inline void SetHeight(T height)
  1639. {
  1640. m_Size.SetHeight(height);
  1641. }
  1642. /**
  1643. * Gets the position of this rectangle
  1644. * @return the position of this rectangle
  1645. */
  1646. inline const Vector2<T>& GetPosition() const
  1647. {
  1648. return m_Position;
  1649. }
  1650. /**
  1651. * Sets the position of this rectangle
  1652. * @param rX x
  1653. * @param rY y
  1654. */
  1655. inline void SetPosition(const T& rX, const T& rY)
  1656. {
  1657. m_Position = Vector2<T>(rX, rY);
  1658. }
  1659. /**
  1660. * Sets the position of this rectangle
  1661. * @param rPosition position
  1662. */
  1663. inline void SetPosition(const Vector2<T>& rPosition)
  1664. {
  1665. m_Position = rPosition;
  1666. }
  1667. /**
  1668. * Gets the size of this rectangle
  1669. * @return the size of this rectangle
  1670. */
  1671. inline const Size2<T>& GetSize() const
  1672. {
  1673. return m_Size;
  1674. }
  1675. /**
  1676. * Sets the size of this rectangle
  1677. * @param rSize size
  1678. */
  1679. inline void SetSize(const Size2<T>& rSize)
  1680. {
  1681. m_Size = rSize;
  1682. }
  1683. /**
  1684. * Gets the center of this rectangle
  1685. * @return the center of this rectangle
  1686. */
  1687. inline const Vector2<T> GetCenter() const
  1688. {
  1689. return Vector2<T>(m_Position.GetX() + m_Size.GetWidth() * 0.5, m_Position.GetY() + m_Size.GetHeight() * 0.5);
  1690. }
  1691. public:
  1692. /**
  1693. * Assignment operator
  1694. */
  1695. Rectangle2& operator = (const Rectangle2& rOther)
  1696. {
  1697. m_Position = rOther.m_Position;
  1698. m_Size = rOther.m_Size;
  1699. return *this;
  1700. }
  1701. /**
  1702. * Equality operator
  1703. */
  1704. inline kt_bool operator == (const Rectangle2& rOther) const
  1705. {
  1706. return (m_Position == rOther.m_Position && m_Size == rOther.m_Size);
  1707. }
  1708. /**
  1709. * Inequality operator
  1710. */
  1711. inline kt_bool operator != (const Rectangle2& rOther) const
  1712. {
  1713. return (m_Position != rOther.m_Position || m_Size != rOther.m_Size);
  1714. }
  1715. private:
  1716. Vector2<T> m_Position;
  1717. Size2<T> m_Size;
  1718. }; // Rectangle2
  1719. ////////////////////////////////////////////////////////////////////////////////////////
  1720. ////////////////////////////////////////////////////////////////////////////////////////
  1721. ////////////////////////////////////////////////////////////////////////////////////////
  1722. class Pose3;
  1723. /**
  1724. * Defines a position (x, y) in 2-dimensional space and heading.
  1725. */
  1726. class Pose2
  1727. {
  1728. public:
  1729. /**
  1730. * Default Constructor
  1731. */
  1732. Pose2()
  1733. : m_Heading(0.0)
  1734. {
  1735. }
  1736. /**
  1737. * Constructor initializing pose parameters
  1738. * @param rPosition position
  1739. * @param heading heading
  1740. **/
  1741. Pose2(const Vector2<kt_double>& rPosition, kt_double heading)
  1742. : m_Position(rPosition)
  1743. , m_Heading(heading)
  1744. {
  1745. }
  1746. /**
  1747. * Constructor initializing pose parameters
  1748. * @param x x-coordinate
  1749. * @param y y-coordinate
  1750. * @param heading heading
  1751. **/
  1752. Pose2(kt_double x, kt_double y, kt_double heading)
  1753. : m_Position(x, y)
  1754. , m_Heading(heading)
  1755. {
  1756. }
  1757. /**
  1758. * Constructs a Pose2 object from a Pose3.
  1759. */
  1760. Pose2(const Pose3& rPose);
  1761. /**
  1762. * Copy constructor
  1763. */
  1764. Pose2(const Pose2& rOther)
  1765. : m_Position(rOther.m_Position)
  1766. , m_Heading(rOther.m_Heading)
  1767. {
  1768. }
  1769. public:
  1770. /**
  1771. * Returns the x-coordinate
  1772. * @return the x-coordinate of the pose
  1773. */
  1774. inline kt_double GetX() const
  1775. {
  1776. return m_Position.GetX();
  1777. }
  1778. /**
  1779. * Sets the x-coordinate
  1780. * @param x the x-coordinate of the pose
  1781. */
  1782. inline void SetX(kt_double x)
  1783. {
  1784. m_Position.SetX(x);
  1785. }
  1786. /**
  1787. * Returns the y-coordinate
  1788. * @return the y-coordinate of the pose
  1789. */
  1790. inline kt_double GetY() const
  1791. {
  1792. return m_Position.GetY();
  1793. }
  1794. /**
  1795. * Sets the y-coordinate
  1796. * @param y the y-coordinate of the pose
  1797. */
  1798. inline void SetY(kt_double y)
  1799. {
  1800. m_Position.SetY(y);
  1801. }
  1802. /**
  1803. * Returns the position
  1804. * @return the position of the pose
  1805. */
  1806. inline const Vector2<kt_double>& GetPosition() const
  1807. {
  1808. return m_Position;
  1809. }
  1810. /**
  1811. * Sets the position
  1812. * @param rPosition of the pose
  1813. */
  1814. inline void SetPosition(const Vector2<kt_double>& rPosition)
  1815. {
  1816. m_Position = rPosition;
  1817. }
  1818. /**
  1819. * Returns the heading of the pose (in radians)
  1820. * @return the heading of the pose
  1821. */
  1822. inline kt_double GetHeading() const
  1823. {
  1824. return m_Heading;
  1825. }
  1826. /**
  1827. * Sets the heading
  1828. * @param heading of the pose
  1829. */
  1830. inline void SetHeading(kt_double heading)
  1831. {
  1832. m_Heading = heading;
  1833. }
  1834. /**
  1835. * Return the squared distance between two Pose2
  1836. * @return squared distance
  1837. */
  1838. inline kt_double SquaredDistance(const Pose2& rOther) const
  1839. {
  1840. return m_Position.SquaredDistance(rOther.m_Position);
  1841. }
  1842. public:
  1843. /**
  1844. * Assignment operator
  1845. */
  1846. inline Pose2& operator = (const Pose2& rOther)
  1847. {
  1848. m_Position = rOther.m_Position;
  1849. m_Heading = rOther.m_Heading;
  1850. return *this;
  1851. }
  1852. /**
  1853. * Equality operator
  1854. */
  1855. inline kt_bool operator == (const Pose2& rOther) const
  1856. {
  1857. return (m_Position == rOther.m_Position && m_Heading == rOther.m_Heading);
  1858. }
  1859. /**
  1860. * Inequality operator
  1861. */
  1862. inline kt_bool operator != (const Pose2& rOther) const
  1863. {
  1864. return (m_Position != rOther.m_Position || m_Heading != rOther.m_Heading);
  1865. }
  1866. /**
  1867. * In place Pose2 add.
  1868. */
  1869. inline void operator += (const Pose2& rOther)
  1870. {
  1871. m_Position += rOther.m_Position;
  1872. m_Heading = math::NormalizeAngle(m_Heading + rOther.m_Heading);
  1873. }
  1874. /**
  1875. * Binary Pose2 add
  1876. * @param rOther
  1877. * @return Pose2 sum
  1878. */
  1879. inline Pose2 operator + (const Pose2& rOther) const
  1880. {
  1881. return Pose2(m_Position + rOther.m_Position, math::NormalizeAngle(m_Heading + rOther.m_Heading));
  1882. }
  1883. /**
  1884. * Binary Pose2 subtract
  1885. * @param rOther
  1886. * @return Pose2 difference
  1887. */
  1888. inline Pose2 operator - (const Pose2& rOther) const
  1889. {
  1890. return Pose2(m_Position - rOther.m_Position, math::NormalizeAngle(m_Heading - rOther.m_Heading));
  1891. }
  1892. /**
  1893. * Read pose from input stream
  1894. * @param rStream input stream
  1895. */
  1896. friend inline std::istream& operator >> (std::istream& rStream, const Pose2& /*rPose*/)
  1897. {
  1898. // Implement me!!
  1899. return rStream;
  1900. }
  1901. /**
  1902. * Write this pose onto output stream
  1903. * @param rStream output stream
  1904. * @param rPose to read
  1905. */
  1906. friend inline std::ostream& operator << (std::ostream& rStream, const Pose2& rPose)
  1907. {
  1908. rStream << rPose.m_Position.GetX() << " " << rPose.m_Position.GetY() << " " << rPose.m_Heading;
  1909. return rStream;
  1910. }
  1911. private:
  1912. Vector2<kt_double> m_Position;
  1913. kt_double m_Heading;
  1914. }; // Pose2
  1915. /**
  1916. * Type declaration of Pose2 vector
  1917. */
  1918. typedef std::vector< Pose2 > Pose2Vector;
  1919. ////////////////////////////////////////////////////////////////////////////////////////
  1920. ////////////////////////////////////////////////////////////////////////////////////////
  1921. ////////////////////////////////////////////////////////////////////////////////////////
  1922. /**
  1923. * Defines a position and orientation in 3-dimensional space.
  1924. * Karto uses a right-handed coordinate system with X, Y as the 2-D ground plane and X is forward and Y is left.
  1925. * Values in Vector3 used to define position must have units of meters.
  1926. * The value of angle when defining orientation in two dimensions must be in units of radians.
  1927. * The definition of orientation in three dimensions uses quaternions.
  1928. */
  1929. class Pose3
  1930. {
  1931. public:
  1932. /**
  1933. * Default constructor
  1934. */
  1935. Pose3()
  1936. {
  1937. }
  1938. /**
  1939. * Create a new Pose3 object from the given position.
  1940. * @param rPosition position vector in three space.
  1941. */
  1942. Pose3(const Vector3<kt_double>& rPosition)
  1943. : m_Position(rPosition)
  1944. {
  1945. }
  1946. /**
  1947. * Create a new Pose3 object from the given position and orientation.
  1948. * @param rPosition position vector in three space.
  1949. * @param rOrientation quaternion orientation in three space.
  1950. */
  1951. Pose3(const Vector3<kt_double>& rPosition, const karto::Quaternion& rOrientation)
  1952. : m_Position(rPosition)
  1953. , m_Orientation(rOrientation)
  1954. {
  1955. }
  1956. /**
  1957. * Copy constructor
  1958. */
  1959. Pose3(const Pose3& rOther)
  1960. : m_Position(rOther.m_Position)
  1961. , m_Orientation(rOther.m_Orientation)
  1962. {
  1963. }
  1964. /**
  1965. * Constructs a Pose3 object from a Pose2.
  1966. */
  1967. Pose3(const Pose2& rPose)
  1968. {
  1969. m_Position = Vector3<kt_double>(rPose.GetX(), rPose.GetY(), 0.0);
  1970. m_Orientation.FromEulerAngles(rPose.GetHeading(), 0.0, 0.0);
  1971. }
  1972. public:
  1973. /**
  1974. * Get the position of the pose as a 3D vector as const. Values have units of meters.
  1975. * @return 3-dimensional position vector as const
  1976. */
  1977. inline const Vector3<kt_double>& GetPosition() const
  1978. {
  1979. return m_Position;
  1980. }
  1981. /**
  1982. * Set the position of the pose as a 3D vector. Values have units of meters.
  1983. * @return 3-dimensional position vector
  1984. */
  1985. inline void SetPosition(const Vector3<kt_double>& rPosition)
  1986. {
  1987. m_Position = rPosition;
  1988. }
  1989. /**
  1990. * Get the orientation quaternion of the pose as const.
  1991. * @return orientation quaternion as const
  1992. */
  1993. inline const Quaternion& GetOrientation() const
  1994. {
  1995. return m_Orientation;
  1996. }
  1997. /**
  1998. * Get the orientation quaternion of the pose.
  1999. * @return orientation quaternion
  2000. */
  2001. inline void SetOrientation(const Quaternion& rOrientation)
  2002. {
  2003. m_Orientation = rOrientation;
  2004. }
  2005. /**
  2006. * Returns a string representation of this pose
  2007. * @return string representation of this pose
  2008. */
  2009. inline std::string ToString()
  2010. {
  2011. std::stringstream converter;
  2012. converter.precision(std::numeric_limits<double>::digits10);
  2013. converter << GetPosition() << " " << GetOrientation();
  2014. return converter.str();
  2015. }
  2016. public:
  2017. /**
  2018. * Assignment operator
  2019. */
  2020. inline Pose3& operator = (const Pose3& rOther)
  2021. {
  2022. m_Position = rOther.m_Position;
  2023. m_Orientation = rOther.m_Orientation;
  2024. return *this;
  2025. }
  2026. /**
  2027. * Equality operator
  2028. */
  2029. inline kt_bool operator == (const Pose3& rOther) const
  2030. {
  2031. return (m_Position == rOther.m_Position && m_Orientation == rOther.m_Orientation);
  2032. }
  2033. /**
  2034. * Inequality operator
  2035. */
  2036. inline kt_bool operator != (const Pose3& rOther) const
  2037. {
  2038. return (m_Position != rOther.m_Position || m_Orientation != rOther.m_Orientation);
  2039. }
  2040. /**
  2041. * Write Pose3 onto output stream
  2042. * @param rStream output stream
  2043. * @param rPose to write
  2044. */
  2045. friend inline std::ostream& operator << (std::ostream& rStream, const Pose3& rPose)
  2046. {
  2047. rStream << rPose.GetPosition() << ", " << rPose.GetOrientation();
  2048. return rStream;
  2049. }
  2050. /**
  2051. * Read Pose3 from input stream
  2052. * @param rStream input stream
  2053. */
  2054. friend inline std::istream& operator >> (std::istream& rStream, const Pose3& /*rPose*/)
  2055. {
  2056. // Implement me!!
  2057. return rStream;
  2058. }
  2059. private:
  2060. Vector3<kt_double> m_Position;
  2061. Quaternion m_Orientation;
  2062. }; // Pose3
  2063. ////////////////////////////////////////////////////////////////////////////////////////
  2064. ////////////////////////////////////////////////////////////////////////////////////////
  2065. ////////////////////////////////////////////////////////////////////////////////////////
  2066. /**
  2067. * Defines a Matrix 3 x 3 class.
  2068. */
  2069. class Matrix3
  2070. {
  2071. public:
  2072. /**
  2073. * Default constructor
  2074. */
  2075. Matrix3()
  2076. {
  2077. Clear();
  2078. }
  2079. /**
  2080. * Copy constructor
  2081. */
  2082. inline Matrix3(const Matrix3& rOther)
  2083. {
  2084. memcpy(m_Matrix, rOther.m_Matrix, 9*sizeof(kt_double));
  2085. }
  2086. public:
  2087. /**
  2088. * Sets this matrix to identity matrix
  2089. */
  2090. void SetToIdentity()
  2091. {
  2092. memset(m_Matrix, 0, 9*sizeof(kt_double));
  2093. for (kt_int32s i = 0; i < 3; i++)
  2094. {
  2095. m_Matrix[i][i] = 1.0;
  2096. }
  2097. }
  2098. /**
  2099. * Sets this matrix to zero matrix
  2100. */
  2101. void Clear()
  2102. {
  2103. memset(m_Matrix, 0, 9*sizeof(kt_double));
  2104. }
  2105. /**
  2106. * Sets this matrix to be the rotation matrix of rotation around given axis
  2107. * @param x x-coordinate of axis
  2108. * @param y y-coordinate of axis
  2109. * @param z z-coordinate of axis
  2110. * @param radians amount of rotation
  2111. */
  2112. void FromAxisAngle(kt_double x, kt_double y, kt_double z, const kt_double radians)
  2113. {
  2114. kt_double cosRadians = cos(radians);
  2115. kt_double sinRadians = sin(radians);
  2116. kt_double oneMinusCos = 1.0 - cosRadians;
  2117. kt_double xx = x * x;
  2118. kt_double yy = y * y;
  2119. kt_double zz = z * z;
  2120. kt_double xyMCos = x * y * oneMinusCos;
  2121. kt_double xzMCos = x * z * oneMinusCos;
  2122. kt_double yzMCos = y * z * oneMinusCos;
  2123. kt_double xSin = x * sinRadians;
  2124. kt_double ySin = y * sinRadians;
  2125. kt_double zSin = z * sinRadians;
  2126. m_Matrix[0][0] = xx * oneMinusCos + cosRadians;
  2127. m_Matrix[0][1] = xyMCos - zSin;
  2128. m_Matrix[0][2] = xzMCos + ySin;
  2129. m_Matrix[1][0] = xyMCos + zSin;
  2130. m_Matrix[1][1] = yy * oneMinusCos + cosRadians;
  2131. m_Matrix[1][2] = yzMCos - xSin;
  2132. m_Matrix[2][0] = xzMCos - ySin;
  2133. m_Matrix[2][1] = yzMCos + xSin;
  2134. m_Matrix[2][2] = zz * oneMinusCos + cosRadians;
  2135. }
  2136. /**
  2137. * Returns transposed version of this matrix
  2138. * @return transposed matrix
  2139. */
  2140. Matrix3 Transpose() const
  2141. {
  2142. Matrix3 transpose;
  2143. for (kt_int32u row = 0; row < 3; row++)
  2144. {
  2145. for (kt_int32u col = 0; col < 3; col++)
  2146. {
  2147. transpose.m_Matrix[row][col] = m_Matrix[col][row];
  2148. }
  2149. }
  2150. return transpose;
  2151. }
  2152. /**
  2153. * Returns the inverse of the matrix
  2154. */
  2155. Matrix3 Inverse() const
  2156. {
  2157. Matrix3 kInverse = *this;
  2158. kt_bool haveInverse = InverseFast(kInverse, 1e-14);
  2159. if (haveInverse == false)
  2160. {
  2161. assert(false);
  2162. }
  2163. return kInverse;
  2164. }
  2165. /**
  2166. * Internal helper method for inverse matrix calculation
  2167. * This code is lifted from the OgreMatrix3 class!!
  2168. */
  2169. kt_bool InverseFast(Matrix3& rkInverse, kt_double fTolerance = KT_TOLERANCE) const
  2170. {
  2171. // Invert a 3x3 using cofactors. This is about 8 times faster than
  2172. // the Numerical Recipes code which uses Gaussian elimination.
  2173. rkInverse.m_Matrix[0][0] = m_Matrix[1][1]*m_Matrix[2][2] - m_Matrix[1][2]*m_Matrix[2][1];
  2174. rkInverse.m_Matrix[0][1] = m_Matrix[0][2]*m_Matrix[2][1] - m_Matrix[0][1]*m_Matrix[2][2];
  2175. rkInverse.m_Matrix[0][2] = m_Matrix[0][1]*m_Matrix[1][2] - m_Matrix[0][2]*m_Matrix[1][1];
  2176. rkInverse.m_Matrix[1][0] = m_Matrix[1][2]*m_Matrix[2][0] - m_Matrix[1][0]*m_Matrix[2][2];
  2177. rkInverse.m_Matrix[1][1] = m_Matrix[0][0]*m_Matrix[2][2] - m_Matrix[0][2]*m_Matrix[2][0];
  2178. rkInverse.m_Matrix[1][2] = m_Matrix[0][2]*m_Matrix[1][0] - m_Matrix[0][0]*m_Matrix[1][2];
  2179. rkInverse.m_Matrix[2][0] = m_Matrix[1][0]*m_Matrix[2][1] - m_Matrix[1][1]*m_Matrix[2][0];
  2180. rkInverse.m_Matrix[2][1] = m_Matrix[0][1]*m_Matrix[2][0] - m_Matrix[0][0]*m_Matrix[2][1];
  2181. rkInverse.m_Matrix[2][2] = m_Matrix[0][0]*m_Matrix[1][1] - m_Matrix[0][1]*m_Matrix[1][0];
  2182. kt_double fDet = m_Matrix[0][0]*rkInverse.m_Matrix[0][0] +
  2183. m_Matrix[0][1]*rkInverse.m_Matrix[1][0] +
  2184. m_Matrix[0][2]*rkInverse.m_Matrix[2][0];
  2185. if (fabs(fDet) <= fTolerance)
  2186. {
  2187. return false;
  2188. }
  2189. kt_double fInvDet = 1.0/fDet;
  2190. for (size_t row = 0; row < 3; row++)
  2191. {
  2192. for (size_t col = 0; col < 3; col++)
  2193. {
  2194. rkInverse.m_Matrix[row][col] *= fInvDet;
  2195. }
  2196. }
  2197. return true;
  2198. }
  2199. /**
  2200. * Returns a string representation of this matrix
  2201. * @return string representation of this matrix
  2202. */
  2203. inline std::string ToString() const
  2204. {
  2205. std::stringstream converter;
  2206. converter.precision(std::numeric_limits<double>::digits10);
  2207. for (int row = 0; row < 3; row++)
  2208. {
  2209. for (int col = 0; col < 3; col++)
  2210. {
  2211. converter << m_Matrix[row][col] << " ";
  2212. }
  2213. }
  2214. return converter.str();
  2215. }
  2216. public:
  2217. /**
  2218. * Assignment operator
  2219. */
  2220. inline Matrix3& operator = (const Matrix3& rOther)
  2221. {
  2222. memcpy(m_Matrix, rOther.m_Matrix, 9*sizeof(kt_double));
  2223. return *this;
  2224. }
  2225. /**
  2226. * Matrix element access, allows use of construct mat(r, c)
  2227. * @param row
  2228. * @param column
  2229. * @return reference to mat(r,c)
  2230. */
  2231. inline kt_double& operator()(kt_int32u row, kt_int32u column)
  2232. {
  2233. return m_Matrix[row][column];
  2234. }
  2235. /**
  2236. * Read-only matrix element access, allows use of construct mat(r, c)
  2237. * @param row
  2238. * @param column
  2239. * @return mat(r,c)
  2240. */
  2241. inline kt_double operator()(kt_int32u row, kt_int32u column) const
  2242. {
  2243. return m_Matrix[row][column];
  2244. }
  2245. /**
  2246. * Binary Matrix3 multiplication.
  2247. * @param rOther
  2248. * @return Matrix3 product
  2249. */
  2250. Matrix3 operator * (const Matrix3& rOther) const
  2251. {
  2252. Matrix3 product;
  2253. for (size_t row = 0; row < 3; row++)
  2254. {
  2255. for (size_t col = 0; col < 3; col++)
  2256. {
  2257. product.m_Matrix[row][col] = m_Matrix[row][0]*rOther.m_Matrix[0][col] +
  2258. m_Matrix[row][1]*rOther.m_Matrix[1][col] +
  2259. m_Matrix[row][2]*rOther.m_Matrix[2][col];
  2260. }
  2261. }
  2262. return product;
  2263. }
  2264. /**
  2265. * Matrix3 and Pose2 multiplication - matrix * pose [3x3 * 3x1 = 3x1]
  2266. * @param rPose2
  2267. * @return Pose2 product
  2268. */
  2269. inline Pose2 operator * (const Pose2& rPose2) const
  2270. {
  2271. Pose2 pose2;
  2272. pose2.SetX(m_Matrix[0][0] * rPose2.GetX() + m_Matrix[0][1] *
  2273. rPose2.GetY() + m_Matrix[0][2] * rPose2.GetHeading());
  2274. pose2.SetY(m_Matrix[1][0] * rPose2.GetX() + m_Matrix[1][1] *
  2275. rPose2.GetY() + m_Matrix[1][2] * rPose2.GetHeading());
  2276. pose2.SetHeading(m_Matrix[2][0] * rPose2.GetX() + m_Matrix[2][1] *
  2277. rPose2.GetY() + m_Matrix[2][2] * rPose2.GetHeading());
  2278. return pose2;
  2279. }
  2280. /**
  2281. * In place Matrix3 add.
  2282. * @param rkMatrix
  2283. */
  2284. inline void operator += (const Matrix3& rkMatrix)
  2285. {
  2286. for (kt_int32u row = 0; row < 3; row++)
  2287. {
  2288. for (kt_int32u col = 0; col < 3; col++)
  2289. {
  2290. m_Matrix[row][col] += rkMatrix.m_Matrix[row][col];
  2291. }
  2292. }
  2293. }
  2294. /**
  2295. * Write Matrix3 onto output stream
  2296. * @param rStream output stream
  2297. * @param rMatrix to write
  2298. */
  2299. friend inline std::ostream& operator << (std::ostream& rStream, const Matrix3& rMatrix)
  2300. {
  2301. rStream << rMatrix.ToString();
  2302. return rStream;
  2303. }
  2304. private:
  2305. kt_double m_Matrix[3][3];
  2306. }; // Matrix3
  2307. ////////////////////////////////////////////////////////////////////////////////////////
  2308. ////////////////////////////////////////////////////////////////////////////////////////
  2309. ////////////////////////////////////////////////////////////////////////////////////////
  2310. /**
  2311. * Defines a general Matrix class.
  2312. */
  2313. class Matrix
  2314. {
  2315. public:
  2316. /**
  2317. * Constructs a matrix of size rows x columns
  2318. */
  2319. Matrix(kt_int32u rows, kt_int32u columns)
  2320. : m_Rows(rows)
  2321. , m_Columns(columns)
  2322. , m_pData(NULL)
  2323. {
  2324. Allocate();
  2325. Clear();
  2326. }
  2327. /**
  2328. * Destructor
  2329. */
  2330. virtual ~Matrix()
  2331. {
  2332. delete [] m_pData;
  2333. }
  2334. public:
  2335. /**
  2336. * Set all entries to 0
  2337. */
  2338. void Clear()
  2339. {
  2340. if (m_pData != NULL)
  2341. {
  2342. memset(m_pData, 0, sizeof(kt_double) * m_Rows * m_Columns);
  2343. }
  2344. }
  2345. /**
  2346. * Gets the number of rows of the matrix
  2347. * @return nubmer of rows
  2348. */
  2349. inline kt_int32u GetRows() const
  2350. {
  2351. return m_Rows;
  2352. }
  2353. /**
  2354. * Gets the number of columns of the matrix
  2355. * @return nubmer of columns
  2356. */
  2357. inline kt_int32u GetColumns() const
  2358. {
  2359. return m_Columns;
  2360. }
  2361. /**
  2362. * Returns a reference to the entry at (row,column)
  2363. * @param row
  2364. * @param column
  2365. * @return reference to entry at (row,column)
  2366. */
  2367. inline kt_double& operator()(kt_int32u row, kt_int32u column)
  2368. {
  2369. RangeCheck(row, column);
  2370. return m_pData[row + column * m_Rows];
  2371. }
  2372. /**
  2373. * Returns a const reference to the entry at (row,column)
  2374. * @param row
  2375. * @param column
  2376. * @return const reference to entry at (row,column)
  2377. */
  2378. inline const kt_double& operator()(kt_int32u row, kt_int32u column) const
  2379. {
  2380. RangeCheck(row, column);
  2381. return m_pData[row + column * m_Rows];
  2382. }
  2383. private:
  2384. /**
  2385. * Allocate space for the matrix
  2386. */
  2387. void Allocate()
  2388. {
  2389. try
  2390. {
  2391. if (m_pData != NULL)
  2392. {
  2393. delete[] m_pData;
  2394. }
  2395. m_pData = new kt_double[m_Rows * m_Columns];
  2396. }
  2397. catch (const std::bad_alloc& ex)
  2398. {
  2399. throw Exception("Matrix allocation error");
  2400. }
  2401. if (m_pData == NULL)
  2402. {
  2403. throw Exception("Matrix allocation error");
  2404. }
  2405. }
  2406. /**
  2407. * Checks if (row,column) is a valid entry into the matrix
  2408. * @param row
  2409. * @param column
  2410. */
  2411. inline void RangeCheck(kt_int32u row, kt_int32u column) const
  2412. {
  2413. if (math::IsUpTo(row, m_Rows) == false)
  2414. {
  2415. throw Exception("Matrix - RangeCheck ERROR!!!!");
  2416. }
  2417. if (math::IsUpTo(column, m_Columns) == false)
  2418. {
  2419. throw Exception("Matrix - RangeCheck ERROR!!!!");
  2420. }
  2421. }
  2422. private:
  2423. kt_int32u m_Rows;
  2424. kt_int32u m_Columns;
  2425. kt_double* m_pData;
  2426. }; // Matrix
  2427. ////////////////////////////////////////////////////////////////////////////////////////
  2428. ////////////////////////////////////////////////////////////////////////////////////////
  2429. ////////////////////////////////////////////////////////////////////////////////////////
  2430. /**
  2431. * Defines a bounding box in 2-dimensional real space.
  2432. */
  2433. class BoundingBox2
  2434. {
  2435. public:
  2436. /*
  2437. * Default constructor
  2438. */
  2439. BoundingBox2()
  2440. : m_Minimum(999999999999999999.99999, 999999999999999999.99999)
  2441. , m_Maximum(-999999999999999999.99999, -999999999999999999.99999)
  2442. {
  2443. }
  2444. public:
  2445. /**
  2446. * Get bounding box minimum
  2447. */
  2448. inline const Vector2<kt_double>& GetMinimum() const
  2449. {
  2450. return m_Minimum;
  2451. }
  2452. /**
  2453. * Set bounding box minimum
  2454. */
  2455. inline void SetMinimum(const Vector2<kt_double>& mMinimum)
  2456. {
  2457. m_Minimum = mMinimum;
  2458. }
  2459. /**
  2460. * Get bounding box maximum
  2461. */
  2462. inline const Vector2<kt_double>& GetMaximum() const
  2463. {
  2464. return m_Maximum;
  2465. }
  2466. /**
  2467. * Set bounding box maximum
  2468. */
  2469. inline void SetMaximum(const Vector2<kt_double>& rMaximum)
  2470. {
  2471. m_Maximum = rMaximum;
  2472. }
  2473. /**
  2474. * Get the size of the bounding box
  2475. */
  2476. inline Size2<kt_double> GetSize() const
  2477. {
  2478. Vector2<kt_double> size = m_Maximum - m_Minimum;
  2479. return Size2<kt_double>(size.GetX(), size.GetY());
  2480. }
  2481. /**
  2482. * Add vector to bounding box
  2483. */
  2484. inline void Add(const Vector2<kt_double>& rPoint)
  2485. {
  2486. m_Minimum.MakeFloor(rPoint);
  2487. m_Maximum.MakeCeil(rPoint);
  2488. }
  2489. /**
  2490. * Add other bounding box to bounding box
  2491. */
  2492. inline void Add(const BoundingBox2& rBoundingBox)
  2493. {
  2494. Add(rBoundingBox.GetMinimum());
  2495. Add(rBoundingBox.GetMaximum());
  2496. }
  2497. /**
  2498. * Whether the given point is in the bounds of this box
  2499. * @param rPoint
  2500. * @return in bounds?
  2501. */
  2502. inline kt_bool IsInBounds(const Vector2<kt_double>& rPoint) const
  2503. {
  2504. return (math::InRange(rPoint.GetX(), m_Minimum.GetX(), m_Maximum.GetX()) &&
  2505. math::InRange(rPoint.GetY(), m_Minimum.GetY(), m_Maximum.GetY()));
  2506. }
  2507. private:
  2508. Vector2<kt_double> m_Minimum;
  2509. Vector2<kt_double> m_Maximum;
  2510. }; // BoundingBox2
  2511. ////////////////////////////////////////////////////////////////////////////////////////
  2512. ////////////////////////////////////////////////////////////////////////////////////////
  2513. ////////////////////////////////////////////////////////////////////////////////////////
  2514. /**
  2515. * Implementation of a Pose2 transform
  2516. */
  2517. class Transform
  2518. {
  2519. public:
  2520. /**
  2521. * Constructs a transformation from the origin to the given pose
  2522. * @param rPose pose
  2523. */
  2524. Transform(const Pose2& rPose)
  2525. {
  2526. SetTransform(Pose2(), rPose);
  2527. }
  2528. /**
  2529. * Constructs a transformation from the first pose to the second pose
  2530. * @param rPose1 first pose
  2531. * @param rPose2 second pose
  2532. */
  2533. Transform(const Pose2& rPose1, const Pose2& rPose2)
  2534. {
  2535. SetTransform(rPose1, rPose2);
  2536. }
  2537. public:
  2538. /**
  2539. * Transforms the pose according to this transform
  2540. * @param rSourcePose pose to transform from
  2541. * @return transformed pose
  2542. */
  2543. inline Pose2 TransformPose(const Pose2& rSourcePose)
  2544. {
  2545. Pose2 newPosition = m_Transform + m_Rotation * rSourcePose;
  2546. kt_double angle = math::NormalizeAngle(rSourcePose.GetHeading() + m_Transform.GetHeading());
  2547. return Pose2(newPosition.GetPosition(), angle);
  2548. }
  2549. /**
  2550. * Inverse transformation of the pose according to this transform
  2551. * @param rSourcePose pose to transform from
  2552. * @return transformed pose
  2553. */
  2554. inline Pose2 InverseTransformPose(const Pose2& rSourcePose)
  2555. {
  2556. Pose2 newPosition = m_InverseRotation * (rSourcePose - m_Transform);
  2557. kt_double angle = math::NormalizeAngle(rSourcePose.GetHeading() - m_Transform.GetHeading());
  2558. // components of transform
  2559. return Pose2(newPosition.GetPosition(), angle);
  2560. }
  2561. private:
  2562. /**
  2563. * Sets this to be the transformation from the first pose to the second pose
  2564. * @param rPose1 first pose
  2565. * @param rPose2 second pose
  2566. */
  2567. void SetTransform(const Pose2& rPose1, const Pose2& rPose2)
  2568. {
  2569. if (rPose1 == rPose2)
  2570. {
  2571. m_Rotation.SetToIdentity();
  2572. m_InverseRotation.SetToIdentity();
  2573. m_Transform = Pose2();
  2574. return;
  2575. }
  2576. // heading transformation
  2577. m_Rotation.FromAxisAngle(0, 0, 1, rPose2.GetHeading() - rPose1.GetHeading());
  2578. m_InverseRotation.FromAxisAngle(0, 0, 1, rPose1.GetHeading() - rPose2.GetHeading());
  2579. // position transformation
  2580. Pose2 newPosition;
  2581. if (rPose1.GetX() != 0.0 || rPose1.GetY() != 0.0)
  2582. {
  2583. newPosition = rPose2 - m_Rotation * rPose1;
  2584. }
  2585. else
  2586. {
  2587. newPosition = rPose2;
  2588. }
  2589. m_Transform = Pose2(newPosition.GetPosition(), rPose2.GetHeading() - rPose1.GetHeading());
  2590. }
  2591. private:
  2592. // pose transformation
  2593. Pose2 m_Transform;
  2594. Matrix3 m_Rotation;
  2595. Matrix3 m_InverseRotation;
  2596. }; // Transform
  2597. ////////////////////////////////////////////////////////////////////////////////////////
  2598. ////////////////////////////////////////////////////////////////////////////////////////
  2599. ////////////////////////////////////////////////////////////////////////////////////////
  2600. /**
  2601. * Enumerated type for valid LaserRangeFinder types
  2602. */
  2603. typedef enum
  2604. {
  2605. LaserRangeFinder_Custom = 0,
  2606. LaserRangeFinder_Sick_LMS100 = 1,
  2607. LaserRangeFinder_Sick_LMS200 = 2,
  2608. LaserRangeFinder_Sick_LMS291 = 3,
  2609. LaserRangeFinder_Hokuyo_UTM_30LX = 4,
  2610. LaserRangeFinder_Hokuyo_URG_04LX = 5
  2611. } LaserRangeFinderType;
  2612. ////////////////////////////////////////////////////////////////////////////////////////
  2613. ////////////////////////////////////////////////////////////////////////////////////////
  2614. ////////////////////////////////////////////////////////////////////////////////////////
  2615. /**
  2616. * Abstract base class for Parameters
  2617. */
  2618. class AbstractParameter
  2619. {
  2620. public:
  2621. /**
  2622. * Constructs a parameter with the given name
  2623. * @param rName
  2624. * @param pParameterManger
  2625. */
  2626. AbstractParameter(const std::string& rName, ParameterManager* pParameterManger = NULL)
  2627. : m_Name(rName)
  2628. {
  2629. // if parameter manager is provided add myself to it!
  2630. if (pParameterManger != NULL)
  2631. {
  2632. pParameterManger->Add(this);
  2633. }
  2634. }
  2635. /**
  2636. * Constructs a parameter with the given name and description
  2637. * @param rName
  2638. * @param rDescription
  2639. * @param pParameterManger
  2640. */
  2641. AbstractParameter(const std::string& rName,
  2642. const std::string& rDescription,
  2643. ParameterManager* pParameterManger = NULL)
  2644. : m_Name(rName)
  2645. , m_Description(rDescription)
  2646. {
  2647. // if parameter manager is provided add myself to it!
  2648. if (pParameterManger != NULL)
  2649. {
  2650. pParameterManger->Add(this);
  2651. }
  2652. }
  2653. /**
  2654. * Destructor
  2655. */
  2656. virtual ~AbstractParameter()
  2657. {
  2658. }
  2659. public:
  2660. /**
  2661. * Gets the name of this object
  2662. * @return name
  2663. */
  2664. inline const std::string& GetName() const
  2665. {
  2666. return m_Name;
  2667. }
  2668. /**
  2669. * Returns the parameter description
  2670. * @return parameter description
  2671. */
  2672. inline const std::string& GetDescription() const
  2673. {
  2674. return m_Description;
  2675. }
  2676. /**
  2677. * Get parameter value as string.
  2678. * @return value as string
  2679. */
  2680. virtual const std::string GetValueAsString() const = 0;
  2681. /**
  2682. * Set parameter value from string.
  2683. * @param rStringValue value as string
  2684. */
  2685. virtual void SetValueFromString(const std::string& rStringValue) = 0;
  2686. /**
  2687. * Clones the parameter
  2688. * @return clone
  2689. */
  2690. virtual AbstractParameter* Clone() = 0;
  2691. public:
  2692. /**
  2693. * Write this parameter onto output stream
  2694. * @param rStream output stream
  2695. * @param rParameter
  2696. */
  2697. friend std::ostream& operator << (std::ostream& rStream, const AbstractParameter& rParameter)
  2698. {
  2699. rStream.precision(6);
  2700. rStream.flags(std::ios::fixed);
  2701. rStream << rParameter.GetName() << " = " << rParameter.GetValueAsString();
  2702. return rStream;
  2703. }
  2704. private:
  2705. std::string m_Name;
  2706. std::string m_Description;
  2707. }; // AbstractParameter
  2708. ////////////////////////////////////////////////////////////////////////////////////////
  2709. ////////////////////////////////////////////////////////////////////////////////////////
  2710. ////////////////////////////////////////////////////////////////////////////////////////
  2711. /**
  2712. * Parameter class
  2713. */
  2714. template<typename T>
  2715. class Parameter : public AbstractParameter
  2716. {
  2717. public:
  2718. /**
  2719. * Parameter with given name and value
  2720. * @param rName
  2721. * @param value
  2722. * @param pParameterManger
  2723. */
  2724. Parameter(const std::string& rName, T value, ParameterManager* pParameterManger = NULL)
  2725. : AbstractParameter(rName, pParameterManger)
  2726. , m_Value(value)
  2727. {
  2728. }
  2729. /**
  2730. * Parameter with given name, description and value
  2731. * @param rName
  2732. * @param rDescription
  2733. * @param value
  2734. * @param pParameterManger
  2735. */
  2736. Parameter(const std::string& rName,
  2737. const std::string& rDescription,
  2738. T value,
  2739. ParameterManager* pParameterManger = NULL)
  2740. : AbstractParameter(rName, rDescription, pParameterManger)
  2741. , m_Value(value)
  2742. {
  2743. }
  2744. /**
  2745. * Destructor
  2746. */
  2747. virtual ~Parameter()
  2748. {
  2749. }
  2750. public:
  2751. /**
  2752. * Gets value of parameter
  2753. * @return parameter value
  2754. */
  2755. inline const T& GetValue() const
  2756. {
  2757. return m_Value;
  2758. }
  2759. /**
  2760. * Sets value of parameter
  2761. * @param rValue
  2762. */
  2763. inline void SetValue(const T& rValue)
  2764. {
  2765. m_Value = rValue;
  2766. }
  2767. /**
  2768. * Gets value of parameter as string
  2769. * @return string version of value
  2770. */
  2771. virtual const std::string GetValueAsString() const
  2772. {
  2773. std::stringstream converter;
  2774. converter << m_Value;
  2775. return converter.str();
  2776. }
  2777. /**
  2778. * Sets value of parameter from string
  2779. * @param rStringValue
  2780. */
  2781. virtual void SetValueFromString(const std::string& rStringValue)
  2782. {
  2783. std::stringstream converter;
  2784. converter.str(rStringValue);
  2785. converter >> m_Value;
  2786. }
  2787. /**
  2788. * Clone this parameter
  2789. * @return clone of this parameter
  2790. */
  2791. virtual Parameter* Clone()
  2792. {
  2793. return new Parameter(GetName(), GetDescription(), GetValue());
  2794. }
  2795. public:
  2796. /**
  2797. * Assignment operator
  2798. */
  2799. Parameter& operator = (const Parameter& rOther)
  2800. {
  2801. m_Value = rOther.m_Value;
  2802. return *this;
  2803. }
  2804. /**
  2805. * Sets the value of this parameter to given value
  2806. */
  2807. T operator = (T value)
  2808. {
  2809. m_Value = value;
  2810. return m_Value;
  2811. }
  2812. protected:
  2813. /**
  2814. * Parameter value
  2815. */
  2816. T m_Value;
  2817. }; // Parameter
  2818. template<>
  2819. inline void Parameter<kt_double>::SetValueFromString(const std::string& rStringValue)
  2820. {
  2821. int precision = std::numeric_limits<double>::digits10;
  2822. std::stringstream converter;
  2823. converter.precision(precision);
  2824. converter.str(rStringValue);
  2825. m_Value = 0.0;
  2826. converter >> m_Value;
  2827. }
  2828. template<>
  2829. inline const std::string Parameter<kt_double>::GetValueAsString() const
  2830. {
  2831. std::stringstream converter;
  2832. converter.precision(std::numeric_limits<double>::digits10);
  2833. converter << m_Value;
  2834. return converter.str();
  2835. }
  2836. template<>
  2837. inline void Parameter<kt_bool>::SetValueFromString(const std::string& rStringValue)
  2838. {
  2839. if (rStringValue == "true" || rStringValue == "TRUE")
  2840. {
  2841. m_Value = true;
  2842. }
  2843. else
  2844. {
  2845. m_Value = false;
  2846. }
  2847. }
  2848. template<>
  2849. inline const std::string Parameter<kt_bool>::GetValueAsString() const
  2850. {
  2851. if (m_Value == true)
  2852. {
  2853. return "true";
  2854. }
  2855. return "false";
  2856. }
  2857. ////////////////////////////////////////////////////////////////////////////////////////
  2858. ////////////////////////////////////////////////////////////////////////////////////////
  2859. ////////////////////////////////////////////////////////////////////////////////////////
  2860. /**
  2861. * Parameter enum class
  2862. */
  2863. class ParameterEnum : public Parameter<kt_int32s>
  2864. {
  2865. typedef std::map<std::string, kt_int32s> EnumMap;
  2866. public:
  2867. /**
  2868. * Construct a Parameter object with name and value
  2869. * @param rName parameter name
  2870. * @param value of parameter
  2871. * @param pParameterManger
  2872. */
  2873. ParameterEnum(const std::string& rName, kt_int32s value, ParameterManager* pParameterManger = NULL)
  2874. : Parameter<kt_int32s>(rName, value, pParameterManger)
  2875. {
  2876. }
  2877. /**
  2878. * Destructor
  2879. */
  2880. virtual ~ParameterEnum()
  2881. {
  2882. }
  2883. public:
  2884. /**
  2885. * Return a clone of this instance
  2886. * @return clone
  2887. */
  2888. virtual Parameter<kt_int32s>* Clone()
  2889. {
  2890. ParameterEnum* pEnum = new ParameterEnum(GetName(), GetValue());
  2891. pEnum->m_EnumDefines = m_EnumDefines;
  2892. return pEnum;
  2893. }
  2894. /**
  2895. * Set parameter value from string.
  2896. * @param rStringValue value as string
  2897. */
  2898. virtual void SetValueFromString(const std::string& rStringValue)
  2899. {
  2900. if (m_EnumDefines.find(rStringValue) != m_EnumDefines.end())
  2901. {
  2902. m_Value = m_EnumDefines[rStringValue];
  2903. }
  2904. else
  2905. {
  2906. std::string validValues;
  2907. const_forEach(EnumMap, &m_EnumDefines)
  2908. {
  2909. validValues += iter->first + ", ";
  2910. }
  2911. throw Exception("Unable to set enum: " + rStringValue + ". Valid values are: " + validValues);
  2912. }
  2913. }
  2914. /**
  2915. * Get parameter value as string.
  2916. * @return value as string
  2917. */
  2918. virtual const std::string GetValueAsString() const
  2919. {
  2920. const_forEach(EnumMap, &m_EnumDefines)
  2921. {
  2922. if (iter->second == m_Value)
  2923. {
  2924. return iter->first;
  2925. }
  2926. }
  2927. throw Exception("Unable to lookup enum");
  2928. }
  2929. /**
  2930. * Defines the enum with the given name as having the given value
  2931. * @param value
  2932. * @param rName
  2933. */
  2934. void DefineEnumValue(kt_int32s value, const std::string& rName)
  2935. {
  2936. if (m_EnumDefines.find(rName) == m_EnumDefines.end())
  2937. {
  2938. m_EnumDefines[rName] = value;
  2939. }
  2940. else
  2941. {
  2942. std::cerr << "Overriding enum value: " << m_EnumDefines[rName] << " with " << value << std::endl;
  2943. m_EnumDefines[rName] = value;
  2944. assert(false);
  2945. }
  2946. }
  2947. public:
  2948. /**
  2949. * Assignment operator
  2950. */
  2951. ParameterEnum& operator = (const ParameterEnum& rOther)
  2952. {
  2953. SetValue(rOther.GetValue());
  2954. return *this;
  2955. }
  2956. /**
  2957. * Assignment operator
  2958. */
  2959. kt_int32s operator = (kt_int32s value)
  2960. {
  2961. SetValue(value);
  2962. return m_Value;
  2963. }
  2964. private:
  2965. EnumMap m_EnumDefines;
  2966. }; // ParameterEnum
  2967. ////////////////////////////////////////////////////////////////////////////////////////
  2968. ////////////////////////////////////////////////////////////////////////////////////////
  2969. ////////////////////////////////////////////////////////////////////////////////////////
  2970. /**
  2971. * Set of parameters
  2972. */
  2973. class Parameters : public Object
  2974. {
  2975. public:
  2976. // @cond EXCLUDE
  2977. KARTO_Object(Parameters)
  2978. // @endcond
  2979. public:
  2980. /**
  2981. * Parameters
  2982. * @param rName
  2983. */
  2984. Parameters(const std::string& rName)
  2985. : Object(rName)
  2986. {
  2987. }
  2988. /**
  2989. * Destructor
  2990. */
  2991. virtual ~Parameters()
  2992. {
  2993. }
  2994. private:
  2995. Parameters(const Parameters&);
  2996. const Parameters& operator=(const Parameters&);
  2997. }; // Parameters
  2998. ////////////////////////////////////////////////////////////////////////////////////////
  2999. ////////////////////////////////////////////////////////////////////////////////////////
  3000. ////////////////////////////////////////////////////////////////////////////////////////
  3001. class SensorData;
  3002. /**
  3003. * Abstract Sensor base class
  3004. */
  3005. class KARTO_EXPORT Sensor : public Object
  3006. {
  3007. public:
  3008. // @cond EXCLUDE
  3009. KARTO_Object(Sensor)
  3010. // @endcond
  3011. protected:
  3012. /**
  3013. * Construct a Sensor
  3014. * @param rName sensor name
  3015. */
  3016. Sensor(const Name& rName);
  3017. public:
  3018. /**
  3019. * Destructor
  3020. */
  3021. virtual ~Sensor();
  3022. public:
  3023. /**
  3024. * Gets this range finder sensor's offset
  3025. * @return offset pose
  3026. */
  3027. inline const Pose2& GetOffsetPose() const
  3028. {
  3029. return m_pOffsetPose->GetValue();
  3030. }
  3031. /**
  3032. * Sets this range finder sensor's offset
  3033. * @param rPose
  3034. */
  3035. inline void SetOffsetPose(const Pose2& rPose)
  3036. {
  3037. m_pOffsetPose->SetValue(rPose);
  3038. }
  3039. /**
  3040. * Validates sensor
  3041. * @return true if valid
  3042. */
  3043. virtual kt_bool Validate() = 0;
  3044. /**
  3045. * Validates sensor data
  3046. * @param pSensorData sensor data
  3047. * @return true if valid
  3048. */
  3049. virtual kt_bool Validate(SensorData* pSensorData) = 0;
  3050. private:
  3051. /**
  3052. * Restrict the copy constructor
  3053. */
  3054. Sensor(const Sensor&);
  3055. /**
  3056. * Restrict the assignment operator
  3057. */
  3058. const Sensor& operator=(const Sensor&);
  3059. private:
  3060. /**
  3061. * Sensor offset pose
  3062. */
  3063. Parameter<Pose2>* m_pOffsetPose;
  3064. }; // Sensor
  3065. /**
  3066. * Type declaration of Sensor vector
  3067. */
  3068. typedef std::vector<Sensor*> SensorVector;
  3069. ////////////////////////////////////////////////////////////////////////////////////////
  3070. ////////////////////////////////////////////////////////////////////////////////////////
  3071. ////////////////////////////////////////////////////////////////////////////////////////
  3072. /**
  3073. * Type declaration of <Name, Sensor*> map
  3074. */
  3075. typedef std::map<Name, Sensor*> SensorManagerMap;
  3076. /**
  3077. * Manages sensors
  3078. */
  3079. class KARTO_EXPORT SensorManager
  3080. {
  3081. public:
  3082. /**
  3083. * Constructor
  3084. */
  3085. SensorManager()
  3086. {
  3087. }
  3088. /**
  3089. * Destructor
  3090. */
  3091. virtual ~SensorManager()
  3092. {
  3093. }
  3094. public:
  3095. /**
  3096. * Get singleton instance of SensorManager
  3097. */
  3098. static SensorManager* GetInstance();
  3099. public:
  3100. /**
  3101. * Registers a sensor by it's name. The Sensor name must be unique, if not sensor is not registered
  3102. * unless override is set to true
  3103. * @param pSensor sensor to register
  3104. * @param override
  3105. * @return true if sensor is registered with SensorManager, false if Sensor name is not unique
  3106. */
  3107. void RegisterSensor(Sensor* pSensor, kt_bool override = false)
  3108. {
  3109. Validate(pSensor);
  3110. if ((m_Sensors.find(pSensor->GetName()) != m_Sensors.end()) && !override)
  3111. {
  3112. throw Exception("Cannot register sensor: already registered: [" +
  3113. pSensor->GetName().ToString() +
  3114. "] (Consider setting 'override' to true)");
  3115. }
  3116. std::cout << "Registering sensor: [" << pSensor->GetName().ToString() << "]" << std::endl;
  3117. m_Sensors[pSensor->GetName()] = pSensor;
  3118. }
  3119. /**
  3120. * Unregisters the given sensor
  3121. * @param pSensor sensor to unregister
  3122. */
  3123. void UnregisterSensor(Sensor* pSensor)
  3124. {
  3125. Validate(pSensor);
  3126. if (m_Sensors.find(pSensor->GetName()) != m_Sensors.end())
  3127. {
  3128. std::cout << "Unregistering sensor: " << pSensor->GetName().ToString() << std::endl;
  3129. m_Sensors.erase(pSensor->GetName());
  3130. }
  3131. else
  3132. {
  3133. throw Exception("Cannot unregister sensor: not registered: [" + pSensor->GetName().ToString() + "]");
  3134. }
  3135. }
  3136. /**
  3137. * Gets the sensor with the given name
  3138. * @param rName name of sensor
  3139. * @return sensor
  3140. */
  3141. Sensor* GetSensorByName(const Name& rName)
  3142. {
  3143. if (m_Sensors.find(rName) != m_Sensors.end())
  3144. {
  3145. return m_Sensors[rName];
  3146. }
  3147. throw Exception("Sensor not registered: [" + rName.ToString() + "] (Did you add the sensor to the Dataset?)");
  3148. }
  3149. /**
  3150. * Gets the sensor with the given name
  3151. * @param rName name of sensor
  3152. * @return sensor
  3153. */
  3154. template<class T>
  3155. T* GetSensorByName(const Name& rName)
  3156. {
  3157. Sensor* pSensor = GetSensorByName(rName);
  3158. return dynamic_cast<T*>(pSensor);
  3159. }
  3160. /**
  3161. * Gets all registered sensors
  3162. * @return vector of all registered sensors
  3163. */
  3164. SensorVector GetAllSensors()
  3165. {
  3166. SensorVector sensors;
  3167. forEach(SensorManagerMap, &m_Sensors)
  3168. {
  3169. sensors.push_back(iter->second);
  3170. }
  3171. return sensors;
  3172. }
  3173. protected:
  3174. /**
  3175. * Checks that given sensor is not NULL and has non-empty name
  3176. * @param pSensor sensor to validate
  3177. */
  3178. static void Validate(Sensor* pSensor)
  3179. {
  3180. if (pSensor == NULL)
  3181. {
  3182. throw Exception("Invalid sensor: NULL");
  3183. }
  3184. else if (pSensor->GetName().ToString() == "")
  3185. {
  3186. throw Exception("Invalid sensor: nameless");
  3187. }
  3188. }
  3189. protected:
  3190. /**
  3191. * Sensor map
  3192. */
  3193. SensorManagerMap m_Sensors;
  3194. };
  3195. ////////////////////////////////////////////////////////////////////////////////////////
  3196. ////////////////////////////////////////////////////////////////////////////////////////
  3197. ////////////////////////////////////////////////////////////////////////////////////////
  3198. /**
  3199. * Sensor that provides pose information relative to world coordinates.
  3200. *
  3201. * The user can set the offset pose of the drive sensor. If no value is provided by the user the default is no offset,
  3202. * i.e, the sensor is initially at the world origin, oriented along the positive z axis.
  3203. */
  3204. class Drive : public Sensor
  3205. {
  3206. public:
  3207. // @cond EXCLUDE
  3208. KARTO_Object(Drive)
  3209. // @endcond
  3210. public:
  3211. /**
  3212. * Constructs a Drive object
  3213. */
  3214. Drive(const std::string& rName)
  3215. : Sensor(rName)
  3216. {
  3217. }
  3218. /**
  3219. * Destructor
  3220. */
  3221. virtual ~Drive()
  3222. {
  3223. }
  3224. public:
  3225. virtual kt_bool Validate()
  3226. {
  3227. return true;
  3228. }
  3229. virtual kt_bool Validate(SensorData* pSensorData)
  3230. {
  3231. if (pSensorData == NULL)
  3232. {
  3233. return false;
  3234. }
  3235. return true;
  3236. }
  3237. private:
  3238. Drive(const Drive&);
  3239. const Drive& operator=(const Drive&);
  3240. }; // class Drive
  3241. ////////////////////////////////////////////////////////////////////////////////////////
  3242. ////////////////////////////////////////////////////////////////////////////////////////
  3243. ////////////////////////////////////////////////////////////////////////////////////////
  3244. class LocalizedRangeScan;
  3245. class CoordinateConverter;
  3246. /**
  3247. * The LaserRangeFinder defines a laser sensor that provides the pose offset position of a localized range scan relative to the robot.
  3248. * The user can set an offset pose for the sensor relative to the robot coordinate system. If no value is provided
  3249. * by the user, the sensor is set to be at the origin of the robot coordinate system.
  3250. * The LaserRangeFinder contains parameters for physical laser sensor used by the mapper for scan matching
  3251. * Also contains information about the maximum range of the sensor and provides a threshold
  3252. * for limiting the range of readings.
  3253. * The optimal value for the range threshold depends on the angular resolution of the scan and
  3254. * the desired map resolution. RangeThreshold should be set as large as possible while still
  3255. * providing "solid" coverage between consecutive range readings. The diagram below illustrates
  3256. * the relationship between map resolution and the range threshold.
  3257. */
  3258. class KARTO_EXPORT LaserRangeFinder : public Sensor
  3259. {
  3260. public:
  3261. // @cond EXCLUDE
  3262. KARTO_Object(LaserRangeFinder)
  3263. // @endcond
  3264. public:
  3265. /**
  3266. * Destructor
  3267. */
  3268. virtual ~LaserRangeFinder()
  3269. {
  3270. }
  3271. public:
  3272. /**
  3273. * Gets this range finder sensor's minimum range
  3274. * @return minimum range
  3275. */
  3276. inline kt_double GetMinimumRange() const
  3277. {
  3278. return m_pMinimumRange->GetValue();
  3279. }
  3280. /**
  3281. * Sets this range finder sensor's minimum range
  3282. * @param minimumRange
  3283. */
  3284. inline void SetMinimumRange(kt_double minimumRange)
  3285. {
  3286. m_pMinimumRange->SetValue(minimumRange);
  3287. SetRangeThreshold(GetRangeThreshold());
  3288. }
  3289. /**
  3290. * Gets this range finder sensor's maximum range
  3291. * @return maximum range
  3292. */
  3293. inline kt_double GetMaximumRange() const
  3294. {
  3295. return m_pMaximumRange->GetValue();
  3296. }
  3297. /**
  3298. * Sets this range finder sensor's maximum range
  3299. * @param maximumRange
  3300. */
  3301. inline void SetMaximumRange(kt_double maximumRange)
  3302. {
  3303. m_pMaximumRange->SetValue(maximumRange);
  3304. SetRangeThreshold(GetRangeThreshold());
  3305. }
  3306. /**
  3307. * Gets the range threshold
  3308. * @return range threshold
  3309. */
  3310. inline kt_double GetRangeThreshold() const
  3311. {
  3312. return m_pRangeThreshold->GetValue();
  3313. }
  3314. /**
  3315. * Sets the range threshold
  3316. * @param rangeThreshold
  3317. */
  3318. inline void SetRangeThreshold(kt_double rangeThreshold)
  3319. {
  3320. // make sure rangeThreshold is within laser range finder range
  3321. m_pRangeThreshold->SetValue(math::Clip(rangeThreshold, GetMinimumRange(), GetMaximumRange()));
  3322. if (math::DoubleEqual(GetRangeThreshold(), rangeThreshold) == false)
  3323. {
  3324. std::cout << "Info: clipped range threshold to be within minimum and maximum range!" << std::endl;
  3325. }
  3326. }
  3327. /**
  3328. * Gets this range finder sensor's minimum angle
  3329. * @return minimum angle
  3330. */
  3331. inline kt_double GetMinimumAngle() const
  3332. {
  3333. return m_pMinimumAngle->GetValue();
  3334. }
  3335. /**
  3336. * Sets this range finder sensor's minimum angle
  3337. * @param minimumAngle
  3338. */
  3339. inline void SetMinimumAngle(kt_double minimumAngle)
  3340. {
  3341. m_pMinimumAngle->SetValue(minimumAngle);
  3342. Update();
  3343. }
  3344. /**
  3345. * Gets this range finder sensor's maximum angle
  3346. * @return maximum angle
  3347. */
  3348. inline kt_double GetMaximumAngle() const
  3349. {
  3350. return m_pMaximumAngle->GetValue();
  3351. }
  3352. /**
  3353. * Sets this range finder sensor's maximum angle
  3354. * @param maximumAngle
  3355. */
  3356. inline void SetMaximumAngle(kt_double maximumAngle)
  3357. {
  3358. m_pMaximumAngle->SetValue(maximumAngle);
  3359. Update();
  3360. }
  3361. /**
  3362. * Gets this range finder sensor's angular resolution
  3363. * @return angular resolution
  3364. */
  3365. inline kt_double GetAngularResolution() const
  3366. {
  3367. return m_pAngularResolution->GetValue();
  3368. }
  3369. /**
  3370. * Sets this range finder sensor's angular resolution
  3371. * @param angularResolution
  3372. */
  3373. inline void SetAngularResolution(kt_double angularResolution)
  3374. {
  3375. if (m_pType->GetValue() == LaserRangeFinder_Custom)
  3376. {
  3377. m_pAngularResolution->SetValue(angularResolution);
  3378. }
  3379. else if (m_pType->GetValue() == LaserRangeFinder_Sick_LMS100)
  3380. {
  3381. if (math::DoubleEqual(angularResolution, math::DegreesToRadians(0.25)))
  3382. {
  3383. m_pAngularResolution->SetValue(math::DegreesToRadians(0.25));
  3384. }
  3385. else if (math::DoubleEqual(angularResolution, math::DegreesToRadians(0.50)))
  3386. {
  3387. m_pAngularResolution->SetValue(math::DegreesToRadians(0.50));
  3388. }
  3389. else
  3390. {
  3391. std::stringstream stream;
  3392. stream << "Invalid resolution for Sick LMS100: ";
  3393. stream << angularResolution;
  3394. throw Exception(stream.str());
  3395. }
  3396. }
  3397. else if (m_pType->GetValue() == LaserRangeFinder_Sick_LMS200 ||
  3398. m_pType->GetValue() == LaserRangeFinder_Sick_LMS291)
  3399. {
  3400. if (math::DoubleEqual(angularResolution, math::DegreesToRadians(0.25)))
  3401. {
  3402. m_pAngularResolution->SetValue(math::DegreesToRadians(0.25));
  3403. }
  3404. else if (math::DoubleEqual(angularResolution, math::DegreesToRadians(0.50)))
  3405. {
  3406. m_pAngularResolution->SetValue(math::DegreesToRadians(0.50));
  3407. }
  3408. else if (math::DoubleEqual(angularResolution, math::DegreesToRadians(1.00)))
  3409. {
  3410. m_pAngularResolution->SetValue(math::DegreesToRadians(1.00));
  3411. }
  3412. else
  3413. {
  3414. std::stringstream stream;
  3415. stream << "Invalid resolution for Sick LMS291: ";
  3416. stream << angularResolution;
  3417. throw Exception(stream.str());
  3418. }
  3419. }
  3420. else if (m_pType->GetValue() == LaserRangeFinder_Hokuyo_UTM_30LX)
  3421. {
  3422. if (math::DoubleEqual(angularResolution, math::DegreesToRadians(0.25)))
  3423. {
  3424. m_pAngularResolution->SetValue(math::DegreesToRadians(0.25));
  3425. }
  3426. else
  3427. {
  3428. std::stringstream stream;
  3429. stream << "Invalid resolution for Hokuyo_UTM_30LX: ";
  3430. stream << angularResolution;
  3431. throw Exception(stream.str());
  3432. }
  3433. }
  3434. else if (m_pType->GetValue() == LaserRangeFinder_Hokuyo_URG_04LX)
  3435. {
  3436. if (math::DoubleEqual(angularResolution, math::DegreesToRadians(0.352)))
  3437. {
  3438. m_pAngularResolution->SetValue(math::DegreesToRadians(0.352));
  3439. }
  3440. else
  3441. {
  3442. std::stringstream stream;
  3443. stream << "Invalid resolution for Hokuyo_URG_04LX: ";
  3444. stream << angularResolution;
  3445. throw Exception(stream.str());
  3446. }
  3447. }
  3448. else
  3449. {
  3450. throw Exception("Can't set angular resolution, please create a LaserRangeFinder of type Custom");
  3451. }
  3452. Update();
  3453. }
  3454. /**
  3455. * Return Laser type
  3456. */
  3457. inline kt_int32s GetType()
  3458. {
  3459. return m_pType->GetValue();
  3460. }
  3461. /**
  3462. * Gets the number of range readings each localized range scan must contain to be a valid scan.
  3463. * @return number of range readings
  3464. */
  3465. inline kt_int32u GetNumberOfRangeReadings() const
  3466. {
  3467. return m_NumberOfRangeReadings;
  3468. }
  3469. virtual kt_bool Validate()
  3470. {
  3471. Update();
  3472. if (math::InRange(GetRangeThreshold(), GetMinimumRange(), GetMaximumRange()) == false)
  3473. {
  3474. std::cout << "Please set range threshold to a value between ["
  3475. << GetMinimumRange() << ";" << GetMaximumRange() << "]" << std::endl;
  3476. return false;
  3477. }
  3478. return true;
  3479. }
  3480. virtual kt_bool Validate(SensorData* pSensorData);
  3481. /**
  3482. * Get point readings (potentially scale readings if given coordinate converter is not null)
  3483. * @param pLocalizedRangeScan
  3484. * @param pCoordinateConverter
  3485. * @param ignoreThresholdPoints
  3486. * @param flipY
  3487. */
  3488. const PointVectorDouble GetPointReadings(LocalizedRangeScan* pLocalizedRangeScan,
  3489. CoordinateConverter* pCoordinateConverter,
  3490. kt_bool ignoreThresholdPoints = true,
  3491. kt_bool flipY = false) const;
  3492. public:
  3493. /**
  3494. * Create a laser range finder of the given type and ID
  3495. * @param type
  3496. * @param rName name of sensor - if no name is specified default name will be assigned
  3497. * @return laser range finder
  3498. */
  3499. static LaserRangeFinder* CreateLaserRangeFinder(LaserRangeFinderType type, const Name& rName)
  3500. {
  3501. LaserRangeFinder* pLrf = NULL;
  3502. switch (type)
  3503. {
  3504. // see http://www.hizook.com/files/publications/SICK_LMS100.pdf
  3505. // set range threshold to 18m
  3506. case LaserRangeFinder_Sick_LMS100:
  3507. {
  3508. pLrf = new LaserRangeFinder((rName.GetName() != "") ? rName : Name("Sick LMS 100"));
  3509. // Sensing range is 18 meters (at 10% reflectivity, max range of 20 meters), with an error of about 20mm
  3510. pLrf->m_pMinimumRange->SetValue(0.0);
  3511. pLrf->m_pMaximumRange->SetValue(20.0);
  3512. // 270 degree range, 50 Hz
  3513. pLrf->m_pMinimumAngle->SetValue(math::DegreesToRadians(-135));
  3514. pLrf->m_pMaximumAngle->SetValue(math::DegreesToRadians(135));
  3515. // 0.25 degree angular resolution
  3516. pLrf->m_pAngularResolution->SetValue(math::DegreesToRadians(0.25));
  3517. pLrf->m_NumberOfRangeReadings = 1081;
  3518. }
  3519. break;
  3520. // see http://www.hizook.com/files/publications/SICK_LMS200-291_Tech_Info.pdf
  3521. // set range threshold to 10m
  3522. case LaserRangeFinder_Sick_LMS200:
  3523. {
  3524. pLrf = new LaserRangeFinder((rName.GetName() != "") ? rName : Name("Sick LMS 200"));
  3525. // Sensing range is 80 meters
  3526. pLrf->m_pMinimumRange->SetValue(0.0);
  3527. pLrf->m_pMaximumRange->SetValue(80.0);
  3528. // 180 degree range, 75 Hz
  3529. pLrf->m_pMinimumAngle->SetValue(math::DegreesToRadians(-90));
  3530. pLrf->m_pMaximumAngle->SetValue(math::DegreesToRadians(90));
  3531. // 0.5 degree angular resolution
  3532. pLrf->m_pAngularResolution->SetValue(math::DegreesToRadians(0.5));
  3533. pLrf->m_NumberOfRangeReadings = 361;
  3534. }
  3535. break;
  3536. // see http://www.hizook.com/files/publications/SICK_LMS200-291_Tech_Info.pdf
  3537. // set range threshold to 30m
  3538. case LaserRangeFinder_Sick_LMS291:
  3539. {
  3540. pLrf = new LaserRangeFinder((rName.GetName() != "") ? rName : Name("Sick LMS 291"));
  3541. // Sensing range is 80 meters
  3542. pLrf->m_pMinimumRange->SetValue(0.0);
  3543. pLrf->m_pMaximumRange->SetValue(80.0);
  3544. // 180 degree range, 75 Hz
  3545. pLrf->m_pMinimumAngle->SetValue(math::DegreesToRadians(-90));
  3546. pLrf->m_pMaximumAngle->SetValue(math::DegreesToRadians(90));
  3547. // 0.5 degree angular resolution
  3548. pLrf->m_pAngularResolution->SetValue(math::DegreesToRadians(0.5));
  3549. pLrf->m_NumberOfRangeReadings = 361;
  3550. }
  3551. break;
  3552. // see http://www.hizook.com/files/publications/Hokuyo_UTM_LaserRangeFinder_LIDAR.pdf
  3553. // set range threshold to 30m
  3554. case LaserRangeFinder_Hokuyo_UTM_30LX:
  3555. {
  3556. pLrf = new LaserRangeFinder((rName.GetName() != "") ? rName : Name("Hokuyo UTM-30LX"));
  3557. // Sensing range is 30 meters
  3558. pLrf->m_pMinimumRange->SetValue(0.1);
  3559. pLrf->m_pMaximumRange->SetValue(30.0);
  3560. // 270 degree range, 40 Hz
  3561. pLrf->m_pMinimumAngle->SetValue(math::DegreesToRadians(-135));
  3562. pLrf->m_pMaximumAngle->SetValue(math::DegreesToRadians(135));
  3563. // 0.25 degree angular resolution
  3564. pLrf->m_pAngularResolution->SetValue(math::DegreesToRadians(0.25));
  3565. pLrf->m_NumberOfRangeReadings = 1081;
  3566. }
  3567. break;
  3568. // see http://www.hizook.com/files/publications/HokuyoURG_Datasheet.pdf
  3569. // set range threshold to 3.5m
  3570. case LaserRangeFinder_Hokuyo_URG_04LX:
  3571. {
  3572. pLrf = new LaserRangeFinder((rName.GetName() != "") ? rName : Name("Hokuyo URG-04LX"));
  3573. // Sensing range is 4 meters. It has detection problems when
  3574. // scanning absorptive surfaces (such as black trimming).
  3575. pLrf->m_pMinimumRange->SetValue(0.02);
  3576. pLrf->m_pMaximumRange->SetValue(4.0);
  3577. // 240 degree range, 10 Hz
  3578. pLrf->m_pMinimumAngle->SetValue(math::DegreesToRadians(-120));
  3579. pLrf->m_pMaximumAngle->SetValue(math::DegreesToRadians(120));
  3580. // 0.352 degree angular resolution
  3581. pLrf->m_pAngularResolution->SetValue(math::DegreesToRadians(0.352));
  3582. pLrf->m_NumberOfRangeReadings = 751;
  3583. }
  3584. break;
  3585. case LaserRangeFinder_Custom:
  3586. {
  3587. pLrf = new LaserRangeFinder((rName.GetName() != "") ? rName : Name("User-Defined LaserRangeFinder"));
  3588. // Sensing range is 80 meters.
  3589. pLrf->m_pMinimumRange->SetValue(0.0);
  3590. pLrf->m_pMaximumRange->SetValue(80.0);
  3591. // 180 degree range
  3592. pLrf->m_pMinimumAngle->SetValue(math::DegreesToRadians(-90));
  3593. pLrf->m_pMaximumAngle->SetValue(math::DegreesToRadians(90));
  3594. // 1.0 degree angular resolution
  3595. pLrf->m_pAngularResolution->SetValue(math::DegreesToRadians(1.0));
  3596. pLrf->m_NumberOfRangeReadings = 181;
  3597. }
  3598. break;
  3599. }
  3600. if (pLrf != NULL)
  3601. {
  3602. pLrf->m_pType->SetValue(type);
  3603. Pose2 defaultOffset;
  3604. pLrf->SetOffsetPose(defaultOffset);
  3605. }
  3606. return pLrf;
  3607. }
  3608. private:
  3609. /**
  3610. * Constructs a LaserRangeFinder object with given ID
  3611. */
  3612. LaserRangeFinder(const Name& rName)
  3613. : Sensor(rName)
  3614. , m_NumberOfRangeReadings(0)
  3615. {
  3616. m_pMinimumRange = new Parameter<kt_double>("MinimumRange", 0.0, GetParameterManager());
  3617. m_pMaximumRange = new Parameter<kt_double>("MaximumRange", 80.0, GetParameterManager());
  3618. m_pMinimumAngle = new Parameter<kt_double>("MinimumAngle", -KT_PI_2, GetParameterManager());
  3619. m_pMaximumAngle = new Parameter<kt_double>("MaximumAngle", KT_PI_2, GetParameterManager());
  3620. m_pAngularResolution = new Parameter<kt_double>("AngularResolution",
  3621. math::DegreesToRadians(1),
  3622. GetParameterManager());
  3623. m_pRangeThreshold = new Parameter<kt_double>("RangeThreshold", 12.0, GetParameterManager());
  3624. m_pType = new ParameterEnum("Type", LaserRangeFinder_Custom, GetParameterManager());
  3625. m_pType->DefineEnumValue(LaserRangeFinder_Custom, "Custom");
  3626. m_pType->DefineEnumValue(LaserRangeFinder_Sick_LMS100, "Sick_LMS100");
  3627. m_pType->DefineEnumValue(LaserRangeFinder_Sick_LMS200, "Sick_LMS200");
  3628. m_pType->DefineEnumValue(LaserRangeFinder_Sick_LMS291, "Sick_LMS291");
  3629. m_pType->DefineEnumValue(LaserRangeFinder_Hokuyo_UTM_30LX, "Hokuyo_UTM_30LX");
  3630. m_pType->DefineEnumValue(LaserRangeFinder_Hokuyo_URG_04LX, "Hokuyo_URG_04LX");
  3631. }
  3632. /**
  3633. * Set the number of range readings based on the minimum and
  3634. * maximum angles of the sensor and the angular resolution
  3635. */
  3636. void Update()
  3637. {
  3638. m_NumberOfRangeReadings = static_cast<kt_int32u>(math::Round((GetMaximumAngle() -
  3639. GetMinimumAngle())
  3640. / GetAngularResolution()) + 1);
  3641. }
  3642. private:
  3643. LaserRangeFinder(const LaserRangeFinder&);
  3644. const LaserRangeFinder& operator=(const LaserRangeFinder&);
  3645. private:
  3646. // sensor m_Parameters
  3647. Parameter<kt_double>* m_pMinimumAngle;
  3648. Parameter<kt_double>* m_pMaximumAngle;
  3649. Parameter<kt_double>* m_pAngularResolution;
  3650. Parameter<kt_double>* m_pMinimumRange;
  3651. Parameter<kt_double>* m_pMaximumRange;
  3652. Parameter<kt_double>* m_pRangeThreshold;
  3653. ParameterEnum* m_pType;
  3654. kt_int32u m_NumberOfRangeReadings;
  3655. // static std::string LaserRangeFinderTypeNames[6];
  3656. }; // LaserRangeFinder
  3657. ////////////////////////////////////////////////////////////////////////////////////////
  3658. ////////////////////////////////////////////////////////////////////////////////////////
  3659. ////////////////////////////////////////////////////////////////////////////////////////
  3660. /**
  3661. * Enumerated type for valid grid cell states
  3662. */
  3663. typedef enum
  3664. {
  3665. GridStates_Unknown = 0,
  3666. GridStates_Occupied = 100,
  3667. GridStates_Free = 255
  3668. } GridStates;
  3669. ////////////////////////////////////////////////////////////////////////////////////////
  3670. ////////////////////////////////////////////////////////////////////////////////////////
  3671. ////////////////////////////////////////////////////////////////////////////////////////
  3672. /**
  3673. * The CoordinateConverter class is used to convert coordinates between world and grid coordinates
  3674. * In world coordinates 1.0 = 1 meter where 1 in grid coordinates = 1 pixel!
  3675. * Default scale for coordinate converter is 20 that converters to 1 pixel = 0.05 meter
  3676. */
  3677. class CoordinateConverter
  3678. {
  3679. public:
  3680. /**
  3681. * Default constructor
  3682. */
  3683. CoordinateConverter()
  3684. : m_Scale(20.0)
  3685. {
  3686. }
  3687. public:
  3688. /**
  3689. * Scales the value
  3690. * @param value
  3691. * @return scaled value
  3692. */
  3693. inline kt_double Transform(kt_double value)
  3694. {
  3695. return value * m_Scale;
  3696. }
  3697. /**
  3698. * Converts the point from world coordinates to grid coordinates
  3699. * @param rWorld world coordinate
  3700. * @param flipY
  3701. * @return grid coordinate
  3702. */
  3703. inline Vector2<kt_int32s> WorldToGrid(const Vector2<kt_double>& rWorld, kt_bool flipY = false) const
  3704. {
  3705. kt_double gridX = (rWorld.GetX() - m_Offset.GetX()) * m_Scale;
  3706. kt_double gridY = 0.0;
  3707. if (flipY == false)
  3708. {
  3709. gridY = (rWorld.GetY() - m_Offset.GetY()) * m_Scale;
  3710. }
  3711. else
  3712. {
  3713. gridY = (m_Size.GetHeight() / m_Scale - rWorld.GetY() + m_Offset.GetY()) * m_Scale;
  3714. }
  3715. return Vector2<kt_int32s>(static_cast<kt_int32s>(math::Round(gridX)), static_cast<kt_int32s>(math::Round(gridY)));
  3716. }
  3717. /**
  3718. * Converts the point from grid coordinates to world coordinates
  3719. * @param rGrid world coordinate
  3720. * @param flipY
  3721. * @return world coordinate
  3722. */
  3723. inline Vector2<kt_double> GridToWorld(const Vector2<kt_int32s>& rGrid, kt_bool flipY = false) const
  3724. {
  3725. kt_double worldX = m_Offset.GetX() + rGrid.GetX() / m_Scale;
  3726. kt_double worldY = 0.0;
  3727. if (flipY == false)
  3728. {
  3729. worldY = m_Offset.GetY() + rGrid.GetY() / m_Scale;
  3730. }
  3731. else
  3732. {
  3733. worldY = m_Offset.GetY() + (m_Size.GetHeight() - rGrid.GetY()) / m_Scale;
  3734. }
  3735. return Vector2<kt_double>(worldX, worldY);
  3736. }
  3737. /**
  3738. * Gets the scale
  3739. * @return scale
  3740. */
  3741. inline kt_double GetScale() const
  3742. {
  3743. return m_Scale;
  3744. }
  3745. /**
  3746. * Sets the scale
  3747. * @param scale
  3748. */
  3749. inline void SetScale(kt_double scale)
  3750. {
  3751. m_Scale = scale;
  3752. }
  3753. /**
  3754. * Gets the offset
  3755. * @return offset
  3756. */
  3757. inline const Vector2<kt_double>& GetOffset() const
  3758. {
  3759. return m_Offset;
  3760. }
  3761. /**
  3762. * Sets the offset
  3763. * @param rOffset
  3764. */
  3765. inline void SetOffset(const Vector2<kt_double>& rOffset)
  3766. {
  3767. m_Offset = rOffset;
  3768. }
  3769. /**
  3770. * Sets the size
  3771. * @param rSize
  3772. */
  3773. inline void SetSize(const Size2<kt_int32s>& rSize)
  3774. {
  3775. m_Size = rSize;
  3776. }
  3777. /**
  3778. * Gets the size
  3779. * @return size
  3780. */
  3781. inline const Size2<kt_int32s>& GetSize() const
  3782. {
  3783. return m_Size;
  3784. }
  3785. /**
  3786. * Gets the resolution
  3787. * @return resolution
  3788. */
  3789. inline kt_double GetResolution() const
  3790. {
  3791. return 1.0 / m_Scale;
  3792. }
  3793. /**
  3794. * Sets the resolution
  3795. * @param resolution
  3796. */
  3797. inline void SetResolution(kt_double resolution)
  3798. {
  3799. m_Scale = 1.0 / resolution;
  3800. }
  3801. /**
  3802. * Gets the bounding box
  3803. * @return bounding box
  3804. */
  3805. inline BoundingBox2 GetBoundingBox() const
  3806. {
  3807. BoundingBox2 box;
  3808. kt_double minX = GetOffset().GetX();
  3809. kt_double minY = GetOffset().GetY();
  3810. kt_double maxX = minX + GetSize().GetWidth() * GetResolution();
  3811. kt_double maxY = minY + GetSize().GetHeight() * GetResolution();
  3812. box.SetMinimum(GetOffset());
  3813. box.SetMaximum(Vector2<kt_double>(maxX, maxY));
  3814. return box;
  3815. }
  3816. private:
  3817. Size2<kt_int32s> m_Size;
  3818. kt_double m_Scale;
  3819. Vector2<kt_double> m_Offset;
  3820. }; // CoordinateConverter
  3821. ////////////////////////////////////////////////////////////////////////////////////////
  3822. ////////////////////////////////////////////////////////////////////////////////////////
  3823. ////////////////////////////////////////////////////////////////////////////////////////
  3824. /**
  3825. * Defines a grid class
  3826. */
  3827. template<typename T>
  3828. class Grid
  3829. {
  3830. public:
  3831. /**
  3832. * Creates a grid of given size and resolution
  3833. * @param width
  3834. * @param height
  3835. * @param resolution
  3836. * @return grid pointer
  3837. */
  3838. static Grid* CreateGrid(kt_int32s width, kt_int32s height, kt_double resolution)
  3839. {
  3840. Grid* pGrid = new Grid(width, height);
  3841. pGrid->GetCoordinateConverter()->SetScale(1.0 / resolution);
  3842. return pGrid;
  3843. }
  3844. /**
  3845. * Destructor
  3846. */
  3847. virtual ~Grid()
  3848. {
  3849. delete [] m_pData;
  3850. delete m_pCoordinateConverter;
  3851. }
  3852. public:
  3853. /**
  3854. * Clear out the grid data
  3855. */
  3856. void Clear()
  3857. {
  3858. memset(m_pData, 0, GetDataSize() * sizeof(T));
  3859. }
  3860. /**
  3861. * Returns a clone of this grid
  3862. * @return grid clone
  3863. */
  3864. Grid* Clone()
  3865. {
  3866. Grid* pGrid = CreateGrid(GetWidth(), GetHeight(), GetResolution());
  3867. pGrid->GetCoordinateConverter()->SetOffset(GetCoordinateConverter()->GetOffset());
  3868. memcpy(pGrid->GetDataPointer(), GetDataPointer(), GetDataSize());
  3869. return pGrid;
  3870. }
  3871. /**
  3872. * Resizes the grid (deletes all old data)
  3873. * @param width
  3874. * @param height
  3875. */
  3876. virtual void Resize(kt_int32s width, kt_int32s height)
  3877. {
  3878. m_Width = width;
  3879. m_Height = height;
  3880. m_WidthStep = math::AlignValue<kt_int32s>(width, 8);
  3881. if (m_pData != NULL)
  3882. {
  3883. delete[] m_pData;
  3884. m_pData = NULL;
  3885. }
  3886. try
  3887. {
  3888. m_pData = new T[GetDataSize()];
  3889. if (m_pCoordinateConverter == NULL)
  3890. {
  3891. m_pCoordinateConverter = new CoordinateConverter();
  3892. }
  3893. m_pCoordinateConverter->SetSize(Size2<kt_int32s>(width, height));
  3894. }
  3895. catch(...)
  3896. {
  3897. m_pData = NULL;
  3898. m_Width = 0;
  3899. m_Height = 0;
  3900. m_WidthStep = 0;
  3901. }
  3902. Clear();
  3903. }
  3904. /**
  3905. * Checks whether the given coordinates are valid grid indices
  3906. * @param rGrid
  3907. */
  3908. inline kt_bool IsValidGridIndex(const Vector2<kt_int32s>& rGrid) const
  3909. {
  3910. return (math::IsUpTo(rGrid.GetX(), m_Width) && math::IsUpTo(rGrid.GetY(), m_Height));
  3911. }
  3912. /**
  3913. * Gets the index into the data pointer of the given grid coordinate
  3914. * @param rGrid
  3915. * @param boundaryCheck default value is true
  3916. * @return grid index
  3917. */
  3918. virtual kt_int32s GridIndex(const Vector2<kt_int32s>& rGrid, kt_bool boundaryCheck = true) const
  3919. {
  3920. if (boundaryCheck == true)
  3921. {
  3922. if (IsValidGridIndex(rGrid) == false)
  3923. {
  3924. std::stringstream error;
  3925. error << "Index " << rGrid << " out of range. Index must be between [0; "
  3926. << m_Width << ") and [0; " << m_Height << ")";
  3927. throw Exception(error.str());
  3928. }
  3929. }
  3930. kt_int32s index = rGrid.GetX() + (rGrid.GetY() * m_WidthStep);
  3931. if (boundaryCheck == true)
  3932. {
  3933. assert(math::IsUpTo(index, GetDataSize()));
  3934. }
  3935. return index;
  3936. }
  3937. /**
  3938. * Gets the grid coordinate from an index
  3939. * @param index
  3940. * @return grid coordinate
  3941. */
  3942. Vector2<kt_int32s> IndexToGrid(kt_int32s index) const
  3943. {
  3944. Vector2<kt_int32s> grid;
  3945. grid.SetY(index / m_WidthStep);
  3946. grid.SetX(index - grid.GetY() * m_WidthStep);
  3947. return grid;
  3948. }
  3949. /**
  3950. * Converts the point from world coordinates to grid coordinates
  3951. * @param rWorld world coordinate
  3952. * @param flipY
  3953. * @return grid coordinate
  3954. */
  3955. inline Vector2<kt_int32s> WorldToGrid(const Vector2<kt_double>& rWorld, kt_bool flipY = false) const
  3956. {
  3957. return GetCoordinateConverter()->WorldToGrid(rWorld, flipY);
  3958. }
  3959. /**
  3960. * Converts the point from grid coordinates to world coordinates
  3961. * @param rGrid world coordinate
  3962. * @param flipY
  3963. * @return world coordinate
  3964. */
  3965. inline Vector2<kt_double> GridToWorld(const Vector2<kt_int32s>& rGrid, kt_bool flipY = false) const
  3966. {
  3967. return GetCoordinateConverter()->GridToWorld(rGrid, flipY);
  3968. }
  3969. /**
  3970. * Gets pointer to data at given grid coordinate
  3971. * @param rGrid grid coordinate
  3972. * @return grid point
  3973. */
  3974. T* GetDataPointer(const Vector2<kt_int32s>& rGrid)
  3975. {
  3976. kt_int32s index = GridIndex(rGrid, true);
  3977. return m_pData + index;
  3978. }
  3979. /**
  3980. * Gets pointer to data at given grid coordinate
  3981. * @param rGrid grid coordinate
  3982. * @return grid point
  3983. */
  3984. T* GetDataPointer(const Vector2<kt_int32s>& rGrid) const
  3985. {
  3986. kt_int32s index = GridIndex(rGrid, true);
  3987. return m_pData + index;
  3988. }
  3989. /**
  3990. * Gets the width of the grid
  3991. * @return width of the grid
  3992. */
  3993. inline kt_int32s GetWidth() const
  3994. {
  3995. return m_Width;
  3996. };
  3997. /**
  3998. * Gets the height of the grid
  3999. * @return height of the grid
  4000. */
  4001. inline kt_int32s GetHeight() const
  4002. {
  4003. return m_Height;
  4004. };
  4005. /**
  4006. * Get the size as a Size2<kt_int32s>
  4007. * @return size of the grid
  4008. */
  4009. inline const Size2<kt_int32s> GetSize() const
  4010. {
  4011. return Size2<kt_int32s>(m_Width, m_Height);
  4012. }
  4013. /**
  4014. * Gets the width step in bytes
  4015. * @return width step
  4016. */
  4017. inline kt_int32s GetWidthStep() const
  4018. {
  4019. return m_WidthStep;
  4020. }
  4021. /**
  4022. * Gets the grid data pointer
  4023. * @return data pointer
  4024. */
  4025. inline T* GetDataPointer()
  4026. {
  4027. return m_pData;
  4028. }
  4029. /**
  4030. * Gets const grid data pointer
  4031. * @return data pointer
  4032. */
  4033. inline T* GetDataPointer() const
  4034. {
  4035. return m_pData;
  4036. }
  4037. /**
  4038. * Gets the allocated grid size in bytes
  4039. * @return data size
  4040. */
  4041. inline kt_int32s GetDataSize() const
  4042. {
  4043. return m_WidthStep * m_Height;
  4044. }
  4045. /**
  4046. * Get value at given grid coordinate
  4047. * @param rGrid grid coordinate
  4048. * @return value
  4049. */
  4050. inline T GetValue(const Vector2<kt_int32s>& rGrid) const
  4051. {
  4052. kt_int32s index = GridIndex(rGrid);
  4053. return m_pData[index];
  4054. }
  4055. /**
  4056. * Gets the coordinate converter for this grid
  4057. * @return coordinate converter
  4058. */
  4059. inline CoordinateConverter* GetCoordinateConverter() const
  4060. {
  4061. return m_pCoordinateConverter;
  4062. }
  4063. /**
  4064. * Gets the resolution
  4065. * @return resolution
  4066. */
  4067. inline kt_double GetResolution() const
  4068. {
  4069. return GetCoordinateConverter()->GetResolution();
  4070. }
  4071. /**
  4072. * Gets the grids bounding box
  4073. * @return bounding box
  4074. */
  4075. inline BoundingBox2 GetBoundingBox() const
  4076. {
  4077. return GetCoordinateConverter()->GetBoundingBox();
  4078. }
  4079. /**
  4080. * Increments all the grid cells from (x0, y0) to (x1, y1);
  4081. * if applicable, apply f to each cell traced
  4082. * @param x0
  4083. * @param y0
  4084. * @param x1
  4085. * @param y1
  4086. * @param f
  4087. */
  4088. void TraceLine(kt_int32s x0, kt_int32s y0, kt_int32s x1, kt_int32s y1, Functor* f = NULL)
  4089. {
  4090. kt_bool steep = abs(y1 - y0) > abs(x1 - x0);
  4091. if (steep)
  4092. {
  4093. std::swap(x0, y0);
  4094. std::swap(x1, y1);
  4095. }
  4096. if (x0 > x1)
  4097. {
  4098. std::swap(x0, x1);
  4099. std::swap(y0, y1);
  4100. }
  4101. kt_int32s deltaX = x1 - x0;
  4102. kt_int32s deltaY = abs(y1 - y0);
  4103. kt_int32s error = 0;
  4104. kt_int32s ystep;
  4105. kt_int32s y = y0;
  4106. if (y0 < y1)
  4107. {
  4108. ystep = 1;
  4109. }
  4110. else
  4111. {
  4112. ystep = -1;
  4113. }
  4114. kt_int32s pointX;
  4115. kt_int32s pointY;
  4116. for (kt_int32s x = x0; x <= x1; x++)
  4117. {
  4118. if (steep)
  4119. {
  4120. pointX = y;
  4121. pointY = x;
  4122. }
  4123. else
  4124. {
  4125. pointX = x;
  4126. pointY = y;
  4127. }
  4128. error += deltaY;
  4129. if (2 * error >= deltaX)
  4130. {
  4131. y += ystep;
  4132. error -= deltaX;
  4133. }
  4134. Vector2<kt_int32s> gridIndex(pointX, pointY);
  4135. if (IsValidGridIndex(gridIndex))
  4136. {
  4137. kt_int32s index = GridIndex(gridIndex, false);
  4138. T* pGridPointer = GetDataPointer();
  4139. pGridPointer[index]++;
  4140. if (f != NULL)
  4141. {
  4142. (*f)(index);
  4143. }
  4144. }
  4145. }
  4146. }
  4147. protected:
  4148. /**
  4149. * Constructs grid of given size
  4150. * @param width
  4151. * @param height
  4152. */
  4153. Grid(kt_int32s width, kt_int32s height)
  4154. : m_pData(NULL)
  4155. , m_pCoordinateConverter(NULL)
  4156. {
  4157. Resize(width, height);
  4158. }
  4159. private:
  4160. kt_int32s m_Width; // width of grid
  4161. kt_int32s m_Height; // height of grid
  4162. kt_int32s m_WidthStep; // 8 bit aligned width of grid
  4163. T* m_pData; // grid data
  4164. // coordinate converter to convert between world coordinates and grid coordinates
  4165. CoordinateConverter* m_pCoordinateConverter;
  4166. }; // Grid
  4167. ////////////////////////////////////////////////////////////////////////////////////////
  4168. ////////////////////////////////////////////////////////////////////////////////////////
  4169. ////////////////////////////////////////////////////////////////////////////////////////
  4170. /**
  4171. * For making custom data
  4172. */
  4173. class CustomData : public Object
  4174. {
  4175. public:
  4176. // @cond EXCLUDE
  4177. KARTO_Object(CustomData)
  4178. // @endcond
  4179. public:
  4180. /**
  4181. * Constructor
  4182. */
  4183. CustomData()
  4184. : Object()
  4185. {
  4186. }
  4187. /**
  4188. * Destructor
  4189. */
  4190. virtual ~CustomData()
  4191. {
  4192. }
  4193. public:
  4194. /**
  4195. * Write out this custom data as a string
  4196. * @return string representation of this data object
  4197. */
  4198. virtual const std::string Write() const = 0;
  4199. /**
  4200. * Read in this custom data from a string
  4201. * @param rValue string representation of this data object
  4202. */
  4203. virtual void Read(const std::string& rValue) = 0;
  4204. private:
  4205. CustomData(const CustomData&);
  4206. const CustomData& operator=(const CustomData&);
  4207. };
  4208. /**
  4209. * Type declaration of CustomData vector
  4210. */
  4211. typedef std::vector<CustomData*> CustomDataVector;
  4212. ////////////////////////////////////////////////////////////////////////////////////////
  4213. ////////////////////////////////////////////////////////////////////////////////////////
  4214. ////////////////////////////////////////////////////////////////////////////////////////
  4215. /**
  4216. * SensorData is a base class for all sensor data
  4217. */
  4218. class KARTO_EXPORT SensorData : public Object
  4219. {
  4220. public:
  4221. // @cond EXCLUDE
  4222. KARTO_Object(SensorData)
  4223. // @endcond
  4224. public:
  4225. /**
  4226. * Destructor
  4227. */
  4228. virtual ~SensorData();
  4229. public:
  4230. /**
  4231. * Gets sensor data id
  4232. * @return sensor id
  4233. */
  4234. inline kt_int32s GetStateId() const
  4235. {
  4236. return m_StateId;
  4237. }
  4238. /**
  4239. * Sets sensor data id
  4240. * @param stateId id
  4241. */
  4242. inline void SetStateId(kt_int32s stateId)
  4243. {
  4244. m_StateId = stateId;
  4245. }
  4246. /**
  4247. * Gets sensor unique id
  4248. * @return unique id
  4249. */
  4250. inline kt_int32s GetUniqueId() const
  4251. {
  4252. return m_UniqueId;
  4253. }
  4254. /**
  4255. * Sets sensor unique id
  4256. * @param uniqueId
  4257. */
  4258. inline void SetUniqueId(kt_int32u uniqueId)
  4259. {
  4260. m_UniqueId = uniqueId;
  4261. }
  4262. /**
  4263. * Gets sensor data time
  4264. * @return time
  4265. */
  4266. inline kt_double GetTime() const
  4267. {
  4268. return m_Time;
  4269. }
  4270. /**
  4271. * Sets sensor data time
  4272. * @param time
  4273. */
  4274. inline void SetTime(kt_double time)
  4275. {
  4276. m_Time = time;
  4277. }
  4278. /**
  4279. * Get the sensor that created this sensor data
  4280. * @return sensor
  4281. */
  4282. inline const Name& GetSensorName() const
  4283. {
  4284. return m_SensorName;
  4285. }
  4286. /**
  4287. * Add a CustomData object to sensor data
  4288. * @param pCustomData
  4289. */
  4290. inline void AddCustomData(CustomData* pCustomData)
  4291. {
  4292. m_CustomData.push_back(pCustomData);
  4293. }
  4294. /**
  4295. * Get all custom data objects assigned to sensor data
  4296. * @return CustomDataVector&
  4297. */
  4298. inline const CustomDataVector& GetCustomData() const
  4299. {
  4300. return m_CustomData;
  4301. }
  4302. protected:
  4303. /**
  4304. * Construct a SensorData object with a sensor name
  4305. */
  4306. SensorData(const Name& rSensorName);
  4307. private:
  4308. /**
  4309. * Restrict the copy constructor
  4310. */
  4311. SensorData(const SensorData&);
  4312. /**
  4313. * Restrict the assignment operator
  4314. */
  4315. const SensorData& operator=(const SensorData&);
  4316. private:
  4317. /**
  4318. * ID unique to individual sensor
  4319. */
  4320. kt_int32s m_StateId;
  4321. /**
  4322. * ID unique across all sensor data
  4323. */
  4324. kt_int32s m_UniqueId;
  4325. /**
  4326. * Sensor that created this sensor data
  4327. */
  4328. Name m_SensorName;
  4329. /**
  4330. * Time the sensor data was created
  4331. */
  4332. kt_double m_Time;
  4333. CustomDataVector m_CustomData;
  4334. };
  4335. ////////////////////////////////////////////////////////////////////////////////////////
  4336. ////////////////////////////////////////////////////////////////////////////////////////
  4337. ////////////////////////////////////////////////////////////////////////////////////////
  4338. /**
  4339. * Type declaration of range readings vector
  4340. */
  4341. typedef std::vector<kt_double> RangeReadingsVector;
  4342. /**
  4343. * LaserRangeScan representing the range readings from a laser range finder sensor.
  4344. */
  4345. class LaserRangeScan : public SensorData
  4346. {
  4347. public:
  4348. // @cond EXCLUDE
  4349. KARTO_Object(LaserRangeScan)
  4350. // @endcond
  4351. public:
  4352. /**
  4353. * Constructs a scan from the given sensor with the given readings
  4354. * @param rSensorName
  4355. */
  4356. LaserRangeScan(const Name& rSensorName)
  4357. : SensorData(rSensorName)
  4358. , m_pRangeReadings(NULL)
  4359. , m_NumberOfRangeReadings(0)
  4360. {
  4361. }
  4362. /**
  4363. * Constructs a scan from the given sensor with the given readings
  4364. * @param rSensorName
  4365. * @param rRangeReadings
  4366. */
  4367. LaserRangeScan(const Name& rSensorName, const RangeReadingsVector& rRangeReadings)
  4368. : SensorData(rSensorName)
  4369. , m_pRangeReadings(NULL)
  4370. , m_NumberOfRangeReadings(0)
  4371. {
  4372. assert(rSensorName.ToString() != "");
  4373. SetRangeReadings(rRangeReadings);
  4374. }
  4375. /**
  4376. * Destructor
  4377. */
  4378. virtual ~LaserRangeScan()
  4379. {
  4380. delete [] m_pRangeReadings;
  4381. }
  4382. public:
  4383. /**
  4384. * Gets the range readings of this scan
  4385. * @return range readings of this scan
  4386. */
  4387. inline kt_double* GetRangeReadings() const
  4388. {
  4389. return m_pRangeReadings;
  4390. }
  4391. inline RangeReadingsVector GetRangeReadingsVector() const
  4392. {
  4393. return RangeReadingsVector(m_pRangeReadings, m_pRangeReadings + m_NumberOfRangeReadings);
  4394. }
  4395. /**
  4396. * Sets the range readings for this scan
  4397. * @param rRangeReadings
  4398. */
  4399. inline void SetRangeReadings(const RangeReadingsVector& rRangeReadings)
  4400. {
  4401. // ignore for now! XXXMAE BUGUBUG 05/21/2010 << TODO(lucbettaieb): What the heck is this??
  4402. // if (rRangeReadings.size() != GetNumberOfRangeReadings())
  4403. // {
  4404. // std::stringstream error;
  4405. // error << "Given number of readings (" << rRangeReadings.size()
  4406. // << ") does not match expected number of range finder (" << GetNumberOfRangeReadings() << ")";
  4407. // throw Exception(error.str());
  4408. // }
  4409. if (!rRangeReadings.empty())
  4410. {
  4411. if (rRangeReadings.size() != m_NumberOfRangeReadings)
  4412. {
  4413. // delete old readings
  4414. delete [] m_pRangeReadings;
  4415. // store size of array!
  4416. m_NumberOfRangeReadings = static_cast<kt_int32u>(rRangeReadings.size());
  4417. // allocate range readings
  4418. m_pRangeReadings = new kt_double[m_NumberOfRangeReadings];
  4419. }
  4420. // copy readings
  4421. kt_int32u index = 0;
  4422. const_forEach(RangeReadingsVector, &rRangeReadings)
  4423. {
  4424. m_pRangeReadings[index++] = *iter;
  4425. }
  4426. }
  4427. else
  4428. {
  4429. delete [] m_pRangeReadings;
  4430. m_pRangeReadings = NULL;
  4431. }
  4432. }
  4433. /**
  4434. * Gets the laser range finder sensor that generated this scan
  4435. * @return laser range finder sensor of this scan
  4436. */
  4437. inline LaserRangeFinder* GetLaserRangeFinder() const
  4438. {
  4439. return SensorManager::GetInstance()->GetSensorByName<LaserRangeFinder>(GetSensorName());
  4440. }
  4441. /**
  4442. * Gets the number of range readings
  4443. * @return number of range readings
  4444. */
  4445. inline kt_int32u GetNumberOfRangeReadings() const
  4446. {
  4447. return m_NumberOfRangeReadings;
  4448. }
  4449. private:
  4450. LaserRangeScan(const LaserRangeScan&);
  4451. const LaserRangeScan& operator=(const LaserRangeScan&);
  4452. private:
  4453. kt_double* m_pRangeReadings;
  4454. kt_int32u m_NumberOfRangeReadings;
  4455. }; // LaserRangeScan
  4456. ////////////////////////////////////////////////////////////////////////////////////////
  4457. ////////////////////////////////////////////////////////////////////////////////////////
  4458. ////////////////////////////////////////////////////////////////////////////////////////
  4459. /**
  4460. * DrivePose representing the pose value of a drive sensor.
  4461. */
  4462. class DrivePose : public SensorData
  4463. {
  4464. public:
  4465. // @cond EXCLUDE
  4466. KARTO_Object(DrivePose)
  4467. // @endcond
  4468. public:
  4469. /**
  4470. * Constructs a pose of the given drive sensor
  4471. * @param rSensorName
  4472. */
  4473. DrivePose(const Name& rSensorName)
  4474. : SensorData(rSensorName)
  4475. {
  4476. }
  4477. /**
  4478. * Destructor
  4479. */
  4480. virtual ~DrivePose()
  4481. {
  4482. }
  4483. public:
  4484. /**
  4485. * Gets the odometric pose of this scan
  4486. * @return odometric pose of this scan
  4487. */
  4488. inline const Pose3& GetOdometricPose() const
  4489. {
  4490. return m_OdometricPose;
  4491. }
  4492. /**
  4493. * Sets the odometric pose of this scan
  4494. * @param rPose
  4495. */
  4496. inline void SetOdometricPose(const Pose3& rPose)
  4497. {
  4498. m_OdometricPose = rPose;
  4499. }
  4500. private:
  4501. DrivePose(const DrivePose&);
  4502. const DrivePose& operator=(const DrivePose&);
  4503. private:
  4504. /**
  4505. * Odometric pose of robot
  4506. */
  4507. Pose3 m_OdometricPose;
  4508. }; // class DrivePose
  4509. ////////////////////////////////////////////////////////////////////////////////////////
  4510. ////////////////////////////////////////////////////////////////////////////////////////
  4511. ////////////////////////////////////////////////////////////////////////////////////////
  4512. /**
  4513. * The LocalizedRangeScan contains range data from a single sweep of a laser range finder sensor
  4514. * in a two-dimensional space and position information. The odometer position is the position
  4515. * reported by the robot when the range data was recorded. The corrected position is the position
  4516. * calculated by the mapper (or localizer)
  4517. * LocalizedRangeScan包含二维空间中激光测距仪传感器单次扫描的距离数据和位置信息。
  4518. * 里程表位置是记录里程数据时机器人报告的位置。校正后的位置是由映射器(或定位器)计算的位置
  4519. */
  4520. class LocalizedRangeScan : public LaserRangeScan
  4521. {
  4522. public:
  4523. // @cond EXCLUDE
  4524. KARTO_Object(LocalizedRangeScan)
  4525. // @endcond
  4526. public:
  4527. /**
  4528. * Constructs a range scan from the given range finder with the given readings
  4529. */
  4530. LocalizedRangeScan(const Name& rSensorName, const RangeReadingsVector& rReadings)
  4531. : LaserRangeScan(rSensorName, rReadings)
  4532. , m_IsDirty(true)
  4533. {
  4534. }
  4535. /**
  4536. * Destructor
  4537. */
  4538. virtual ~LocalizedRangeScan()
  4539. {
  4540. }
  4541. private:
  4542. mutable boost::shared_mutex m_Lock;
  4543. public:
  4544. /**
  4545. * Gets the odometric pose of this scan
  4546. * @return odometric pose of this scan
  4547. */
  4548. inline const Pose2& GetOdometricPose() const
  4549. {
  4550. return m_OdometricPose;
  4551. }
  4552. /**
  4553. * Sets the odometric pose of this scan
  4554. * @param rPose
  4555. */
  4556. inline void SetOdometricPose(const Pose2& rPose)
  4557. {
  4558. m_OdometricPose = rPose;
  4559. }
  4560. /**
  4561. * Gets the (possibly corrected) robot pose at which this scan was taken. The corrected robot pose of the scan
  4562. * is usually set by an external module such as a localization or mapping module when it is determined
  4563. * that the original pose was incorrect. The external module will set the correct pose based on
  4564. * additional sensor data and any context information it has. If the pose has not been corrected,
  4565. * a call to this method returns the same pose as GetOdometricPose().
  4566. * @return corrected pose
  4567. */
  4568. inline const Pose2& GetCorrectedPose() const
  4569. {
  4570. return m_CorrectedPose;
  4571. }
  4572. /**
  4573. * Moves the scan by moving the robot pose to the given location.
  4574. * @param rPose new pose of the robot of this scan
  4575. */
  4576. inline void SetCorrectedPose(const Pose2& rPose)
  4577. {
  4578. m_CorrectedPose = rPose;
  4579. m_IsDirty = true;
  4580. }
  4581. /**
  4582. * Gets barycenter of point readings
  4583. */
  4584. inline const Pose2& GetBarycenterPose() const
  4585. {
  4586. boost::shared_lock<boost::shared_mutex> lock(m_Lock);
  4587. if (m_IsDirty)
  4588. {
  4589. // throw away constness and do an update!
  4590. lock.unlock();
  4591. boost::unique_lock<boost::shared_mutex> uniqueLock(m_Lock);
  4592. const_cast<LocalizedRangeScan*>(this)->Update();
  4593. }
  4594. return m_BarycenterPose;
  4595. }
  4596. /**
  4597. * Gets barycenter if the given parameter is true, otherwise returns the scanner pose
  4598. * @param useBarycenter
  4599. * @return barycenter if parameter is true, otherwise scanner pose
  4600. */
  4601. inline Pose2 GetReferencePose(kt_bool useBarycenter) const
  4602. {
  4603. boost::shared_lock<boost::shared_mutex> lock(m_Lock);
  4604. if (m_IsDirty)
  4605. {
  4606. // throw away constness and do an update!
  4607. lock.unlock();
  4608. boost::unique_lock<boost::shared_mutex> uniqueLock(m_Lock);
  4609. const_cast<LocalizedRangeScan*>(this)->Update();
  4610. }
  4611. return useBarycenter ? GetBarycenterPose() : GetSensorPose();
  4612. }
  4613. /**
  4614. * Computes the position of the sensor
  4615. * @return scan pose
  4616. */
  4617. inline Pose2 GetSensorPose() const
  4618. {
  4619. return GetSensorAt(m_CorrectedPose);
  4620. }
  4621. /**
  4622. * Computes the robot pose given the corrected scan pose
  4623. * @param rScanPose pose of the sensor
  4624. */
  4625. void SetSensorPose(const Pose2& rScanPose)
  4626. {
  4627. Pose2 deviceOffsetPose2 = GetLaserRangeFinder()->GetOffsetPose();
  4628. kt_double offsetLength = deviceOffsetPose2.GetPosition().Length();
  4629. kt_double offsetHeading = deviceOffsetPose2.GetHeading();
  4630. kt_double angleoffset = atan2(deviceOffsetPose2.GetY(), deviceOffsetPose2.GetX());
  4631. kt_double correctedHeading = math::NormalizeAngle(rScanPose.GetHeading());
  4632. Pose2 worldSensorOffset = Pose2(offsetLength * cos(correctedHeading + angleoffset - offsetHeading),
  4633. offsetLength * sin(correctedHeading + angleoffset - offsetHeading),
  4634. offsetHeading);
  4635. m_CorrectedPose = rScanPose - worldSensorOffset;
  4636. Update();
  4637. }
  4638. /**
  4639. * Computes the position of the sensor if the robot were at the given pose
  4640. * @param rPose
  4641. * @return sensor pose
  4642. */
  4643. inline Pose2 GetSensorAt(const Pose2& rPose) const
  4644. {
  4645. return Transform(rPose).TransformPose(GetLaserRangeFinder()->GetOffsetPose());
  4646. }
  4647. /**
  4648. * Gets the bounding box of this scan
  4649. * @return bounding box of this scan
  4650. */
  4651. inline const BoundingBox2& GetBoundingBox() const
  4652. {
  4653. boost::shared_lock<boost::shared_mutex> lock(m_Lock);
  4654. if (m_IsDirty)
  4655. {
  4656. // throw away constness and do an update!
  4657. lock.unlock();
  4658. boost::unique_lock<boost::shared_mutex> uniqueLock(m_Lock);
  4659. const_cast<LocalizedRangeScan*>(this)->Update();
  4660. }
  4661. return m_BoundingBox;
  4662. }
  4663. /**
  4664. * Get point readings in local coordinates
  4665. */
  4666. inline const PointVectorDouble& GetPointReadings(kt_bool wantFiltered = false) const
  4667. {
  4668. boost::shared_lock<boost::shared_mutex> lock(m_Lock);
  4669. if (m_IsDirty)
  4670. {
  4671. // throw away constness and do an update!
  4672. lock.unlock();
  4673. boost::unique_lock<boost::shared_mutex> uniqueLock(m_Lock);
  4674. const_cast<LocalizedRangeScan*>(this)->Update();
  4675. }
  4676. if (wantFiltered == true)
  4677. {
  4678. return m_PointReadings;
  4679. }
  4680. else
  4681. {
  4682. return m_UnfilteredPointReadings;
  4683. }
  4684. }
  4685. private:
  4686. /**
  4687. * Compute point readings based on range readings
  4688. * Only range readings within [minimum range; range threshold] are returned
  4689. */
  4690. virtual void Update()
  4691. {
  4692. LaserRangeFinder* pLaserRangeFinder = GetLaserRangeFinder();
  4693. if (pLaserRangeFinder != NULL)
  4694. {
  4695. m_PointReadings.clear();
  4696. m_UnfilteredPointReadings.clear();
  4697. kt_double rangeThreshold = pLaserRangeFinder->GetRangeThreshold();
  4698. kt_double minimumAngle = pLaserRangeFinder->GetMinimumAngle();
  4699. kt_double angularResolution = pLaserRangeFinder->GetAngularResolution();
  4700. Pose2 scanPose = GetSensorPose();
  4701. // compute point readings
  4702. Vector2<kt_double> rangePointsSum;
  4703. kt_int32u beamNum = 0;
  4704. for (kt_int32u i = 0; i < pLaserRangeFinder->GetNumberOfRangeReadings(); i++, beamNum++)
  4705. {
  4706. kt_double rangeReading = GetRangeReadings()[i];
  4707. if (!math::InRange(rangeReading, pLaserRangeFinder->GetMinimumRange(), rangeThreshold))
  4708. {
  4709. kt_double angle = scanPose.GetHeading() + minimumAngle + beamNum * angularResolution;
  4710. Vector2<kt_double> point;
  4711. point.SetX(scanPose.GetX() + (rangeReading * cos(angle)));
  4712. point.SetY(scanPose.GetY() + (rangeReading * sin(angle)));
  4713. m_UnfilteredPointReadings.push_back(point);
  4714. continue;
  4715. }
  4716. kt_double angle = scanPose.GetHeading() + minimumAngle + beamNum * angularResolution;
  4717. Vector2<kt_double> point;
  4718. point.SetX(scanPose.GetX() + (rangeReading * cos(angle)));
  4719. point.SetY(scanPose.GetY() + (rangeReading * sin(angle)));
  4720. m_PointReadings.push_back(point);
  4721. m_UnfilteredPointReadings.push_back(point);
  4722. rangePointsSum += point;
  4723. }
  4724. // compute barycenter
  4725. kt_double nPoints = static_cast<kt_double>(m_PointReadings.size());
  4726. if (nPoints != 0.0)
  4727. {
  4728. Vector2<kt_double> averagePosition = Vector2<kt_double>(rangePointsSum / nPoints);
  4729. m_BarycenterPose = Pose2(averagePosition, 0.0);
  4730. }
  4731. else
  4732. {
  4733. m_BarycenterPose = scanPose;
  4734. }
  4735. // calculate bounding box of scan
  4736. m_BoundingBox = BoundingBox2();
  4737. m_BoundingBox.Add(scanPose.GetPosition());
  4738. forEach(PointVectorDouble, &m_PointReadings)
  4739. {
  4740. m_BoundingBox.Add(*iter);
  4741. }
  4742. }
  4743. m_IsDirty = false;
  4744. }
  4745. private:
  4746. LocalizedRangeScan(const LocalizedRangeScan&);
  4747. const LocalizedRangeScan& operator=(const LocalizedRangeScan&);
  4748. private:
  4749. /**
  4750. * Odometric pose of robot
  4751. */
  4752. Pose2 m_OdometricPose;
  4753. /**
  4754. * Corrected pose of robot calculated by mapper (or localizer)
  4755. */
  4756. Pose2 m_CorrectedPose;
  4757. protected:
  4758. /**
  4759. * Average of all the point readings
  4760. */
  4761. Pose2 m_BarycenterPose;
  4762. /**
  4763. * Vector of point readings
  4764. */
  4765. PointVectorDouble m_PointReadings;
  4766. /**
  4767. * Vector of unfiltered point readings
  4768. */
  4769. PointVectorDouble m_UnfilteredPointReadings;
  4770. /**
  4771. * Bounding box of localized range scan
  4772. */
  4773. BoundingBox2 m_BoundingBox;
  4774. /**
  4775. * Internal flag used to update point readings, barycenter and bounding box
  4776. */
  4777. kt_bool m_IsDirty;
  4778. }; // LocalizedRangeScan
  4779. /**
  4780. * Type declaration of LocalizedRangeScan vector
  4781. */
  4782. typedef std::vector<LocalizedRangeScan*> LocalizedRangeScanVector;
  4783. ////////////////////////////////////////////////////////////////////////////////////////
  4784. ////////////////////////////////////////////////////////////////////////////////////////
  4785. ////////////////////////////////////////////////////////////////////////////////////////
  4786. /**
  4787. * The LocalizedRangeScanWithPoints is an extension of the LocalizedRangeScan with precomputed points.
  4788. */
  4789. class LocalizedRangeScanWithPoints : public LocalizedRangeScan
  4790. {
  4791. public:
  4792. // @cond EXCLUDE
  4793. KARTO_Object(LocalizedRangeScanWithPoints)
  4794. // @endcond
  4795. public:
  4796. /**
  4797. * Constructs a range scan from the given range finder with the given readings. Precomptued points should be
  4798. * in the robot frame.
  4799. */
  4800. LocalizedRangeScanWithPoints(const Name& rSensorName, const RangeReadingsVector& rReadings,
  4801. const PointVectorDouble& rPoints)
  4802. : LocalizedRangeScan(rSensorName, rReadings),
  4803. m_Points(rPoints)
  4804. {
  4805. }
  4806. /**
  4807. * Destructor
  4808. */
  4809. virtual ~LocalizedRangeScanWithPoints()
  4810. {
  4811. }
  4812. private:
  4813. /**
  4814. * Update the points based on the latest sensor pose.
  4815. */
  4816. void Update()
  4817. {
  4818. m_PointReadings.clear();
  4819. m_UnfilteredPointReadings.clear();
  4820. Pose2 scanPose = GetSensorPose();
  4821. Pose2 robotPose = GetCorrectedPose();
  4822. // update point readings
  4823. Vector2<kt_double> rangePointsSum;
  4824. for (kt_int32u i = 0; i < m_Points.size(); i++)
  4825. {
  4826. // check if this has a NaN
  4827. if (!std::isfinite(m_Points[i].GetX()) || !std::isfinite(m_Points[i].GetY()))
  4828. {
  4829. Vector2<kt_double> point(m_Points[i].GetX(), m_Points[i].GetY());
  4830. m_UnfilteredPointReadings.push_back(point);
  4831. continue;
  4832. }
  4833. // transform into world coords
  4834. Pose2 pointPose(m_Points[i].GetX(), m_Points[i].GetY(), 0);
  4835. Pose2 result = Transform(robotPose).TransformPose(pointPose);
  4836. Vector2<kt_double> point(result.GetX(), result.GetY());
  4837. m_PointReadings.push_back(point);
  4838. m_UnfilteredPointReadings.push_back(point);
  4839. rangePointsSum += point;
  4840. }
  4841. // compute barycenter
  4842. kt_double nPoints = static_cast<kt_double>(m_PointReadings.size());
  4843. if (nPoints != 0.0)
  4844. {
  4845. Vector2<kt_double> averagePosition = Vector2<kt_double>(rangePointsSum / nPoints);
  4846. m_BarycenterPose = Pose2(averagePosition, 0.0);
  4847. }
  4848. else
  4849. {
  4850. m_BarycenterPose = scanPose;
  4851. }
  4852. // calculate bounding box of scan
  4853. m_BoundingBox = BoundingBox2();
  4854. m_BoundingBox.Add(scanPose.GetPosition());
  4855. forEach(PointVectorDouble, &m_PointReadings)
  4856. {
  4857. m_BoundingBox.Add(*iter);
  4858. }
  4859. m_IsDirty = false;
  4860. }
  4861. private:
  4862. LocalizedRangeScanWithPoints(const LocalizedRangeScanWithPoints&);
  4863. const LocalizedRangeScanWithPoints& operator=(const LocalizedRangeScanWithPoints&);
  4864. private:
  4865. const PointVectorDouble m_Points;
  4866. }; // LocalizedRangeScanWithPoints
  4867. ////////////////////////////////////////////////////////////////////////////////////////
  4868. ////////////////////////////////////////////////////////////////////////////////////////
  4869. ////////////////////////////////////////////////////////////////////////////////////////
  4870. class OccupancyGrid;
  4871. class KARTO_EXPORT CellUpdater : public Functor
  4872. {
  4873. public:
  4874. CellUpdater(OccupancyGrid* pGrid)
  4875. : m_pOccupancyGrid(pGrid)
  4876. {
  4877. }
  4878. /**
  4879. * Destructor
  4880. */
  4881. virtual ~CellUpdater() {}
  4882. /**
  4883. * Updates the cell at the given index based on the grid's hits and pass counters
  4884. * @param index
  4885. */
  4886. virtual void operator() (kt_int32u index);
  4887. private:
  4888. OccupancyGrid* m_pOccupancyGrid;
  4889. }; // CellUpdater
  4890. /**
  4891. * Occupancy grid definition. See GridStates for possible grid values.
  4892. */
  4893. class OccupancyGrid : public Grid<kt_int8u>
  4894. {
  4895. friend class CellUpdater;
  4896. friend class IncrementalOccupancyGrid;
  4897. public:
  4898. /**
  4899. * Constructs an occupancy grid of given size
  4900. * @param width
  4901. * @param height
  4902. * @param rOffset
  4903. * @param resolution
  4904. */
  4905. OccupancyGrid(kt_int32s width, kt_int32s height, const Vector2<kt_double>& rOffset, kt_double resolution)
  4906. : Grid<kt_int8u>(width, height)
  4907. , m_pCellPassCnt(Grid<kt_int32u>::CreateGrid(0, 0, resolution))
  4908. , m_pCellHitsCnt(Grid<kt_int32u>::CreateGrid(0, 0, resolution))
  4909. , m_pCellUpdater(NULL)
  4910. {
  4911. m_pCellUpdater = new CellUpdater(this);
  4912. if (karto::math::DoubleEqual(resolution, 0.0))
  4913. {
  4914. throw Exception("Resolution cannot be 0");
  4915. }
  4916. m_pMinPassThrough = new Parameter<kt_int32u>("MinPassThrough", 2);
  4917. m_pOccupancyThreshold = new Parameter<kt_double>("OccupancyThreshold", 0.1);
  4918. GetCoordinateConverter()->SetScale(1.0 / resolution);
  4919. GetCoordinateConverter()->SetOffset(rOffset);
  4920. }
  4921. /**
  4922. * Destructor
  4923. */
  4924. virtual ~OccupancyGrid()
  4925. {
  4926. delete m_pCellUpdater;
  4927. delete m_pCellPassCnt;
  4928. delete m_pCellHitsCnt;
  4929. delete m_pMinPassThrough;
  4930. delete m_pOccupancyThreshold;
  4931. }
  4932. public:
  4933. /**
  4934. * Create an occupancy grid from the given scans using the given resolution
  4935. * @param rScans
  4936. * @param resolution
  4937. */
  4938. static OccupancyGrid* CreateFromScans(const LocalizedRangeScanVector& rScans, kt_double resolution)
  4939. {
  4940. if (rScans.empty())
  4941. {
  4942. return NULL;
  4943. }
  4944. kt_int32s width, height;
  4945. Vector2<kt_double> offset;
  4946. ComputeDimensions(rScans, resolution, width, height, offset);
  4947. OccupancyGrid* pOccupancyGrid = new OccupancyGrid(width, height, offset, resolution);
  4948. pOccupancyGrid->CreateFromScans(rScans);
  4949. return pOccupancyGrid;
  4950. }
  4951. /**
  4952. * Make a clone
  4953. * @return occupancy grid clone
  4954. */
  4955. OccupancyGrid* Clone() const
  4956. {
  4957. OccupancyGrid* pOccupancyGrid = new OccupancyGrid(GetWidth(),
  4958. GetHeight(),
  4959. GetCoordinateConverter()->GetOffset(),
  4960. 1.0 / GetCoordinateConverter()->GetScale());
  4961. memcpy(pOccupancyGrid->GetDataPointer(), GetDataPointer(), GetDataSize());
  4962. pOccupancyGrid->GetCoordinateConverter()->SetSize(GetCoordinateConverter()->GetSize());
  4963. pOccupancyGrid->m_pCellPassCnt = m_pCellPassCnt->Clone();
  4964. pOccupancyGrid->m_pCellHitsCnt = m_pCellHitsCnt->Clone();
  4965. return pOccupancyGrid;
  4966. }
  4967. /**
  4968. * Check if grid point is free
  4969. * @param rPose
  4970. * @return whether the cell at the given point is free space
  4971. */
  4972. virtual kt_bool IsFree(const Vector2<kt_int32s>& rPose) const
  4973. {
  4974. kt_int8u* pOffsets = reinterpret_cast<kt_int8u*>(GetDataPointer(rPose));
  4975. if (*pOffsets == GridStates_Free)
  4976. {
  4977. return true;
  4978. }
  4979. return false;
  4980. }
  4981. /**
  4982. * Casts a ray from the given point (up to the given max range)
  4983. * and returns the distance to the closest obstacle
  4984. * @param rPose2
  4985. * @param maxRange
  4986. * @return distance to closest obstacle
  4987. */
  4988. virtual kt_double RayCast(const Pose2& rPose2, kt_double maxRange) const
  4989. {
  4990. double scale = GetCoordinateConverter()->GetScale();
  4991. kt_double x = rPose2.GetX();
  4992. kt_double y = rPose2.GetY();
  4993. kt_double theta = rPose2.GetHeading();
  4994. kt_double sinTheta = sin(theta);
  4995. kt_double cosTheta = cos(theta);
  4996. kt_double xStop = x + maxRange * cosTheta;
  4997. kt_double xSteps = 1 + fabs(xStop - x) * scale;
  4998. kt_double yStop = y + maxRange * sinTheta;
  4999. kt_double ySteps = 1 + fabs(yStop - y) * scale;
  5000. kt_double steps = math::Maximum(xSteps, ySteps);
  5001. kt_double delta = maxRange / steps;
  5002. kt_double distance = delta;
  5003. for (kt_int32u i = 1; i < steps; i++)
  5004. {
  5005. kt_double x1 = x + distance * cosTheta;
  5006. kt_double y1 = y + distance * sinTheta;
  5007. Vector2<kt_int32s> gridIndex = WorldToGrid(Vector2<kt_double>(x1, y1));
  5008. if (IsValidGridIndex(gridIndex) && IsFree(gridIndex))
  5009. {
  5010. distance = (i + 1) * delta;
  5011. }
  5012. else
  5013. {
  5014. break;
  5015. }
  5016. }
  5017. return (distance < maxRange)? distance : maxRange;
  5018. }
  5019. /**
  5020. * Sets the minimum number of beams that must pass through a cell before it
  5021. * will be considered to be occupied or unoccupied.
  5022. * This prevents stray beams from messing up the map.
  5023. */
  5024. void SetMinPassThrough(kt_int32u count)
  5025. {
  5026. m_pMinPassThrough->SetValue(count);
  5027. }
  5028. /**
  5029. * Sets the minimum ratio of beams hitting cell to beams passing through
  5030. * cell for cell to be marked as occupied.
  5031. */
  5032. void SetOccupancyThreshold(kt_double thresh)
  5033. {
  5034. m_pOccupancyThreshold->SetValue(thresh);
  5035. }
  5036. protected:
  5037. /**
  5038. * Get cell hit grid
  5039. * @return Grid<kt_int32u>*
  5040. */
  5041. virtual Grid<kt_int32u>* GetCellHitsCounts()
  5042. {
  5043. return m_pCellHitsCnt;
  5044. }
  5045. /**
  5046. * Get cell pass grid
  5047. * @return Grid<kt_int32u>*
  5048. */
  5049. virtual Grid<kt_int32u>* GetCellPassCounts()
  5050. {
  5051. return m_pCellPassCnt;
  5052. }
  5053. protected:
  5054. /**
  5055. * Calculate grid dimensions from localized range scans
  5056. * @param rScans
  5057. * @param resolution
  5058. * @param rWidth
  5059. * @param rHeight
  5060. * @param rOffset
  5061. */
  5062. static void ComputeDimensions(const LocalizedRangeScanVector& rScans,
  5063. kt_double resolution,
  5064. kt_int32s& rWidth,
  5065. kt_int32s& rHeight,
  5066. Vector2<kt_double>& rOffset)
  5067. {
  5068. BoundingBox2 boundingBox;
  5069. const_forEach(LocalizedRangeScanVector, &rScans)
  5070. {
  5071. boundingBox.Add((*iter)->GetBoundingBox());
  5072. }
  5073. kt_double scale = 1.0 / resolution;
  5074. Size2<kt_double> size = boundingBox.GetSize();
  5075. rWidth = static_cast<kt_int32s>(math::Round(size.GetWidth() * scale));
  5076. rHeight = static_cast<kt_int32s>(math::Round(size.GetHeight() * scale));
  5077. rOffset = boundingBox.GetMinimum();
  5078. }
  5079. /**
  5080. * Create grid using scans
  5081. * @param rScans
  5082. */
  5083. virtual void CreateFromScans(const LocalizedRangeScanVector& rScans)
  5084. {
  5085. m_pCellPassCnt->Resize(GetWidth(), GetHeight());
  5086. m_pCellPassCnt->GetCoordinateConverter()->SetOffset(GetCoordinateConverter()->GetOffset());
  5087. m_pCellHitsCnt->Resize(GetWidth(), GetHeight());
  5088. m_pCellHitsCnt->GetCoordinateConverter()->SetOffset(GetCoordinateConverter()->GetOffset());
  5089. const_forEach(LocalizedRangeScanVector, &rScans)
  5090. {
  5091. LocalizedRangeScan* pScan = *iter;
  5092. AddScan(pScan);
  5093. }
  5094. Update();
  5095. }
  5096. /**
  5097. * Adds the scan's information to this grid's counters (optionally
  5098. * update the grid's cells' occupancy status)
  5099. * @param pScan
  5100. * @param doUpdate whether to update the grid's cell's occupancy status
  5101. * @return returns false if an endpoint fell off the grid, otherwise true
  5102. */
  5103. virtual kt_bool AddScan(LocalizedRangeScan* pScan, kt_bool doUpdate = false)
  5104. {
  5105. kt_double rangeThreshold = pScan->GetLaserRangeFinder()->GetRangeThreshold();
  5106. kt_double maxRange = pScan->GetLaserRangeFinder()->GetMaximumRange();
  5107. kt_double minRange = pScan->GetLaserRangeFinder()->GetMinimumRange();
  5108. Vector2<kt_double> scanPosition = pScan->GetSensorPose().GetPosition();
  5109. // get scan point readings
  5110. const PointVectorDouble& rPointReadings = pScan->GetPointReadings(false);
  5111. kt_bool isAllInMap = true;
  5112. // draw lines from scan position to all point readings
  5113. int pointIndex = 0;
  5114. const_forEachAs(PointVectorDouble, &rPointReadings, pointsIter)
  5115. {
  5116. Vector2<kt_double> point = *pointsIter;
  5117. kt_double rangeReading = pScan->GetRangeReadings()[pointIndex];
  5118. kt_bool isEndPointValid = rangeReading < (rangeThreshold - KT_TOLERANCE);
  5119. if (rangeReading <= minRange || rangeReading >= maxRange || std::isnan(rangeReading))
  5120. {
  5121. // ignore these readings
  5122. pointIndex++;
  5123. continue;
  5124. }
  5125. else if (rangeReading >= rangeThreshold)
  5126. {
  5127. // trace up to range reading
  5128. kt_double ratio = rangeThreshold / rangeReading;
  5129. kt_double dx = point.GetX() - scanPosition.GetX();
  5130. kt_double dy = point.GetY() - scanPosition.GetY();
  5131. point.SetX(scanPosition.GetX() + ratio * dx);
  5132. point.SetY(scanPosition.GetY() + ratio * dy);
  5133. }
  5134. kt_bool isInMap = RayTrace(scanPosition, point, isEndPointValid, doUpdate);
  5135. if (!isInMap)
  5136. {
  5137. isAllInMap = false;
  5138. }
  5139. pointIndex++;
  5140. }
  5141. return isAllInMap;
  5142. }
  5143. /**
  5144. * Traces a beam from the start position to the end position marking
  5145. * the bookkeeping arrays accordingly.
  5146. * @param rWorldFrom start position of beam
  5147. * @param rWorldTo end position of beam
  5148. * @param isEndPointValid is the reading within the range threshold?
  5149. * @param doUpdate whether to update the cells' occupancy status immediately
  5150. * @return returns false if an endpoint fell off the grid, otherwise true
  5151. */
  5152. virtual kt_bool RayTrace(const Vector2<kt_double>& rWorldFrom,
  5153. const Vector2<kt_double>& rWorldTo,
  5154. kt_bool isEndPointValid,
  5155. kt_bool doUpdate = false)
  5156. {
  5157. assert(m_pCellPassCnt != NULL && m_pCellHitsCnt != NULL);
  5158. Vector2<kt_int32s> gridFrom = m_pCellPassCnt->WorldToGrid(rWorldFrom);
  5159. Vector2<kt_int32s> gridTo = m_pCellPassCnt->WorldToGrid(rWorldTo);
  5160. CellUpdater* pCellUpdater = doUpdate ? m_pCellUpdater : NULL;
  5161. m_pCellPassCnt->TraceLine(gridFrom.GetX(), gridFrom.GetY(), gridTo.GetX(), gridTo.GetY(), pCellUpdater);
  5162. // for the end point
  5163. if (isEndPointValid)
  5164. {
  5165. if (m_pCellPassCnt->IsValidGridIndex(gridTo))
  5166. {
  5167. kt_int32s index = m_pCellPassCnt->GridIndex(gridTo, false);
  5168. kt_int32u* pCellPassCntPtr = m_pCellPassCnt->GetDataPointer();
  5169. kt_int32u* pCellHitCntPtr = m_pCellHitsCnt->GetDataPointer();
  5170. // increment cell pass through and hit count
  5171. pCellPassCntPtr[index]++;
  5172. pCellHitCntPtr[index]++;
  5173. if (doUpdate)
  5174. {
  5175. (*m_pCellUpdater)(index);
  5176. }
  5177. }
  5178. }
  5179. return m_pCellPassCnt->IsValidGridIndex(gridTo);
  5180. }
  5181. /**
  5182. * Updates a single cell's value based on the given counters
  5183. * @param pCell
  5184. * @param cellPassCnt
  5185. * @param cellHitCnt
  5186. */
  5187. virtual void UpdateCell(kt_int8u* pCell, kt_int32u cellPassCnt, kt_int32u cellHitCnt)
  5188. {
  5189. if (cellPassCnt > m_pMinPassThrough->GetValue())
  5190. {
  5191. kt_double hitRatio = static_cast<kt_double>(cellHitCnt) / static_cast<kt_double>(cellPassCnt);
  5192. if (hitRatio > m_pOccupancyThreshold->GetValue())
  5193. {
  5194. *pCell = GridStates_Occupied;
  5195. }
  5196. else
  5197. {
  5198. *pCell = GridStates_Free;
  5199. }
  5200. }
  5201. }
  5202. /**
  5203. * Update the grid based on the values in m_pCellHitsCnt and m_pCellPassCnt
  5204. */
  5205. virtual void Update()
  5206. {
  5207. assert(m_pCellPassCnt != NULL && m_pCellHitsCnt != NULL);
  5208. // clear grid
  5209. Clear();
  5210. // set occupancy status of cells
  5211. kt_int8u* pDataPtr = GetDataPointer();
  5212. kt_int32u* pCellPassCntPtr = m_pCellPassCnt->GetDataPointer();
  5213. kt_int32u* pCellHitCntPtr = m_pCellHitsCnt->GetDataPointer();
  5214. kt_int32u nBytes = GetDataSize();
  5215. for (kt_int32u i = 0; i < nBytes; i++, pDataPtr++, pCellPassCntPtr++, pCellHitCntPtr++)
  5216. {
  5217. UpdateCell(pDataPtr, *pCellPassCntPtr, *pCellHitCntPtr);
  5218. }
  5219. }
  5220. /**
  5221. * Resizes the grid (deletes all old data)
  5222. * @param width
  5223. * @param height
  5224. */
  5225. virtual void Resize(kt_int32s width, kt_int32s height)
  5226. {
  5227. Grid<kt_int8u>::Resize(width, height);
  5228. m_pCellPassCnt->Resize(width, height);
  5229. m_pCellHitsCnt->Resize(width, height);
  5230. }
  5231. protected:
  5232. /**
  5233. * Counters of number of times a beam passed through a cell
  5234. */
  5235. Grid<kt_int32u>* m_pCellPassCnt;
  5236. /**
  5237. * Counters of number of times a beam ended at a cell
  5238. */
  5239. Grid<kt_int32u>* m_pCellHitsCnt;
  5240. private:
  5241. /**
  5242. * Restrict the copy constructor
  5243. */
  5244. OccupancyGrid(const OccupancyGrid&);
  5245. /**
  5246. * Restrict the assignment operator
  5247. */
  5248. const OccupancyGrid& operator=(const OccupancyGrid&);
  5249. private:
  5250. CellUpdater* m_pCellUpdater;
  5251. ////////////////////////////////////////////////////////////
  5252. // NOTE: These two values are dependent on the resolution. If the resolution is too small,
  5253. // then not many beams will hit the cell!
  5254. // Number of beams that must pass through a cell before it will be considered to be occupied
  5255. // or unoccupied. This prevents stray beams from messing up the map.
  5256. Parameter<kt_int32u>* m_pMinPassThrough;
  5257. // Minimum ratio of beams hitting cell to beams passing through cell for cell to be marked as occupied
  5258. Parameter<kt_double>* m_pOccupancyThreshold;
  5259. }; // OccupancyGrid
  5260. ////////////////////////////////////////////////////////////////////////////////////////
  5261. ////////////////////////////////////////////////////////////////////////////////////////
  5262. ////////////////////////////////////////////////////////////////////////////////////////
  5263. /**
  5264. * Dataset info
  5265. * Contains title, author and other information about the dataset
  5266. */
  5267. class DatasetInfo : public Object
  5268. {
  5269. public:
  5270. // @cond EXCLUDE
  5271. KARTO_Object(DatasetInfo)
  5272. // @endcond
  5273. public:
  5274. DatasetInfo()
  5275. : Object()
  5276. {
  5277. m_pTitle = new Parameter<std::string>("Title", "", GetParameterManager());
  5278. m_pAuthor = new Parameter<std::string>("Author", "", GetParameterManager());
  5279. m_pDescription = new Parameter<std::string>("Description", "", GetParameterManager());
  5280. m_pCopyright = new Parameter<std::string>("Copyright", "", GetParameterManager());
  5281. }
  5282. virtual ~DatasetInfo()
  5283. {
  5284. }
  5285. public:
  5286. /**
  5287. * Dataset title
  5288. */
  5289. const std::string& GetTitle() const
  5290. {
  5291. return m_pTitle->GetValue();
  5292. }
  5293. /**
  5294. * Dataset author(s)
  5295. */
  5296. const std::string& GetAuthor() const
  5297. {
  5298. return m_pAuthor->GetValue();
  5299. }
  5300. /**
  5301. * Dataset description
  5302. */
  5303. const std::string& GetDescription() const
  5304. {
  5305. return m_pDescription->GetValue();
  5306. }
  5307. /**
  5308. * Dataset copyrights
  5309. */
  5310. const std::string& GetCopyright() const
  5311. {
  5312. return m_pCopyright->GetValue();
  5313. }
  5314. private:
  5315. DatasetInfo(const DatasetInfo&);
  5316. const DatasetInfo& operator=(const DatasetInfo&);
  5317. private:
  5318. Parameter<std::string>* m_pTitle;
  5319. Parameter<std::string>* m_pAuthor;
  5320. Parameter<std::string>* m_pDescription;
  5321. Parameter<std::string>* m_pCopyright;
  5322. }; // class DatasetInfo
  5323. ////////////////////////////////////////////////////////////////////////////////////////
  5324. ////////////////////////////////////////////////////////////////////////////////////////
  5325. ////////////////////////////////////////////////////////////////////////////////////////
  5326. /**
  5327. * Karto dataset. Stores LaserRangeFinders and LocalizedRangeScans and manages memory of allocated LaserRangeFinders
  5328. * and LocalizedRangeScans
  5329. */
  5330. class Dataset
  5331. {
  5332. public:
  5333. /**
  5334. * Default constructor
  5335. */
  5336. Dataset()
  5337. : m_pDatasetInfo(NULL)
  5338. {
  5339. }
  5340. /**
  5341. * Destructor
  5342. */
  5343. virtual ~Dataset()
  5344. {
  5345. Clear();
  5346. }
  5347. public:
  5348. /**
  5349. * Adds object to this dataset
  5350. * @param pObject
  5351. */
  5352. void Add(Object* pObject)
  5353. {
  5354. if (pObject != NULL)
  5355. {
  5356. if (dynamic_cast<Sensor*>(pObject))
  5357. {
  5358. Sensor* pSensor = dynamic_cast<Sensor*>(pObject);
  5359. if (pSensor != NULL)
  5360. {
  5361. m_SensorNameLookup[pSensor->GetName()] = pSensor;
  5362. karto::SensorManager::GetInstance()->RegisterSensor(pSensor);
  5363. }
  5364. m_Objects.push_back(pObject);
  5365. }
  5366. else if (dynamic_cast<SensorData*>(pObject))
  5367. {
  5368. SensorData* pSensorData = dynamic_cast<SensorData*>(pObject);
  5369. m_Objects.push_back(pSensorData);
  5370. }
  5371. else if (dynamic_cast<DatasetInfo*>(pObject))
  5372. {
  5373. m_pDatasetInfo = dynamic_cast<DatasetInfo*>(pObject);
  5374. }
  5375. else
  5376. {
  5377. m_Objects.push_back(pObject);
  5378. }
  5379. }
  5380. }
  5381. /**
  5382. * Get sensor states
  5383. * @return sensor state
  5384. */
  5385. inline const ObjectVector& GetObjects() const
  5386. {
  5387. return m_Objects;
  5388. }
  5389. /**
  5390. * Get dataset info
  5391. * @return dataset info
  5392. */
  5393. inline DatasetInfo* GetDatasetInfo()
  5394. {
  5395. return m_pDatasetInfo;
  5396. }
  5397. /**
  5398. * Delete all stored data
  5399. */
  5400. virtual void Clear()
  5401. {
  5402. for (std::map<Name, Sensor*>::iterator iter = m_SensorNameLookup.begin(); iter != m_SensorNameLookup.end(); ++iter)
  5403. {
  5404. karto::SensorManager::GetInstance()->UnregisterSensor(iter->second);
  5405. }
  5406. forEach(ObjectVector, &m_Objects)
  5407. {
  5408. delete *iter;
  5409. }
  5410. m_Objects.clear();
  5411. if (m_pDatasetInfo != NULL)
  5412. {
  5413. delete m_pDatasetInfo;
  5414. m_pDatasetInfo = NULL;
  5415. }
  5416. }
  5417. private:
  5418. std::map<Name, Sensor*> m_SensorNameLookup;
  5419. ObjectVector m_Objects;
  5420. DatasetInfo* m_pDatasetInfo;
  5421. }; // Dataset
  5422. ////////////////////////////////////////////////////////////////////////////////////////
  5423. ////////////////////////////////////////////////////////////////////////////////////////
  5424. ////////////////////////////////////////////////////////////////////////////////////////
  5425. /**
  5426. * An array that can be resized as long as the size
  5427. * does not exceed the initial capacity
  5428. */
  5429. class LookupArray
  5430. {
  5431. public:
  5432. /**
  5433. * Constructs lookup array
  5434. */
  5435. LookupArray()
  5436. : m_pArray(NULL)
  5437. , m_Capacity(0)
  5438. , m_Size(0)
  5439. {
  5440. }
  5441. /**
  5442. * Destructor
  5443. */
  5444. virtual ~LookupArray()
  5445. {
  5446. assert(m_pArray != NULL);
  5447. delete[] m_pArray;
  5448. m_pArray = NULL;
  5449. }
  5450. public:
  5451. /**
  5452. * Clear array
  5453. */
  5454. void Clear()
  5455. {
  5456. memset(m_pArray, 0, sizeof(kt_int32s) * m_Capacity);
  5457. }
  5458. /**
  5459. * Gets size of array
  5460. * @return array size
  5461. */
  5462. kt_int32u GetSize() const
  5463. {
  5464. return m_Size;
  5465. }
  5466. /**
  5467. * Sets size of array (resize if not big enough)
  5468. * @param size
  5469. */
  5470. void SetSize(kt_int32u size)
  5471. {
  5472. assert(size != 0);
  5473. if (size > m_Capacity)
  5474. {
  5475. if (m_pArray != NULL)
  5476. {
  5477. delete [] m_pArray;
  5478. }
  5479. m_Capacity = size;
  5480. m_pArray = new kt_int32s[m_Capacity];
  5481. }
  5482. m_Size = size;
  5483. }
  5484. /**
  5485. * Gets reference to value at given index
  5486. * @param index
  5487. * @return reference to value at index
  5488. */
  5489. inline kt_int32s& operator [] (kt_int32u index)
  5490. {
  5491. assert(index < m_Size);
  5492. return m_pArray[index];
  5493. }
  5494. /**
  5495. * Gets value at given index
  5496. * @param index
  5497. * @return value at index
  5498. */
  5499. inline kt_int32s operator [] (kt_int32u index) const
  5500. {
  5501. assert(index < m_Size);
  5502. return m_pArray[index];
  5503. }
  5504. /**
  5505. * Gets array pointer
  5506. * @return array pointer
  5507. */
  5508. inline kt_int32s* GetArrayPointer()
  5509. {
  5510. return m_pArray;
  5511. }
  5512. /**
  5513. * Gets array pointer
  5514. * @return array pointer
  5515. */
  5516. inline kt_int32s* GetArrayPointer() const
  5517. {
  5518. return m_pArray;
  5519. }
  5520. private:
  5521. kt_int32s* m_pArray;
  5522. kt_int32u m_Capacity;
  5523. kt_int32u m_Size;
  5524. }; // LookupArray
  5525. ////////////////////////////////////////////////////////////////////////////////////////
  5526. ////////////////////////////////////////////////////////////////////////////////////////
  5527. ////////////////////////////////////////////////////////////////////////////////////////
  5528. /**
  5529. * Create lookup tables for point readings at varying angles in grid.
  5530. * For each angle, grid indexes are calculated for each range reading.
  5531. * This is to speed up finding best angle/position for a localized range scan
  5532. *
  5533. * Used heavily in mapper and localizer.
  5534. *
  5535. * In the localizer, this is a huge speed up for calculating possible position. For each particle,
  5536. * a probability is calculated. The range scan is the same, but all grid indexes at all possible angles are
  5537. * calculated. So when calculating the particle probability at a specific angle, the index table is used
  5538. * to look up probability in probability grid!
  5539. *
  5540. */
  5541. template<typename T>
  5542. class GridIndexLookup
  5543. {
  5544. public:
  5545. /**
  5546. * Construct a GridIndexLookup with a grid
  5547. * @param pGrid
  5548. */
  5549. GridIndexLookup(Grid<T>* pGrid)
  5550. : m_pGrid(pGrid)
  5551. , m_Capacity(0)
  5552. , m_Size(0)
  5553. , m_ppLookupArray(NULL)
  5554. {
  5555. }
  5556. /**
  5557. * Destructor
  5558. */
  5559. virtual ~GridIndexLookup()
  5560. {
  5561. DestroyArrays();
  5562. }
  5563. public:
  5564. /**
  5565. * Gets the lookup array for a particular angle index
  5566. * @param index
  5567. * @return lookup array
  5568. */
  5569. const LookupArray* GetLookupArray(kt_int32u index) const
  5570. {
  5571. assert(math::IsUpTo(index, m_Size));
  5572. return m_ppLookupArray[index];
  5573. }
  5574. /**
  5575. * Get angles
  5576. * @return std::vector<kt_double>& angles
  5577. */
  5578. const std::vector<kt_double>& GetAngles() const
  5579. {
  5580. return m_Angles;
  5581. }
  5582. /**
  5583. * Compute lookup table of the points of the given scan for the given angular space
  5584. * @param pScan the scan
  5585. * @param angleCenter
  5586. * @param angleOffset computes lookup arrays for the angles within this offset around angleStart
  5587. * @param angleResolution how fine a granularity to compute lookup arrays in the angular space
  5588. */
  5589. void ComputeOffsets(LocalizedRangeScan* pScan,
  5590. kt_double angleCenter,
  5591. kt_double angleOffset,
  5592. kt_double angleResolution)
  5593. {
  5594. assert(angleOffset != 0.0);
  5595. assert(angleResolution != 0.0);
  5596. kt_int32u nAngles = static_cast<kt_int32u>(math::Round(angleOffset * 2.0 / angleResolution) + 1);
  5597. SetSize(nAngles);
  5598. //////////////////////////////////////////////////////
  5599. // convert points into local coordinates of scan pose
  5600. const PointVectorDouble& rPointReadings = pScan->GetPointReadings();
  5601. // compute transform to scan pose
  5602. Transform transform(pScan->GetSensorPose());
  5603. Pose2Vector localPoints;
  5604. const_forEach(PointVectorDouble, &rPointReadings)
  5605. {
  5606. // do inverse transform to get points in local coordinates
  5607. Pose2 vec = transform.InverseTransformPose(Pose2(*iter, 0.0));
  5608. localPoints.push_back(vec);
  5609. }
  5610. //////////////////////////////////////////////////////
  5611. // create lookup array for different angles
  5612. kt_double angle = 0.0;
  5613. kt_double startAngle = angleCenter - angleOffset;
  5614. for (kt_int32u angleIndex = 0; angleIndex < nAngles; angleIndex++)
  5615. {
  5616. angle = startAngle + angleIndex * angleResolution;
  5617. ComputeOffsets(angleIndex, angle, localPoints, pScan);
  5618. }
  5619. // assert(math::DoubleEqual(angle, angleCenter + angleOffset));
  5620. }
  5621. private:
  5622. /**
  5623. * Compute lookup value of points for given angle
  5624. * @param angleIndex
  5625. * @param angle
  5626. * @param rLocalPoints
  5627. */
  5628. void ComputeOffsets(kt_int32u angleIndex, kt_double angle, const Pose2Vector& rLocalPoints, LocalizedRangeScan* pScan)
  5629. {
  5630. m_ppLookupArray[angleIndex]->SetSize(static_cast<kt_int32u>(rLocalPoints.size()));
  5631. m_Angles.at(angleIndex) = angle;
  5632. // set up point array by computing relative offsets to points readings
  5633. // when rotated by given angle
  5634. const Vector2<kt_double>& rGridOffset = m_pGrid->GetCoordinateConverter()->GetOffset();
  5635. kt_double cosine = cos(angle);
  5636. kt_double sine = sin(angle);
  5637. kt_int32u readingIndex = 0;
  5638. kt_int32s* pAngleIndexPointer = m_ppLookupArray[angleIndex]->GetArrayPointer();
  5639. kt_double maxRange = pScan->GetLaserRangeFinder()->GetMaximumRange();
  5640. const_forEach(Pose2Vector, &rLocalPoints)
  5641. {
  5642. const Vector2<kt_double>& rPosition = iter->GetPosition();
  5643. if (std::isnan(pScan->GetRangeReadings()[readingIndex]) || std::isinf(pScan->GetRangeReadings()[readingIndex]))
  5644. {
  5645. pAngleIndexPointer[readingIndex] = INVALID_SCAN;
  5646. readingIndex++;
  5647. continue;
  5648. }
  5649. // counterclockwise rotation and that rotation is about the origin (0, 0).
  5650. Vector2<kt_double> offset;
  5651. offset.SetX(cosine * rPosition.GetX() - sine * rPosition.GetY());
  5652. offset.SetY(sine * rPosition.GetX() + cosine * rPosition.GetY());
  5653. // have to compensate for the grid offset when getting the grid index
  5654. Vector2<kt_int32s> gridPoint = m_pGrid->WorldToGrid(offset + rGridOffset);
  5655. // use base GridIndex to ignore ROI
  5656. kt_int32s lookupIndex = m_pGrid->Grid<T>::GridIndex(gridPoint, false);
  5657. pAngleIndexPointer[readingIndex] = lookupIndex;
  5658. readingIndex++;
  5659. }
  5660. assert(readingIndex == rLocalPoints.size());
  5661. }
  5662. /**
  5663. * Sets size of lookup table (resize if not big enough)
  5664. * @param size
  5665. */
  5666. void SetSize(kt_int32u size)
  5667. {
  5668. assert(size != 0);
  5669. if (size > m_Capacity)
  5670. {
  5671. if (m_ppLookupArray != NULL)
  5672. {
  5673. DestroyArrays();
  5674. }
  5675. m_Capacity = size;
  5676. m_ppLookupArray = new LookupArray*[m_Capacity];
  5677. for (kt_int32u i = 0; i < m_Capacity; i++)
  5678. {
  5679. m_ppLookupArray[i] = new LookupArray();
  5680. }
  5681. }
  5682. m_Size = size;
  5683. m_Angles.resize(size);
  5684. }
  5685. /**
  5686. * Delete the arrays
  5687. */
  5688. void DestroyArrays()
  5689. {
  5690. for (kt_int32u i = 0; i < m_Capacity; i++)
  5691. {
  5692. delete m_ppLookupArray[i];
  5693. }
  5694. delete[] m_ppLookupArray;
  5695. m_ppLookupArray = NULL;
  5696. }
  5697. private:
  5698. Grid<T>* m_pGrid;
  5699. kt_int32u m_Capacity;
  5700. kt_int32u m_Size;
  5701. LookupArray **m_ppLookupArray;
  5702. // for sanity check
  5703. std::vector<kt_double> m_Angles;
  5704. }; // class GridIndexLookup
  5705. ////////////////////////////////////////////////////////////////////////////////////////
  5706. ////////////////////////////////////////////////////////////////////////////////////////
  5707. ////////////////////////////////////////////////////////////////////////////////////////
  5708. inline Pose2::Pose2(const Pose3& rPose)
  5709. : m_Position(rPose.GetPosition().GetX(), rPose.GetPosition().GetY())
  5710. {
  5711. kt_double t1, t2;
  5712. // calculates heading from orientation
  5713. rPose.GetOrientation().ToEulerAngles(m_Heading, t1, t2);
  5714. }
  5715. ////////////////////////////////////////////////////////////////////////////////////////
  5716. ////////////////////////////////////////////////////////////////////////////////////////
  5717. ////////////////////////////////////////////////////////////////////////////////////////
  5718. // @cond EXCLUDE
  5719. template<typename T>
  5720. inline void Object::SetParameter(const std::string& rName, T value)
  5721. {
  5722. AbstractParameter* pParameter = GetParameter(rName);
  5723. if (pParameter != NULL)
  5724. {
  5725. std::stringstream stream;
  5726. stream << value;
  5727. pParameter->SetValueFromString(stream.str());
  5728. }
  5729. else
  5730. {
  5731. throw Exception("Parameter does not exist: " + rName);
  5732. }
  5733. }
  5734. template<>
  5735. inline void Object::SetParameter(const std::string& rName, kt_bool value)
  5736. {
  5737. AbstractParameter* pParameter = GetParameter(rName);
  5738. if (pParameter != NULL)
  5739. {
  5740. pParameter->SetValueFromString(value ? "true" : "false");
  5741. }
  5742. else
  5743. {
  5744. throw Exception("Parameter does not exist: " + rName);
  5745. }
  5746. }
  5747. // @endcond
  5748. /*@}*/
  5749. } // namespace karto
  5750. #endif // OPEN_KARTO_KARTO_H