ftdi_read_eeprom.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2012, Yujin Robot.
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of Yujin Robot nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00038 /*****************************************************************************
00039  ** Includes
00040  *****************************************************************************/
00041 
00042 #include <ftdi.h>
00043 #include <cstring>
00044 #include <ecl/command_line.hpp>
00045 
00046 /*****************************************************************************
00047 ** Preprocessor
00048 *****************************************************************************/
00049 
00050 #define REQUEST_EEPROM_SIZE 0
00051 
00052 /*****************************************************************************
00053  ** Using
00054  *****************************************************************************/
00055 
00056 using ecl::CmdLine;
00057 using ecl::UnlabeledValueArg;
00058 using ecl::ValueArg;
00059 using ecl::SwitchArg;
00060 using std::string;
00061 
00062 /*****************************************************************************
00063 ** Functions
00064 *****************************************************************************/
00065 
00066 bool decode(unsigned char* eeprom_binary, const int &size) {
00067   ftdi_eeprom eeprom;
00068   std::cout << "  Decoding into eeprom structure." << std::endl;
00069   // put the binary into an eeprom structure
00070   if ( ftdi_eeprom_decode(&eeprom, eeprom_binary, size) != 0 ) {
00071     return false;
00072   }
00073   std::cout << "Eeprom:" << std::endl;
00074   std::cout << "    Manufacturer: " << eeprom.manufacturer << std::endl;
00075   std::cout << "    Product     : " << eeprom.product << std::endl;
00076   std::cout << "    Vendor Id   : " << eeprom.vendor_id << std::endl;
00077   std::cout << "    Product Id  : " << eeprom.product_id << std::endl;
00078   std::cout << "    Serial Id   : " << eeprom.serial << std::endl;
00079   std::cout << "    Self Powered: " << eeprom.self_powered << std::endl;
00080   std::cout << "    Remote Wake : " << eeprom.remote_wakeup << std::endl;
00081   std::cout << "    Use Serial  : " << eeprom.use_serial << std::endl;
00082   std::cout << "    In Iso      : " << eeprom.in_is_isochronous << std::endl;
00083   std::cout << "    Out Iso     : " << eeprom.out_is_isochronous << std::endl;
00084   std::cout << "    Suspend     : " << eeprom.suspend_pull_downs << std::endl;
00085   std::cout << "    Max Power   : " << eeprom.max_power << std::endl;
00086   std::cout << "    Chip Type   : " << eeprom.chip_type << std::endl;
00087   return true;
00088 }
00089 /*****************************************************************************
00090  ** Main
00091  *****************************************************************************/
00092 
00093 int main(int argc, char **argv)
00094 {
00095   const int vendor_id = 0x0403;
00096   const int product_id = 0x6001;
00097 
00098   /*********************
00099    ** Parse Command Line
00100    **********************/
00101   CmdLine cmd_line("This is used to read an eeprom on an ftdi device.", ' ', "0.1");
00102   ValueArg<std::string> serial_arg(
00103       "s", "serial", "Identify the device via the old serial id (if there are multiple attached) ['unspecified'].", false,
00104       "unspecified", "string");
00105   cmd_line.add(serial_arg);
00106   cmd_line.parse(argc, argv);
00107   bool using_serial_id = false;
00108   string serial_id;
00109   if (serial_arg.getValue() != "unspecified")
00110   {
00111     using_serial_id = true;
00112     serial_id = serial_arg.getValue();
00113   }
00114 
00115   /*********************
00116    ** Debug output
00117    **********************/
00118   std::cout << "Input Information" << std::endl;
00119   if (!using_serial_id)
00120   {
00121     std::cout << "  Serial id: unused (first device found.)" << std::endl;
00122   }
00123   else
00124   {
00125     std::cout << "  Serial id: " << serial_id << std::endl;
00126   }
00127 
00128   /*********************
00129    ** Open a context
00130    **********************/
00131   struct ftdi_context ftdi;
00132   if (ftdi_init(&ftdi) < 0)
00133   {
00134     std::cerr << "ftdi_init failed" << std::endl;
00135     return EXIT_FAILURE;
00136   }
00137   if (!using_serial_id)
00138   { // simply open up the first found.
00139     if (ftdi_usb_open(&ftdi, vendor_id, product_id) != 0)
00140     {
00141       std::cerr << "Couldn't find/open an ftdi device [" << ftdi.error_str << "]" << std::endl;
00142       return EXIT_FAILURE;
00143     }
00144   }
00145   else
00146   {
00147     if (ftdi_usb_open_desc(&ftdi, vendor_id, product_id, NULL, serial_id.c_str()) < 0)
00148     {
00149       std::cerr << "Couldn't open the device with serial id string: " << serial_id << std::endl;
00150       return EXIT_FAILURE;
00151     }
00152   }
00153   /******************************************
00154    ** Eeeprom Binary (Requested size)
00155    *******************************************/
00156   std::cout << "Eeprom Binary" << std::endl;
00157   unsigned char eeprom_binary[512];
00158   int size = ftdi_read_eeprom_getsize(&ftdi, eeprom_binary, 512);
00159   if (size < 0)
00160   {
00161     std::cerr << "Error: Could not read the eeprom from the requested device." << std::endl;
00162     return EXIT_FAILURE;
00163   }
00164   std::cout << "  Read binary [" << size << " bytes]." << std::endl;
00165   std::cout << "  Write binary [eeprom.req]." << std::endl;
00166   FILE *fp = fopen ("eeprom.req", "wb");
00167   fwrite (&eeprom_binary, 1, size, fp);
00168   fclose (fp);
00169 
00170   if ( !decode(eeprom_binary, size) ) {
00171     std::cerr << "Error: Could not write raw binary eeprom into the eeprom structure." << std::endl;
00172     return EXIT_FAILURE;
00173   }
00174 
00175 #if REQUEST_EEPROM_SIZE
00176   /******************************************
00177    ** Eeeprom Binary (Fixed size)
00178    *******************************************/
00179   // this is what the official example does.
00180   size = 128;
00181   int result = ftdi_read_eeprom(&ftdi,eeprom_binary);
00182   if ( result < 0 ) {
00183     std::cerr << "Error: Could not read the eeprom from the requested device." << std::endl;
00184     return EXIT_FAILURE;
00185   }
00186   fp = fopen ("eeprom.fix", "wb");
00187   fwrite (&eeprom_binary, 1, size, fp);
00188   fclose (fp);
00189   std::cout << "  Write binary [eeprom.fix]." << std::endl;
00190 
00191   if ( !decode(eeprom_binary, size) ) {
00192     std::cerr << "Error: Could not write raw binary eeprom into the eeprom structure." << std::endl;
00193     return EXIT_FAILURE;
00194   }
00195 #endif
00196   std::cout << "Done." << std::endl;
00197 
00198   return 0;
00199 }
00200 
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Friends Defines


kobuki_udev
Author(s): Daniel Stonier
autogenerated on Thu Nov 22 2012 19:34:17