ftdi_write_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  */
00040 /*****************************************************************************
00041  ** Includes
00042  *****************************************************************************/
00043 
00044 #include <ftdi.h>
00045 #include <cstring>
00046 #include <ecl/command_line.hpp>
00047 
00048 /*****************************************************************************
00049  ** Main
00050  *****************************************************************************/
00051 
00052 int main(int argc, char **argv)
00053 {
00054   const int vendor_id = 0x0403;
00055   const int product_id = 0x6001;
00056   int result;
00057 
00058   /*********************
00059    ** Parse Command Line
00060    **********************/
00061   ecl::CmdLine cmd_line("This is used to write 'kobuki' on an ftdi device.", ' ', "0.1");
00062   ecl::ValueArg<std::string> serial_arg(
00063       "s", "serial", "Identify the device via the old serial id (if there are multiple attached) ['unspecified'].", false,
00064       "unspecified", "string");
00065   ecl::ValueArg<std::string> filename_arg(
00066       "f", "filename", "Name of the eeprom binary. ['eeprom.new'].", false,
00067       "eeprom.new", "string");
00068   cmd_line.add(serial_arg);
00069   cmd_line.add(filename_arg);
00070   cmd_line.parse(argc, argv);
00071   bool using_serial_id = false;
00072   std::string serial_id;
00073   if (serial_arg.getValue() != "unspecified")
00074   {
00075     using_serial_id = true;
00076     serial_id = serial_arg.getValue();
00077   }
00078   std::string filename = filename_arg.getValue();
00079 
00080   /*********************
00081    ** Debug output
00082    **********************/
00083   std::cout << "Input Information" << std::endl;
00084   if (!using_serial_id)
00085   {
00086     std::cout << "  Serial id: unused (first device found.)" << std::endl;
00087   }
00088   else
00089   {
00090     std::cout << "  Serial id: " << serial_id << std::endl;
00091   }
00092 
00093   /*********************
00094    ** Open a context
00095    **********************/
00096   struct ftdi_context ftdi;
00097   if (ftdi_init(&ftdi) < 0)
00098   {
00099     std::cerr << "ftdi_init failed" << std::endl;
00100     return EXIT_FAILURE;
00101   }
00102   if (!using_serial_id)
00103   { // simply open up the first found.
00104     if (ftdi_usb_open(&ftdi, vendor_id, product_id) != 0)
00105     {
00106       std::cerr << "Couldn't find/open an ftdi device [" << ftdi.error_str << "]" << std::endl;
00107       return EXIT_FAILURE;
00108     }
00109   }
00110   else
00111   {
00112     if (ftdi_usb_open_desc(&ftdi, vendor_id, product_id, NULL, serial_id.c_str()) < 0)
00113     {
00114       std::cerr << "Couldn't open the device with serial id string: " << serial_id << std::endl;
00115       return EXIT_FAILURE;
00116     }
00117   }
00118 
00119 
00120   /******************************************
00121    ** Load Eeeprom Binary
00122    *******************************************/
00123   std::cout << "Load eeprom binary" << std::endl;
00124   unsigned char eeprom_binary[512];
00125   FILE *fp = fopen(filename.c_str(), "rb");
00126   if ( fp == NULL ) {
00127     std::cerr << "Error: could not read the eeprom binary file." << std::endl;
00128     return EXIT_FAILURE;
00129   }
00130   size_t n = fread(eeprom_binary,1,512,fp);
00131   if ( ( n != 512 ) && ( !feof(fp) ) ) {
00132     std::cerr << "Error: failed read from eeoprom binary file" << std::endl;
00133   } else {
00134     std::cout << "  Size: " << n << " bytes" << std::endl;
00135   }
00136   fclose (fp);
00137 
00138   /*********************
00139   ** Erasing eeprom
00140   **********************/
00141   std::cout << "Erasing eeprom" << std::endl;
00142   result = ftdi_erase_eeprom(&ftdi);
00143   if ( result == -1 ) {
00144     std::cerr << "Error: erase failed." << std::endl;
00145     return EXIT_FAILURE;
00146   } else if ( result == -2 ) {
00147     std::cerr << "Error: usb device unavailable." << std::endl;
00148     return EXIT_FAILURE;
00149   } else {
00150     std::cout << "  Ok" << std::endl;
00151   }
00152 
00153   /*********************
00154   ** Flashing Eeprom
00155   **********************/
00156   std::cout << "Flashing eeprom" << std::endl;
00157   result = ftdi_write_eeprom(&ftdi, eeprom_binary);
00158   if (result < 0)
00159   {
00160     std::cerr << "Error : write failed [" << ftdi_get_error_string(&ftdi) << "]" << std::endl;
00161     return EXIT_FAILURE;
00162   } else {
00163     std::cout << "  Ok" << std::endl;
00164   }
00165 
00166   /*********************
00167   ** Cleanup
00168   **********************/
00169   std::cout << "Done." << std::endl;
00170 
00171   return 0;
00172 }
00173 


kobuki_ftdi
Author(s): Younghun Ju
autogenerated on Mon Oct 6 2014 01:31:47