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