00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029 #include "rtabmap/core/SensorData.h"
00030 #include "rtabmap/core/Compression.h"
00031 #include "rtabmap/core/util3d_transforms.h"
00032 #include "rtabmap/utilite/ULogger.h"
00033 #include <rtabmap/utilite/UMath.h>
00034 #include <rtabmap/utilite/UConversion.h>
00035
00036 namespace rtabmap
00037 {
00038
00039
00040 SensorData::SensorData() :
00041 _id(0),
00042 _stamp(0.0),
00043 _cellSize(0.0f)
00044 {
00045 }
00046
00047
00048 SensorData::SensorData(
00049 const cv::Mat & image,
00050 int id,
00051 double stamp,
00052 const cv::Mat & userData) :
00053 _id(id),
00054 _stamp(stamp),
00055 _cellSize(0.0f)
00056 {
00057 if(image.rows == 1)
00058 {
00059 UASSERT(image.type() == CV_8UC1);
00060 _imageCompressed = image;
00061 }
00062 else if(!image.empty())
00063 {
00064 UASSERT(image.type() == CV_8UC1 ||
00065 image.type() == CV_8UC3);
00066 _imageRaw = image;
00067 }
00068
00069 if(userData.type() == CV_8UC1 && userData.rows == 1 && userData.cols > int(3*sizeof(int)))
00070 {
00071 _userDataCompressed = userData;
00072 }
00073 else
00074 {
00075 _userDataRaw = userData;
00076 }
00077 }
00078
00079
00080 SensorData::SensorData(
00081 const cv::Mat & image,
00082 const CameraModel & cameraModel,
00083 int id,
00084 double stamp,
00085 const cv::Mat & userData) :
00086 _id(id),
00087 _stamp(stamp),
00088 _cameraModels(std::vector<CameraModel>(1, cameraModel)),
00089 _cellSize(0.0f)
00090 {
00091 if(image.rows == 1)
00092 {
00093 UASSERT(image.type() == CV_8UC1);
00094 _imageCompressed = image;
00095 }
00096 else if(!image.empty())
00097 {
00098 UASSERT(image.type() == CV_8UC1 ||
00099 image.type() == CV_8UC3);
00100 _imageRaw = image;
00101 }
00102
00103 if(userData.type() == CV_8UC1 && userData.rows == 1 && userData.cols > int(3*sizeof(int)))
00104 {
00105 _userDataCompressed = userData;
00106 }
00107 else
00108 {
00109 _userDataRaw = userData;
00110 }
00111 }
00112
00113
00114 SensorData::SensorData(
00115 const cv::Mat & rgb,
00116 const cv::Mat & depth,
00117 const CameraModel & cameraModel,
00118 int id,
00119 double stamp,
00120 const cv::Mat & userData) :
00121 _id(id),
00122 _stamp(stamp),
00123 _cameraModels(std::vector<CameraModel>(1, cameraModel)),
00124 _cellSize(0.0f)
00125 {
00126 if(rgb.rows == 1)
00127 {
00128 UASSERT(rgb.type() == CV_8UC1);
00129 _imageCompressed = rgb;
00130 }
00131 else if(!rgb.empty())
00132 {
00133 UASSERT(rgb.type() == CV_8UC1 ||
00134 rgb.type() == CV_8UC3);
00135 _imageRaw = rgb;
00136 }
00137
00138 if(depth.rows == 1)
00139 {
00140 UASSERT(depth.type() == CV_8UC1);
00141 _depthOrRightCompressed = depth;
00142 }
00143 else if(!depth.empty())
00144 {
00145 UASSERT(depth.type() == CV_32FC1 ||
00146 depth.type() == CV_16UC1);
00147 _depthOrRightRaw = depth;
00148 }
00149
00150 if(userData.type() == CV_8UC1 && userData.rows == 1 && userData.cols > int(3*sizeof(int)))
00151 {
00152 _userDataCompressed = userData;
00153 }
00154 else
00155 {
00156 _userDataRaw = userData;
00157 }
00158 }
00159
00160
00161 SensorData::SensorData(
00162 const LaserScan & laserScan,
00163 const cv::Mat & rgb,
00164 const cv::Mat & depth,
00165 const CameraModel & cameraModel,
00166 int id,
00167 double stamp,
00168 const cv::Mat & userData) :
00169 _id(id),
00170 _stamp(stamp),
00171 _cameraModels(std::vector<CameraModel>(1, cameraModel)),
00172 _cellSize(0.0f)
00173 {
00174 if(rgb.rows == 1)
00175 {
00176 UASSERT(rgb.type() == CV_8UC1);
00177 _imageCompressed = rgb;
00178 }
00179 else if(!rgb.empty())
00180 {
00181 UASSERT(rgb.type() == CV_8UC1 ||
00182 rgb.type() == CV_8UC3);
00183 _imageRaw = rgb;
00184 }
00185 if(depth.rows == 1)
00186 {
00187 UASSERT(depth.type() == CV_8UC1);
00188 _depthOrRightCompressed = depth;
00189 }
00190 else if(!depth.empty())
00191 {
00192 UASSERT(depth.type() == CV_32FC1 ||
00193 depth.type() == CV_16UC1);
00194 _depthOrRightRaw = depth;
00195 }
00196
00197 if(!laserScan.isCompressed())
00198 {
00199 _laserScanRaw = laserScan;
00200 }
00201 else
00202 {
00203 _laserScanCompressed = laserScan;
00204 }
00205
00206 if(userData.type() == CV_8UC1 && userData.rows == 1 && userData.cols > int(3*sizeof(int)))
00207 {
00208 _userDataCompressed = userData;
00209 }
00210 else
00211 {
00212 _userDataRaw = userData;
00213 }
00214 }
00215
00216
00217 SensorData::SensorData(
00218 const cv::Mat & rgb,
00219 const cv::Mat & depth,
00220 const std::vector<CameraModel> & cameraModels,
00221 int id,
00222 double stamp,
00223 const cv::Mat & userData) :
00224 _id(id),
00225 _stamp(stamp),
00226 _cameraModels(cameraModels),
00227 _cellSize(0.0f)
00228 {
00229 if(rgb.rows == 1)
00230 {
00231 UASSERT(rgb.type() == CV_8UC1);
00232 _imageCompressed = rgb;
00233 }
00234 else if(!rgb.empty())
00235 {
00236 UASSERT(rgb.type() == CV_8UC1 ||
00237 rgb.type() == CV_8UC3);
00238 _imageRaw = rgb;
00239 }
00240 if(depth.rows == 1)
00241 {
00242 UASSERT(depth.type() == CV_8UC1);
00243 _depthOrRightCompressed = depth;
00244 }
00245 else if(!depth.empty())
00246 {
00247 UASSERT(depth.type() == CV_32FC1 ||
00248 depth.type() == CV_16UC1);
00249 _depthOrRightRaw = depth;
00250 }
00251
00252 if(userData.type() == CV_8UC1 && userData.rows == 1 && userData.cols > int(3*sizeof(int)))
00253 {
00254 _userDataCompressed = userData;
00255 }
00256 else
00257 {
00258 _userDataRaw = userData;
00259 }
00260 }
00261
00262
00263 SensorData::SensorData(
00264 const LaserScan & laserScan,
00265 const cv::Mat & rgb,
00266 const cv::Mat & depth,
00267 const std::vector<CameraModel> & cameraModels,
00268 int id,
00269 double stamp,
00270 const cv::Mat & userData) :
00271 _id(id),
00272 _stamp(stamp),
00273 _cameraModels(cameraModels),
00274 _cellSize(0.0f)
00275 {
00276 if(rgb.rows == 1)
00277 {
00278 UASSERT(rgb.type() == CV_8UC1);
00279 _imageCompressed = rgb;
00280 }
00281 else if(!rgb.empty())
00282 {
00283 UASSERT(rgb.type() == CV_8UC1 ||
00284 rgb.type() == CV_8UC3);
00285 _imageRaw = rgb;
00286 }
00287 if(depth.rows == 1)
00288 {
00289 UASSERT(depth.type() == CV_8UC1);
00290 _depthOrRightCompressed = depth;
00291 }
00292 else if(!depth.empty())
00293 {
00294 UASSERT(depth.type() == CV_32FC1 ||
00295 depth.type() == CV_16UC1);
00296 _depthOrRightRaw = depth;
00297 }
00298
00299 if(!laserScan.isCompressed())
00300 {
00301 _laserScanRaw = laserScan;
00302 }
00303 else
00304 {
00305 _laserScanCompressed = laserScan;
00306 }
00307
00308 if(userData.type() == CV_8UC1 && userData.rows == 1 && userData.cols > int(3*sizeof(int)))
00309 {
00310 _userDataCompressed = userData;
00311 }
00312 else
00313 {
00314 _userDataRaw = userData;
00315 }
00316 }
00317
00318
00319 SensorData::SensorData(
00320 const cv::Mat & left,
00321 const cv::Mat & right,
00322 const StereoCameraModel & cameraModel,
00323 int id,
00324 double stamp,
00325 const cv::Mat & userData):
00326 _id(id),
00327 _stamp(stamp),
00328 _stereoCameraModel(cameraModel),
00329 _cellSize(0.0f)
00330 {
00331 if(left.rows == 1)
00332 {
00333 UASSERT(left.type() == CV_8UC1);
00334 _imageCompressed = left;
00335 }
00336 else if(!left.empty())
00337 {
00338 UASSERT(left.type() == CV_8UC1 ||
00339 left.type() == CV_8UC3 ||
00340 left.type() == CV_16UC1);
00341 _imageRaw = left;
00342 }
00343 if(right.rows == 1)
00344 {
00345 UASSERT(right.type() == CV_8UC1);
00346 _depthOrRightCompressed = right;
00347 }
00348 else if(!right.empty())
00349 {
00350 UASSERT(right.type() == CV_8UC1 ||
00351 right.type() == CV_16UC1);
00352 _depthOrRightRaw = right;
00353 }
00354
00355 if(userData.type() == CV_8UC1 && userData.rows == 1 && userData.cols > int(3*sizeof(int)))
00356 {
00357 _userDataCompressed = userData;
00358 }
00359 else
00360 {
00361 _userDataRaw = userData;
00362 }
00363
00364 }
00365
00366
00367 SensorData::SensorData(
00368 const LaserScan & laserScan,
00369 const cv::Mat & left,
00370 const cv::Mat & right,
00371 const StereoCameraModel & cameraModel,
00372 int id,
00373 double stamp,
00374 const cv::Mat & userData) :
00375 _id(id),
00376 _stamp(stamp),
00377 _stereoCameraModel(cameraModel),
00378 _cellSize(0.0f)
00379 {
00380 if(left.rows == 1)
00381 {
00382 UASSERT(left.type() == CV_8UC1);
00383 _imageCompressed = left;
00384 }
00385 else if(!left.empty())
00386 {
00387 UASSERT(left.type() == CV_8UC1 ||
00388 left.type() == CV_8UC3);
00389 _imageRaw = left;
00390 }
00391 if(right.rows == 1)
00392 {
00393 UASSERT(right.type() == CV_8UC1);
00394 _depthOrRightCompressed = right;
00395 }
00396 else if(!right.empty())
00397 {
00398 UASSERT(right.type() == CV_8UC1);
00399 _depthOrRightRaw = right;
00400 }
00401
00402 if(!laserScan.isCompressed())
00403 {
00404 _laserScanRaw = laserScan;
00405 }
00406 else
00407 {
00408 _laserScanCompressed = laserScan;
00409 }
00410
00411 if(userData.type() == CV_8UC1 && userData.rows == 1 && userData.cols > int(3*sizeof(int)))
00412 {
00413 _userDataCompressed = userData;
00414 }
00415 else
00416 {
00417 _userDataRaw = userData;
00418 }
00419 }
00420
00421 SensorData::SensorData(
00422 const IMU & imu,
00423 int id,
00424 double stamp) :
00425 _id(id),
00426 _stamp(stamp),
00427 _cellSize(0.0f)
00428 {
00429 imu_ = imu;
00430 }
00431
00432 SensorData::~SensorData()
00433 {
00434 }
00435
00436 void SensorData::setUserDataRaw(const cv::Mat & userDataRaw)
00437 {
00438 if(!userDataRaw.empty() && !_userDataRaw.empty())
00439 {
00440 UWARN("Cannot write new user data (%d bytes) over existing user "
00441 "data (%d bytes, %d compressed). Set user data of %d to null "
00442 "before setting a new one.",
00443 int(userDataRaw.total()*userDataRaw.elemSize()),
00444 int(_userDataRaw.total()*_userDataRaw.elemSize()),
00445 _userDataCompressed.cols,
00446 this->id());
00447 return;
00448 }
00449 _userDataRaw = userDataRaw;
00450 }
00451
00452 void SensorData::setUserData(const cv::Mat & userData)
00453 {
00454 if(!userData.empty() && (!_userDataCompressed.empty() || !_userDataRaw.empty()))
00455 {
00456 UWARN("Cannot write new user data (%d bytes) over existing user "
00457 "data (%d bytes, %d compressed). Set user data of %d to null "
00458 "before setting a new one.",
00459 int(userData.total()*userData.elemSize()),
00460 int(_userDataRaw.total()*_userDataRaw.elemSize()),
00461 _userDataCompressed.cols,
00462 this->id());
00463 return;
00464 }
00465 _userDataRaw = cv::Mat();
00466 _userDataCompressed = cv::Mat();
00467
00468 if(!userData.empty())
00469 {
00470 if(userData.type() == CV_8UC1 && userData.rows == 1 && userData.cols > int(3*sizeof(int)))
00471 {
00472 _userDataCompressed = userData;
00473 }
00474 else
00475 {
00476 _userDataRaw = userData;
00477 _userDataCompressed = compressData2(userData);
00478 }
00479 }
00480 }
00481
00482 void SensorData::setOccupancyGrid(
00483 const cv::Mat & ground,
00484 const cv::Mat & obstacles,
00485 const cv::Mat & empty,
00486 float cellSize,
00487 const cv::Point3f & viewPoint)
00488 {
00489 UDEBUG("ground=%d obstacles=%d empty=%d", ground.cols, obstacles.cols, empty.cols);
00490 if((!ground.empty() && (!_groundCellsCompressed.empty() || !_groundCellsRaw.empty())) ||
00491 (!obstacles.empty() && (!_obstacleCellsCompressed.empty() || !_obstacleCellsRaw.empty())) ||
00492 (!empty.empty() && (!_emptyCellsCompressed.empty() || !_emptyCellsRaw.empty())))
00493 {
00494 UWARN("Occupancy grid cannot be overwritten! id=%d", this->id());
00495 return;
00496 }
00497
00498 _groundCellsRaw = cv::Mat();
00499 _groundCellsCompressed = cv::Mat();
00500 _obstacleCellsRaw = cv::Mat();
00501 _obstacleCellsCompressed = cv::Mat();
00502 _emptyCellsRaw = cv::Mat();
00503 _emptyCellsCompressed = cv::Mat();
00504
00505 CompressionThread ctGround(ground);
00506 CompressionThread ctObstacles(obstacles);
00507 CompressionThread ctEmpty(empty);
00508
00509 if(!ground.empty())
00510 {
00511 if(ground.type() == CV_32FC2 || ground.type() == CV_32FC3 || ground.type() == CV_32FC(4) || ground.type() == CV_32FC(5) || ground.type() == CV_32FC(6) || ground.type() == CV_32FC(7))
00512 {
00513 _groundCellsRaw = ground;
00514 ctGround.start();
00515 }
00516 else if(ground.type() == CV_8UC1)
00517 {
00518 UASSERT(ground.type() == CV_8UC1);
00519 _groundCellsCompressed = ground;
00520 }
00521 }
00522 if(!obstacles.empty())
00523 {
00524 if(obstacles.type() == CV_32FC2 || obstacles.type() == CV_32FC3 || obstacles.type() == CV_32FC(4) || obstacles.type() == CV_32FC(5) || obstacles.type() == CV_32FC(6) || obstacles.type() == CV_32FC(7))
00525 {
00526 _obstacleCellsRaw = obstacles;
00527 ctObstacles.start();
00528 }
00529 else if(obstacles.type() == CV_8UC1)
00530 {
00531 UASSERT(obstacles.type() == CV_8UC1);
00532 _obstacleCellsCompressed = obstacles;
00533 }
00534 }
00535 if(!empty.empty())
00536 {
00537 if(empty.type() == CV_32FC2 || empty.type() == CV_32FC3 || empty.type() == CV_32FC(4) || empty.type() == CV_32FC(5) || empty.type() == CV_32FC(6) || empty.type() == CV_32FC(7))
00538 {
00539 _emptyCellsRaw = empty;
00540 ctEmpty.start();
00541 }
00542 else if(empty.type() == CV_8UC1)
00543 {
00544 UASSERT(empty.type() == CV_8UC1);
00545 _emptyCellsCompressed = empty;
00546 }
00547 }
00548 ctGround.join();
00549 ctObstacles.join();
00550 ctEmpty.join();
00551 if(!_groundCellsRaw.empty())
00552 {
00553 _groundCellsCompressed = ctGround.getCompressedData();
00554 }
00555 if(!_obstacleCellsRaw.empty())
00556 {
00557 _obstacleCellsCompressed = ctObstacles.getCompressedData();
00558 }
00559 if(!_emptyCellsRaw.empty())
00560 {
00561 _emptyCellsCompressed = ctEmpty.getCompressedData();
00562 }
00563
00564 _cellSize = cellSize;
00565 _viewPoint = viewPoint;
00566 }
00567
00568 void SensorData::uncompressData()
00569 {
00570 cv::Mat tmpA, tmpB, tmpD, tmpE, tmpF, tmpG;
00571 LaserScan tmpC;
00572 uncompressData(_imageCompressed.empty()?0:&tmpA,
00573 _depthOrRightCompressed.empty()?0:&tmpB,
00574 _laserScanCompressed.isEmpty()?0:&tmpC,
00575 _userDataCompressed.empty()?0:&tmpD,
00576 _groundCellsCompressed.empty()?0:&tmpE,
00577 _obstacleCellsCompressed.empty()?0:&tmpF,
00578 _emptyCellsCompressed.empty()?0:&tmpG);
00579 }
00580
00581 void SensorData::uncompressData(
00582 cv::Mat * imageRaw,
00583 cv::Mat * depthRaw,
00584 LaserScan * laserScanRaw,
00585 cv::Mat * userDataRaw,
00586 cv::Mat * groundCellsRaw,
00587 cv::Mat * obstacleCellsRaw,
00588 cv::Mat * emptyCellsRaw)
00589 {
00590 UDEBUG("%d data(%d,%d,%d,%d,%d,%d,%d)", this->id(), imageRaw?1:0, depthRaw?1:0, laserScanRaw?1:0, userDataRaw?1:0, groundCellsRaw?1:0, obstacleCellsRaw?1:0, emptyCellsRaw?1:0);
00591 if(imageRaw == 0 &&
00592 depthRaw == 0 &&
00593 laserScanRaw == 0 &&
00594 userDataRaw == 0 &&
00595 groundCellsRaw == 0 &&
00596 obstacleCellsRaw == 0 &&
00597 emptyCellsRaw == 0)
00598 {
00599 return;
00600 }
00601 uncompressDataConst(
00602 imageRaw,
00603 depthRaw,
00604 laserScanRaw,
00605 userDataRaw,
00606 groundCellsRaw,
00607 obstacleCellsRaw,
00608 emptyCellsRaw);
00609
00610 if(imageRaw && !imageRaw->empty() && _imageRaw.empty())
00611 {
00612 _imageRaw = *imageRaw;
00613
00614 if(!_imageRaw.empty() && _cameraModels.size())
00615 {
00616 cv::Size size(_imageRaw.cols/_cameraModels.size(), _imageRaw.rows);
00617 for(unsigned int i=0; i<_cameraModels.size(); ++i)
00618 {
00619 if(_cameraModels[i].fx() && _cameraModels[i].fy() && _cameraModels[i].imageWidth() == 0)
00620 {
00621 _cameraModels[i].setImageSize(size);
00622 }
00623 }
00624 }
00625 }
00626 if(depthRaw && !depthRaw->empty() && _depthOrRightRaw.empty())
00627 {
00628 _depthOrRightRaw = *depthRaw;
00629 }
00630 if(laserScanRaw && !laserScanRaw->isEmpty() && _laserScanRaw.isEmpty())
00631 {
00632 _laserScanRaw = *laserScanRaw;
00633 if(_laserScanCompressed.format() == LaserScan::kUnknown)
00634 {
00635 _laserScanCompressed = LaserScan(_laserScanCompressed.data(), _laserScanCompressed.maxPoints(), _laserScanCompressed.maxRange(), _laserScanRaw.format(), _laserScanCompressed.localTransform());
00636 }
00637 }
00638 if(userDataRaw && !userDataRaw->empty() && _userDataRaw.empty())
00639 {
00640 _userDataRaw = *userDataRaw;
00641 }
00642 if(groundCellsRaw && !groundCellsRaw->empty() && _groundCellsRaw.empty())
00643 {
00644 _groundCellsRaw = *groundCellsRaw;
00645 }
00646 if(obstacleCellsRaw && !obstacleCellsRaw->empty() && _obstacleCellsRaw.empty())
00647 {
00648 _obstacleCellsRaw = *obstacleCellsRaw;
00649 }
00650 if(emptyCellsRaw && !emptyCellsRaw->empty() && _emptyCellsRaw.empty())
00651 {
00652 _emptyCellsRaw = *emptyCellsRaw;
00653 }
00654 }
00655
00656 void SensorData::uncompressDataConst(
00657 cv::Mat * imageRaw,
00658 cv::Mat * depthRaw,
00659 LaserScan * laserScanRaw,
00660 cv::Mat * userDataRaw,
00661 cv::Mat * groundCellsRaw,
00662 cv::Mat * obstacleCellsRaw,
00663 cv::Mat * emptyCellsRaw) const
00664 {
00665 if(imageRaw)
00666 {
00667 *imageRaw = _imageRaw;
00668 }
00669 if(depthRaw)
00670 {
00671 *depthRaw = _depthOrRightRaw;
00672 }
00673 if(laserScanRaw)
00674 {
00675 *laserScanRaw = _laserScanRaw;
00676 }
00677 if(userDataRaw)
00678 {
00679 *userDataRaw = _userDataRaw;
00680 }
00681 if(groundCellsRaw)
00682 {
00683 *groundCellsRaw = _groundCellsRaw;
00684 }
00685 if(obstacleCellsRaw)
00686 {
00687 *obstacleCellsRaw = _obstacleCellsRaw;
00688 }
00689 if(emptyCellsRaw)
00690 {
00691 *emptyCellsRaw = _emptyCellsRaw;
00692 }
00693 if( (imageRaw && imageRaw->empty()) ||
00694 (depthRaw && depthRaw->empty()) ||
00695 (laserScanRaw && laserScanRaw->isEmpty()) ||
00696 (userDataRaw && userDataRaw->empty()) ||
00697 (groundCellsRaw && groundCellsRaw->empty()) ||
00698 (obstacleCellsRaw && obstacleCellsRaw->empty()) ||
00699 (emptyCellsRaw && emptyCellsRaw->empty()))
00700 {
00701 rtabmap::CompressionThread ctImage(_imageCompressed, true);
00702 rtabmap::CompressionThread ctDepth(_depthOrRightCompressed, true);
00703 rtabmap::CompressionThread ctLaserScan(_laserScanCompressed.data(), false);
00704 rtabmap::CompressionThread ctUserData(_userDataCompressed, false);
00705 rtabmap::CompressionThread ctGroundCells(_groundCellsCompressed, false);
00706 rtabmap::CompressionThread ctObstacleCells(_obstacleCellsCompressed, false);
00707 rtabmap::CompressionThread ctEmptyCells(_emptyCellsCompressed, false);
00708 if(imageRaw && imageRaw->empty() && !_imageCompressed.empty())
00709 {
00710 UASSERT(_imageCompressed.type() == CV_8UC1);
00711 ctImage.start();
00712 }
00713 if(depthRaw && depthRaw->empty() && !_depthOrRightCompressed.empty())
00714 {
00715 UASSERT(_depthOrRightCompressed.type() == CV_8UC1);
00716 ctDepth.start();
00717 }
00718 if(laserScanRaw && laserScanRaw->isEmpty() && !_laserScanCompressed.isEmpty())
00719 {
00720 UASSERT(_laserScanCompressed.isCompressed());
00721 ctLaserScan.start();
00722 }
00723 if(userDataRaw && userDataRaw->empty() && !_userDataCompressed.empty())
00724 {
00725 UASSERT(_userDataCompressed.type() == CV_8UC1);
00726 ctUserData.start();
00727 }
00728 if(groundCellsRaw && groundCellsRaw->empty() && !_groundCellsCompressed.empty())
00729 {
00730 UASSERT(_groundCellsCompressed.type() == CV_8UC1);
00731 ctGroundCells.start();
00732 }
00733 if(obstacleCellsRaw && obstacleCellsRaw->empty() && !_obstacleCellsCompressed.empty())
00734 {
00735 UASSERT(_obstacleCellsCompressed.type() == CV_8UC1);
00736 ctObstacleCells.start();
00737 }
00738 if(emptyCellsRaw && emptyCellsRaw->empty() && !_emptyCellsCompressed.empty())
00739 {
00740 UASSERT(_emptyCellsCompressed.type() == CV_8UC1);
00741 ctEmptyCells.start();
00742 }
00743 ctImage.join();
00744 ctDepth.join();
00745 ctLaserScan.join();
00746 ctUserData.join();
00747 ctGroundCells.join();
00748 ctObstacleCells.join();
00749 ctEmptyCells.join();
00750
00751 if(imageRaw && imageRaw->empty())
00752 {
00753 *imageRaw = ctImage.getUncompressedData();
00754 if(imageRaw->empty())
00755 {
00756 if(_imageCompressed.empty())
00757 {
00758 UWARN("Requested raw image data, but the sensor data (%d) doesn't have image.", this->id());
00759 }
00760 else
00761 {
00762 UERROR("Requested image data, but failed to uncompress (%d).", this->id());
00763 }
00764 }
00765 }
00766 if(depthRaw && depthRaw->empty())
00767 {
00768 *depthRaw = ctDepth.getUncompressedData();
00769 if(depthRaw->empty())
00770 {
00771 if(_depthOrRightCompressed.empty())
00772 {
00773 UWARN("Requested depth/right image data, but the sensor data (%d) doesn't have depth/right image.", this->id());
00774 }
00775 else
00776 {
00777 UERROR("Requested depth/right image data, but failed to uncompress (%d).", this->id());
00778 }
00779 }
00780 }
00781 if(laserScanRaw && laserScanRaw->isEmpty())
00782 {
00783 *laserScanRaw = LaserScan(ctLaserScan.getUncompressedData(), _laserScanCompressed.maxPoints(), _laserScanCompressed.maxRange(), _laserScanCompressed.format(), _laserScanCompressed.localTransform());
00784
00785 if(laserScanRaw->isEmpty())
00786 {
00787 if(_laserScanCompressed.isEmpty())
00788 {
00789 UWARN("Requested laser scan data, but the sensor data (%d) doesn't have laser scan.", this->id());
00790 }
00791 else
00792 {
00793 UERROR("Requested laser scan data, but failed to uncompress (%d).", this->id());
00794 }
00795 }
00796 }
00797 if(userDataRaw && userDataRaw->empty())
00798 {
00799 *userDataRaw = ctUserData.getUncompressedData();
00800
00801 if(userDataRaw->empty())
00802 {
00803 if(_userDataCompressed.empty())
00804 {
00805 UWARN("Requested user data, but the sensor data (%d) doesn't have user data.", this->id());
00806 }
00807 else
00808 {
00809 UERROR("Requested user data, but failed to uncompress (%d).", this->id());
00810 }
00811 }
00812 }
00813 if(groundCellsRaw && groundCellsRaw->empty())
00814 {
00815 *groundCellsRaw = ctGroundCells.getUncompressedData();
00816 }
00817 if(obstacleCellsRaw && obstacleCellsRaw->empty())
00818 {
00819 *obstacleCellsRaw = ctObstacleCells.getUncompressedData();
00820 }
00821 if(emptyCellsRaw && emptyCellsRaw->empty())
00822 {
00823 *emptyCellsRaw = ctEmptyCells.getUncompressedData();
00824 }
00825 }
00826 }
00827
00828 void SensorData::setFeatures(const std::vector<cv::KeyPoint> & keypoints, const std::vector<cv::Point3f> & keypoints3D, const cv::Mat & descriptors)
00829 {
00830 UASSERT_MSG(keypoints3D.empty() || keypoints.size() == keypoints3D.size(), uFormat("keypoints=%d keypoints3D=%d", (int)keypoints.size(), (int)keypoints3D.size()).c_str());
00831 UASSERT_MSG(descriptors.empty() || (int)keypoints.size() == descriptors.rows, uFormat("keypoints=%d descriptors=%d", (int)keypoints.size(), descriptors.rows).c_str());
00832 _keypoints = keypoints;
00833 _keypoints3D = keypoints3D;
00834 _descriptors = descriptors;
00835 }
00836
00837 long SensorData::getMemoryUsed() const
00838 {
00839 return _imageCompressed.total()*_imageCompressed.elemSize() +
00840 _imageRaw.total()*_imageRaw.elemSize() +
00841 _depthOrRightCompressed.total()*_depthOrRightCompressed.elemSize() +
00842 _depthOrRightRaw.total()*_depthOrRightRaw.elemSize() +
00843 _userDataCompressed.total()*_userDataCompressed.elemSize() +
00844 _userDataRaw.total()*_userDataRaw.elemSize() +
00845 _laserScanCompressed.data().total()*_laserScanCompressed.data().elemSize() +
00846 _laserScanRaw.data().total()*_laserScanRaw.data().elemSize() +
00847 _groundCellsCompressed.total()*_groundCellsCompressed.elemSize() +
00848 _groundCellsRaw.total()*_groundCellsRaw.elemSize() +
00849 _obstacleCellsCompressed.total()*_obstacleCellsCompressed.elemSize() +
00850 _obstacleCellsRaw.total()*_obstacleCellsRaw.elemSize()+
00851 _emptyCellsCompressed.total()*_emptyCellsCompressed.elemSize() +
00852 _emptyCellsRaw.total()*_emptyCellsRaw.elemSize()+
00853 _keypoints.size() * sizeof(float) * 7 +
00854 _keypoints3D.size() * sizeof(float)*3 +
00855 _descriptors.total()*_descriptors.elemSize();
00856 }
00857
00858 bool SensorData::isPointVisibleFromCameras(const cv::Point3f & pt) const
00859 {
00860 if(_cameraModels.size() >= 1)
00861 {
00862 for(unsigned int i=0; i<_cameraModels.size(); ++i)
00863 {
00864 if(_cameraModels[i].isValidForProjection() && !_cameraModels[i].localTransform().isNull())
00865 {
00866 cv::Point3f ptInCameraFrame = util3d::transformPoint(pt, _cameraModels[i].localTransform().inverse());
00867 if(ptInCameraFrame.z > 0.0f)
00868 {
00869 int borderWidth = int(float(_cameraModels[i].imageWidth())* 0.2);
00870 int u, v;
00871 _cameraModels[i].reproject(ptInCameraFrame.x, ptInCameraFrame.y, ptInCameraFrame.z, u, v);
00872 if(uIsInBounds(u, borderWidth, _cameraModels[i].imageWidth()-2*borderWidth) &&
00873 uIsInBounds(v, borderWidth, _cameraModels[i].imageHeight()-2*borderWidth))
00874 {
00875 return true;
00876 }
00877 }
00878 }
00879 }
00880 }
00881 else if(_stereoCameraModel.isValidForProjection())
00882 {
00883 cv::Point3f ptInCameraFrame = util3d::transformPoint(pt, _stereoCameraModel.localTransform().inverse());
00884 if(ptInCameraFrame.z > 0.0f)
00885 {
00886 int u, v;
00887 _stereoCameraModel.left().reproject(ptInCameraFrame.x, ptInCameraFrame.y, ptInCameraFrame.z, u, v);
00888 return uIsInBounds(u, 0, _stereoCameraModel.left().imageWidth()) &&
00889 uIsInBounds(v, 0, _stereoCameraModel.left().imageHeight());
00890 }
00891 }
00892 else
00893 {
00894 UERROR("no valid camera model!");
00895 }
00896 return false;
00897 }
00898
00899 }
00900