31 #include <opencv2/imgproc/types_c.h> 34 #include <dc1394/dc1394.h> 54 if (DC1394_SUCCESS != dc1394_video_set_transmission(camera_, DC1394_OFF) ||
55 DC1394_SUCCESS != dc1394_capture_stop(camera_))
57 UWARN(
"unable to stop camera");
61 dc1394_capture_stop(camera_);
62 dc1394_camera_free(camera_);
67 dc1394_free(context_);
72 const std::string & guid()
const {
return guid_;}
79 dc1394_capture_stop(camera_);
80 dc1394_camera_free(camera_);
88 context_ = dc1394_new ();
91 UERROR(
"Could not initialize dc1394_context.\n" 92 "Make sure /dev/raw1394 exists, you have access permission,\n" 93 "and libraw1394 development package is installed.");
98 dc1394camera_list_t *list;
99 err = dc1394_camera_enumerate(context_, &list);
100 if (err != DC1394_SUCCESS)
102 UERROR(
"Could not get camera list");
108 UERROR(
"No cameras found");
109 dc1394_camera_free_list (list);
113 dc1394_camera_free_list (list);
116 camera_ = dc1394_camera_new (context_, guid);
119 UERROR(
"Failed to initialize camera with GUID [%016lx]", guid);
124 value[0]= camera_->guid & 0xffffffff;
125 value[1]= (camera_->guid >>32) & 0x000000ff;
126 value[2]= (camera_->guid >>40) & 0xfffff;
127 guid_ =
uFormat(
"%06x%02x%08x", value[2], value[1], value[0]);
129 UINFO(
"camera model: %s %s", camera_->vendor, camera_->model);
133 bool bmode = camera_->bmode_capable;
135 && (DC1394_SUCCESS !=
136 dc1394_video_set_operation_mode(camera_,
137 DC1394_OPERATION_MODE_1394B)))
140 UWARN(
"failed to set IEEE1394b mode");
144 dc1394speed_t request = DC1394_ISO_SPEED_3200;
149 request = DC1394_ISO_SPEED_400;
156 if (request <= DC1394_ISO_SPEED_MIN)
159 dc1394speed_t curSpeed;
160 if (DC1394_SUCCESS == dc1394_video_get_iso_speed(camera_, &curSpeed) && curSpeed <= DC1394_ISO_SPEED_MAX)
166 rate = 100 << (curSpeed - DC1394_ISO_SPEED_MIN);
170 UWARN(
"Unable to get ISO speed; assuming 400Mb/s");
172 request = DC1394_ISO_SPEED_400;
177 request = (dc1394speed_t) ((
int) request - 1);
182 if (DC1394_SUCCESS != dc1394_video_set_iso_speed(camera_, request))
184 UERROR(
"Failed to set iso speed");
189 dc1394video_modes_t vmodes;
190 err = dc1394_video_get_supported_modes(camera_, &vmodes);
191 if (err != DC1394_SUCCESS)
193 UERROR(
"unable to get supported video modes");
194 return (dc1394video_mode_t) 0;
199 dc1394video_mode_t videoMode = DC1394_VIDEO_MODE_FORMAT7_3;
200 for (
uint32_t i = 0; i < vmodes.num; ++i)
202 if (vmodes.modes[i] == videoMode)
209 UERROR(
"unable to get video mode %d", videoMode);
213 if (DC1394_SUCCESS != dc1394_video_set_mode(camera_, videoMode))
215 UERROR(
"Failed to set video mode %d", videoMode);
220 if (dc1394_is_video_mode_scalable(videoMode) == DC1394_TRUE)
222 if (DC1394_SUCCESS != dc1394_format7_set_color_coding(camera_, videoMode, DC1394_COLOR_CODING_RAW16))
224 UERROR(
"Could not set color coding");
228 if (DC1394_SUCCESS != dc1394_format7_get_recommended_packet_size(camera_, videoMode, &packetSize))
230 UERROR(
"Could not get default packet size");
234 if (DC1394_SUCCESS != dc1394_format7_set_packet_size(camera_, videoMode, packetSize))
236 UERROR(
"Could not set packet size");
242 UERROR(
"Video is not in mode scalable");
247 if (DC1394_SUCCESS != dc1394_capture_setup(camera_, 4, DC1394_CAPTURE_FLAGS_DEFAULT))
249 UERROR(
"Failed to open device!");
254 if (DC1394_SUCCESS != dc1394_video_set_transmission(camera_, DC1394_ON))
256 UERROR(
"Failed to start device!");
263 bool getImages(cv::Mat & left, cv::Mat & right)
267 dc1394video_frame_t * frame =
NULL;
268 UDEBUG(
"[%016lx] waiting camera", camera_->guid);
269 dc1394_capture_dequeue (camera_, DC1394_CAPTURE_POLICY_WAIT, &frame);
272 UERROR(
"Unable to capture frame");
275 dc1394video_frame_t frame1 = *frame;
277 size_t frame1_size = frame->total_bytes;
278 frame1.image = (
unsigned char *) malloc(frame1_size);
279 frame1.allocated_image_bytes = frame1_size;
280 frame1.color_coding = DC1394_COLOR_CODING_RAW8;
281 int err = dc1394_deinterlace_stereo_frames(frame, &frame1, DC1394_STEREO_METHOD_INTERLACED);
282 if (err != DC1394_SUCCESS)
285 dc1394_capture_enqueue(camera_, frame);
286 UERROR(
"Could not extract stereo frames");
290 uint8_t* capture_buffer =
reinterpret_cast<uint8_t *
>(frame1.image);
293 cv::Mat image(frame->size[1], frame->size[0], CV_8UC3);
294 cv::Mat image2 = image.clone();
298 cv::cvtColor(cv::Mat(frame->size[1], frame->size[0], CV_8UC1, capture_buffer), left, CV_BayerRG2BGR);
299 cv::cvtColor(cv::Mat(frame->size[1], frame->size[0], CV_8UC1, capture_buffer+image.total()), right, CV_BayerRG2GRAY);
301 dc1394_capture_enqueue(camera_, frame);
311 dc1394camera_t *camera_;
319 #ifdef RTABMAP_DC1394 327 Camera(imageRate, localTransform)
328 #ifdef RTABMAP_DC1394
333 #ifdef RTABMAP_DC1394 334 device_ =
new DC1394Device();
340 #ifdef RTABMAP_DC1394 347 #ifdef RTABMAP_DC1394 350 bool ok = device_->init();
354 if(!calibrationFolder.empty())
356 if(!stereoModel_.load(calibrationFolder, cameraName.empty()?device_->guid():cameraName,
false))
358 UWARN(
"Missing calibration files for camera \"%s\" in \"%s\" folder, you should calibrate the camera!",
359 cameraName.empty()?device_->guid().c_str():cameraName.c_str(), calibrationFolder.c_str());
363 UINFO(
"Stereo parameters: fx=%f cx=%f cy=%f baseline=%f",
364 stereoModel_.left().fx(),
365 stereoModel_.left().cx(),
366 stereoModel_.left().cy(),
367 stereoModel_.baseline());
374 UERROR(
"CameraDC1394: RTAB-Map is not built with dc1394 support!");
381 #ifdef RTABMAP_DC1394 382 return stereoModel_.isValidForProjection();
390 #ifdef RTABMAP_DC1394 393 return device_->guid();
402 #ifdef RTABMAP_DC1394 406 device_->getImages(left, right);
408 if(!left.empty() && !right.empty())
411 if(stereoModel_.left().isValidForRectification())
413 left = stereoModel_.left().rectifyImage(left);
415 if(stereoModel_.right().isValidForRectification())
417 right = stereoModel_.right().rectifyImage(right);
420 if(stereoModel_.isValidForProjection())
423 stereoModel_.left().fx(),
424 stereoModel_.left().fy(),
425 stereoModel_.left().cx(),
426 stereoModel_.left().cy(),
427 stereoModel_.baseline(),
435 UERROR(
"CameraDC1394: RTAB-Map is not built with dc1394 support!");
def init(descriptorDim, matchThreshold, iterations, cuda, model_path)
Some conversion functions.
#define UASSERT(condition)
virtual SensorData captureImage(CameraInfo *info=0)
const Transform & getLocalTransform() const
virtual std::string getSerial() const
virtual bool init(const std::string &calibrationFolder=".", const std::string &cameraName="")
virtual ~CameraStereoDC1394()
CameraStereoDC1394(float imageRate=0.0f, const Transform &localTransform=Transform::getIdentity())
std::string UTILITE_EXP uFormat(const char *fmt,...)
virtual bool isCalibrated() const