fix(sample): ctrl auto max/min exp time after open 2.

This commit is contained in:
TinyO 2019-10-23 11:12:18 +08:00
parent 65a2a6c181
commit 7c4052e4c0

View File

@ -39,12 +39,23 @@ int main(int argc, char *argv[]) {
// auto-exposure: 0 // auto-exposure: 0
api->SetOptionValue(Option::EXPOSURE_MODE, 0); api->SetOptionValue(Option::EXPOSURE_MODE, 0);
// max_gain: range [0,48], default 48
api->SetOptionValue(Option::MAX_GAIN, 48);
// max_exposure_time: range [0,240], default 240 // max_exposure_time: range [0,240], default 240
api->SetOptionValue(Option::MAX_EXPOSURE_TIME, 240); api->SetOptionValue(Option::MAX_EXPOSURE_TIME, 240);
// desired_brightness: range [0,255], default 192
api->SetOptionValue(Option::DESIRED_BRIGHTNESS, 192);
frame_rate = api->GetOptionValue(Option::FRAME_RATE);
LOG(INFO) << "Enable auto-exposure"; LOG(INFO) << "Enable auto-exposure";
LOG(INFO) << "Set EXPOSURE_MODE to "
<< api->GetOptionValue(Option::EXPOSURE_MODE);
LOG(INFO) << "Set MAX_GAIN to " << api->GetOptionValue(Option::MAX_GAIN);
LOG(INFO) << "Set MAX_EXPOSURE_TIME to " LOG(INFO) << "Set MAX_EXPOSURE_TIME to "
<< api->GetOptionValue(Option::MAX_EXPOSURE_TIME); << api->GetOptionValue(Option::MAX_EXPOSURE_TIME);
LOG(INFO) << "Set DESIRED_BRIGHTNESS to "
<< api->GetOptionValue(Option::DESIRED_BRIGHTNESS);
} }
// Set auto exposure options fo S2000/S2100/S210A/S200B // Set auto exposure options fo S2000/S2100/S210A/S200B
@ -52,14 +63,24 @@ int main(int argc, char *argv[]) {
model == Model::STANDARD200B) { model == Model::STANDARD200B) {
// auto-exposure: 0 // auto-exposure: 0
api->SetOptionValue(Option::EXPOSURE_MODE, 0); api->SetOptionValue(Option::EXPOSURE_MODE, 0);
// max_gain: range [0,255], default 8
api->SetOptionValue(Option::MAX_GAIN, 8);
// max_exposure_time: range [0,1000], default 333 // max_exposure_time: range [0,1000], default 333
api->SetOptionValue(Option::MAX_EXPOSURE_TIME, 333); api->SetOptionValue(Option::MAX_EXPOSURE_TIME, 333);
// desired_brightness: range [1,255], default 122
api->SetOptionValue(Option::DESIRED_BRIGHTNESS, 122);
// min_exposure_time: range [0,1000], default 0 // min_exposure_time: range [0,1000], default 0
api->SetOptionValue(Option::MIN_EXPOSURE_TIME, 0); api->SetOptionValue(Option::MIN_EXPOSURE_TIME, 0);
LOG(INFO) << "Enable auto-exposure"; LOG(INFO) << "Enable auto-exposure";
LOG(INFO) << "Set EXPOSURE_MODE to "
<< api->GetOptionValue(Option::EXPOSURE_MODE);
LOG(INFO) << "Set MAX_GAIN to " << api->GetOptionValue(Option::MAX_GAIN);
LOG(INFO) << "Set MAX_EXPOSURE_TIME to " LOG(INFO) << "Set MAX_EXPOSURE_TIME to "
<< api->GetOptionValue(Option::MAX_EXPOSURE_TIME); << api->GetOptionValue(Option::MAX_EXPOSURE_TIME);
LOG(INFO) << "Set DESIRED_BRIGHTNESS to "
<< api->GetOptionValue(Option::DESIRED_BRIGHTNESS);
LOG(INFO) << "Set MIN_EXPOSURE_TIME to " LOG(INFO) << "Set MIN_EXPOSURE_TIME to "
<< api->GetOptionValue(Option::MIN_EXPOSURE_TIME); << api->GetOptionValue(Option::MIN_EXPOSURE_TIME);
} }