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 <sensor_msgs/image_encodings.h>
00046 #include "format7.h"
00047 #include "modes.h"
00048
00049
00058 bool Format7::start(dc1394camera_t *camera,
00059 dc1394video_mode_t mode,
00060 Config &newconfig)
00061 {
00062 active_ = false;
00063
00064
00065 binning_x_ = newconfig.binning_x;
00066 binning_y_ = newconfig.binning_y;
00067 roi_.x_offset = newconfig.x_offset;
00068 roi_.y_offset = newconfig.y_offset;
00069 roi_.width = newconfig.roi_width;
00070 roi_.height = newconfig.roi_height;
00071
00072 uint32_t packet_size = newconfig.format7_packet_size;
00073
00074
00075
00076 if (newconfig.bayer_method != "")
00077 {
00078 ROS_WARN_STREAM("Bayer method [" << newconfig.bayer_method
00079 << "] not supported for Format7 modes."
00080 << " Using image_proc instead.");
00081 newconfig.bayer_method = "";
00082 }
00083
00084
00085
00086 uint32_t sensor_width = 0, sensor_height = 0;
00087
00088 for (int scan_mode = DC1394_VIDEO_MODE_FORMAT7_MIN;
00089 scan_mode <= DC1394_VIDEO_MODE_FORMAT7_MAX;
00090 ++scan_mode)
00091 {
00092 uint32_t scan_width, scan_height;
00093
00094
00095 if (dc1394_format7_get_max_image_size(camera,
00096 (dc1394video_mode_t) scan_mode,
00097 &scan_width, &scan_height)
00098 != DC1394_SUCCESS)
00099 continue;
00100
00101 if (scan_width > sensor_width)
00102 sensor_width = scan_width;
00103
00104 if (scan_height > sensor_height)
00105 sensor_height = scan_height;
00106 }
00107
00108 if (DC1394_SUCCESS != dc1394_format7_get_max_image_size(camera, mode,
00109 &maxWidth_,
00110 &maxHeight_))
00111 {
00112 ROS_ERROR("Could not get max image size");
00113 return false;
00114 }
00115
00116 if (newconfig.binning_x == 0 || newconfig.binning_y == 0)
00117 {
00118 binning_x_ = sensor_width / maxWidth_;
00119 binning_y_ = sensor_height / maxHeight_;
00120 }
00121 else
00122 {
00123 binning_x_ = newconfig.binning_x;
00124 binning_y_ = newconfig.binning_y;
00125 }
00126
00127 maxWidth_ *= binning_x_;
00128 maxHeight_ *= binning_y_;
00129
00130 if ((roi_.x_offset | roi_.y_offset | roi_.width | roi_.height) == 0)
00131 {
00132 roi_.width = maxWidth_;
00133 roi_.height = maxHeight_;
00134 }
00135
00136 uint32_t unit_w, unit_h, unit_x, unit_y;
00137
00138 if (DC1394_SUCCESS != dc1394_format7_get_unit_size(camera, mode,
00139 &unit_w, &unit_h))
00140 {
00141 ROS_ERROR("Could not get ROI size units");
00142 return false;
00143 }
00144
00145 unit_w *= binning_x_;
00146 unit_h *= binning_y_;
00147
00148 if (DC1394_SUCCESS != dc1394_format7_get_unit_position(camera, mode,
00149 &unit_x, &unit_y))
00150 {
00151 ROS_ERROR("Could not get ROI position units");
00152 return false;
00153 }
00154
00155
00156 if (unit_x == 0) unit_x = 1;
00157 if (unit_y == 0) unit_y = 1;
00158
00159 unit_x *= binning_x_;
00160 unit_y *= binning_y_;
00161
00162 ROS_INFO_STREAM("Format7 unit size: ("
00163 << unit_w << "x" << unit_h
00164 << "), position: ("
00165 << unit_x << "x" << unit_y
00166 << ")");
00167 ROS_INFO_STREAM("Format7 region size: ("
00168 << roi_.width << "x" << roi_.height
00169 << "), offset: ("
00170 << roi_.x_offset << ", " << roi_.y_offset
00171 << ")");
00172
00173
00174
00175
00176
00177 dc1394_format7_set_image_position(camera, mode, 0, 0);
00178
00179 if ((roi_.width % unit_w) || (roi_.height % unit_h))
00180 {
00182 ROS_ERROR("Requested image size invalid; (w,h) must be"
00183 " a multiple of (%d, %d)", unit_w, unit_h);
00184 return false;
00185 }
00186
00187 uint32_t binned_width = roi_.width / binning_x_;
00188 uint32_t binned_height = roi_.height / binning_y_;
00189
00190 uint32_t binned_x_offset = roi_.x_offset / binning_x_;
00191 uint32_t binned_y_offset = roi_.y_offset / binning_y_;
00192
00193 if (DC1394_SUCCESS != dc1394_format7_set_image_size(camera, mode,
00194 binned_width,
00195 binned_height))
00196 {
00197 ROS_ERROR("Could not set size of ROI");
00198 return false;
00199 }
00200
00201 if ((roi_.x_offset % unit_x) || (roi_.y_offset % unit_y))
00202 {
00203 ROS_ERROR("Requested image position invalid; (x,y) must"
00204 " be a multiple of (%d, %d)", unit_x, unit_y);
00205 return false;
00206 }
00207
00208 if (DC1394_SUCCESS != dc1394_format7_set_image_position(camera, mode,
00209 binned_x_offset,
00210 binned_y_offset))
00211 {
00212 ROS_ERROR("Could not set position of ROI");
00213 return false;
00214 }
00215
00216
00217
00218 coding_ = Modes::getColorCoding(camera, mode,
00219 newconfig.format7_color_coding);
00220
00221 if (DC1394_SUCCESS != dc1394_format7_set_color_coding(camera, mode,
00222 coding_))
00223 {
00224 ROS_ERROR("Could not set color coding");
00225 return false;
00226 }
00227
00228 uint32_t rec_packet_size;
00229
00230 if (DC1394_SUCCESS
00231 != dc1394_format7_get_recommended_packet_size(camera, mode,
00232 &rec_packet_size))
00233 {
00234 ROS_ERROR("Could not get default packet size");
00235 return false;
00236 }
00237
00238 if (0 == packet_size)
00239 packet_size = rec_packet_size;
00240
00241 uint32_t unit_bytes, max_bytes;
00242
00243 if (DC1394_SUCCESS
00244 != dc1394_format7_get_packet_parameters(camera, mode,
00245 &unit_bytes, &max_bytes))
00246 {
00247 ROS_ERROR("Could not determine maximum and increment for packet size");
00248 return false;
00249 }
00250
00251 if (packet_size % unit_bytes
00252 || (max_bytes > 0 && packet_size > max_bytes))
00253 {
00254 ROS_ERROR("Invalid packet size: %d. Must be a "
00255 "multiple of %d, at most %d [%d]",
00256 packet_size, unit_bytes, max_bytes, rec_packet_size);
00257 return false;
00258 }
00259
00260 if (DC1394_SUCCESS != dc1394_format7_set_packet_size(camera, mode,
00261 packet_size))
00262 {
00263 ROS_ERROR("Could not set packet size");
00264 return false;
00265 }
00266
00267 if (coding_ == DC1394_COLOR_CODING_RAW8
00268 || coding_ == DC1394_COLOR_CODING_RAW16)
00269 {
00270 if (DC1394_SUCCESS != dc1394_format7_get_color_filter(camera, mode,
00271 &BayerPattern_))
00272 {
00273 ROS_ERROR("Could not determine color pattern");
00274 return false;
00275 }
00276 }
00277
00278 active_ = true;
00279
00280 return true;
00281 }
00282
00284 void Format7::stop(void)
00285 {
00286 active_ = false;
00287 }
00288
00289 extern std::string bayer_string(dc1394color_filter_t pattern, unsigned int bits);
00290
00292 void Format7::unpackData(sensor_msgs::Image &image, uint8_t *capture_buffer)
00293 {
00294 int image_size;
00295 switch (coding_)
00296 {
00297 case DC1394_COLOR_CODING_MONO8:
00298 image.step = image.width;
00299 image_size = image.height * image.step;
00300 image.encoding = sensor_msgs::image_encodings::MONO8;
00301 image.is_bigendian = false;
00302 image.data.resize(image_size);
00303 memcpy(&image.data[0], capture_buffer, image_size);
00304 break;
00305 case DC1394_COLOR_CODING_YUV411:
00306 image.step = image.width * 3;
00307 image_size = image.height * image.step;
00308 image.encoding = sensor_msgs::image_encodings::RGB8;
00309 image.data.resize(image_size);
00310 yuv::uyyvyy2rgb(reinterpret_cast<unsigned char *> (capture_buffer),
00311 reinterpret_cast<unsigned char *> (&image.data[0]),
00312 image.width * image.height);
00313 break;
00314 case DC1394_COLOR_CODING_YUV422:
00315 image.step = image.width * 3;
00316 image_size = image.height * image.step;
00317 image.encoding = sensor_msgs::image_encodings::RGB8;
00318 image.data.resize(image_size);
00319 yuv::uyvy2rgb(reinterpret_cast<unsigned char *> (capture_buffer),
00320 reinterpret_cast<unsigned char *> (&image.data[0]),
00321 image.width * image.height);
00322 break;
00323 case DC1394_COLOR_CODING_YUV444:
00324 image.step=image.width * 3;
00325 image_size = image.height * image.step;
00326 image.encoding = sensor_msgs::image_encodings::RGB8;
00327 image.data.resize(image_size);
00328 yuv::uyv2rgb(reinterpret_cast<unsigned char *> (capture_buffer),
00329 reinterpret_cast<unsigned char *> (&image.data[0]),
00330 image.width * image.height);
00331 break;
00332 case DC1394_COLOR_CODING_RGB8:
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 memcpy(&image.data[0], capture_buffer, image_size);
00338 break;
00339 case DC1394_COLOR_CODING_MONO16:
00340 image.step=image.width*2;
00341 image_size = image.height*image.step;
00342 image.encoding = sensor_msgs::image_encodings::MONO16;
00343 image.is_bigendian = true;
00344 image.data.resize(image_size);
00345 memcpy(&image.data[0], capture_buffer, image_size);
00346 break;
00347 case DC1394_COLOR_CODING_RGB16:
00348 image.step = image.width * 6;
00349 image_size = image.height * image.step;
00350 image.encoding = sensor_msgs::image_encodings::TYPE_16UC3;
00351 image.is_bigendian = true;
00352 image.data.resize(image_size);
00353 memcpy(&image.data[0], capture_buffer, image_size);
00354 break;
00355 case DC1394_COLOR_CODING_MONO16S:
00356 image.step = image.width * 2;
00357 image_size = image.height * image.step;
00358 image.encoding = sensor_msgs::image_encodings::TYPE_16SC1;
00359 image.is_bigendian = true;
00360 image.data.resize(image_size);
00361 memcpy(&image.data[0], capture_buffer, image_size);
00362 break;
00363 case DC1394_COLOR_CODING_RGB16S:
00364 image.step = image.width * 6;
00365 image_size = image.height * image.step;
00366 image.encoding = sensor_msgs::image_encodings::TYPE_16SC3;
00367 image.is_bigendian = true;
00368 image.data.resize(image_size);
00369 memcpy(&image.data[0], capture_buffer, image_size);
00370 break;
00371 case DC1394_COLOR_CODING_RAW8:
00372 image.step = image.width;
00373 image_size = image.height * image.step;
00374 image.encoding = bayer_string(BayerPattern_, 8);
00375 image.data.resize(image_size);
00376 memcpy(&image.data[0], capture_buffer, image_size);
00377 break;
00378 case DC1394_COLOR_CODING_RAW16:
00379 image.step = image.width * 2;
00380 image_size = image.height * image.step;
00381 image.encoding = bayer_string(BayerPattern_, 16);
00382 image.is_bigendian = true;
00383 image.data.resize(image_size);
00384 memcpy(&image.data[0], capture_buffer, image_size);
00385 break;
00386 default:
00387 ROS_ERROR_STREAM("Driver bug: unknown Format7 color coding:"
00388 << coding_);
00389 ROS_BREAK();
00390 }
00391 }
00392
00403 bool Format7::checkCameraInfo(const sensor_msgs::CameraInfo &cinfo)
00404 {
00405
00406 if (cinfo.width == maxWidth_ && cinfo.height == maxHeight_)
00407 {
00408 return true;
00409 }
00410
00411 else if (cinfo.width == roi_.width && cinfo.height == roi_.height)
00412 {
00413 return true;
00414 }
00415 else
00416 {
00417 ROS_WARN_STREAM_THROTTLE(30, "Calibrated image size ("
00418 << cinfo.width << "x" << cinfo.height
00419 << ") matches neither full Format7 size ("
00420 << maxWidth_ << "x" << maxHeight_ << ")"
00421 << ") nor ROI size ("
00422 << roi_.width << "x" << roi_.height << ")");
00423 return false;
00424 }
00425 }
00426
00437 void Format7::setOperationalParameters(sensor_msgs::CameraInfo &cinfo)
00438 {
00439
00440 cinfo.binning_x = binning_x_;
00441 cinfo.binning_y = binning_y_;
00442 cinfo.roi = roi_;
00443
00444
00445 cinfo.roi.do_rectify = false;
00446
00447 if (cinfo.K[0] == 0.0)
00448 return;
00449
00450 bool roiMatchesCalibration = (cinfo.width == roi_.width
00451 && cinfo.height == roi_.height);
00452
00453 if (cinfo.width == maxWidth_ && cinfo.height == maxHeight_)
00454 {
00455
00456 if (!roiMatchesCalibration)
00457 {
00458
00459 cinfo.roi.do_rectify = true;
00460 }
00461 }
00462 else
00463 {
00464
00465 if (!roiMatchesCalibration)
00466 {
00467
00468
00469 cinfo.roi.do_rectify = true;
00470 }
00471 }
00472 }