writer.hpp
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  * RACT, 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  */
00037 /*****************************************************************************
00038  ** Includes
00039  *****************************************************************************/
00040 
00041 #include <cstring>
00042 #include <ftdi.h>
00043 
00044 /*****************************************************************************
00045  ** Definition
00046  *****************************************************************************/
00047 
00049 
00052 class FTDI_Writer {
00053 public:
00057   FTDI_Writer() :
00058     log_level(0),
00059     serial_only(false),
00060     use_first_device(false),
00061     vendor_id(0x0403),
00062     product_id(0x6001)
00063   {;}
00064 
00069   void reset_flags() {
00070     serial_only = false;
00071     use_first_device = false;
00072     return;
00073   }
00074 
00081   int write(const std::string &new_id_) {
00082     serial_only = true;
00083     use_first_device = true;
00084     int ret_val = write("", new_id_, "", "");
00085     reset_flags();
00086 
00087     return ret_val;
00088   }
00089 
00097   int write(const std::string &old_id_, const std::string &new_id_)
00098   {
00099     serial_only = true;
00100     int ret_val = write(old_id_, new_id_, "", "");
00101     reset_flags();
00102 
00103     return ret_val;
00104   }
00105 
00115   int write(const std::string &old_id_, const std::string &new_id_, const std::string &manufacturer_, const std::string &product_)
00116   {
00117 //    int ret;
00118 //    int i, no_devices;
00119     struct ftdi_context ftdic;
00120 //    struct ftdi_device_list *devlist, *curdev;
00121 /*
00122     char manufacturer[128], description[128];
00123     char serial[128];
00124 */
00125 
00126     /* Initialization */
00127     if (ftdi_init(&ftdic) < 0)
00128     {
00129       std::cerr << "ftdi_init failed" << std::endl;
00130       return -1;
00131     }
00132 
00133 //    if ((no_devices = ftdi_usb_find_all(&ftdic, &devlist, vendor_id, product_id)) < 0)
00134 //    {
00135 //      std::cerr << "ftdi_usb_find_all failed: " << ftdi_get_error_string(&ftdic) << std::endl;
00136 //      return -1;
00137 //    }
00138 //    std::cout << "Number of FTDI devices found: " << no_devices << std::endl;
00139 //    std::cout << std::endl;
00140 //
00141 //
00142 //    i = 0;
00143 //    for (curdev = devlist; curdev != NULL; i++)
00144 //    {
00145 //      if( i > no_devices ) break; // Exceptional cases
00146 //
00147 //      std::cout << "Target Device #" << i << std::endl;
00148 #if 0
00149       if ((ret = ftdi_usb_get_strings(&ftdic, curdev->dev, manufacturer, 128, description, 128, serial, 128)) < 0)
00150       {
00151         std::cerr << "ftdi_usb_get_strings failed: " << ftdi_get_error_string(&ftdic) << "." << std::endl;
00152         return -1;
00153         /*
00154         if( std::string(ftdi_get_error_string(&ftdic)).find("Operation not permitted")  == -1 ) {
00155           continue;
00156         }
00157         else
00158           return EXIT_FAILURE;
00159         */
00160       }
00161       std::cout << "  Manufacturer: " << manufacturer << std::endl;
00162       std::cout << "  Description : " << description << std::endl;
00163       std::cout << "  Serial Id   : " << serial << std::endl;
00164       std::cout << std::endl;
00165 
00166       if ((!use_first_device) && (serial != old_id_)) {
00167         std::cout << "It is not intedend target." << std::endl;
00168         std::cout << "target: " << old_id_ << ", current: " << serial << std::endl;
00169         curdev = curdev->next;
00170         continue;
00171       }
00172 #endif
00173       // Open the ftdi device
00174       if (use_first_device) {
00175         if (ftdi_usb_open(&ftdic, vendor_id, product_id) < 0)
00176         {
00177           std::cerr << "Couldn't find/open a ftdi device." << std::endl;
00178           return -1;
00179         }
00180       } else {
00181         if (ftdi_usb_open_desc(&ftdic, vendor_id, product_id, NULL, old_id_.c_str()) < 0)
00182         {
00183           std::cerr << "Couldn't open the device with serial id string " << old_id_ << std::endl;
00184           return -1;
00185         }
00186       }
00187 
00188       // Open an Eeprom
00189       //std::cout << "Eeprom Binary" << std::endl;
00190       ftdi_eeprom eeprom;
00191       unsigned char eeprom_binary[512];
00192       int result = ftdi_read_eeprom(&ftdic, eeprom_binary);
00193       int size = FTDI_DEFAULT_EEPROM_SIZE;
00194       // this never works for me
00195       // int size = ftdi_read_eeprom_getsize(&ftdi, eeprom_binary, 512);
00196       if (size < 0)
00197       {
00198         std::cerr << "Error: Could not read the eeprom from the requested device." << std::endl;
00199         return -1;
00200       }
00201       std::cout << "Read eeprom binary [" << size << " bytes]." << std::endl;
00202 
00203       std::cout << "Decoding into eeprom structure." << std::endl;
00204       // put the binary into an eeprom structure
00205       if ( ftdi_eeprom_decode(&eeprom, eeprom_binary, size) != 0 ) {
00206         std::cerr << "Error: Could not write raw binary eeprom into the eeprom structure." << std::endl;
00207         return -1;//EXIT_FAILURE;
00208       }
00209 
00210       std::string new_manufacturer = manufacturer_;
00211       std::string new_product = product_;
00212       std::string new_id = new_id_;
00213 
00214       //Preparnig eeprom data to write
00215       eeprom.chip_type = TYPE_R;
00216       eeprom.size = size;
00217       free(eeprom.serial);
00218       eeprom.serial = (char*)malloc(new_id.size() + 1);
00219       std::strcpy(eeprom.serial, new_id.c_str());
00220       if (!serial_only) {
00221         free(eeprom.manufacturer);
00222         eeprom.manufacturer = (char*)malloc(new_manufacturer.size() + 1);
00223         std::strcpy(eeprom.manufacturer, new_manufacturer.c_str());
00224         free(eeprom.product);
00225         eeprom.product = (char*)malloc(new_product.size() + 1);
00226         std::strcpy(eeprom.product, new_product.c_str());
00227       }
00228 
00229       /* Build new eeprom in binary */
00230       std::cout << "Building new eeprom binary." << std::endl;
00231       int eeprom_binary_length = ftdi_eeprom_build(&eeprom, eeprom_binary);
00232       if (eeprom_binary_length == -1)
00233       {
00234         std::cerr << "Eeprom binary exceeded 128 bytes, reduce the size of your strings." << std::endl;
00235         return -1;
00236         //continue;
00237         //return EXIT_FAILURE;
00238       }
00239       else if (eeprom_binary_length == -2)
00240       {
00241         std::cerr << "Eeprom structure not valid." << std::endl;
00242         return -1; //continue;
00243         //return EXIT_FAILURE;
00244       }
00245 
00246       /* Flashing eeprom on ftdi chip */
00247       std::cout << "Flashing eeprom binary." << std::endl;
00248       result = ftdi_write_eeprom(&ftdic, eeprom_binary);
00249       if (result < 0)
00250       {
00251         std::cerr << "  Could not rewrite the eeprom." << std::endl;
00252         return -1; //continue;
00253         //return EXIT_FAILURE;
00254       }
00255       std::cout << "  Flashed " << ftdic.eeprom_size << " bytes" << std::endl;
00256 
00257 #if 0
00258       // Verification
00259       if ((ret = ftdi_usb_get_strings(&ftdic, curdev->dev, manufacturer, 128, description, 128, serial, 128)) < 0)
00260       {
00261         std::cerr << "ftdi_usb_get_strings failed: " << ftdi_get_error_string(&ftdic) << "." << std::endl;
00262         return -1;
00263       }
00264       std::cout << "Verify Device #" << i << std::endl;
00265       std::cout << "  Manufacturer: " << manufacturer << std::endl;
00266       std::cout << "  Description : " << description << std::endl;
00267       std::cout << "  Serial Id   : " << serial << std::endl;
00268       std::cout << std::endl;
00269 #endif
00270       std::cout << "Done." << std::endl;
00271 //
00272 //      curdev = curdev->next;
00273 //    }
00274 //
00275 //    ftdi_list_free(&devlist);
00276     ftdi_deinit(&ftdic);
00277     return 0;
00278   }
00279 
00280 private:
00281   int log_level; 
00282   bool serial_only; 
00283   bool use_first_device; 
00288   const unsigned short vendor_id;
00289 
00293   const unsigned short product_id;
00294 };


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