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
00037 #include <cmath>
00038 #include "featuresstereo.h"
00039 #include "trigger.h"
00040
00049
00050
00052 namespace
00053 {
00054
00055
00056 static const char *feature_names_[DC1394_FEATURE_NUM] =
00057 {
00058 "brightness",
00059 "exposure",
00060 "sharpness",
00061 "whitebalance",
00062 "hue",
00063 "saturation",
00064 "gamma",
00065 "shutter",
00066 "gain",
00067 "iris",
00068 "focus",
00069 "temperature",
00070 "trigger",
00071 "trigger_delay",
00072 "white_shading",
00073 "frame_rate",
00074 "zoom",
00075 "pan",
00076 "tilt",
00077 "optical_filter",
00078 "capture_size",
00079 "capture_quality"
00080 };
00081
00087 inline const char *featureName(dc1394feature_t feature)
00088 {
00089 if (feature >= DC1394_FEATURE_MIN && feature <= DC1394_FEATURE_MAX)
00090 return feature_names_[feature - DC1394_FEATURE_MIN];
00091 else
00092 return "(unknown)";
00093 }
00094
00095
00096 static const char *mode_names_[DC1394_FEATURE_MODE_NUM] =
00097 {
00098 "Manual",
00099 "Auto",
00100 "OnePush",
00101 };
00102
00108 inline const char *modeName(dc1394feature_mode_t mode)
00109 {
00110 if (mode >= DC1394_FEATURE_MODE_MIN && mode <= DC1394_FEATURE_MODE_MAX)
00111 return mode_names_[mode - DC1394_FEATURE_MODE_MIN];
00112 else
00113 return "(unknown)";
00114 }
00115 }
00116
00118
00120
00125 Features::Features(dc1394camera_t *camera):
00126 camera_(camera)
00127 {
00128 trigger_.reset(new Trigger(camera));
00129 }
00130
00140 bool Features::initialize(Config *newconfig)
00141 {
00142 bool retval = true;
00143
00144 if (DC1394_SUCCESS != dc1394_feature_get_all(camera_, &feature_set_))
00145 {
00146 ROS_ERROR("could not get camera feature information");
00147 return false;
00148 }
00149
00150
00151 configure(DC1394_FEATURE_BRIGHTNESS,
00152 &newconfig->auto_brightness, &newconfig->brightness);
00153 configure(DC1394_FEATURE_EXPOSURE,
00154 &newconfig->auto_exposure, &newconfig->exposure);
00155 configure(DC1394_FEATURE_FOCUS,
00156 &newconfig->auto_focus, &newconfig->focus);
00157 configure(DC1394_FEATURE_GAIN,
00158 &newconfig->auto_gain, &newconfig->gain);
00159 configure(DC1394_FEATURE_GAMMA,
00160 &newconfig->auto_gamma, &newconfig->gamma);
00161 configure(DC1394_FEATURE_HUE,
00162 &newconfig->auto_hue, &newconfig->hue);
00163 configure(DC1394_FEATURE_IRIS,
00164 &newconfig->auto_iris, &newconfig->iris);
00165 configure(DC1394_FEATURE_SATURATION,
00166 &newconfig->auto_saturation, &newconfig->saturation);
00167 configure(DC1394_FEATURE_SHARPNESS,
00168 &newconfig->auto_sharpness, &newconfig->sharpness);
00169 configure(DC1394_FEATURE_SHUTTER,
00170 &newconfig->auto_shutter, &newconfig->shutter);
00171 configure(DC1394_FEATURE_TRIGGER,
00172 &newconfig->auto_trigger, &newconfig->trigger);
00173 configure(DC1394_FEATURE_PAN,
00174 &newconfig->auto_pan, &newconfig->pan);
00175 configure(DC1394_FEATURE_FRAME_RATE,
00176 &newconfig->auto_frame_rate_feature, &newconfig->frame_rate_feature);
00177 configure(DC1394_FEATURE_WHITE_BALANCE, &newconfig->auto_white_balance,
00178 &newconfig->white_balance_BU, &newconfig->white_balance_RV);
00179 configure(DC1394_FEATURE_ZOOM,
00180 &newconfig->auto_zoom, &newconfig->zoom);
00181
00182
00183 if (hasTrigger())
00184 retval = trigger_->initialize(newconfig);
00185
00186
00187 oldconfig_ = *newconfig;
00188 return retval;
00189 }
00190
00203 void Features::reconfigure(Config *newconfig)
00204 {
00205 updateIfChanged(DC1394_FEATURE_BRIGHTNESS,
00206 oldconfig_.auto_brightness, &newconfig->auto_brightness,
00207 oldconfig_.brightness, &newconfig->brightness);
00208 updateIfChanged(DC1394_FEATURE_EXPOSURE,
00209 oldconfig_.auto_exposure, &newconfig->auto_exposure,
00210 oldconfig_.exposure, &newconfig->exposure);
00211 updateIfChanged(DC1394_FEATURE_FOCUS,
00212 oldconfig_.auto_focus, &newconfig->auto_focus,
00213 oldconfig_.focus, &newconfig->focus);
00214 updateIfChanged(DC1394_FEATURE_GAIN,
00215 oldconfig_.auto_gain, &newconfig->auto_gain,
00216 oldconfig_.gain, &newconfig->gain);
00217 updateIfChanged(DC1394_FEATURE_GAMMA,
00218 oldconfig_.auto_gamma, &newconfig->auto_gamma,
00219 oldconfig_.gamma, &newconfig->gamma);
00220 updateIfChanged(DC1394_FEATURE_HUE,
00221 oldconfig_.auto_hue, &newconfig->auto_hue,
00222 oldconfig_.hue, &newconfig->hue);
00223 updateIfChanged(DC1394_FEATURE_IRIS,
00224 oldconfig_.auto_iris, &newconfig->auto_iris,
00225 oldconfig_.iris, &newconfig->iris);
00226 updateIfChanged(DC1394_FEATURE_SATURATION,
00227 oldconfig_.auto_saturation, &newconfig->auto_saturation,
00228 oldconfig_.saturation, &newconfig->saturation);
00229 updateIfChanged(DC1394_FEATURE_SHARPNESS,
00230 oldconfig_.auto_sharpness, &newconfig->auto_sharpness,
00231 oldconfig_.sharpness, &newconfig->sharpness);
00232 updateIfChanged(DC1394_FEATURE_SHUTTER,
00233 oldconfig_.auto_shutter, &newconfig->auto_shutter,
00234 oldconfig_.shutter, &newconfig->shutter);
00235 updateIfChanged(DC1394_FEATURE_PAN,
00236 oldconfig_.auto_pan, &newconfig->auto_pan,
00237 oldconfig_.pan, &newconfig->pan);
00238 updateIfChanged(DC1394_FEATURE_FRAME_RATE,
00239 oldconfig_.auto_frame_rate_feature, &newconfig->auto_frame_rate_feature,
00240 oldconfig_.frame_rate_feature, &newconfig->frame_rate_feature);
00241 updateIfChanged(DC1394_FEATURE_TRIGGER,
00242 oldconfig_.auto_trigger, &newconfig->auto_trigger,
00243 oldconfig_.trigger, &newconfig->trigger);
00244
00245
00246 updateIfChanged(DC1394_FEATURE_WHITE_BALANCE,
00247 oldconfig_.auto_white_balance,
00248 &newconfig->auto_white_balance,
00249 oldconfig_.white_balance_BU, &newconfig->white_balance_BU,
00250 oldconfig_.white_balance_RV, &newconfig->white_balance_RV);
00251 updateIfChanged(DC1394_FEATURE_ZOOM,
00252 oldconfig_.auto_zoom, &newconfig->auto_zoom,
00253 oldconfig_.zoom, &newconfig->zoom);
00254
00255
00256 if (hasTrigger())
00257 trigger_->reconfigure(newconfig);
00258
00259
00260 oldconfig_ = *newconfig;
00261 }
00262
00264
00266
00285 void Features::configure(dc1394feature_t feature, int *control,
00286 double *value, double *value2)
00287 {
00288
00289 dc1394feature_info_t *finfo =
00290 &feature_set_.feature[feature - DC1394_FEATURE_MIN];
00291
00292 if (!finfo->available)
00293 {
00294 *control = camera1394stereo::Camera1394Stereo_None;
00295 return;
00296 }
00297
00298 switch (*control)
00299 {
00300 case camera1394stereo::Camera1394Stereo_Off:
00301 setOff(finfo);
00302 break;
00303
00304 case camera1394stereo::Camera1394Stereo_Query:
00305 getValues(finfo, value, value2);
00306 break;
00307
00308 case camera1394stereo::Camera1394Stereo_Auto:
00309 if (!setMode(finfo, DC1394_FEATURE_MODE_AUTO))
00310 {
00311 setOff(finfo);
00312 }
00313 break;
00314
00315 case camera1394stereo::Camera1394Stereo_Manual:
00316 if (!setMode(finfo, DC1394_FEATURE_MODE_MANUAL))
00317 {
00318 setOff(finfo);
00319 break;
00320 }
00321
00322
00323 if (finfo->absolute_capable && finfo->abs_control)
00324 {
00325
00326 float fmin, fmax;
00327 if (DC1394_SUCCESS ==
00328 dc1394_feature_get_absolute_boundaries(camera_, feature,
00329 &fmin, &fmax))
00330 {
00331
00332 if (*value < fmin)
00333 *value = (double) fmin;
00334 else if (*value > fmax)
00335 *value = (double) fmax;
00336 }
00337 else
00338 {
00339 ROS_WARN_STREAM("failed to get feature "
00340 << featureName(feature) << " boundaries ");
00341 }
00342
00343
00344 float fval = *value;
00345 if (DC1394_SUCCESS !=
00346 dc1394_feature_set_absolute_value(camera_, feature, fval))
00347 {
00348 ROS_WARN_STREAM("failed to set feature "
00349 << featureName(feature) << " to " << fval);
00350 }
00351 }
00352 else
00353 {
00354
00355 *value = rint(*value);
00356
00357
00358 if (*value < finfo->min)
00359 *value = (double) finfo->min;
00360 else if (*value > finfo->max)
00361 *value = (double) finfo->max;
00362
00363 dc1394error_t rc;
00364 uint32_t ival = (uint32_t) *value;
00365
00366
00367 if (feature == DC1394_FEATURE_WHITE_BALANCE)
00368 {
00369 *value2 = rint(*value2);
00370
00371
00372 if (*value2 < finfo->min)
00373 *value2 = (double) finfo->min;
00374 else if (*value2 > finfo->max)
00375 *value2 = (double) finfo->max;
00376
00377 uint32_t ival2 = (uint32_t) *value2;
00378 rc = dc1394_feature_whitebalance_set_value(camera_, ival, ival2);
00379 }
00380 else
00381 {
00382
00383 rc = dc1394_feature_set_value(camera_, feature, ival);
00384 }
00385 if (rc != DC1394_SUCCESS)
00386 {
00387 ROS_WARN_STREAM("failed to set feature "
00388 << featureName(feature) << " to " << ival);
00389 }
00390 }
00391 break;
00392
00393 case camera1394stereo::Camera1394Stereo_OnePush:
00394
00395 setMode(finfo, DC1394_FEATURE_MODE_ONE_PUSH_AUTO);
00396
00397
00398 setOff(finfo);
00399 break;
00400
00401 case camera1394stereo::Camera1394Stereo_None:
00402
00403 ROS_INFO_STREAM("feature " << featureName(feature)
00404 << " exists, cannot set to None");
00405 break;
00406
00407 default:
00408 ROS_WARN_STREAM("unknown state (" << *control
00409 <<") for feature " << featureName(feature));
00410 }
00411
00412
00413 *control = getState(finfo);
00414 ROS_DEBUG_STREAM("feature " << featureName(feature)
00415 << " now in state " << *control);
00416 }
00417
00425 Features::state_t Features::getState(dc1394feature_info_t *finfo)
00426 {
00427 dc1394feature_t feature = finfo->id;
00428 dc1394error_t rc;
00429
00430 if (!finfo->available)
00431 {
00432
00433 return camera1394stereo::Camera1394Stereo_None;
00434 }
00435
00436 if (finfo->on_off_capable)
00437 {
00438
00439 dc1394switch_t pwr;
00440 rc = dc1394_feature_get_power(camera_, feature, &pwr);
00441 if (rc != DC1394_SUCCESS)
00442 {
00443 ROS_WARN_STREAM("failed to get feature " << featureName(feature)
00444 << " Power setting ");
00445 }
00446 else if (pwr == DC1394_OFF)
00447 {
00448
00449 return camera1394stereo::Camera1394Stereo_Off;
00450 }
00451 }
00452
00453
00454 dc1394feature_mode_t mode;
00455 rc = dc1394_feature_get_mode(camera_, feature, &mode);
00456 if (rc != DC1394_SUCCESS)
00457 {
00458 ROS_WARN_STREAM("failed to get current mode of feature "
00459 << featureName(feature));
00460
00461 return camera1394stereo::Camera1394Stereo_Off;
00462 }
00463
00464 switch (mode)
00465 {
00466 case DC1394_FEATURE_MODE_MANUAL:
00467 return camera1394stereo::Camera1394Stereo_Manual;
00468 case DC1394_FEATURE_MODE_AUTO:
00469 return camera1394stereo::Camera1394Stereo_Auto;
00470 case DC1394_FEATURE_MODE_ONE_PUSH_AUTO:
00471 return camera1394stereo::Camera1394Stereo_OnePush;
00472 default:
00473 return camera1394stereo::Camera1394Stereo_Off;
00474 }
00475 }
00476
00486 void Features::getValues(dc1394feature_info_t *finfo,
00487 double *value, double *value2)
00488 {
00489 dc1394feature_t feature = finfo->id;
00490 dc1394error_t rc;
00491
00492 if (!finfo->readout_capable)
00493 {
00494 ROS_INFO_STREAM("feature " << featureName(feature)
00495 << " value not available from device");
00496 return;
00497 }
00498
00499 if (feature == DC1394_FEATURE_WHITE_BALANCE)
00500 {
00501
00502 if (finfo->absolute_capable && finfo->abs_control)
00503 {
00504
00505
00506 rc = DC1394_FUNCTION_NOT_SUPPORTED;
00507 }
00508 else
00509 {
00510
00511 uint32_t bu_val;
00512 uint32_t rv_val;
00513 rc = dc1394_feature_whitebalance_get_value(camera_, &bu_val, &rv_val);
00514 if (DC1394_SUCCESS == rc)
00515 {
00516
00517 *value = bu_val;
00518 *value2 = rv_val;
00519 }
00520 }
00521 if (DC1394_SUCCESS == rc)
00522 {
00523 ROS_DEBUG_STREAM("feature " << featureName(feature)
00524 << " Blue/U: " << *value
00525 << " Red/V: " << *value2);
00526 }
00527 else
00528 {
00529 ROS_WARN_STREAM("failed to get values for feature "
00530 << featureName(feature));
00531 }
00532 }
00533 else
00534 {
00535
00536 if (finfo->absolute_capable && finfo->abs_control)
00537 {
00538
00539 float fval;
00540 rc = dc1394_feature_get_absolute_value(camera_, feature, &fval);
00541 if (DC1394_SUCCESS == rc)
00542 {
00543 *value = fval;
00544 }
00545 }
00546 else
00547 {
00548 uint32_t ival;
00549 rc = dc1394_feature_get_value(camera_, feature, &ival);
00550 if (DC1394_SUCCESS == rc)
00551 {
00552 *value = ival;
00553 }
00554 }
00555 if (DC1394_SUCCESS == rc)
00556 {
00557 ROS_DEBUG_STREAM("feature " << featureName(feature)
00558 << " has value " << *value);
00559 }
00560 else
00561 {
00562 ROS_WARN_STREAM("failed to get value of feature "
00563 << featureName(feature));
00564 }
00565 }
00566 }
00567
00576 bool Features::setMode(dc1394feature_info_t *finfo, dc1394feature_mode_t mode)
00577 {
00578 dc1394feature_t feature = finfo->id;
00579 if (hasMode(finfo, mode))
00580 {
00581 ROS_DEBUG_STREAM("setting feature " << featureName(feature)
00582 << " mode to " << modeName(mode));
00583 if (DC1394_SUCCESS !=
00584 dc1394_feature_set_mode(camera_, feature, mode))
00585 {
00586 ROS_WARN_STREAM("failed to set feature " << featureName(feature)
00587 << " mode to " << modeName(mode));
00588 return false;
00589 }
00590 }
00591 else
00592 {
00593
00594 ROS_DEBUG_STREAM("no " << modeName(mode)
00595 << " mode for feature " << featureName(feature));
00596 return false;
00597 }
00598 return true;
00599 }
00600
00607 void Features::setOff(dc1394feature_info_t *finfo)
00608 {
00609 dc1394feature_t feature = finfo->id;
00610 if (finfo->on_off_capable)
00611 {
00612 ROS_DEBUG_STREAM("setting feature " << featureName(feature) << " Off");
00613 if (DC1394_SUCCESS !=
00614 dc1394_feature_set_power(camera_, feature, DC1394_OFF))
00615 {
00616 ROS_WARN_STREAM("failed to set feature " << featureName(feature)
00617 << " Off ");
00618 }
00619 }
00620 else
00621 {
00622
00623
00624 ROS_DEBUG_STREAM("no Off mode for feature " << featureName(feature));
00625 }
00626 }
00627
00642 void Features::updateIfChanged(dc1394feature_t feature,
00643 int old_control, int *control,
00644 double old_value, double *value)
00645 {
00646 if ((old_control != *control) || (old_value != *value))
00647 {
00648 configure(feature, control, value);
00649 }
00650 }
00651
00669 void Features::updateIfChanged(dc1394feature_t feature,
00670 int old_control, int *control,
00671 double old_value, double *value,
00672 double old_value2, double *value2)
00673 {
00674 if ((old_control != *control)
00675 || (old_value != *value)
00676 || (old_value2 != *value2))
00677 {
00678 configure(feature, control, value, value2);
00679 }
00680 }