25 #include <boost/algorithm/string.hpp> 31 #include <linux/videodev2.h> 37 #define TO_FIXED(X) (((Sint32)(X))<<(FIXED_BITS)) 38 #define FROM_FIXED(X) (((Sint32)(X))>>(FIXED_BITS)) 41 #define INCPANTILT 64 // 1° 44 #include <boost/interprocess/sync/scoped_lock.hpp> 45 typedef boost::interprocess::scoped_lock<boost::interprocess::interprocess_mutex>
Lock;
53 if(in ==
' ')
return '_';
54 if(!isalnum(in))
return '_';
82 if(!videoDevice.empty()) {
88 boost::this_thread::sleep(boost::posix_time::milliseconds(100));
90 printf(
"Error grabbing first image\n");
97 printf(
"Error: image format not supported changed to: %ipix x %ipix @ %3.1fHz\n",
width_, height_, fps_);
108 boost::this_thread::sleep(boost::posix_time::milliseconds(10));
111 printf(
"Error grabbing\n");
115 printf(
"videoIn->signalquit\n");
119 gettimeofday(&now, NULL);
131 if(entry->valid ==
false) {
132 entry->error_msg <<
"v4lgetInfo not valid\n";
135 if((v4l2_ioctl(
pVideoIn_->
fd, VIDIOC_QUERYCTRL, entry->queryctrl)) < 0) {
136 entry->valid =
false;
137 entry->error_msg <<
"v4l2_ioctl querycontrol error\n";
139 }
else if(entry->queryctrl->flags & V4L2_CTRL_FLAG_DISABLED) {
140 entry->valid =
false;
141 entry->error_msg <<
"control disabled\n";
143 }
else if(entry->hasValidType() ==
false) {
144 entry->valid =
false;
145 entry->error_msg <<
"unsupported type\n";
148 entry->varName = std::string((
const char *) entry->queryctrl->name);
149 boost::algorithm::to_lower(entry->varName);
151 std::transform(entry->varName.begin(), entry->varName.end(), entry->varName.begin(),
V4RCam::removeNonAlNum);
152 boost::algorithm::trim_left_if(entry->varName, boost::algorithm::is_any_of(
"_"));
153 boost::algorithm::trim_right_if(entry->varName, boost::algorithm::is_any_of(
"_"));
154 boost::algorithm::replace_all(entry->varName,
"___",
"_");
155 boost::algorithm::replace_all(entry->varName,
"__",
"_");
164 if(entry->valid ==
false) {
165 entry->error_msg <<
"v4lget not valid\n";
168 struct v4l2_control control;
169 control.id = entry->queryctrl->id;
171 if(v4l2_ioctl(
pVideoIn_->
fd, VIDIOC_G_CTRL, &control) < 0) {
172 entry->error_msg <<
"v4l2_ioctl get control error\n";
175 entry->currentValue = control.value;
176 boost::this_thread::sleep(boost::posix_time::milliseconds(10));
177 entry->info_msg <<
"current = " << entry->currentValue <<
"\n";
184 if(entry->valid ==
false) {
185 entry->error_msg <<
"v4lset not valid\n";
188 struct v4l2_control control;
189 control.id = entry->queryctrl->id;
190 control.value = entry->targetValue;
191 if(v4l2_ioctl(
pVideoIn_->
fd, VIDIOC_S_CTRL, &control) < 0) {
192 entry->error_msg <<
"v4l2_ioctl set( " << control.value <<
") control error\n";
195 boost::this_thread::sleep(boost::posix_time::milliseconds(10));
196 entry->currentValue = entry->targetValue;
197 entry->info_msg <<
"current = " << entry->currentValue <<
"\n";
203 if(entry->currentValue == entry->targetValue) {
206 if(entry->valid ==
false) {
207 entry->currentValue = entry->targetValue;
208 entry->error_msg <<
"v4lupdate not valid\n";
212 if(entry->targetValue % entry->queryctrl->step) {
213 entry->info_msg <<
"target value " << entry->targetValue <<
"between steps " << entry->queryctrl->step;
214 entry->targetValue = (entry->targetValue / entry->queryctrl->step) * entry->queryctrl->step;
215 entry->info_msg <<
"new target value = " << entry->targetValue << std::endl;
217 if(entry->targetValue > entry->queryctrl->maximum) {
218 entry->info_msg <<
"clipping taget value = " << entry->targetValue <<
" to maximum = " << entry->queryctrl->maximum <<
"\n";
219 entry->targetValue = entry->queryctrl->maximum;
221 if(entry->targetValue < entry->queryctrl->minimum) {
222 entry->info_msg <<
"clipping taget value = " << entry->targetValue <<
" to minimum = " << entry->queryctrl->minimum <<
"\n";
223 entry->targetValue = entry->queryctrl->minimum;
226 struct v4l2_control control;
227 control.id = entry->queryctrl->id;
228 control.value = entry->targetValue;
229 if(v4l2_ioctl(
pVideoIn_->
fd, VIDIOC_S_CTRL, &control) < 0) {
230 entry->error_msg <<
"v4l2_ioctl set( " << control.value <<
") control error\n";
233 if(entry->queryctrl->flags & V4L2_CTRL_FLAG_WRITE_ONLY) {
234 entry->info_msg <<
"entry is write only\n";
235 entry->currentValue = entry->targetValue;
237 if(v4l2_ioctl(
pVideoIn_->
fd, VIDIOC_G_CTRL, &control) < 0) {
238 entry->error_msg <<
"v4l2_ioctl get control error, to verify\n";
241 entry->currentValue = control.value;
242 if(control.value != entry->targetValue) {
243 entry->error_msg <<
"v4l2_ioctl set and get are different. -> ";
244 entry->error_msg << entry->targetValue <<
" != " << control.value << std::endl;
248 entry->info_msg <<
"current = " << entry->currentValue <<
"\n";
255 , queryctrl(new v4l2_queryctrl)
267 if(
queryctrl->type == V4L2_CTRL_TYPE_INTEGER)
return true;
268 if(
queryctrl->type == V4L2_CTRL_TYPE_BOOLEAN)
return true;
269 if(
queryctrl->type == V4L2_CTRL_TYPE_MENU)
return true;
270 if(
queryctrl->type == V4L2_CTRL_TYPE_BUTTON)
return true;
271 if(
queryctrl->type == V4L2_CTRL_TYPE_INTEGER64)
return true;
272 if(
queryctrl->type == V4L2_CTRL_TYPE_CTRL_CLASS)
return true;
273 if(
queryctrl->type == V4L2_CTRL_TYPE_STRING)
return true;
274 if(
queryctrl->type == V4L2_CTRL_TYPE_BITMASK)
return true;
275 if(
queryctrl->type == V4L2_CTRL_TYPE_BITMASK)
return true;
280 std::stringstream ss;
282 ss << std::setw(9) << std::hex << std::showbase <<
queryctrl->id <<
" = " <<
varName;
283 if(
valid ==
false)
return ss.str();
284 ss <<
" >> " <<
queryctrl->name << std::endl;
287 ss <<
", default = " <<
queryctrl->default_value <<
", step = " <<
queryctrl->step << std::endl;
289 if(
queryctrl->flags & V4L2_CTRL_FLAG_DISABLED) ss <<
" disabled";
290 if(
queryctrl->flags & V4L2_CTRL_FLAG_GRABBED) ss <<
" grabbed";
291 if(
queryctrl->flags & V4L2_CTRL_FLAG_READ_ONLY) ss <<
" read only";
292 if(
queryctrl->flags & V4L2_CTRL_FLAG_UPDATE) ss <<
" update";
293 if(
queryctrl->flags & V4L2_CTRL_FLAG_INACTIVE) ss <<
" inactive";
294 if(
queryctrl->flags & V4L2_CTRL_FLAG_SLIDER) ss <<
" slider";
295 if(
queryctrl->flags & V4L2_CTRL_FLAG_WRITE_ONLY) ss <<
" write only";
296 if(
queryctrl->flags & V4L2_CTRL_FLAG_VOLATILE) ss <<
" volatile";
297 if(
queryctrl->flags == 0) ss <<
" empty";
299 if(
queryctrl->type == V4L2_CTRL_TYPE_INTEGER) ss <<
" integer";
300 else if(
queryctrl->type == V4L2_CTRL_TYPE_BOOLEAN) ss <<
"boolean";
301 else if(
queryctrl->type == V4L2_CTRL_TYPE_MENU) ss <<
"menu";
302 else if(
queryctrl->type == V4L2_CTRL_TYPE_BUTTON) ss <<
"button";
303 else if(
queryctrl->type == V4L2_CTRL_TYPE_INTEGER64) ss <<
"integer64";
304 else if(
queryctrl->type == V4L2_CTRL_TYPE_CTRL_CLASS) ss <<
"ctrl_class";
305 else if(
queryctrl->type == V4L2_CTRL_TYPE_STRING) ss <<
"string";
306 else if(
queryctrl->type == V4L2_CTRL_TYPE_BITMASK) ss <<
"bitmask";
307 else ss <<
"unsupported";
359 #ifdef V4L2_CTRL_FLAG_NEXT_CTRL // ref --> v4l3upc 360 queryctrl.id = V4L2_CTRL_FLAG_NEXT_CTRL;
361 if(0 == v4l2_ioctl(
pVideoIn_->
fd, VIDIOC_QUERYCTRL, &queryctrl)) {
363 boost::this_thread::sleep(boost::posix_time::milliseconds(10));
365 queryctrl.id |= V4L2_CTRL_FLAG_NEXT_CTRL;
366 }
while(0 == v4l2_ioctl(
pVideoIn_->
fd, VIDIOC_QUERYCTRL, &queryctrl));
372 for(
int i = V4L2_CID_BASE; i < V4L2_CID_LASTP1; i++) {
376 for(queryctrl.id = V4L2_CID_PRIVATE_BASE; (v4l2_ioctl(
pVideoIn_->
fd, VIDIOC_QUERYCTRL, &queryctrl) == 0) ; queryctrl.id++) {
378 boost::this_thread::sleep(boost::posix_time::milliseconds(10));
390 struct v4l2_queryctrl queryctrl;
391 struct v4l2_control control_s;
393 memset(&queryctrl, 0,
sizeof(queryctrl));
394 memset(&control_s, 0,
sizeof(control_s));
395 configfile = fopen(filename.c_str(),
"w");
396 if(configfile == NULL) {
397 error_msg_ <<
"saving configfile: " << filename <<
" failed" << std::endl;
399 fprintf(configfile,
"id value # luvcview control settings configuration file\n");
401 queryctrl.id = (*it)->queryctrl->id;
402 if(0 == ioctl(
pVideoIn_->
fd, VIDIOC_QUERYCTRL, &queryctrl)) {
403 if(queryctrl.flags & V4L2_CTRL_FLAG_DISABLED)
405 control_s.id = queryctrl.id;
406 v4l2_ioctl(
pVideoIn_->
fd, VIDIOC_G_CTRL, &control_s);
407 boost::this_thread::sleep(boost::posix_time::milliseconds(10));
408 fprintf(configfile,
"%-10d %-10d # name:%-32s type:%d min:%-5d max:%-5d step:%-5d def:%d\n",
409 queryctrl.id, control_s.value, queryctrl.name, queryctrl.type, queryctrl.minimum,
410 queryctrl.maximum, queryctrl.step, queryctrl.default_value);
411 printf(
"%-10d %-10d # name:%-32s type:%d min:%-5d max:%-5d step:%-5d def:%d\n",
412 queryctrl.id, control_s.value, queryctrl.name, queryctrl.type, queryctrl.minimum,
413 queryctrl.maximum, queryctrl.step, queryctrl.default_value);
414 boost::this_thread::sleep(boost::posix_time::milliseconds(10));
419 boost::this_thread::sleep(boost::posix_time::milliseconds(100));
420 info_msg_ <<
"saved configfile: " << filename << std::endl;
427 struct v4l2_control control;
429 memset(&control, 0,
sizeof(control));
430 configfile = fopen(filename.c_str(),
"r");
431 if(configfile == NULL) {
432 error_msg_ <<
"configfile: " << filename <<
" open failed" << std::endl;
434 info_msg_ <<
"loading controls from luvcview.cfg\n";
436 while(NULL != fgets(buffer,
sizeof(buffer), configfile)) {
437 sscanf(buffer,
"%i%i", &control.id, &control.value);
438 if(v4l2_ioctl(
pVideoIn_->
fd, VIDIOC_S_CTRL, &control))
439 info_msg_ <<
"ERROR id: " << control.id <<
" val: " << control.value << std::endl;
441 info_msg_ <<
"OK id: " << control.id <<
" val: " << control.value << std::endl;
442 boost::this_thread::sleep(boost::posix_time::milliseconds(20));
445 info_msg_ <<
"loaded configfile: " << filename << std::endl;
#define DEFAULT_AVIFILENAME
std::string pullInfoMsg()
int v4lset(ControlEntryPtr entry)
boost::interprocess::scoped_lock< boost::interprocess::interprocess_mutex > Lock
bool hasInfoMsg() const
returns false if therer are any error msgs waiting for pull
#define DEFAULT_VIDEODEVICE
const std::vector< ControlEntryPtr > & detectControlEnties()
v4l2_queryctrl * queryctrl
name of the v4l2 control
int format_
not supported yet
bool hasValidType() const
creates an info string related to the v4l2 control
std::stringstream error_msg
info msgs stream
std::string videoDevice_
pointer to the v4l2 device
std::string aviFilename_
device name /dev/videoX
int close_v4l2(struct vdIn *vd)
std::string pullErrorMsg()
return true if the value type is supported
int grabmethod_
image formate
int save_controls(const std::string &filename)
std::stringstream error_msg_
int v4lupdate(ControlEntryPtr entry)
std::stringstream info_msg
target value to set after a write
timeval timeLastFrame_
frames per second
int uvcGrab(struct vdIn *vd)
static char removeNonAlNum(char in)
ControlEntryPtr getControlEntry(std::string varName)
std::string getQueryCtrlInfo() const
error msgs in the case something happend
boost::interprocess::interprocess_mutex mutexImage_
duration between last and the frame before the last one
int targetValue
current value of the control after read or set
int v4lgetInfo(ControlEntryPtr entry)
v4lcontrols
std::vector< ControlEntryPtr > controlEntries_
mutex to secure critical sections
int load_controls(const std::string &filename)
double durationLastFrame_
time stamp of the last frame
boost::shared_ptr< ControlEntry > ControlEntryPtr
int v4lget(ControlEntryPtr entry)
int init_videoIn(struct vdIn *vd, char *device, int width, int height, float fps, int format, int grabmethod, char *avifilename)
V4RCam()
shared pointer for ControlEntry
bool hasErrorMsg() const
clears the info_msgs stringstream and crates a info string
std::stringstream info_msg_
FD initCamera(const std::string &videoDevice="")
vector of the current supported control entries
int currentValue
pointer to the original related control
std::string pullErrorMsg()
std::string pullInfoMsg()
clears the error_msgs stringstream and crates a info string
#define DEFAULT_GRABMETHODE
~ControlEntry()
construtor