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()),
58 spinOncePreviousStamp_(0.0),
60 uvs_initialized_(
false),
62 stampEpochOffset_(0.0),
63 smoothing_(smoothing),
171 if(textureId_ != 0 && texCoord != 0)
174 cv::cvtColor(data.
imageRaw(), rgbImage, cv::COLOR_BGR2RGBA);
176 glBindTexture(GL_TEXTURE_2D, textureId_);
177 glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_LINEAR);
178 glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_LINEAR);
179 glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_WRAP_S, GL_CLAMP_TO_EDGE);
180 glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_WRAP_T, GL_CLAMP_TO_EDGE);
182 glPixelStorei(GL_UNPACK_ALIGNMENT, 4);
186 glTexImage2D(GL_TEXTURE_2D, 0, GL_RGBA, rgbImage.cols, rgbImage.rows, 0, GL_RGBA, GL_UNSIGNED_BYTE, rgbImage.data);
188 GLint error = glGetError();
189 if(error != GL_NO_ERROR)
191 LOGE(
"OpenGL: Could not allocate texture (0x%x)\n", error);
207 bool ignoreFrame =
false;
278 cv::transpose(rgb,rgbt);
282 cv::transpose(depth,deptht);
290 model.cx()>0?model.imageWidth()-model.cx():0,
291 model.localTransform()*
rtabmap::Transform(0,-1,0,0, 1,0,0,0, 0,0,1,0));
295 std::vector<cv::KeyPoint> keypoints = data.
keypoints();
296 for(
size_t i=0; i<keypoints.size(); ++i)
298 keypoints[i].pt.x = data.
keypoints()[i].pt.y;
299 keypoints[i].pt.y = rgb.rows - data.
keypoints()[i].pt.x;
310 cv::flip(depth,depth,0);
316 model.cx()>0?model.imageWidth()-model.cx():0,
317 model.cy()>0?model.imageHeight()-model.cy():0,
322 std::vector<cv::KeyPoint> keypoints = data.
keypoints();
323 for(
size_t i=0; i<keypoints.size(); ++i)
325 keypoints[i].pt.x = rgb.cols - data.
keypoints()[i].pt.x;
326 keypoints[i].pt.y = rgb.rows - data.
keypoints()[i].pt.y;
338 cv::flip(depth,depth,1);
344 model.cy()>0?model.imageHeight()-model.cy():0,
346 model.localTransform()*
rtabmap::Transform(0,1,0,0, -1,0,0,0, 0,0,1,0));
350 std::vector<cv::KeyPoint> keypoints = data.
keypoints();
351 for(
size_t i=0; i<keypoints.size(); ++i)
353 keypoints[i].pt.x = rgb.cols - data.
keypoints()[i].pt.y;
354 keypoints[i].pt.y = data.
keypoints()[i].pt.x;
376 info.
reg.
covariance = cv::Mat::eye(6,6,CV_64FC1) * (firstFrame?9999.0:0.0001);
384 LOGI(
"Publish odometry message (variance=%f)", firstFrame?9999:0.0001);
391 LOGW(
"Odometry lost");
406 const cv::Mat & pointCloudData,
411 std::vector<cv::KeyPoint> * kpts,
412 std::vector<cv::Point3f> * kpts3D,
415 if(!pointCloudData.empty())
417 cv::Mat scanData(1, pointCloudData.cols, CV_32FC4);
418 float * ptr = scanData.ptr<
float>();
419 const float * inPtr = pointCloudData.ptr<
float>();
420 int ic = pointCloudData.channels();
421 UASSERT(pointCloudData.depth() == CV_32F && ic >= 3);
424 for(
unsigned int i=0;i<points; ++i)
426 cv::Point3f pt(inPtr[i*ic], inPtr[i*ic + 1], inPtr[i*ic + 2]);
429 ptr[oi*4 + 1] = pt.y;
430 ptr[oi*4 + 2] = pt.z;
437 unsigned char r=255,g=255,b=255;
440 b=rgb.at<cv::Vec3b>(v,u).val[0];
441 g=rgb.at<cv::Vec3b>(v,u).val[1];
442 r=rgb.at<cv::Vec3b>(v,u).val[2];
444 kpts->push_back(cv::KeyPoint(u,v,kptsSize));
446 kpts3D->push_back(org);
448 *(
int*)&ptr[oi*4 + 3] =
int(b) | (int(g) << 8) | (
int(r) << 16);
glm::mat4 glmFromTransform(const rtabmap::Transform &transform)
virtual bool isCalibrated() const
void setImageSize(const cv::Size &size)
0 degree rotation (natural orientation)
const double & stamp() const
cv::Point3f RTABMAP_EXP transformPoint(const cv::Point3f &pt, const Transform &transform)
void addEnvSensor(int type, float value)
const std::vector< cv::Point3f > & keypoints3D() const
virtual SensorData captureImage(CameraInfo *info=0)
ScreenRotation colorCameraToDisplayRotation_
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)
float transformed_uvs_[8]
const cv::Mat & depthOrRightRaw() const
void setRGBDImage(const cv::Mat &rgb, const cv::Mat &depth, const CameraModel &model, bool clearPreviousData=true)
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)
const std::vector< cv::KeyPoint > & keypoints() const
cv::Mat RTABMAP_EXP fastBilateralFiltering(const cv::Mat &depth, float sigmaS=15.0f, float sigmaR=0.05f, bool earlyDivision=false)
void setGPS(const GPS &gps)
void reproject(float x, float y, float z, float &u, float &v) const
void poseReceived(const Transform &pose)
void post(UEvent *event, bool async=true) const
#define UASSERT(condition)
const std::vector< CameraModel > & cameraModels() const
virtual void mainLoopBegin()
Transform deviceTColorCamera_
CameraMobile(bool smoothing=false)
const cv::Mat & imageRaw() const
UTimer spinOnceFrameRateTimer_
UTimer cameraStartedTime_
EnvSensors lastEnvSensors_
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)
static const float bilateralFilteringSigmaS
virtual void capturePoseOnly()
virtual bool init(const std::string &calibrationFolder=".", const std::string &cameraName="")
void setEnvSensors(const EnvSensors &sensors)
void uSleep(unsigned int ms)
static const rtabmap::Transform opticalRotation
static const float bilateralFilteringSigmaR
double spinOncePreviousStamp_
ULogger class and convenient macros.
void setStamp(double stamp)
void setGroundTruth(const Transform &pose)
static const rtabmap::Transform opticalRotationInv
bool inFrame(int u, int v) const
static LaserScan backwardCompatibility(const cv::Mat &oldScanFormat, int maxPoints=0, int maxRange=0, const Transform &localTransform=Transform::getIdentity())
bool isValidForProjection() const
glm::mat4 projectionMatrix_
void setFeatures(const std::vector< cv::KeyPoint > &keypoints, const std::vector< cv::Point3f > &keypoints3D, const cv::Mat &descriptors)
void setData(const SensorData &data, const Transform &pose, const glm::mat4 &viewMatrix, const glm::mat4 &projectionMatrix, const float *texCoord)
void setGPS(const GPS &gps)
GLM_FUNC_DECL matType< T, P > inverse(matType< T, P > const &m)