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  */
00041 /*****************************************************************************
00042  ** Includes
00043  *****************************************************************************/
00044 
00045 #include <ftdi.h>
00046 #include <cstring>
00047 #include <ecl/command_line.hpp>
00048 
00049 /*****************************************************************************
00050 ** Preprocessor
00051 *****************************************************************************/
00052 
00053 #define REQUEST_EEPROM_SIZE 0
00054 
00055 /*****************************************************************************
00056  ** Using
00057  *****************************************************************************/
00058 
00059 using ecl::CmdLine;
00060 using ecl::UnlabeledValueArg;
00061 using ecl::ValueArg;
00062 using ecl::SwitchArg;
00063 using std::string;
00064 
00065 /*****************************************************************************
00066 ** Functions
00067 *****************************************************************************/
00068 
00069 bool decode(unsigned char* eeprom_binary, const int &size) {
00070   ftdi_eeprom eeprom;
00071   std::cout << "  Decoding into eeprom structure." << std::endl;
00072   // put the binary into an eeprom structure
00073   if ( ftdi_eeprom_decode(&eeprom, eeprom_binary, size) != 0 ) {
00074     return false;
00075   }
00076   std::cout << "Eeprom:" << std::endl;
00077   std::cout << "    Manufacturer: " << eeprom.manufacturer << std::endl;
00078   std::cout << "    Product     : " << eeprom.product << std::endl;
00079   std::cout << "    Vendor Id   : " << eeprom.vendor_id << std::endl;
00080   std::cout << "    Product Id  : " << eeprom.product_id << std::endl;
00081   std::cout << "    Serial Id   : " << eeprom.serial << std::endl;
00082   std::cout << "    Self Powered: " << eeprom.self_powered << std::endl;
00083   std::cout << "    Remote Wake : " << eeprom.remote_wakeup << std::endl;
00084   std::cout << "    Use Serial  : " << eeprom.use_serial << std::endl;
00085   std::cout << "    In Iso      : " << eeprom.in_is_isochronous << std::endl;
00086   std::cout << "    Out Iso     : " << eeprom.out_is_isochronous << std::endl;
00087   std::cout << "    Suspend     : " << eeprom.suspend_pull_downs << std::endl;
00088   std::cout << "    Max Power   : " << eeprom.max_power << std::endl;
00089   std::cout << "    Chip Type   : " << eeprom.chip_type << std::endl;
00090   return true;
00091 }
00092 /*****************************************************************************
00093  ** Main
00094  *****************************************************************************/
00095 
00096 int main(int argc, char **argv)
00097 {
00098   const int vendor_id = 0x0403;
00099   const int product_id = 0x6001;
00100 
00101   /*********************
00102    ** Parse Command Line
00103    **********************/
00104   CmdLine cmd_line("This is used to read an eeprom on an ftdi device.", ' ', "0.1");
00105   ValueArg<std::string> serial_arg(
00106       "s", "serial", "Identify the device via the old serial id (if there are multiple attached) ['unspecified'].", false,
00107       "unspecified", "string");
00108   cmd_line.add(serial_arg);
00109   cmd_line.parse(argc, argv);
00110   bool using_serial_id = false;
00111   string serial_id;
00112   if (serial_arg.getValue() != "unspecified")
00113   {
00114     using_serial_id = true;
00115     serial_id = serial_arg.getValue();
00116   }
00117 
00118   /*********************
00119    ** Debug output
00120    **********************/
00121   std::cout << "Input Information" << std::endl;
00122   if (!using_serial_id)
00123   {
00124     std::cout << "  Serial id: unused (first device found.)" << std::endl;
00125   }
00126   else
00127   {
00128     std::cout << "  Serial id: " << serial_id << std::endl;
00129   }
00130 
00131   /*********************
00132    ** Open a context
00133    **********************/
00134   struct ftdi_context ftdi;
00135   if (ftdi_init(&ftdi) < 0)
00136   {
00137     std::cerr << "ftdi_init failed" << std::endl;
00138     return EXIT_FAILURE;
00139   }
00140   if (!using_serial_id)
00141   { // simply open up the first found.
00142     if (ftdi_usb_open(&ftdi, vendor_id, product_id) != 0)
00143     {
00144       std::cerr << "Couldn't find/open an ftdi device [" << ftdi.error_str << "]" << std::endl;
00145       return EXIT_FAILURE;
00146     }
00147   }
00148   else
00149   {
00150     if (ftdi_usb_open_desc(&ftdi, vendor_id, product_id, NULL, serial_id.c_str()) < 0)
00151     {
00152       std::cerr << "Couldn't open the device with serial id string: " << serial_id << std::endl;
00153       return EXIT_FAILURE;
00154     }
00155   }
00156   /******************************************
00157    ** Eeeprom Binary (Requested size)
00158    *******************************************/
00159   std::cout << "Eeprom Binary" << std::endl;
00160   unsigned char eeprom_binary[512];
00161   int size = ftdi_read_eeprom_getsize(&ftdi, eeprom_binary, 512);
00162   if (size < 0)
00163   {
00164     std::cerr << "Error: Could not read the eeprom from the requested device." << std::endl;
00165     return EXIT_FAILURE;
00166   }
00167   std::cout << "  Read binary [" << size << " bytes]." << std::endl;
00168   std::cout << "  Write binary [eeprom.req]." << std::endl;
00169   FILE *fp = fopen ("eeprom.req", "wb");
00170   fwrite (&eeprom_binary, 1, size, fp);
00171   fclose (fp);
00172 
00173   if ( !decode(eeprom_binary, size) ) {
00174     std::cerr << "Error: Could not write raw binary eeprom into the eeprom structure." << std::endl;
00175     return EXIT_FAILURE;
00176   }
00177 
00178 #if REQUEST_EEPROM_SIZE
00179   /******************************************
00180    ** Eeeprom Binary (Fixed size)
00181    *******************************************/
00182   // this is what the official example does.
00183   size = 128;
00184   int result = ftdi_read_eeprom(&ftdi,eeprom_binary);
00185   if ( result < 0 ) {
00186     std::cerr << "Error: Could not read the eeprom from the requested device." << std::endl;
00187     return EXIT_FAILURE;
00188   }
00189   fp = fopen ("eeprom.fix", "wb");
00190   fwrite (&eeprom_binary, 1, size, fp);
00191   fclose (fp);
00192   std::cout << "  Write binary [eeprom.fix]." << std::endl;
00193 
00194   if ( !decode(eeprom_binary, size) ) {
00195     std::cerr << "Error: Could not write raw binary eeprom into the eeprom structure." << std::endl;
00196     return EXIT_FAILURE;
00197   }
00198 #endif
00199   std::cout << "Done." << std::endl;
00200 
00201   return 0;
00202 }
00203 


kobuki_ftdi
Author(s): Younghun Ju
autogenerated on Thu Jun 6 2019 20:24:42