39 #include <opencv2/stitching/detail/exposure_compensate.hpp> 43 #include <pcl/io/io.h> 52 _stereoExposureCompensation(
false),
55 _stereoToDepth(
false),
56 _scanFromDepth(
false),
62 _scanNormalsRadius(0.0
f),
63 _stereoDense(new
StereoBM(parameters)),
65 _bilateralFiltering(
false),
102 UERROR(
"Loaded distortion model \"%s\" is not valid!", path.c_str());
104 _distortionModel = 0;
140 UWARN(
"no more images...");
149 if(dynamic_cast<CameraFreenect2*>(
_camera) != 0)
163 UERROR(
"CameraFreenect2: Failed to kill normally the Freenect2 driver! The thread is locked " 164 "on waitForNewFrame() method of libfreenect2. This maybe caused by not linking on the right libusb. " 165 "Note that rtabmap should link on libusb of libfreenect2. " 166 "Tip before starting rtabmap: \"$ export LD_LIBRARY_PATH=~/libfreenect2/depends/libusb/lib:$LD_LIBRARY_PATH\"");
187 cv::Mat depth = data.
depthRaw().clone();
193 UERROR(
"Distortion model size is %dx%d but dpeth image is %dx%d!",
214 UERROR(
"Decimation of depth images should be exact (decimation=%d, size=(%d,%d))! " 222 for(
unsigned int i=0; i<models.size(); ++i)
224 if(models[i].isValidForProjection())
244 cv::flip(data.
imageRaw(), tmpRgb, 1);
262 cv::flip(data.
depthRaw(), tmpDepth, 1);
270 #if CV_MAJOR_VERSION < 3 271 UWARN(
"Stereo exposure compensation not implemented for OpenCV version under 3.");
275 cv::Ptr<cv::detail::ExposureCompensator> compensator = cv::detail::ExposureCompensator::createDefault(cv::detail::ExposureCompensator::GAIN);
276 std::vector<cv::Point> topLeftCorners(2, cv::Point(0,0));
277 std::vector<cv::UMat> images;
278 std::vector<cv::UMat> masks(2, cv::UMat(data.
imageRaw().size(), CV_8UC1, cv::Scalar(255)));
279 images.push_back(data.
imageRaw().getUMat(cv::ACCESS_READ));
280 images.push_back(data.
rightRaw().getUMat(cv::ACCESS_READ));
281 compensator->feed(topLeftCorners, images, masks);
282 cv::Mat img = data.
imageRaw().clone();
283 compensator->apply(0, cv::Point(0,0), img, masks[0]);
286 compensator->apply(1, cv::Point(0,0), img, masks[1]);
288 cv::detail::GainCompensator * gainCompensator = (cv::detail::GainCompensator*)compensator.get();
289 UDEBUG(
"gains = %f %f ", gainCompensator->gains()[0], gainCompensator->gains()[1]);
326 pcl::IndicesPtr validIndices(
new std::vector<int>);
337 if(validIndices->size())
342 float ratio = float(cloud->size()) /
float(validIndices->size());
343 maxPoints = ratio * maxPoints;
345 else if(!cloud->is_dense)
347 pcl::PointCloud<pcl::PointXYZRGB>::Ptr denseCloud(
new pcl::PointCloud<pcl::PointXYZRGB>);
348 pcl::copyPointCloud(*cloud, *validIndices, *denseCloud);
356 Eigen::Vector3f viewPoint(baseToScan.
x(), baseToScan.
y(), baseToScan.
z());
358 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr cloudNormals(
new pcl::PointCloud<pcl::PointXYZRGBNormal>);
359 pcl::concatenateFields(*cloud, *normals, *cloudNormals);
374 UWARN(
"Option to create laser scan from depth image is enabled, but " 375 "there is already a laser scan in the captured sensor data. Scan from " 376 "depth will not be created.");
LaserScan RTABMAP_EXP laserScanFromPointCloud(const pcl::PCLPointCloud2 &cloud, bool filterNaNs=true)
const cv::Size & imageSize() const
CameraThread(Camera *camera, const ParametersMap ¶meters=ParametersMap())
void enableBilateralFiltering(float sigmaS, float sigmaR)
void setImageRate(float imageRate)
cv::Mat RTABMAP_EXP depthFromDisparity(const cv::Mat &disparity, float fx, float baseline, int type=CV_32FC1)
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 setCameraModels(const std::vector< CameraModel > &models)
void setImageRate(float imageRate)
const LaserScan & laserScanRaw() const
const cv::Mat & imageRaw() const
void post(UEvent *event, bool async=true) const
void setImageRaw(const cv::Mat &imageRaw)
virtual void mainLoopKill()
void setCameraModel(const CameraModel &model)
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
virtual cv::Mat computeDisparity(const cv::Mat &leftImage, const cv::Mat &rightImage) const =0
#define UASSERT_MSG(condition, msg_str)
cv::Mat RTABMAP_EXP decimate(const cv::Mat &image, int d)
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)
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
virtual void mainLoopBegin()
void undistort(cv::Mat &depth) const
void postUpdate(SensorData *data, CameraInfo *info=0) const
ULogger class and convenient macros.
const StereoCameraModel & stereoCameraModel() const
float timeImageDecimation
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)
const Transform & localTransform() const
void setDepthOrRightRaw(const cv::Mat &depthOrImageRaw)
void setLaserScanRaw(const LaserScan &laserScanRaw)