wg_eeprom.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2008, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
36 #include "ros/ros.h"
37 
38 #include <boost/thread.hpp>
39 
40 namespace ethercat_hardware
41 {
42 
43 
45 {
46  uint16_t page_;
47  union
48  {
49  uint8_t command_;
50  struct
51  {
52  uint8_t operation_ :4;
53  uint8_t start_ :1;
54  uint8_t busy_ :1;
55  uint8_t unused2_ :2;
56  }__attribute__ ((__packed__));
57  };
58 
59  void build_read(unsigned page)
60  {
61  this->page_ = page & 0xffff;
62  this->operation_ = SPI_READ_OP;
63  this->start_ = 1;
64  }
65  void build_write(unsigned page)
66  {
67  this->page_ = page & 0xffff;
68  this->operation_ = SPI_WRITE_OP;
69  this->start_ = 1;
70  }
71  void build_arbitrary(unsigned length)
72  {
73  this->page_ = (length-1) & 0xffff;
75  this->start_ = 1;
76  }
77 
78  static const unsigned SPI_READ_OP = 0;
79  static const unsigned SPI_WRITE_OP = 1;
80  static const unsigned SPI_ARBITRARY_OP = 3;
81 
82  static const unsigned SPI_COMMAND_ADDR = 0x0230;
83  static const unsigned SPI_BUFFER_ADDR = 0xF400;
84 }__attribute__ ((__packed__));
85 
86 
87 
89 {
90  union {
91  uint8_t raw_;
92  struct {
93  uint8_t page_size_ : 1;
94  uint8_t write_protect_ : 1;
95  uint8_t eeprom_size_ : 4;
96  uint8_t compare_ : 1;
97  uint8_t ready_ : 1;
98  } __attribute__ ((__packed__));
99  } __attribute__ ((__packed__));
100 } __attribute__ ((__packed__));
101 
102 
103 
104 
106 {
107 
108 }
109 
110 
120 {
122  // TODO : poll for a given number of millseconds instead of a given number of cycles
123  //start_time = 0;
124  unsigned tries = 0;
125  do {
126  //read_time = time;
127  ++tries;
128  if (!readSpiEepromCmd(com, mbx, cmd))
129  {
130  ROS_ERROR("Error reading SPI Eeprom Cmd busy bit");
131  return false;
132  }
133 
134  if (!cmd.busy_)
135  {
136  return true;
137  }
138 
139  usleep(100);
140  } while (tries <= 10);
141 
142  ROS_ERROR("Timed out waiting for SPI state machine to be idle (%d)", tries);
143  return false;
144 }
145 
146 
157 {
158  if (!waitForSpiEepromReady(com, mbx))
159  {
160  return false;
161  }
162 
163  // Send command
164  if (mbx->writeMailbox(com, WG0XSpiEepromCmd::SPI_COMMAND_ADDR, &cmd, sizeof(cmd)))
165  {
166  ROS_ERROR("Error writing SPI EEPROM command");
167  return false;
168  }
169 
170  // Now read back SPI EEPROM state machine register, and check :
171  // 1. for state machine to become ready
172  // 2. that command data was properly write and not corrupted
173  WG0XSpiEepromCmd stat;
174  unsigned tries = 0;
175  do
176  {
177  if (!readSpiEepromCmd(com, mbx, stat))
178  {
179  return false;
180  }
181 
182  if (stat.operation_ != cmd.operation_)
183  {
184  ROS_ERROR("Invalid readback of SPI EEPROM operation : got 0x%X, expected 0x%X\n", stat.operation_, cmd.operation_);
185  return false;
186  }
187 
188  // return true if command has completed
189  if (!stat.busy_)
190  {
191  if (tries > 0)
192  {
193  ROS_WARN("Eeprom state machine took %d cycles", tries);
194  }
195  return true;;
196  }
197 
198  fprintf(stderr, "eeprom busy reading again, waiting...\n");
199  usleep(100);
200  } while (++tries < 10);
201 
202  ROS_ERROR("Eeprom SPI state machine busy after %d cycles", tries);
203  return false;
204 }
205 
206 
221 bool WGEeprom::readEepromPage(EthercatCom *com, WGMailbox *mbx, unsigned page, void* data, unsigned length)
222 {
223  boost::lock_guard<boost::mutex> lock(mutex_);
224 
225  if (length > MAX_EEPROM_PAGE_SIZE)
226  {
227  ROS_ERROR("Eeprom read length %d > %d", length, MAX_EEPROM_PAGE_SIZE);
228  return false;
229  }
230 
231  if (page >= NUM_EEPROM_PAGES)
232  {
233  ROS_ERROR("Eeprom read page %d > %d", page, NUM_EEPROM_PAGES-1);
234  return false;
235  }
236 
237  // Since we don't know the size of the eeprom there is not always 264 bytes available.
238  // This may try to read 264 bytes, but only the first 256 bytes may be valid.
239  // To avoid any odd issue, zero out FPGA buffer before asking for eeprom data.
240  memset(data,0,length);
241  if (mbx->writeMailbox(com, WG0XSpiEepromCmd::SPI_BUFFER_ADDR, data, length))
242  {
243  ROS_ERROR("Error zeroing eeprom data buffer");
244  return false;
245  }
246 
247  // Send command to SPI state machine to perform read of eeprom,
248  // sendSpiEepromCmd will automatically wait for SPI state machine
249  // to be idle before a new command is sent
251  memset(&cmd,0,sizeof(cmd));
252  cmd.build_read(page);
253  if (!sendSpiEepromCmd(com, mbx, cmd))
254  {
255  ROS_ERROR("Error sending SPI read command");
256  return false;
257  }
258 
259  // Wait for SPI Eeprom Read to complete
260  // sendSPICommand will wait for Command to finish before returning
261 
262  // Read eeprom page data from FPGA buffer
263  if (mbx->readMailbox(com, WG0XSpiEepromCmd::SPI_BUFFER_ADDR, data, length))
264  {
265  ROS_ERROR("Error reading eeprom data from buffer");
266  return false;
267  }
268 
269  return true;
270 }
271 
272 
287 bool WGEeprom::writeEepromPage(EthercatCom *com, WGMailbox *mbx, unsigned page, const void* data, unsigned length)
288 {
289  boost::lock_guard<boost::mutex> lock(mutex_);
290 
291  if (length > 264)
292  {
293  ROS_ERROR("Eeprom write length %d > %d", length, MAX_EEPROM_PAGE_SIZE);
294  return false;
295  }
296 
297  if (page >= NUM_EEPROM_PAGES)
298  {
299  ROS_ERROR("Eeprom write page %d > %d", page, NUM_EEPROM_PAGES-1);
300  return false;
301  }
302 
303  // wait for eeprom to be ready before write data into FPGA buffer
304  if (!waitForSpiEepromReady(com, mbx))
305  {
306  return false;
307  }
308 
309  const void *write_buf = data;
310 
311  // if needed, pad data to 264 byte in buf
312  uint8_t buf[MAX_EEPROM_PAGE_SIZE];
313  if (length < MAX_EEPROM_PAGE_SIZE)
314  {
315  memcpy(buf, data, length);
316  memset(buf+length, 0xFF, MAX_EEPROM_PAGE_SIZE-length);
317  write_buf = buf;
318  }
319 
320  // Write data to FPGA buffer
321  if (mbx->writeMailbox(com, WG0XSpiEepromCmd::SPI_BUFFER_ADDR, write_buf, MAX_EEPROM_PAGE_SIZE))
322  {
323  ROS_ERROR("Write of SPI EEPROM buffer failed");
324  return false;
325  }
326 
327  // Have SPI EEPROM state machine start SPI data transfer
329  cmd.build_write(page);
330  if (!sendSpiEepromCmd(com, mbx, cmd))
331  {
332  ROS_ERROR("Error giving SPI EEPROM write command");
333  return false;
334  }
335 
336  // Wait for EEPROM write to complete
337  if (!waitForEepromReady(com, mbx))
338  {
339  return false;
340  }
341 
342  return true;
343 }
344 
345 
358 {
359  // Wait for eeprom write to complete
360  unsigned tries = 0;
361  EepromStatusReg status_reg;
362  do {
363  if (!readEepromStatusReg(com, mbx, status_reg))
364  {
365  return false;
366  }
367  if (status_reg.ready_)
368  {
369  break;
370  }
371  usleep(100);
372  } while (++tries < 20);
373 
374  if (!status_reg.ready_)
375  {
376  ROS_ERROR("Eeprom still busy after %d cycles", tries);
377  return false;
378  }
379 
380  if (tries > 10)
381  {
382  ROS_WARN("EEPROM took %d cycles to be ready", tries);
383  }
384  return true;
385 }
386 
387 
388 
400 {
401  // Status is read from EEPROM by having SPI state machine perform an "abitrary" operation.
402  // With an arbitrary operation, the SPI state machine shifts out byte from buffer, while
403  // storing byte shifted in from device into same location in buffer.
404  // SPI state machine has no idea what command it is sending device or how to intpret its result.
405 
406  // To read eeprom status register, we transfer 2 bytes. The first byte is the read status register
407  // command value (0xD7). When transfering the second byte, the EEPROM should send its status.
408  unsigned char data[2] = {0xD7, 0x00};
409  BOOST_STATIC_ASSERT(sizeof(data) == 2);
410  if (mbx->writeMailbox(com, WG0XSpiEepromCmd::SPI_BUFFER_ADDR, data, sizeof(data)))
411  {
412  ROS_ERROR("Writing SPI buffer");
413  return false;
414  }
415 
416  { // Have SPI state machine trasfer 2 bytes
418  cmd.build_arbitrary(sizeof(data));
419  if (!sendSpiEepromCmd(com, mbx, cmd))
420  {
421  ROS_ERROR("Sending SPI abitrary command");
422  return false;
423  }
424  }
425 
426  // Data read from device should now be stored in FPGA buffer
427  if (mbx->readMailbox(com, WG0XSpiEepromCmd::SPI_BUFFER_ADDR, data, sizeof(data)))
428  {
429  ROS_ERROR("Reading status register data from SPI buffer");
430  return false;
431  }
432 
433  // Status register would be second byte of buffer
434  reg.raw_ = data[1];
435  return true;
436 }
437 
438 
455 {
456  BOOST_STATIC_ASSERT(sizeof(WG0XSpiEepromCmd) == 3);
457  if (mbx->readMailbox(com, WG0XSpiEepromCmd::SPI_COMMAND_ADDR, &cmd, sizeof(cmd)))
458  {
459  ROS_ERROR("Reading SPI command register with mailbox");
460  return false;
461  }
462 
463  return true;
464 }
465 
466 
467 }; //end namespace ethercat_hardware
bool waitForEepromReady(EthercatCom *com, WGMailbox *mbx)
Waits for EEPROM to become ready.
Definition: wg_eeprom.cpp:357
uint8_t ready_
Definition: wg_eeprom.cpp:96
uint8_t eeprom_size_
Definition: wg_eeprom.cpp:94
uint16_t length
Definition: wg_util.h:119
bool sendSpiEepromCmd(EthercatCom *com, WGMailbox *mbx, const WG0XSpiEepromCmd &cmd)
Sends command to SPI EEPROM state machine.
Definition: wg_eeprom.cpp:156
string cmd
static const unsigned SPI_WRITE_OP
Definition: wg_eeprom.cpp:79
bool readSpiEepromCmd(EthercatCom *com, WGMailbox *mbx, WG0XSpiEepromCmd &cmd)
Reads SPI state machine command register.
Definition: wg_eeprom.cpp:454
data
uint8_t compare_
Definition: wg_eeprom.cpp:95
#define ROS_WARN(...)
bool writeEepromPage(EthercatCom *com, WGMailbox *mbx, unsigned page, const void *data, unsigned length)
Write data to single eeprom page.
Definition: wg_eeprom.cpp:287
void build_arbitrary(unsigned length)
Definition: wg_eeprom.cpp:71
int writeMailbox(EthercatCom *com, unsigned address, void const *data, unsigned length)
Write data to WG0X local bus using mailbox communication.
Definition: wg_mailbox.cpp:939
bool readEepromPage(EthercatCom *com, WGMailbox *mbx, unsigned page, void *data, unsigned length)
Read data from single eeprom page.
Definition: wg_eeprom.cpp:221
void build_write(unsigned page)
Definition: wg_eeprom.cpp:65
uint8_t write_protect_
Definition: wg_eeprom.cpp:93
void build_read(unsigned page)
Definition: wg_eeprom.cpp:59
static const unsigned SPI_ARBITRARY_OP
Definition: wg_eeprom.cpp:80
bool readEepromStatusReg(EthercatCom *com, WGMailbox *mbx, EepromStatusReg &reg)
Reads EEPROM status register.
Definition: wg_eeprom.cpp:399
int readMailbox(EthercatCom *com, unsigned address, void *data, unsigned length)
Read data from WG0X local bus using mailbox communication.
Definition: wg_mailbox.cpp:812
union ethercat_hardware::WG0XSpiEepromCmd::@53 __attribute__
uint8_t page_size_
Definition: wg_eeprom.cpp:92
static const unsigned SPI_COMMAND_ADDR
Definition: wg_eeprom.cpp:82
#define ROS_ERROR(...)
bool waitForSpiEepromReady(EthercatCom *com, WGMailbox *mbx)
Waits for SPI eeprom state machine to be idle.
Definition: wg_eeprom.cpp:119
static const unsigned SPI_BUFFER_ADDR
Definition: wg_eeprom.cpp:83
static const unsigned SPI_READ_OP
Definition: wg_eeprom.cpp:78


ethercat_hardware
Author(s): Rob Wheeler , Derek King
autogenerated on Fri Mar 15 2019 02:53:29