40 #include <opencv2/stitching/detail/exposure_compensate.hpp> 44 #include <pcl/io/io.h> 53 _stereoExposureCompensation(
false),
56 _stereoToDepth(
false),
57 _scanFromDepth(
false),
58 _scanDownsampleStep(1),
63 _scanNormalsRadius(0.0
f),
64 _scanForceGroundNormalsUp(
false),
67 _bilateralFiltering(
false),
69 _bilateralSigmaR(0.1),
105 UERROR(
"Loaded distortion model \"%s\" is not valid!", path.c_str());
107 _distortionModel = 0;
140 bool forceGroundNormalsUp)
142 setScanParameters(fromDepth, downsampleStep, rangeMin, rangeMax, voxelSize, normalsK, normalsRadius, forceGroundNormalsUp?0.8
f:0.0
f);
153 float groundNormalsUp)
187 UWARN(
"no more images...");
195 if(dynamic_cast<CameraFreenect2*>(
_camera) != 0)
209 UERROR(
"CameraFreenect2: Failed to kill normally the Freenect2 driver! The thread is locked " 210 "on waitForNewFrame() method of libfreenect2. This maybe caused by not linking on the right libusb. " 211 "Note that rtabmap should link on libusb of libfreenect2. " 212 "Tip before starting rtabmap: \"$ export LD_LIBRARY_PATH=~/libfreenect2/depends/libusb/lib:$LD_LIBRARY_PATH\"");
240 cv::Mat depth = data.
depthRaw().clone();
246 UERROR(
"Distortion model size is %dx%d but dpeth image is %dx%d!",
267 UERROR(
"Decimation of depth images should be exact (decimation=%d, size=(%d,%d))! " 289 UDEBUG(
"depthDecimation=%d", depthDecimation);
294 for(
unsigned int i=0; i<models.size(); ++i)
296 if(models[i].isValidForProjection())
322 cv::flip(data.
imageRaw(), tmpRgb, 1);
340 cv::flip(data.
depthRaw(), tmpDepth, 1);
348 #if CV_MAJOR_VERSION < 3 349 UWARN(
"Stereo exposure compensation not implemented for OpenCV version under 3.");
353 cv::Ptr<cv::detail::ExposureCompensator> compensator = cv::detail::ExposureCompensator::createDefault(cv::detail::ExposureCompensator::GAIN);
354 std::vector<cv::Point> topLeftCorners(2, cv::Point(0,0));
355 std::vector<cv::UMat> images;
356 std::vector<cv::UMat> masks(2, cv::UMat(data.
imageRaw().size(), CV_8UC1, cv::Scalar(255)));
357 images.push_back(data.
imageRaw().getUMat(cv::ACCESS_READ));
358 images.push_back(data.
rightRaw().getUMat(cv::ACCESS_READ));
359 compensator->feed(topLeftCorners, images, masks);
360 cv::Mat imgLeft = data.
imageRaw().clone();
361 compensator->apply(0, cv::Point(0,0), imgLeft, masks[0]);
362 cv::Mat imgRight = data.
rightRaw().clone();
363 compensator->apply(1, cv::Point(0,0), imgRight, masks[1]);
365 cv::detail::GainCompensator * gainCompensator = (cv::detail::GainCompensator*)compensator.get();
366 UDEBUG(
"gains = %f %f ", gainCompensator->gains()[0], gainCompensator->gains()[1]);
401 pcl::IndicesPtr validIndices(
new std::vector<int>);
412 if(validIndices->size())
417 float ratio = float(cloud->size()) /
float(validIndices->size());
418 maxPoints = ratio * maxPoints;
420 else if(!cloud->is_dense)
422 pcl::PointCloud<pcl::PointXYZRGB>::Ptr denseCloud(
new pcl::PointCloud<pcl::PointXYZRGB>);
423 pcl::copyPointCloud(*cloud, *validIndices, *denseCloud);
431 Eigen::Vector3f viewPoint(baseToScan.
x(), baseToScan.
y(), baseToScan.
z());
433 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr cloudNormals(
new pcl::PointCloud<pcl::PointXYZRGBNormal>);
434 pcl::concatenateFields(*cloud, *normals, *cloudNormals);
449 UWARN(
"Option to create laser scan from depth image is enabled, but " 450 "there is already a laser scan in the captured sensor data. Scan from " 451 "depth will not be created.");
471 UWARN(
"IMU's acc and gyr values are null! Please disable IMU filtering.");
486 cv::Vec4d(qx,qy,qz,qw), cv::Mat::eye(3,3,CV_64FC1),
490 UDEBUG(
"%f %f %f %f (gyro=%f %f %f, acc=%f %f %f, %fs)",
const cv::Vec4d & orientation() const
const cv::Size & imageSize() const
void setLaserScan(const LaserScan &laserScan, bool clearPreviousData=true)
const cv::Mat & linearAccelerationCovariance() const
CameraThread(Camera *camera, const ParametersMap ¶meters=ParametersMap())
void enableBilateralFiltering(float sigmaS, float sigmaR)
void setImageRate(float imageRate)
static IMUFilter * create(const ParametersMap ¶meters=ParametersMap())
cv::Mat RTABMAP_EXP depthFromDisparity(const cv::Mat &disparity, float fx, float baseline, int type=CV_32FC1)
void setRGBDImage(const cv::Mat &rgb, const cv::Mat &depth, const CameraModel &model, bool clearPreviousData=true)
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)
void setImageRate(float imageRate)
const LaserScan & laserScanRaw() const
const cv::Mat & imageRaw() const
float _scanForceGroundNormalsUp
const cv::Mat & angularVelocityCovariance() const
void post(UEvent *event, bool async=true) const
virtual void mainLoopKill()
virtual std::string getSerial() const =0
#define UASSERT(condition)
SensorData takeImage(CameraInfo *info=0)
float timeStereoExposureCompensation
bool isValidForProjection() const
clams::DiscreteDepthDistortionModel * _distortionModel
const CameraModel & left() 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
#define UASSERT_MSG(condition, msg_str)
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)
cv::Mat RTABMAP_EXP decimate(const cv::Mat &image, int d)
const cv::Vec3d linearAcceleration() const
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 >())
cv::Mat RTABMAP_EXP computeNormals(const cv::Mat &laserScan, int searchK, float searchRadius)
void setStereoImage(const cv::Mat &left, const cv::Mat &right, const StereoCameraModel &stereoCameraModel, bool clearPreviousData=true)
const cv::Mat & depthOrRightRaw() const
void setDistortionModel(const std::string &path)
void load(const std::string &path)
void uSleep(unsigned int ms)
const std::vector< CameraModel > & cameraModels() const
const Transform & localTransform() const
virtual void mainLoopBegin()
void undistort(cv::Mat &depth) const
void disableIMUFiltering()
void postUpdate(SensorData *data, CameraInfo *info=0) const
ULogger class and convenient macros.
const StereoCameraModel & stereoCameraModel() const
float timeImageDecimation
void setIMU(const IMU &imu)
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)
const Transform & localTransform() const
virtual void getOrientation(double &qx, double &qy, double &qz, double &qw) const =0
const cv::Vec3d & angularVelocity() const
void enableIMUFiltering(int filteringStrategy=1, const ParametersMap ¶meters=ParametersMap())
LaserScan RTABMAP_EXP laserScanFromPointCloud(const pcl::PCLPointCloud2 &cloud, bool filterNaNs=true, bool is2D=false, const Transform &transform=Transform())