photo_camera_list.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  *
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2012, Robert Bosch LLC.
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/or other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of the Robert Bosch nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *
00035  *********************************************************************/
00036 
00037 #include <iostream>
00038 
00039 #include "photo/photo_reporter.hpp"
00040 
00041 #include "photo/photo_camera_list.hpp"
00042 
00043 
00044 photo_camera_list::photo_camera_list( void ) :
00045   camera_list_(NULL),
00046   port_info_list_(NULL),
00047   abilities_list_(NULL)
00048 {
00049 }
00050 
00051 photo_camera_list::~photo_camera_list( void )
00052 {
00053   gp_list_unref( camera_list_ ); //delete camera_list_;
00054   gp_port_info_list_free( port_info_list_ ); //delete port_info_list_;
00055   gp_abilities_list_free( abilities_list_ );  //delete abilities_list_;
00056 }
00057 
00058 
00059 
00060 CameraList* photo_camera_list::getCameraList( void )
00061 {
00062   return camera_list_;
00063 }
00064 
00065 
00066 GPPortInfoList* photo_camera_list::getPortInfoList( void )
00067 {
00068   return port_info_list_;
00069 }
00070 
00071 CameraAbilitiesList* photo_camera_list::getAbilitiesList( void )
00072 {
00073   return abilities_list_;
00074 }
00075 
00076 
00077 bool photo_camera_list::loadPortInfo( ssize_t* port_count )
00078 {
00079   if( port_info_list_ == NULL )
00080   {
00081     // Create a new port info list
00082     if( gp_port_info_list_new( &port_info_list_ ) != GP_OK )
00083     {
00084       photo_reporter::error( "gp_port_info_list_new()" );
00085       return false;
00086     }
00087 
00088     // Populate the list
00089     if( gp_port_info_list_load( port_info_list_ ) != GP_OK )
00090     {
00091       photo_reporter::error( "gp_port_info_list_load()" );
00092       return false;
00093     }
00094   }
00095 
00096   // Count the number of ports in the list
00097   *port_count =  gp_port_info_list_count( port_info_list_ );
00098   if( *port_count < GP_OK )
00099   {
00100     photo_reporter::error( "gp_port_info_list_count()" );
00101     return false;
00102   }
00103 
00104   return true;
00105 }
00106 
00107 bool photo_camera_list::loadAbilities( GPContext* context )
00108 {
00109   // Create a new abilities list
00110   if( gp_abilities_list_new( &abilities_list_ ) != GP_OK )
00111   {
00112     photo_reporter::error( "gp_abilities_list_new()" );
00113     return false;
00114   }
00115 
00116   // Populate the abilities list
00117   if( gp_abilities_list_load( abilities_list_, context ) != GP_OK )
00118   {
00119     photo_reporter::error( "gp_abilities_list_load()" );
00120     return false;
00121   }
00122 
00123   return true;
00124 }
00125 
00126 
00127 
00128 bool photo_camera_list::lookupPortInfo( const std::string port_name, GPPortInfo* port_info )
00129 {
00130   int list_index = 0;
00131 
00132   // Find the port in the list of ports and return the index
00133   list_index = gp_port_info_list_lookup_path( port_info_list_, port_name.c_str() );
00134   if( list_index < GP_OK )
00135   {
00136     photo_reporter::error( "gp_port_info_list_lookup_path()" );
00137     if( list_index == GP_ERROR_UNKNOWN_PORT )
00138     {
00139       std::cerr << "The specified port (" << port_name << ") cannot be found. Use 'gphoto2 --list-ports' to display available ports. The prefix 'serial:' or 'usb:' is required." << std::endl;
00140     }
00141     return false;
00142   }
00143   
00144   // Get the port information from from the information list
00145   if( gp_port_info_list_get_info( port_info_list_, list_index, port_info ) != GP_OK )
00146   {
00147     photo_reporter::error( "gp_port_info_list_get_info()" );
00148     return false;
00149   }
00150 
00151   return true;
00152 }
00153 
00154 
00155 bool photo_camera_list::lookupAbilities( const std::string model_name, CameraAbilities* abilities )
00156 {
00157   int list_index = 0;
00158 
00159   // Find the camera in the list of cameras and return the index
00160   list_index = gp_abilities_list_lookup_model( abilities_list_, model_name.c_str() );
00161   if( list_index < GP_OK )
00162   {
00163     photo_reporter::error( "gp_abilities_list_lookup_model()" );
00164     return false;
00165   }
00166 
00167   // Find the camera's abilities in the abilities list
00168   if( gp_abilities_list_get_abilities( abilities_list_, list_index, abilities ) != GP_OK )
00169   {
00170     photo_reporter::error( "gp_abilities_list_get_abilities()" );
00171     return false;
00172   }
00173 
00174   return true;
00175 }
00176 
00177 
00178 
00179 
00180 
00181 
00182 /*
00183  * This function detects all currently attached photo_cameras and returns them
00184  * in a list. It avoids the generic 'usb:' port entry. This function does not
00185  * open or initialize the photo_cameras.
00186  */
00187 
00188 bool photo_camera_list::autodetect( GPContext* context )
00189 {
00190   ssize_t port_count = 0;
00191  
00192   // Create a new list of cameras
00193   if( gp_list_new( &camera_list_ ) != GP_OK )
00194   {
00195     photo_reporter::error( "gp_list_new()" );
00196     return false;
00197   }
00198 
00199   // Load the low-level port drivers
00200   if( loadPortInfo( &port_count ) == false )
00201   {
00202     return false;
00203   }
00204 
00205   // Load the photo_camera drivers
00206   if( loadAbilities( context ) == false )
00207   {
00208     return false;
00209   }
00210 
00211 
00212   // Filter the list for USB cameras
00213   if( filterCameraList( context, "usb:" ) == false )
00214   {
00215     return false;
00216   }
00217   return true;
00218 }
00219 
00220 
00221 
00222 bool photo_camera_list::filterCameraList( GPContext* context, const std::string match_string )
00223 {
00224   CameraList *working_list = NULL;
00225   const char *name, *value;
00226   int count = 0;
00227 
00228   if( gp_list_new( &working_list ) != GP_OK )
00229   {
00230     photo_reporter::error( "gp_list_new()" );
00231     gp_list_free( working_list );
00232     return false;
00233   }
00234 
00235   // Autodetect the currently attached photo_cameras.
00236   if( gp_abilities_list_detect( abilities_list_, port_info_list_, working_list, context) != GP_OK )
00237   {
00238     photo_reporter::error( "gp_abilities_list_detect()" );
00239     gp_list_free( working_list );
00240     return false;
00241   }
00242   
00243  
00244   count = gp_list_count( working_list );
00245   if( count < GP_OK )
00246   {
00247     photo_reporter::error( "gp_list_count()" );
00248     gp_list_free( working_list );
00249     return false;
00250   }
00251   
00252   // Clear camera_list_ for appending
00253   if( gp_list_reset( camera_list_ ) != GP_OK )
00254   {
00255     photo_reporter::error( "gp_list_reset()" );
00256     gp_list_free( working_list );
00257     return false;
00258   }
00259 
00260   // Filter out the generic 'usb:' entry
00261   for( int i = 0; i < count; i++ )
00262   {
00263 
00264     gp_list_get_name( working_list, i, &name );
00265     gp_list_get_value( working_list, i, &value );
00266 
00267     if( match_string.compare( value ) != 0 )
00268     {
00269       gp_list_append( camera_list_, name, value );
00270     }
00271   }
00272   
00273   gp_list_free( working_list );
00274 
00275   return true;
00276 }
00277 


photo
Author(s): Benjamin Pitzer
autogenerated on Mon Oct 6 2014 10:09:43