31 #include <opencv2/imgproc/types_c.h> 33 #ifdef RTABMAP_FREENECT 34 #include <libfreenect.h> 35 #ifdef FREENECT_DASH_INCLUDES 36 #include <libfreenect-registration.h> 38 #include <libfreenect_registration.h> 45 #ifdef RTABMAP_FREENECT 47 class FreenectDevice :
public UThread {
49 FreenectDevice(
freenect_context * ctx,
int index,
bool color =
true,
bool registered =
true) :
52 registered_(registered),
60 virtual ~FreenectDevice()
63 if(device_ && freenect_close_device(device_) < 0){}
66 const std::string & getSerial()
const {
return serial_;}
73 freenect_close_device(device_);
77 std::vector<std::string> deviceSerials;
78 freenect_device_attributes* attr_list;
79 freenect_device_attributes* item;
80 freenect_list_device_attributes(ctx_, &attr_list);
81 for (item = attr_list; item !=
NULL; item = item->next) {
82 deviceSerials.push_back(std::string(item->camera_serial));
84 freenect_free_device_attributes(attr_list);
86 if(freenect_open_device(ctx_, &device_, index_) < 0)
88 UERROR(
"FreenectDevice: Cannot open Kinect");
92 if(index_ >= 0 && index_ < (
int)deviceSerials.size())
94 serial_ = deviceSerials[index_];
98 UERROR(
"Could not get serial for index %d", index_);
101 UINFO(
"color=%d registered=%d", color_?1:0, registered_?1:0);
103 freenect_set_user(device_,
this);
104 freenect_frame_mode videoMode = freenect_find_video_mode(FREENECT_RESOLUTION_MEDIUM, color_?FREENECT_VIDEO_RGB:FREENECT_VIDEO_IR_8BIT);
105 freenect_frame_mode depthMode = freenect_find_depth_mode(FREENECT_RESOLUTION_MEDIUM, color_ && registered_?FREENECT_DEPTH_REGISTERED:FREENECT_DEPTH_MM);
106 if(!videoMode.is_valid)
108 UERROR(
"Freenect: video mode selected not valid!");
111 if(!depthMode.is_valid)
113 UERROR(
"Freenect: depth mode selected not valid!");
116 UASSERT(videoMode.data_bits_per_pixel == 8 || videoMode.data_bits_per_pixel == 24);
117 UASSERT(depthMode.data_bits_per_pixel == 16);
118 freenect_set_video_mode(device_, videoMode);
119 freenect_set_depth_mode(device_, depthMode);
120 rgbIrBuffer_ = cv::Mat(cv::Size(videoMode.width,videoMode.height), color_?CV_8UC3:CV_8UC1);
121 depthBuffer_ = cv::Mat(cv::Size(depthMode.width,depthMode.height), CV_16UC1);
122 freenect_set_depth_buffer(device_, depthBuffer_.data);
123 freenect_set_video_buffer(device_, rgbIrBuffer_.data);
124 freenect_set_depth_callback(device_, freenect_depth_callback);
125 freenect_set_video_callback(device_, freenect_video_callback);
127 float rgb_focal_length_sxga = 1050.0f;
128 float width_sxga = 1280.0f;
129 float width = freenect_get_current_depth_mode(device_).width;
130 float scale = width / width_sxga;
131 if(color_ && registered_)
133 depthFocal_ = rgb_focal_length_sxga *
scale;
137 freenect_registration reg = freenect_copy_registration(device_);
138 float depth_focal_length_sxga = reg.zero_plane_info.reference_distance / reg.zero_plane_info.reference_pixel_size;
139 freenect_destroy_registration(®);
141 depthFocal_ = depth_focal_length_sxga *
scale;
144 UINFO(
"FreenectDevice: Depth focal = %f", depthFocal_);
148 float getDepthFocal()
const {
return depthFocal_;}
150 void getData(cv::Mat & rgb, cv::Mat & depth)
152 if(this->isRunning())
154 if(!dataReady_.acquire(1, 5000))
156 UERROR(
"Not received any frames since 5 seconds, try to restart the camera again.");
161 rgb = rgbIrLastFrame_;
162 depth = depthLastFrame_;
163 rgbIrLastFrame_ = cv::Mat();
164 depthLastFrame_= cv::Mat();
169 void getAccelerometerValues(
double & x,
double & y,
double & z)
171 freenect_update_tilt_state(device_);
172 freenect_raw_tilt_state*
state = freenect_get_tilt_state(device_);
173 freenect_get_mks_accel(state, &x,&y,&z);
178 void VideoCallback(
void* rgb)
180 UASSERT(rgbIrBuffer_.data == rgb);
182 bool notify = rgbIrLastFrame_.empty();
186 cv::cvtColor(rgbIrBuffer_, rgbIrLastFrame_, CV_RGB2BGR);
190 rgbIrLastFrame_ = rgbIrBuffer_.clone();
192 if(!depthLastFrame_.empty() && notify)
194 dataReady_.release();
199 void DepthCallback(
void* depth)
201 UASSERT(depthBuffer_.data == depth);
203 bool notify = depthLastFrame_.empty();
204 depthLastFrame_ = depthBuffer_.clone();
205 if(!rgbIrLastFrame_.empty() && notify)
207 dataReady_.release();
212 if(device_ && freenect_start_video(device_) < 0)
UERROR(
"Cannot start RGB callback");
215 if(device_ && freenect_stop_video(device_) < 0)
UERROR(
"Cannot stop RGB callback");
218 if(device_ && freenect_start_depth(device_) < 0)
UERROR(
"Cannot start depth callback");
221 if(device_ && freenect_stop_depth(device_) < 0)
UERROR(
"Cannot stop depth callback");
224 virtual void mainLoopBegin()
226 if(device_) freenect_set_led(device_, LED_RED);
231 virtual void mainLoop()
236 if(freenect_process_events_timeout(ctx_, &t) < 0)
238 UERROR(
"FreenectDevice: Cannot process freenect events");
243 virtual void mainLoopEnd()
245 if(device_) freenect_set_led(device_, LED_GREEN);
248 dataReady_.release();
252 FreenectDevice*
device =
static_cast<FreenectDevice*
>(freenect_get_user(dev));
253 device->DepthCallback(depth);
256 FreenectDevice* device =
static_cast<FreenectDevice*
>(freenect_get_user(dev));
257 device->VideoCallback(video);
261 FreenectDevice(
const FreenectDevice& );
262 const FreenectDevice& operator=(
const FreenectDevice& );
271 cv::Mat depthBuffer_;
272 cv::Mat rgbIrBuffer_;
274 cv::Mat depthLastFrame_;
275 cv::Mat rgbIrLastFrame_;
286 #ifdef RTABMAP_FREENECT 294 Camera(imageRate, localTransform)
295 #ifdef RTABMAP_FREENECT
303 #ifdef RTABMAP_FREENECT 304 if(freenect_init(&ctx_,
NULL) < 0)
UERROR(
"Cannot initialize freenect library");
306 freenect_select_subdevices(ctx_, static_cast<freenect_device_flags>(FREENECT_DEVICE_MOTOR | FREENECT_DEVICE_CAMERA));
312 #ifdef RTABMAP_FREENECT 315 freenectDevice_->join(
true);
316 delete freenectDevice_;
321 if(freenect_shutdown(ctx_) < 0){}
328 #ifdef RTABMAP_FREENECT 331 freenectDevice_->join(
true);
332 delete freenectDevice_;
336 if(ctx_ && freenect_num_devices(ctx_) > 0)
339 bool hardwareRegistration =
true;
341 if(!calibrationFolder.empty())
344 FreenectDevice dev(ctx_, deviceId_);
347 UERROR(
"CameraFreenect: Init failed!");
349 std::string calibrationName = dev.getSerial();
350 if(!cameraName.empty())
352 calibrationName = cameraName;
354 stereoModel_.setName(calibrationName,
"depth",
"rgb");
355 hardwareRegistration = !stereoModel_.load(calibrationFolder, calibrationName,
false);
359 hardwareRegistration =
false;
363 if((type_ ==
kTypeIRDepth && !stereoModel_.left().isValidForRectification()) ||
364 (type_ ==
kTypeColorDepth && !stereoModel_.right().isValidForRectification()))
366 UWARN(
"Missing calibration files for camera \"%s\" in \"%s\" folder, default calibration used.",
367 calibrationName.c_str(), calibrationFolder.c_str());
369 else if(type_ ==
kTypeColorDepth && stereoModel_.right().isValidForRectification() && hardwareRegistration)
371 UWARN(
"Missing extrinsic calibration file for camera \"%s\" in \"%s\" folder, default registration is used even if rgb is rectified!",
372 calibrationName.c_str(), calibrationFolder.c_str());
374 else if(type_ ==
kTypeColorDepth && stereoModel_.right().isValidForRectification() && !hardwareRegistration)
376 UINFO(
"Custom calibration files for \"%s\" were found in \"%s\" folder. To use " 377 "factory calibration, remove the corresponding files from that directory.", calibrationName.c_str(), calibrationFolder.c_str());
381 freenectDevice_ =
new FreenectDevice(ctx_, deviceId_, type_==
kTypeColorDepth, hardwareRegistration);
382 if(freenectDevice_->init())
384 freenectDevice_->start();
390 UERROR(
"CameraFreenect: Init failed!");
392 delete freenectDevice_;
397 UERROR(
"CameraFreenect: No devices connected!");
400 UERROR(
"CameraFreenect: RTAB-Map is not built with Freenect support!");
412 #ifdef RTABMAP_FREENECT 415 return freenectDevice_->getSerial();
424 #ifdef RTABMAP_FREENECT 425 if(ctx_ && freenectDevice_)
427 if(freenectDevice_->isRunning())
430 freenectDevice_->getData(rgb, depth);
431 if(!rgb.empty() && !depth.empty())
433 UASSERT(freenectDevice_->getDepthFocal() != 0.0f);
437 freenectDevice_->getDepthFocal(),
438 freenectDevice_->getDepthFocal(),
439 float(rgb.cols/2) - 0.5f,
440 float(rgb.rows/2) - 0.5f,
447 if(stereoModel_.left().isValidForRectification())
449 rgb = stereoModel_.left().rectifyImage(rgb);
450 depth = stereoModel_.left().rectifyImage(depth, 0);
451 model = stereoModel_.left();
456 if(stereoModel_.right().isValidForRectification())
458 rgb = stereoModel_.right().rectifyImage(rgb);
459 model = stereoModel_.right();
461 if(stereoModel_.left().isValidForRectification() && !stereoModel_.stereoTransform().isNull())
463 depth = stereoModel_.left().rectifyImage(depth, 0);
464 depth =
util2d::registerDepth(depth, stereoModel_.left().K(), rgb.size(), stereoModel_.right().K(), stereoModel_.stereoTransform());
473 freenectDevice_->getAccelerometerValues(x,y,z);
474 if(x != 0.0 && y != 0.0 && z != 0.0)
476 Transform opticalTransform(0,-1,0,0, 0,0,-1,0, 1,0,0,0);
479 data.
setIMU(
IMU(cv::Vec3d(0,0,0), cv::Mat(), cv::Vec3d(x, y, z), cv::Mat(), base*
Transform(0,0,1,0, 1,0,0,0, 0,1,0,0)));
485 UERROR(
"CameraFreenect: Re-initialization needed!");
486 delete freenectDevice_;
491 UERROR(
"CameraFreenect: RTAB-Map is not built with Freenect support!");
struct _freenect_context freenect_context
def init(descriptorDim, matchThreshold, iterations, cuda, model_path)
cv::Mat RTABMAP_EXP registerDepth(const cv::Mat &depth, const cv::Mat &depthK, const cv::Size &colorSize, const cv::Mat &colorK, const rtabmap::Transform &transform)
#define UASSERT(condition)
virtual SensorData captureImage(CameraInfo *info=0)
const Transform & getLocalTransform() const
virtual std::string getSerial() const
RecoveryProgressState state
CameraFreenect(int deviceId=0, Type type=kTypeColorDepth, float imageRate=0.0f, const Transform &localTransform=Transform::getIdentity())
void uSleep(unsigned int ms)
virtual ~CameraFreenect()
virtual bool isCalibrated() const
virtual bool init(const std::string &calibrationFolder=".", const std::string &cameraName="")
void setIMU(const IMU &imu)
struct _freenect_device freenect_device