00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00043 #include <stdint.h>
00044 #include "yuv.h"
00045 #include <cstdlib>
00046 #include <sensor_msgs/image_encodings.h>
00047 #include "format7.h"
00048 #include "modes.h"
00049
00050
00059 bool Format7::start(dc1394camera_t *camera,
00060 dc1394video_mode_t mode,
00061 Config &newconfig)
00062 {
00063 active_ = false;
00064
00065
00066 binning_x_ = newconfig.binning_x;
00067 binning_y_ = newconfig.binning_y;
00068 roi_.x_offset = newconfig.x_offset;
00069 roi_.y_offset = newconfig.y_offset;
00070 roi_.width = newconfig.roi_width;
00071 roi_.height = newconfig.roi_height;
00072
00073 uint32_t packet_size = newconfig.format7_packet_size;
00074
00075
00076
00077 if (newconfig.bayer_method != "")
00078 {
00079 ROS_WARN_STREAM("Bayer method [" << newconfig.bayer_method
00080 << "] not supported for Format7 modes."
00081 << " Using image_proc instead.");
00082 newconfig.bayer_method = "";
00083 }
00084
00085 const char* pattern = newconfig.bayer_pattern.c_str();
00086 dc1394color_filter_t bayer_pattern = findBayerPattern(pattern);
00087 if ((bayer_pattern >= DC1394_COLOR_FILTER_MIN)
00088 && (bayer_pattern <= DC1394_COLOR_FILTER_MAX))
00089 {
00090 BayerPattern_ = bayer_pattern;
00091 }
00092 else
00093 {
00094 ROS_WARN_STREAM("Bayer pattern [" << newconfig.bayer_pattern << " ("
00095 << bayer_pattern << ")] is invalid.");
00096 }
00097
00098
00099
00100 uint32_t sensor_width = 0, sensor_height = 0;
00101
00102 for (int scan_mode = DC1394_VIDEO_MODE_FORMAT7_MIN;
00103 scan_mode <= DC1394_VIDEO_MODE_FORMAT7_MAX;
00104 ++scan_mode)
00105 {
00106 uint32_t scan_width, scan_height;
00107
00108
00109 if (dc1394_format7_get_max_image_size(camera,
00110 (dc1394video_mode_t) scan_mode,
00111 &scan_width, &scan_height)
00112 != DC1394_SUCCESS)
00113 continue;
00114
00115 if (scan_width > sensor_width)
00116 sensor_width = scan_width;
00117
00118 if (scan_height > sensor_height)
00119 sensor_height = scan_height;
00120 }
00121
00122 if (DC1394_SUCCESS != dc1394_format7_get_max_image_size(camera, mode,
00123 &maxWidth_,
00124 &maxHeight_))
00125 {
00126 ROS_ERROR("Could not get max image size");
00127 return false;
00128 }
00129
00130 if (newconfig.binning_x == 0 || newconfig.binning_y == 0)
00131 {
00132 binning_x_ = sensor_width / maxWidth_;
00133 binning_y_ = sensor_height / maxHeight_;
00134 }
00135 else
00136 {
00137 binning_x_ = newconfig.binning_x;
00138 binning_y_ = newconfig.binning_y;
00139 }
00140
00141 maxWidth_ *= binning_x_;
00142 maxHeight_ *= binning_y_;
00143
00144 if ((roi_.x_offset | roi_.y_offset | roi_.width | roi_.height) == 0)
00145 {
00146 roi_.width = maxWidth_;
00147 roi_.height = maxHeight_;
00148 }
00149
00150 uint32_t unit_w, unit_h, unit_x, unit_y;
00151
00152 if (DC1394_SUCCESS != dc1394_format7_get_unit_size(camera, mode,
00153 &unit_w, &unit_h))
00154 {
00155 ROS_ERROR("Could not get ROI size units");
00156 return false;
00157 }
00158
00159 unit_w *= binning_x_;
00160 unit_h *= binning_y_;
00161
00162 if (DC1394_SUCCESS != dc1394_format7_get_unit_position(camera, mode,
00163 &unit_x, &unit_y))
00164 {
00165 ROS_ERROR("Could not get ROI position units");
00166 return false;
00167 }
00168
00169
00170 if (unit_x == 0) unit_x = 1;
00171 if (unit_y == 0) unit_y = 1;
00172
00173 unit_x *= binning_x_;
00174 unit_y *= binning_y_;
00175
00176 ROS_INFO_STREAM("Format7 unit size: ("
00177 << unit_w << "x" << unit_h
00178 << "), position: ("
00179 << unit_x << "x" << unit_y
00180 << ")");
00181 ROS_INFO_STREAM("Format7 region size: ("
00182 << roi_.width << "x" << roi_.height
00183 << "), offset: ("
00184 << roi_.x_offset << ", " << roi_.y_offset
00185 << ")");
00186
00187
00188
00189
00190
00191 dc1394_format7_set_image_position(camera, mode, 0, 0);
00192
00193 if ((roi_.width % unit_w) || (roi_.height % unit_h))
00194 {
00196 ROS_ERROR("Requested image size invalid; (w,h) must be"
00197 " a multiple of (%d, %d)", unit_w, unit_h);
00198 return false;
00199 }
00200
00201 uint32_t binned_width = roi_.width / binning_x_;
00202 uint32_t binned_height = roi_.height / binning_y_;
00203
00204 uint32_t binned_x_offset = roi_.x_offset / binning_x_;
00205 uint32_t binned_y_offset = roi_.y_offset / binning_y_;
00206
00207 if (DC1394_SUCCESS != dc1394_format7_set_image_size(camera, mode,
00208 binned_width,
00209 binned_height))
00210 {
00211 ROS_ERROR("Could not set size of ROI");
00212 return false;
00213 }
00214
00215 if ((roi_.x_offset % unit_x) || (roi_.y_offset % unit_y))
00216 {
00217 ROS_ERROR("Requested image position invalid; (x,y) must"
00218 " be a multiple of (%d, %d)", unit_x, unit_y);
00219 return false;
00220 }
00221
00222 if (DC1394_SUCCESS != dc1394_format7_set_image_position(camera, mode,
00223 binned_x_offset,
00224 binned_y_offset))
00225 {
00226 ROS_ERROR("Could not set position of ROI");
00227 return false;
00228 }
00229
00230
00231
00232 coding_ = Modes::getColorCoding(camera, mode,
00233 newconfig.format7_color_coding);
00234
00235 if (DC1394_SUCCESS != dc1394_format7_set_color_coding(camera, mode,
00236 coding_))
00237 {
00238 ROS_ERROR("Could not set color coding");
00239 return false;
00240 }
00241
00242 uint32_t rec_packet_size;
00243
00244 if (DC1394_SUCCESS
00245 != dc1394_format7_get_recommended_packet_size(camera, mode,
00246 &rec_packet_size))
00247 {
00248 ROS_ERROR("Could not get default packet size");
00249 return false;
00250 }
00251
00252 if (0 == packet_size)
00253 packet_size = rec_packet_size;
00254
00255 uint32_t unit_bytes, max_bytes;
00256
00257 if (DC1394_SUCCESS
00258 != dc1394_format7_get_packet_parameters(camera, mode,
00259 &unit_bytes, &max_bytes))
00260 {
00261 ROS_ERROR("Could not determine maximum and increment for packet size");
00262 return false;
00263 }
00264
00265 if (packet_size % unit_bytes
00266 || (max_bytes > 0 && packet_size > max_bytes))
00267 {
00268 ROS_ERROR("Invalid packet size: %d. Must be a "
00269 "multiple of %d, at most %d [%d]",
00270 packet_size, unit_bytes, max_bytes, rec_packet_size);
00271 return false;
00272 }
00273
00274 if (DC1394_SUCCESS != dc1394_format7_set_packet_size(camera, mode,
00275 packet_size))
00276 {
00277 ROS_ERROR("Could not set packet size");
00278 return false;
00279 }
00280
00281 if (coding_ == DC1394_COLOR_CODING_RAW8
00282 || coding_ == DC1394_COLOR_CODING_RAW16)
00283 {
00284 dc1394color_filter_t
00285 color_filter = (dc1394color_filter_t) DC1394_COLOR_FILTER_NUM;
00286 if (DC1394_SUCCESS != dc1394_format7_get_color_filter(camera, mode,
00287 &color_filter))
00288 {
00289 ROS_ERROR("Could not determine color pattern");
00290 return false;
00291 }
00292 if (BayerPattern_ == (dc1394color_filter_t) DC1394_COLOR_FILTER_NUM)
00293 {
00294 BayerPattern_ = color_filter;
00295 }
00296 else if ( BayerPattern_ != color_filter )
00297 {
00298 ROS_WARN_STREAM("Bayer Pattern was set to "
00299 << BayerPattern_ << "but get_color_filter returned "
00300 << color_filter << ". Using " << BayerPattern_);
00301 }
00302 }
00303
00304 active_ = true;
00305
00306 return true;
00307 }
00308
00310 void Format7::stop(void)
00311 {
00312 active_ = false;
00313 }
00314
00315 extern std::string bayer_string(dc1394color_filter_t pattern,
00316 unsigned int bits);
00317
00319 void Format7::unpackData(sensor_msgs::Image &image, uint8_t *capture_buffer)
00320 {
00321 int image_size;
00322 switch (coding_)
00323 {
00324 case DC1394_COLOR_CODING_MONO8:
00325 image.step = image.width;
00326 image_size = image.height * image.step;
00327 image.encoding = sensor_msgs::image_encodings::MONO8;
00328 image.is_bigendian = false;
00329 image.data.resize(image_size);
00330 memcpy(&image.data[0], capture_buffer, image_size);
00331 break;
00332 case DC1394_COLOR_CODING_YUV411:
00333 image.step = image.width * 3;
00334 image_size = image.height * image.step;
00335 image.encoding = sensor_msgs::image_encodings::RGB8;
00336 image.data.resize(image_size);
00337 yuv::uyyvyy2rgb(reinterpret_cast<unsigned char *> (capture_buffer),
00338 reinterpret_cast<unsigned char *> (&image.data[0]),
00339 image.width * image.height);
00340 break;
00341 case DC1394_COLOR_CODING_YUV422:
00342 image.step = image.width * 3;
00343 image_size = image.height * image.step;
00344 image.encoding = sensor_msgs::image_encodings::RGB8;
00345 image.data.resize(image_size);
00346 yuv::uyvy2rgb(reinterpret_cast<unsigned char *> (capture_buffer),
00347 reinterpret_cast<unsigned char *> (&image.data[0]),
00348 image.width * image.height);
00349 break;
00350 case DC1394_COLOR_CODING_YUV444:
00351 image.step=image.width * 3;
00352 image_size = image.height * image.step;
00353 image.encoding = sensor_msgs::image_encodings::RGB8;
00354 image.data.resize(image_size);
00355 yuv::uyv2rgb(reinterpret_cast<unsigned char *> (capture_buffer),
00356 reinterpret_cast<unsigned char *> (&image.data[0]),
00357 image.width * image.height);
00358 break;
00359 case DC1394_COLOR_CODING_RGB8:
00360 image.step=image.width*3;
00361 image_size = image.height*image.step;
00362 image.encoding = sensor_msgs::image_encodings::RGB8;
00363 image.data.resize(image_size);
00364 memcpy(&image.data[0], capture_buffer, image_size);
00365 break;
00366 case DC1394_COLOR_CODING_MONO16:
00367 image.step=image.width*2;
00368 image_size = image.height*image.step;
00369 image.encoding = sensor_msgs::image_encodings::MONO16;
00370 image.is_bigendian = true;
00371 image.data.resize(image_size);
00372 memcpy(&image.data[0], capture_buffer, image_size);
00373 break;
00374 case DC1394_COLOR_CODING_RGB16:
00375 image.step = image.width * 6;
00376 image_size = image.height * image.step;
00377 image.encoding = sensor_msgs::image_encodings::TYPE_16UC3;
00378 image.is_bigendian = true;
00379 image.data.resize(image_size);
00380 memcpy(&image.data[0], capture_buffer, image_size);
00381 break;
00382 case DC1394_COLOR_CODING_MONO16S:
00383 image.step = image.width * 2;
00384 image_size = image.height * image.step;
00385 image.encoding = sensor_msgs::image_encodings::TYPE_16SC1;
00386 image.is_bigendian = true;
00387 image.data.resize(image_size);
00388 memcpy(&image.data[0], capture_buffer, image_size);
00389 break;
00390 case DC1394_COLOR_CODING_RGB16S:
00391 image.step = image.width * 6;
00392 image_size = image.height * image.step;
00393 image.encoding = sensor_msgs::image_encodings::TYPE_16SC3;
00394 image.is_bigendian = true;
00395 image.data.resize(image_size);
00396 memcpy(&image.data[0], capture_buffer, image_size);
00397 break;
00398 case DC1394_COLOR_CODING_RAW8:
00399 image.step = image.width;
00400 image_size = image.height * image.step;
00401 image.encoding = bayer_string(BayerPattern_, 8);
00402 image.data.resize(image_size);
00403 memcpy(&image.data[0], capture_buffer, image_size);
00404 break;
00405 case DC1394_COLOR_CODING_RAW16:
00406 image.step = image.width * 2;
00407 image_size = image.height * image.step;
00408 image.encoding = bayer_string(BayerPattern_, 16);
00409 image.is_bigendian = true;
00410 image.data.resize(image_size);
00411 memcpy(&image.data[0], capture_buffer, image_size);
00412 break;
00413 default:
00414 ROS_ERROR_STREAM("Driver bug: unknown Format7 color coding:"
00415 << coding_);
00416 ROS_BREAK();
00417 }
00418 }
00419
00430 bool Format7::checkCameraInfo(const sensor_msgs::CameraInfo &cinfo)
00431 {
00432
00433 if (cinfo.width == maxWidth_ && cinfo.height == maxHeight_)
00434 {
00435 return true;
00436 }
00437
00438 else if (cinfo.width == roi_.width && cinfo.height == roi_.height)
00439 {
00440 return true;
00441 }
00442 else
00443 {
00444 ROS_WARN_STREAM_THROTTLE(30, "Calibrated image size ("
00445 << cinfo.width << "x" << cinfo.height
00446 << ") matches neither full Format7 size ("
00447 << maxWidth_ << "x" << maxHeight_ << ")"
00448 << ") nor ROI size ("
00449 << roi_.width << "x" << roi_.height << ")");
00450 return false;
00451 }
00452 }
00453
00464 void Format7::setOperationalParameters(sensor_msgs::CameraInfo &cinfo)
00465 {
00466
00467 cinfo.binning_x = binning_x_;
00468 cinfo.binning_y = binning_y_;
00469 cinfo.roi = roi_;
00470
00471
00472 cinfo.roi.do_rectify = false;
00473
00474 if (cinfo.K[0] == 0.0)
00475 return;
00476
00477 bool roiMatchesCalibration = (cinfo.width == roi_.width
00478 && cinfo.height == roi_.height);
00479
00480 if (cinfo.width == maxWidth_ && cinfo.height == maxHeight_)
00481 {
00482
00483 if (!roiMatchesCalibration)
00484 {
00485
00486 cinfo.roi.do_rectify = true;
00487 }
00488 }
00489 else
00490 {
00491
00492 if (!roiMatchesCalibration)
00493 {
00494
00495
00496 cinfo.roi.do_rectify = true;
00497 }
00498 }
00499 }
00500
00507 dc1394color_filter_t Format7::findBayerPattern(const char* bayer)
00508 {
00509
00510
00511 dc1394color_filter_t
00512 pattern = (dc1394color_filter_t) DC1394_COLOR_FILTER_NUM;
00513
00514 if (0 == strcmp(bayer, "bggr"))
00515 {
00516 pattern = DC1394_COLOR_FILTER_BGGR;
00517 }
00518 else if (0 == strcmp(bayer, "grbg"))
00519 {
00520 pattern = DC1394_COLOR_FILTER_GRBG;
00521 }
00522 else if (0 == strcmp(bayer, "rggb"))
00523 {
00524 pattern = DC1394_COLOR_FILTER_RGGB;
00525 }
00526 else if (0 == strcmp(bayer, "gbrg"))
00527 {
00528 pattern = DC1394_COLOR_FILTER_GBRG;
00529 }
00530 else if (0 != strcmp(bayer, ""))
00531 {
00532 ROS_ERROR("unknown bayer pattern [%s]", bayer);
00533 }
00534 return pattern;
00535 }
00536