[Jde-dev] CameraServer y WebCam Philips

JoseMaria jmplaza en gsyc.es
Jue Mar 18 21:20:02 CET 2010


Idem. Lo veo bien como parámetro opcional, de modo que si no se pone
nada el componente CameraServer lo hace lo mejor que puede por defecto.
Muchas aplicaciones usarán justo el componente así, sin saber muchos
detalles de las cámaras que tiene debajo.

Pero si para cierta cámara viene mejor tal o cual combinación, es muy
útil que se pueda especificar vía fichero de configuración y saltarse el
"por defecto" para que la captura se ajuste mejor a las características
especiales de tal o cual cámara o los requisitos de tal o cual
aplicación.

JoseMaria
On Mon, 2010-03-15 at 14:35 +0100, Roberto Calvo wrote:
> El lun, 15-03-2010 a las 09:18 -0400, David Lobato escribió:
> > No veo tan claro que la solución sea añadir otro parámetro. Esto nos
> > obliga a caracterizar cada una de las cámaras que queramos conectar y
> > apañar el código para cada cámara. Una cosa es que soportemos
> > diferentes formatos de salida (RGB888, YUY2,...)  estandarizados para
> > que el que reciba al otro lado sepa a que atenerse, y otra es que haya
> > que controlar al milímetro que entra y que sale. A mi parecer deja de
> > hacer simple el uso del componente.
> 
> Podemos ponerlo como parámetro opcional en el fichero de conf. No
> siempre es necesario utilizarlo, pero hay veces que viene bien para no
> tener que compilar código. Un parámetro opcional lo veo bastante bien.
> 
> > 
> > 
> > Como solución para ir tirando lo acepto, pero creo que tenemos que
> > investigar un poco mas sobre gstreamer para ver como detectar las
> > "capabilities" que da la cámara con código (99% seguro de que se
> > puede) y seleccionar aquella que mejor se adapte a la que se espera
> > como salida (en principio con no cambiar de espacio de colores seria
> > suficiente).
> 
> Totalmente de acuerdo, si con gst-launch es capaz de negociarlo, desde 
> C++ también se puede hacer.
> 
> Aún así, veo muy bueno y versátil disponer de este parámetro opcional en
> el fichero de configuración, ya que nos permite modificar el
> comportamiento de cameraserver sin necesidad de cambiar código. Aunque
> nos de gstreamer las "capabilities", dejaría la opción de detallarle en
> el fichero de conf el formato que queremos. 
> 
> Cada cámara y cada linux es un mundo, por lo que creo que nos vendrá muy
> bien disponer del máximo detalle en los ficheros de conf. Eso si, con
> parámetros opcionales, que podamos arrancar un cameraserver con las
> mínimas líneas de conf tambien es importante.
> 
> un saludo!
> 
> > 
> > 
> > En cuanto al vloopback funcionando con todo, enhorabuena! Los números
> > pintan bastante bien.
> > 
> > 
> > David.
> > 
> > 2010/3/15 JoseMaria <jmplaza en gsyc.es>
> >         Estupendo!!
> >         
> >         Sip, habría que añadir al fichero de configuración ese nuevo
> >         parámetro.
> >         
> >         David está preparando la descripción en el manual 5.0 de
> >         cameraServer,
> >         cameraViewer, etc. Buen sitio para comentar cómo se usan estos
> >         componentes, cómo se configuran, brevemente cómo están hechos
> >         por
> >         dentro, etc. A ver si esta semana conseguimos cerrar una
> >         descripción
> >         buena en el manual de ellos, que ya somos bastantes los que
> >         estamos
> >         usándolos.
> >         
> >         Ánimo,
> >         
> >         JoseMaria
> >         
> >         On Sun, 2010-03-14 at 23:18 +0100, Roberto Calvo wrote:
> >         > Al fin he conseguido hacerlo funcionar. La solución, como no
> >         soporta
> >         > YUY2, es mirar que formato soporta, y lo que he encontrado
> >         es que esta
> >         > cámara soporte I420
> >         > Label         FOURCC in Hex           Bits per pixel
> >            Description
> >         > I420          0x30323449              12
> >            8 bit Y plane followed by 8 bit 2x2 subsampled U and V
> >         planes.
> >         >
> >         > Más info en [1]
> >         >
> >         > Por lo que el código, lo único que cambia es lo siguiente:
> >         >
> >         >      v4l2caps = gst_caps_new_simple ("video/x-raw-yuv",
> >         >                                      "format",
> >         GST_TYPE_FOURCC,
> >         >
> >          GST_MAKE_FOURCC('I','4','2','0'),
> >         >                                      NULL);
> >         >
> >         >
> >         > David, quizás deberíamos añadir al fichero de conf de camera
> >         server este
> >         > parámetro (formato en el que queremos recoger la imagen de
> >         la cámara,
> >         > para optimizar el proceso como has dicho), y añadirlo al que
> >         ya tenemos,
> >         > que es formato que ofrece el servidor. ¿Te parece?
> >         >
> >         > Por cierto, funciona todo bien ya sobre el módulo vloopback,
> >         que ya era
> >         > hora :-))
> >         >
> >         > Algunos datos interesantes probados en la miniITX (1.5Ghz)
> >         >
> >         > CameraServer + Vloopback = ~ 5% de CPU
> >         > CameraServer + Vloopback + ffmpeg grabando = ~ 20% de CPU
> >         >
> >         > un saludete!
> >         >
> >         > [1] http://www.fourcc.org/yuv.php
> >         >
> >         >
> >         > El dom, 14-03-2010 a las 22:05 +0100, Roberto Calvo
> >         escribió:
> >         > > Thanks por la explicación!!, ahora lo voy teniendo más
> >         claro.
> >         > >
> >         > > Lo primero que he hecho es ejecutar el comando desde
> >         consola, para ver
> >         > > si es capaz de negociar gstreamer con esta cámara. Y si es
> >         capaz, ya que
> >         > > termina por mostrar la imagen y negociar con los
> >         siguientes parámetros:
> >         > >
> >         >
> >         > /GstPipeline:pipeline0/GstXImageSink:ximagesink0.GstPad:sink:
> >         > >     caps = video/x-raw-rgb, bpp=(int)16, depth=(int)16,
> >         endianness=(int)1234,
> >         > >     red_mask=(int)63488, green_mask=(int)2016,
> >         blue_mask=(int)31, width=(int)320,
> >         > >     height=(int)240, framerate=(fraction)15/2,
> >         pixel-aspect-ratio=(fraction)1/1
> >         > >
> >         > >
> >         > > He modificado el código para la parte donde se generar los
> >         pipelines, en
> >         > > el caso que conectamos un dispositivo v4l2 (descomentado
> >         la parte de
> >         > > v4l2caps y caps, también he probado sólo dejando caps);
> >         > >
> >         > >
> >         > >   else if (config_.uri.find("v4l://") == 0){/*handle v4l2
> >         source*/
> >         > >       std::string dev = config_.uri.substr(6);/*after
> >         v4l2://*/
> >         > >       source =
> >         gst_element_factory_make("v4lsrc","source");
> >         > >
> >         g_object_set(G_OBJECT(source),"device",dev.c_str(),NULL);
> >         > >       sink = gst_element_factory_make("appsink","sink");
> >         > >       g_object_set(G_OBJECT(sink),"drop",1,NULL);
> >         > >       g_object_set(G_OBJECT(sink),"max-buffers",16,NULL);
> >         > >
> >         > >       videocolor =
> >         gst_element_factory_make("ffmpegcolorspace","videocolor");
> >         > >
> >         gst_bin_add_many(GST_BIN(pipeline),source,videocolor,sink,NULL);
> >         > >
> >           //gst_element_link_filtered(source,videocolor,v4l2caps);
> >         > >       //gst_element_link_filtered(videocolor,sink,caps);
> >         > >     }
> >         > >
> >         > >
> >         > > Después de estar un rato negociando, sale el siguiente
> >         mensaje.
> >         > >
> >         > > info: Starting thread for camera: cameraA
> >         > > error: Error: Error en el flujo de datos interno.
> >         > >
> >         > >
> >         > > Sigo probado configuraciones, a ver que puede estar
> >         pasando ....
> >         > >
> >         > > El sáb, 13-03-2010 a las 17:10 -0500, David Lobato
> >         escribió:
> >         > > > Hola,
> >         > > >
> >         > > >
> >         > > > El error "Could not negociate format" sale cuando alguno
> >         de los
> >         > > > componentes del pipeline no puede funcionar en el
> >         formato que le
> >         > > > estamos pidiendo.
> >         > > >
> >         > > >
> >         > > > El pipeline que hay para v4l2 está bastante optimizado
> >         para a las
> >         > > > cámaras logitech, ya que es la que tengo mas a mano.
> >         Para que funcione
> >         > > > con otras cámaras tenemos que hacer un poco mas
> >         genérico. Lo que
> >         > > > tenemos ahora es:
> >         > > >
> >         > > >
> >         > > > camara -----> ffmpegcolorspaces ------> appsink
> >         > > >               |                                    |
> >         > > >           v4l2caps                         caps
> >         > > >
> >         > > >
> >         > > >
> >         > > >
> >         > > > Gstreamer es capaz de negociar el formato de los datos
> >         que cada
> >         > > > componente intercambia entre si, pero también te deja
> >         especificar
> >         > > > dicho formato con lo que se denominan "capabilities" que
> >         vienen a ser
> >         > > > una descripción del formato.
> >         > > >
> >         > > >
> >         > > > Así en nuestro pipeline tenemos un componente camara, el
> >         componente
> >         > > > ffmpegcolorspaces que es capaz de traducir de un espacio
> >         de color a
> >         > > > otro y el componente appsink, que es un buffer que
> >         almacena los frames
> >         > > > hasta que se los pedimos. Además, "caps" seleccionan el
> >         formato que
> >         > > > hemos configurado en el fichero cfg, de modo que los
> >         frames que
> >         > > > appsink nos da van en el formato que queremos (YUY2,
> >         RGB888, GRAY8 por
> >         > > > el momento).
> >         > > >
> >         > > >
> >         > > > Para el caso concreto de las cámaras logitech, estas son
> >         capaces de
> >         > > > generar datos en yuy2 (YUV422) y jpeg de forma nativa
> >         sin ninguna
> >         > > > transformación software. Pero por alguna razón que
> >         desconozco cuando
> >         > > > montas el pipeline con los elementos comentados (sin
> >         contar v4l2caps)
> >         > > > el formato que negocia la cámara con ffmpegcolorspaces
> >         no es ninguno
> >         > > > de los nativos por lo que se hace una conversión extra
> >         (ver ejecución
> >         > > > al final del mail). Para evitar esto añadí al pipeline
> >         "v4l2caps" que
> >         > > > fijan el formato a YUY2 eliminando la conversión extra.
> >         > > >
> >         > > >
> >         > > > Esto se hace concretamente aquí:
> >         > > > st_element_link_filtered(source,videocolor,v4l2caps);
> >         > > >
> >         > > >
> >         > > > El problema viene cuando pones una cámara que no puede
> >         generar dicho
> >         > > > formato, como parece ser el problema de la philips. Así,
> >         creo que la
> >         > > > solución es simplemente quitar v4l2caps y dejar que se
> >         negocie el
> >         > > > formato, a costa de que no sea el mas optimo, pero
> >         ganando el soporte
> >         > > > de mas cámaras.
> >         > > >
> >         > > >
> >         > > > También cabe la posibilidad de que haya alguna manera
> >         mejor de
> >         > > > hacerlo, que yo de momento no he descubierto. En cuanto
> >         tenga mas
> >         > > > tiempo, me gustaría descubrir un poco mas de gstreamer,
> >         que parece
> >         > > > bastante interesante y potente para lo que buscamos.
> >         > > >
> >         > > >
> >         > > > Espero haber aclarado el asunto.
> >         > > >
> >         > > >
> >         > > > Un saludo,
> >         > > > David.
> >         > > >
> >         > > >
> >         > > >
> >         > > >
> >         > > >
> >         > > > Ejecución que muestra la negociación camara
> >         ffmpegcolorspaces:
> >         > > >
> >         > > >
> >         > > > gst-launch-0.10 -v v4l2src device=/dev/video2 !
> >         ffmpegcolorspace !
> >         > > > video/x-raw-rgb,width=320,height=240 ! ximagesink
> >         > > >
> >         > > >
> >         > > > (gst-launch-0.10:2960): GLib-WARNING **: g_set_prgname()
> >         called
> >         > > > multiple times
> >         > > > Setting pipeline to PAUSED ...
> >         > > > Xlib:  extension "Generic Event Extension" missing on
> >         display
> >         > > > "localhost:10.0".
> >         > > > /GstPipeline:pipeline0/GstV4l2Src:v4l2src0.GstPad:src:
> >         caps =
> >         > > > video/x-raw-yuv, format=(fourcc)I420, width=(int)320,
> >         height=(int)240,
> >         > > > framerate=(fraction)30/1,
> >         pixel-aspect-ratio=(fraction)1/1
> >         > > > Pipeline is live and does not need PREROLL ...
> >         > > > Setting pipeline to PLAYING ...
> >         > > > New clock: GstSystemClock
> >         > >
> >         > /GstPipeline:pipeline0/GstFFMpegCsp:ffmpegcsp0.GstPad:src:
> >         caps =
> >         > > > video/x-raw-rgb, bpp=(int)32, depth=(int)24,
> >         endianness=(int)4321,
> >         > > > red_mask=(int)65280, green_mask=(int)16711680,
> >         > > > blue_mask=(int)-16777216, width=(int)320,
> >         height=(int)240,
> >         > > > framerate=(fraction)30/1,
> >         pixel-aspect-ratio=(fraction)1/1
> >         > >
> >         > /GstPipeline:pipeline0/GstFFMpegCsp:ffmpegcsp0.GstPad:sink:
> >         caps =
> >         > > > video/x-raw-yuv, format=(fourcc)I420, width=(int)320,
> >         height=(int)240,
> >         > > > framerate=(fraction)30/1,
> >         pixel-aspect-ratio=(fraction)1/1
> >         > >
> >         > /GstPipeline:pipeline0/GstCapsFilter:capsfilter0.GstPad:src:
> >         caps =
> >         > > > video/x-raw-rgb, bpp=(int)32, depth=(int)24,
> >         endianness=(int)4321,
> >         > > > red_mask=(int)65280, green_mask=(int)16711680,
> >         > > > blue_mask=(int)-16777216, width=(int)320,
> >         height=(int)240,
> >         > > > framerate=(fraction)30/1,
> >         pixel-aspect-ratio=(fraction)1/1
> >         > >
> >         > /GstPipeline:pipeline0/GstCapsFilter:capsfilter0.GstPad:sink: caps =
> >         > > > video/x-raw-rgb, bpp=(int)32, depth=(int)24,
> >         endianness=(int)4321,
> >         > > > red_mask=(int)65280, green_mask=(int)16711680,
> >         > > > blue_mask=(int)-16777216, width=(int)320,
> >         height=(int)240,
> >         > > > framerate=(fraction)30/1,
> >         pixel-aspect-ratio=(fraction)1/1
> >         > >
> >         > /GstPipeline:pipeline0/GstXImageSink:ximagesink0.GstPad:sink: caps =
> >         > > > video/x-raw-rgb, bpp=(int)32, depth=(int)24,
> >         endianness=(int)4321,
> >         > > > red_mask=(int)65280, green_mask=(int)16711680,
> >         > > > blue_mask=(int)-16777216, width=(int)320,
> >         height=(int)240,
> >         > > > framerate=(fraction)30/1,
> >         pixel-aspect-ratio=(fraction)1/1
> >         > > >
> >         > > >
> >         > > >
> >         > > > 2010/3/13 Roberto Calvo <rocapal en libresoft.es>
> >         > > >
> >         > > >         Buenas,
> >         > > >
> >         > > >         Al arrancar el CameraServer contra la webcam
> >         Philips V4l , me
> >         > > >         da este error:
> >         > > >
> >         > > >         error: Error: Could not negotiate format
> >         > > >
> >         > > >         Y en el dmesg sale esto (parece que no consigue
> >         poner los fps
> >         > > >         adecuados).
> >         > > >
> >         > > >         [14566.456664] pwc: Failed to set video mode
> >         SIF en 1 fps; return
> >         > > >         code = -22
> >         > > >         [14566.613554] pwc: Failed to set video mode
> >         SIF en 2 fps; return
> >         > > >         code = -22
> >         > > >         [14566.766625] pwc: Failed to set video mode
> >         SIF en 3 fps; return
> >         > > >         code = -22
> >         > > >         [14566.927300] pwc: Failed to set video mode
> >         SIF en 4 fps; return
> >         > > >         code = -22
> >         > > >         [14571.280324] pwc: Failed to set video mode
> >         SIF en 31 fps;
> >         > > >         return code = -22
> >         > > >
> >         > > >         David, añadí la opción para v4l al cameraserver:
> >         > > >
> >         > > >          else if (config_.uri.find("v4l://") ==
> >         0){/*handle v4l2
> >         > > >         source*/
> >         > > >              std::string dev =
> >         config_.uri.substr(6);/*after v4l2://*/
> >         > > >              source =
> >         gst_element_factory_make("v4lsrc","source");
> >         > > >
> >          g_object_set(G_OBJECT(source),"device",dev.c_str(),NULL);
> >         > > >              sink =
> >         gst_element_factory_make("appsink","sink");
> >         > > >              g_object_set(G_OBJECT(sink),"drop",1,NULL);
> >         > > >
> >          g_object_set(G_OBJECT(sink),"max-buffers",16,NULL);
> >         > > >
> >         > > >              videocolor =
> >         > > >
> >         gst_element_factory_make("ffmpegcolorspace","videocolor");
> >         > > >
> >         > > >
> >          gst_bin_add_many(GST_BIN(pipeline),source,videocolor,sink,NULL);
> >         > > >
> >          gst_element_link_filtered(source,videocolor,v4l2caps);
> >         > > >
> >          gst_element_link_filtered(videocolor,sink,caps);
> >         > > >            }
> >         > > >
> >         > > >         ¿Ves que puede estar pasando?
> >         > > >
> >         > > >         un saludete!
> >         > > >
> >         > > >         --
> >         > > >         Roberto Calvo Palomino          | Libre
> >         Software Engineering
> >         > > >         Lab (GSyC)
> >         > > >         Tel: (+34) 91 488 85 23         | Universidad
> >         Rey Juan Carlos
> >         > > >         rocapal en libresoft.es            | Edif.
> >         Departamental II -
> >         > > >         Despacho 116
> >         > > >         http://libresoft.es/            | c/Tulipán s/n
> >         28933 Móstoles
> >         > > >         (Madrid)
> >         > > >
> >         > > >         GPG-KEY: http://gsyc.es/~rocapal/rocapal.gpg
> >         > > >
> >         > > >
> >         > > > _______________________________________________
> >         > > > Jde-developers mailing list
> >         > > > Jde-developers en gsyc.es
> >         > > >
> >         http://gsyc.escet.urjc.es/cgi-bin/mailman/listinfo/jde-developers
> >         > >
> >         > > _______________________________________________
> >         > > Jde-developers mailing list
> >         > > Jde-developers en gsyc.es
> >         > >
> >         http://gsyc.escet.urjc.es/cgi-bin/mailman/listinfo/jde-developers
> >         >
> >         > _______________________________________________
> >         > Jde-developers mailing list
> >         > Jde-developers en gsyc.es
> >         >
> >         http://gsyc.escet.urjc.es/cgi-bin/mailman/listinfo/jde-developers
> >         
> >         
> >         
> >         
> >         --
> >         http://gsyc.es/jmplaza
> >         Universidad Rey Juan Carlos
> >         
> >         
> >         
> > 
> > 
> > _______________________________________________
> > Jde-developers mailing list
> > Jde-developers en gsyc.es
> > http://gsyc.escet.urjc.es/cgi-bin/mailman/listinfo/jde-developers
> 


-- 
http://gsyc.es/jmplaza 
Universidad Rey Juan Carlos




More information about the Jde-developers mailing list