Go to the documentation of this file.
47 0.0f, 0.0f, 1.0f, 0.0f,
48 -1.0f, 0.0f, 0.0f, 0.0f,
49 0.0f, -1.0f, 0.0f, 0.0f);
51 0.0f, -1.0f, 0.0f, 0.0f,
52 0.0f, 0.0f, -1.0f, 0.0f,
53 1.0f, 0.0f, 0.0f, 0.0f);
57 deviceTColorCamera_(
Transform::getIdentity()),
59 uvs_initialized_(
false),
60 stampEpochOffset_(0.0),
61 smoothing_(smoothing),
109 int maxWaitTimeMs = maxWaitTime * 1000;
116 while(maxWaitTimeMs>0 &&
poseBuffer_.rbegin()->first < stamp && waitTry < maxWaitTimeMs)
125 if(maxWaitTimeMs > 0)
127 UWARN(
"Could not find poses to interpolate at time %f after waiting %d ms (latest is %f)...", stamp, maxWaitTimeMs,
poseBuffer_.rbegin()->first);
131 UWARN(
"Could not find poses to interpolate at time %f (latest is %f)...", stamp,
poseBuffer_.rbegin()->first);
136 std::map<double, Transform>::const_iterator iterB =
poseBuffer_.lower_bound(stamp);
137 std::map<double, Transform>::const_iterator iterA = iterB;
146 if(iterA == iterB && stamp == iterA->first)
148 pose = iterA->second;
150 else if(stamp >= iterA->first && stamp <= iterB->
first)
152 pose = iterA->second.
interpolate((stamp-iterA->first) / (iterB->first-iterA->first), iterB->second);
156 UWARN(
"Could not find pose data to interpolate at time %f (earliest is %f). Are sensors synchronized?", stamp, iterA->first);
252 cv::cvtColor(
data.imageRaw(), rgbImage, cv::COLOR_BGR2RGBA);
255 glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_LINEAR);
256 glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_LINEAR);
257 glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_WRAP_S, GL_CLAMP_TO_EDGE);
258 glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_WRAP_T, GL_CLAMP_TO_EDGE);
260 glPixelStorei(GL_UNPACK_ALIGNMENT, 4);
264 glTexImage2D(GL_TEXTURE_2D, 0, GL_RGBA, rgbImage.cols, rgbImage.rows, 0, GL_RGBA, GL_UNSIGNED_BYTE, rgbImage.data);
266 GLint
error = glGetError();
267 if(
error != GL_NO_ERROR)
269 LOGE(
"OpenGL: Could not allocate texture (0x%x)\n",
error);
303 LOGE(
"To use CameraMobile::updateOnRender(), CameraMobile::updateDataOnRender() "
304 "should be overridden by inherited classes. Returning empty data!\n");
341 cv::transpose(rgb,rgbt);
345 cv::transpose(depth,deptht);
348 cv::Size sizet(
model.imageHeight(),
model.imageWidth());
354 model.localTransform()*
rtabmap::Transform(0,-1,0,0, 1,0,0,0, 0,0,1,0));
355 model.setImageSize(sizet);
359 for(
size_t i=0;
i<keypoints.size(); ++
i)
373 cv::flip(depth,depth,0);
375 cv::Size sizet(
model.imageWidth(),
model.imageHeight());
382 model.setImageSize(sizet);
386 for(
size_t i=0;
i<keypoints.size(); ++
i)
401 cv::flip(depth,depth,1);
403 cv::Size sizet(
model.imageHeight(),
model.imageWidth());
409 model.localTransform()*
rtabmap::Transform(0,1,0,0, -1,0,0,0, 0,0,1,0));
410 model.setImageSize(sizet);
414 for(
size_t i=0;
i<keypoints.size(); ++
i)
441 info->odomCovariance = cv::Mat::eye(6,6,CV_64FC1) * (
firstFrame_?9999.0:0.0001);
445 info->odomCovariance.at<
double>(3,3) *= 0.01;
446 info->odomCovariance.at<
double>(4,4) *= 0.01;
447 info->odomCovariance.at<
double>(5,5) *= 0.01;
456 UWARN(
"CameraMobile::captureImage() invalid data!");
462 const cv::Mat & pointCloudData,
467 std::vector<cv::KeyPoint> * kpts,
468 std::vector<cv::Point3f> * kpts3D,
471 if(!pointCloudData.empty())
473 cv::Mat scanData(1, pointCloudData.cols, CV_32FC4);
474 float * ptr = scanData.ptr<
float>();
475 const float * inPtr = pointCloudData.ptr<
float>();
476 int ic = pointCloudData.channels();
477 UASSERT(pointCloudData.depth() == CV_32F && ic >= 3);
480 for(
unsigned int i=0;
i<points; ++
i)
482 cv::Point3f pt(inPtr[
i*ic], inPtr[
i*ic + 1], inPtr[
i*ic + 2]);
485 ptr[oi*4 + 1] = pt.y;
486 ptr[oi*4 + 2] = pt.z;
494 model.reproject(pt.x, pt.y, pt.z, u,
v);
495 unsigned char r=255,
g=255,
b=255;
498 b=rgb.at<cv::Vec3b>(
v,u).val[0];
499 g=rgb.at<cv::Vec3b>(
v,u).val[1];
500 r=rgb.at<cv::Vec3b>(
v,u).val[2];
502 kpts->push_back(cv::KeyPoint(u,
v,kptsSize));
504 kpts3D->push_back(org);
506 *(
int*)&ptr[oi*4 + 3] =
int(
b) | (
int(
g) << 8) | (
int(r) << 16);
static LaserScan scanFromPointCloudData(const cv::Mat &pointCloudData, int points, const Transform &pose, const CameraModel &model, const cv::Mat &rgb, std::vector< cv::KeyPoint > *kpts=0, std::vector< cv::Point3f > *kpts3D=0, int kptsSize=3)
bool acquire(int n=1, int ms=0)
virtual SensorData captureImage(SensorCaptureInfo *info=0)
virtual bool isCalibrated() const
static LaserScan backwardCompatibility(const cv::Mat &oldScanFormat, int maxPoints=0, int maxRange=0, const Transform &localTransform=Transform::getIdentity())
ScreenRotation colorCameraToDisplayRotation_
glm::mat4 projectionMatrix_
void setGPS(const GPS &gps)
float transformed_uvs_[8]
void addEnvSensor(int type, float value)
@ ROTATION_270
270 degree rotation.
Transform deviceTColorCamera_
const std::vector< CameraModel > & cameraModels() const
void setRGBDImage(const cv::Mat &rgb, const cv::Mat &depth, const CameraModel &model, bool clearPreviousData=true)
cv::Point3f RTABMAP_CORE_EXPORT transformPoint(const cv::Point3f &pt, const Transform &transform)
static const rtabmap::Transform rtabmap_world_T_opengl_world(0.0f, 0.0f,-1.0f, 0.0f, -1.0f, 0.0f, 0.0f, 0.0f, 0.0f, 1.0f, 0.0f, 0.0f)
cv::Mat RTABMAP_CORE_EXPORT fastBilateralFiltering(const cv::Mat &depth, float sigmaS=15.0f, float sigmaR=0.05f, bool earlyDivision=false)
static const rtabmap::Transform opengl_world_T_rtabmap_world(0.0f, -1.0f, 0.0f, 0.0f, 0.0f, 0.0f, 1.0f, 0.0f, -1.0f, 0.0f, 0.0f, 0.0f)
EnvSensors lastEnvSensors_
constexpr int first(int i)
void update(const SensorData &data, const Transform &pose, const glm::mat4 &viewMatrix, const glm::mat4 &projectionMatrix, const float *texCoord)
bool isValidForProjection() const
@ ROTATION_90
90 degree rotation.
virtual bool getPose(double epochStamp, Transform &pose, cv::Mat &covariance, double maxWaitTime=0.06)
#define UASSERT(condition)
void error(const char *str)
@ ROTATION_180
180 degree rotation.
const double & stamp() const
virtual bool init(const std::string &calibrationFolder=".", const std::string &cameraName="")
static const rtabmap::Transform opticalRotation
void setFeatures(const std::vector< cv::KeyPoint > &keypoints, const std::vector< cv::Point3f > &keypoints3D, const cv::Mat &descriptors)
void poseReceived(const Transform &pose, double deviceStamp)
CameraMobile(bool smoothing=false)
const cv::Mat & imageRaw() const
ULogger class and convenient macros.
virtual SensorData updateDataOnRender(Transform &pose)
static const float bilateralFilteringSigmaS
Array< int, Dynamic, 1 > v
static const float bilateralFilteringSigmaR
void uSleep(unsigned int ms)
static const rtabmap::Transform opticalRotationInv
const std::vector< cv::KeyPoint > & keypoints() const
@ ROTATION_0
0 degree rotation (natural orientation)
const cv::Mat & depthOrRightRaw() const
glm::mat4 glmFromTransform(const rtabmap::Transform &transform)
void setGPS(const GPS &gps)
const std::vector< cv::Point3f > & keypoints3D() const
GLM_FUNC_DECL matType< T, P > inverse(matType< T, P > const &m)
void setEnvSensors(const EnvSensors &sensors)
RTABMAP_DEPRECATED void setDepthOrRightRaw(const cv::Mat &image)
std::map< double, Transform > poseBuffer_
void post(UEvent *event, bool async=true) const
rtabmap
Author(s): Mathieu Labbe
autogenerated on Thu Jul 25 2024 02:50:07