40 #include <opencv2/stitching/detail/exposure_compensate.hpp> 44 #include <pcl/io/io.h> 55 _poseScaleFactor(1.0
f),
57 _stereoExposureCompensation(
false),
60 _stereoToDepth(
false),
61 _scanFromDepth(
false),
62 _scanDownsampleStep(1),
67 _scanNormalsRadius(0.0
f),
68 _scanForceGroundNormalsUp(
false),
71 _bilateralFiltering(
false),
73 _bilateralSigmaR(0.1),
75 _imuBaseFrameConversion(
false)
85 double poseTimeOffset,
86 float poseScaleFactor,
189 UERROR(
"Loaded distortion model \"%s\" is not valid!", path.c_str());
191 _distortionModel = 0;
225 bool forceGroundNormalsUp)
227 setScanParameters(fromDepth, downsampleStep, rangeMin, rangeMax, voxelSize, normalsK, normalsRadius, forceGroundNormalsUp?0.8
f:0.0
f);
238 float groundNormalsUp)
300 UWARN(
"Could not get pose at stamp %f", data.
stamp());
319 UWARN(
"no more images...");
327 if(dynamic_cast<CameraFreenect2*>(
_camera) != 0)
341 UERROR(
"CameraFreenect2: Failed to kill normally the Freenect2 driver! The thread is locked " 342 "on waitForNewFrame() method of libfreenect2. This maybe caused by not linking on the right libusb. " 343 "Note that rtabmap should link on libusb of libfreenect2. " 344 "Tip before starting rtabmap: \"$ export LD_LIBRARY_PATH=~/libfreenect2/depends/libusb/lib:$LD_LIBRARY_PATH\"");
362 std::vector<CameraModel> models;
379 cv::Mat depth = data.
depthRaw().clone();
385 UERROR(
"Distortion model size is %dx%d but depth image is %dx%d!",
406 UERROR(
"Decimation of depth images should be exact (decimation=%d, size=(%d,%d))! " 428 UDEBUG(
"depthDecimation=%d", depthDecimation);
433 for(
unsigned int i=0; i<models.size(); ++i)
435 if(models[i].isValidForProjection())
447 for(
unsigned int i=0; i<stereoModels.size(); ++i)
449 if(stereoModels[i].isValidForProjection())
454 if(!stereoModels.empty())
468 cv::flip(data.
imageRaw(), tmpRgb, 1);
485 cv::flip(data.
depthRaw(), tmpDepth, 1);
492 UWARN(
"Mirroring is not implemented for multiple cameras or stereo...");
500 #if CV_MAJOR_VERSION < 3 501 UWARN(
"Stereo exposure compensation not implemented for OpenCV version under 3.");
505 cv::Ptr<cv::detail::ExposureCompensator> compensator = cv::detail::ExposureCompensator::createDefault(cv::detail::ExposureCompensator::GAIN);
506 std::vector<cv::Point> topLeftCorners(2, cv::Point(0,0));
507 std::vector<cv::UMat> images;
508 std::vector<cv::UMat> masks(2, cv::UMat(data.
imageRaw().size(), CV_8UC1, cv::Scalar(255)));
509 images.push_back(data.
imageRaw().getUMat(cv::ACCESS_READ));
510 images.push_back(data.
rightRaw().getUMat(cv::ACCESS_READ));
511 compensator->feed(topLeftCorners, images, masks);
512 cv::Mat imgLeft = data.
imageRaw().clone();
513 compensator->apply(0, cv::Point(0,0), imgLeft, masks[0]);
514 cv::Mat imgRight = data.
rightRaw().clone();
515 compensator->apply(1, cv::Point(0,0), imgRight, masks[1]);
517 cv::detail::GainCompensator * gainCompensator = (cv::detail::GainCompensator*)compensator.get();
518 UDEBUG(
"gains = %f %f ", gainCompensator->gains()[0], gainCompensator->gains()[1]);
524 UWARN(
"Stereo exposure compensation only is not implemented to multiple stereo cameras...");
552 UWARN(
"Stereo to depth is not implemented for multiple stereo cameras...");
565 pcl::IndicesPtr validIndices(
new std::vector<int>);
575 if(validIndices->size())
580 float ratio = float(cloud->size()) /
float(validIndices->size());
581 maxPoints = ratio * maxPoints;
583 else if(!cloud->is_dense)
585 pcl::PointCloud<pcl::PointXYZRGB>::Ptr denseCloud(
new pcl::PointCloud<pcl::PointXYZRGB>);
586 pcl::copyPointCloud(*cloud, *validIndices, *denseCloud);
594 Eigen::Vector3f viewPoint(baseToScan.
x(), baseToScan.
y(), baseToScan.
z());
596 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr cloudNormals(
new pcl::PointCloud<pcl::PointXYZRGBNormal>);
597 pcl::concatenateFields(*cloud, *normals, *cloudNormals);
611 UWARN(
"Option to create laser scan from depth image is enabled, but " 612 "there is already a laser scan in the captured sensor data. Scan from " 613 "depth will not be created.");
633 UWARN(
"IMU's acc and gyr values are null! Please disable IMU filtering.");
657 cv::Vec4d(qx,qy,qz,qw), cv::Mat::eye(3,3,CV_64FC1),
662 UDEBUG(
"%f %f %f %f (gyro=%f %f %f, acc=%f %f %f, %fs)",
Transform _extrinsicsOdomToCamera
void setLaserScan(const LaserScan &laserScan, bool clearPreviousData=true)
CameraThread(Camera *camera, const ParametersMap ¶meters=ParametersMap())
const cv::Mat & depthOrRightRaw() const
void enableBilateralFiltering(float sigmaS, float sigmaR)
void setImageRate(float imageRate)
void convertToBaseFrame()
static IMUFilter * create(const ParametersMap ¶meters=ParametersMap())
cv::Mat RTABMAP_EXP depthFromDisparity(const cv::Mat &disparity, float fx, float baseline, int type=CV_32FC1)
bool _imuBaseFrameConversion
void setRGBDImage(const cv::Mat &rgb, const cv::Mat &depth, const CameraModel &model, bool clearPreviousData=true)
const std::vector< StereoCameraModel > & stereoCameraModels() const
std::map< std::string, std::string > ParametersMap
cv::Mat RTABMAP_EXP fastBilateralFiltering(const cv::Mat &depth, float sigmaS=15.0f, float sigmaR=0.05f, bool earlyDivision=false)
const cv::Vec4d & orientation() const
void setImageRate(float imageRate)
void post(UEvent *event, bool async=true) const
float _scanForceGroundNormalsUp
virtual void mainLoopKill()
void setCameraModel(const CameraModel &model)
virtual std::string getSerial() const =0
#define UASSERT(condition)
SensorData takeImage(CameraInfo *info=0)
float timeStereoExposureCompensation
clams::DiscreteDepthDistortionModel * _distortionModel
const std::vector< CameraModel > & cameraModels() const
LaserScan RTABMAP_EXP commonFiltering(const LaserScan &scan, int downsamplingStep, float rangeMin=0.0f, float rangeMax=0.0f, float voxelSize=0.0f, int normalK=0, float normalRadius=0.0f, float groundNormalsUp=0.0f)
void update(double gx, double gy, double gz, double ax, double ay, double az, double stamp)
virtual cv::Mat computeDisparity(const cv::Mat &leftImage, const cv::Mat &rightImage) const =0
void setScanParameters(bool fromDepth, int downsampleStep=1, float rangeMin=0.0f, float rangeMax=0.0f, float voxelSize=0.0f, int normalsK=0, int normalsRadius=0.0f, float groundNormalsUp=0.0f)
const cv::Mat & imageRaw() const
cv::Mat RTABMAP_EXP decimate(const cv::Mat &image, int d)
void enableIMUFiltering(int filteringStrategy=1, const ParametersMap ¶meters=ParametersMap(), bool baseFrameConversion=false)
static void registerCurrentThread(const std::string &name)
StereoDense * _stereoDense
pcl::PointCloud< pcl::PointXYZRGB >::Ptr RTABMAP_EXP cloudRGBFromSensorData(const SensorData &sensorData, int decimation=1, float maxDepth=0.0f, float minDepth=0.0f, std::vector< int > *validIndices=0, const ParametersMap &stereoParameters=ParametersMap(), const std::vector< float > &roiRatios=std::vector< float >())
virtual bool getPose(double stamp, Transform &pose, cv::Mat &covariance)
cv::Mat RTABMAP_EXP computeNormals(const cv::Mat &laserScan, int searchK, float searchRadius)
LaserScan laserScanFromPointCloud(const PointCloud2T &cloud, bool filterNaNs, bool is2D, const Transform &transform)
void setStereoImage(const cv::Mat &left, const cv::Mat &right, const StereoCameraModel &stereoCameraModel, bool clearPreviousData=true)
void setDistortionModel(const std::string &path)
void load(const std::string &path)
const Transform & localTransform() const
const cv::Mat & linearAccelerationCovariance() const
const cv::Vec3d & angularVelocity() const
void uSleep(unsigned int ms)
void postUpdate(SensorData *data, CameraInfo *info=0) const
const LaserScan & laserScanRaw() const
virtual void mainLoopBegin()
void disableIMUFiltering()
ULogger class and convenient macros.
const cv::Mat & angularVelocityCovariance() const
virtual bool odomProvided() const
float timeImageDecimation
void undistort(cv::Mat &depth) const
bool odomProvided() const
void setIMU(const IMU &imu)
const cv::Vec3d linearAcceleration() const
void setGroundTruth(const Transform &pose)
float timeBilateralFiltering
bool _stereoExposureCompensation
void join(bool killFirst=false)
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP voxelize(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const pcl::IndicesPtr &indices, float voxelSize)
void setStereoCameraModel(const StereoCameraModel &stereoCameraModel)
virtual void getOrientation(double &qx, double &qy, double &qz, double &qw) const =0