ardupilot/libraries/doc/html/_data_flash_8cpp_source.html

380 lines
38 KiB
HTML
Raw Blame History

This file contains ambiguous Unicode characters

This file contains Unicode characters that might be confused with other characters. If you think that this is intentional, you can safely ignore this warning. Use the Escape button to reveal them.

<!DOCTYPE html PUBLIC "-//W3C//DTD XHTML 1.0 Transitional//EN" "http://www.w3.org/TR/xhtml1/DTD/xhtml1-transitional.dtd">
<html xmlns="http://www.w3.org/1999/xhtml">
<head>
<meta http-equiv="Content-Type" content="text/xhtml;charset=UTF-8"/>
<title>ArduPilot Libraries: /home/jgoppert/Projects/ap/libraries/DataFlash/DataFlash.cpp Source File</title>
<link href="tabs.css" rel="stylesheet" type="text/css"/>
<link href="doxygen.css" rel="stylesheet" type="text/css"/>
</head>
<body>
<!-- Generated by Doxygen 1.7.1 -->
<div class="navigation" id="top">
<div class="tabs">
<ul class="tablist">
<li><a href="main.html"><span>Main&nbsp;Page</span></a></li>
<li><a href="namespaces.html"><span>Namespaces</span></a></li>
<li><a href="annotated.html"><span>Classes</span></a></li>
<li class="current"><a href="files.html"><span>Files</span></a></li>
</ul>
</div>
<div class="tabs2">
<ul class="tablist">
<li><a href="files.html"><span>File&nbsp;List</span></a></li>
<li><a href="globals.html"><span>File&nbsp;Members</span></a></li>
</ul>
</div>
<div class="header">
<div class="headertitle">
<h1>/home/jgoppert/Projects/ap/libraries/DataFlash/DataFlash.cpp</h1> </div>
</div>
<div class="contents">
<a href="_data_flash_8cpp.html">Go to the documentation of this file.</a><div class="fragment"><pre class="fragment"><a name="l00001"></a>00001 <span class="comment">/*</span>
<a name="l00002"></a>00002 <span class="comment"> DataFlash.cpp - DataFlash log library for AT45DB161</span>
<a name="l00003"></a>00003 <span class="comment"> Code by Jordi Muñoz and Jose Julio. DIYDrones.com</span>
<a name="l00004"></a>00004 <span class="comment"> This code works with boards based on ATMega168/328 and ATMega1280/2560 using SPI port</span>
<a name="l00005"></a>00005 <span class="comment"></span>
<a name="l00006"></a>00006 <span class="comment"> This library is free software; you can redistribute it and/or</span>
<a name="l00007"></a>00007 <span class="comment"> modify it under the terms of the GNU Lesser General Public</span>
<a name="l00008"></a>00008 <span class="comment"> License as published by the Free Software Foundation; either</span>
<a name="l00009"></a>00009 <span class="comment"> version 2.1 of the License, or (at your option) any later version.</span>
<a name="l00010"></a>00010 <span class="comment"></span>
<a name="l00011"></a>00011 <span class="comment"> Dataflash library for AT45DB161D flash memory</span>
<a name="l00012"></a>00012 <span class="comment"> Memory organization : 4096 pages of 512 bytes</span>
<a name="l00013"></a>00013 <span class="comment"></span>
<a name="l00014"></a>00014 <span class="comment"> Maximun write bandwidth : 512 bytes in 14ms</span>
<a name="l00015"></a>00015 <span class="comment"> This code is written so the master never has to wait to write the data on the eeprom</span>
<a name="l00016"></a>00016 <span class="comment"></span>
<a name="l00017"></a>00017 <span class="comment"> Methods:</span>
<a name="l00018"></a>00018 <span class="comment"> Init() : Library initialization (SPI initialization)</span>
<a name="l00019"></a>00019 <span class="comment"> StartWrite(page) : Start a write session. page=start page.</span>
<a name="l00020"></a>00020 <span class="comment"> WriteByte(data) : Write a byte</span>
<a name="l00021"></a>00021 <span class="comment"> WriteInt(data) : Write an integer (2 bytes)</span>
<a name="l00022"></a>00022 <span class="comment"> WriteLong(data) : Write a long (4 bytes)</span>
<a name="l00023"></a>00023 <span class="comment"> StartRead(page) : Start a read on (page)</span>
<a name="l00024"></a>00024 <span class="comment"> GetWritePage() : Returns the last page written to</span>
<a name="l00025"></a>00025 <span class="comment"> GetPage() : Returns the last page read</span>
<a name="l00026"></a>00026 <span class="comment"> ReadByte()</span>
<a name="l00027"></a>00027 <span class="comment"> ReadInt()</span>
<a name="l00028"></a>00028 <span class="comment"> ReadLong()</span>
<a name="l00029"></a>00029 <span class="comment"> </span>
<a name="l00030"></a>00030 <span class="comment"> Properties:</span>
<a name="l00031"></a>00031 <span class="comment"> </span>
<a name="l00032"></a>00032 <span class="comment">*/</span>
<a name="l00033"></a>00033
<a name="l00034"></a>00034 <span class="keyword">extern</span> <span class="stringliteral">&quot;C&quot;</span> {
<a name="l00035"></a>00035 <span class="comment">// AVR LibC Includes</span>
<a name="l00036"></a>00036 <span class="preprocessor"> #include &lt;inttypes.h&gt;</span>
<a name="l00037"></a>00037 <span class="preprocessor"> #include &lt;avr/interrupt.h&gt;</span>
<a name="l00038"></a>00038 <span class="preprocessor"> #include &quot;WConstants.h&quot;</span>
<a name="l00039"></a>00039 }
<a name="l00040"></a>00040
<a name="l00041"></a>00041 <span class="preprocessor">#include &quot;<a class="code" href="_data_flash_8h.html">DataFlash.h</a>&quot;</span>
<a name="l00042"></a>00042
<a name="l00043"></a><a class="code" href="_data_flash_8cpp.html#ad98bf7aeba8d826f4a6fa582cf3db870">00043</a> <span class="preprocessor">#define OVERWRITE_DATA 0 // 0: When reach the end page stop, 1: Start overwritten from page 1</span>
<a name="l00044"></a>00044 <span class="preprocessor"></span>
<a name="l00045"></a>00045 <span class="comment">// *** INTERNAL FUNCTIONS ***</span>
<a name="l00046"></a><a class="code" href="_data_flash_8cpp.html#aae4ffcc0a2fcb9d9c0c4ad4c9f6b89e2">00046</a> <span class="keywordtype">unsigned</span> <span class="keywordtype">char</span> <a class="code" href="_data_flash_8cpp.html#aae4ffcc0a2fcb9d9c0c4ad4c9f6b89e2">dataflash_SPI_transfer</a>(<span class="keywordtype">unsigned</span> <span class="keywordtype">char</span> output)
<a name="l00047"></a>00047 {
<a name="l00048"></a>00048 SPDR = output; <span class="comment">// Start the transmission</span>
<a name="l00049"></a>00049 <span class="keywordflow">while</span> (!(SPSR &amp; (1&lt;&lt;SPIF))); <span class="comment">// Wait the end of the transmission</span>
<a name="l00050"></a>00050 <span class="keywordflow">return</span> SPDR;
<a name="l00051"></a>00051 }
<a name="l00052"></a>00052
<a name="l00053"></a><a class="code" href="_data_flash_8cpp.html#a9a80f3c5d30f0297a827ba3eb9de4d9d">00053</a> <span class="keywordtype">void</span> <a class="code" href="_data_flash_8cpp.html#a9a80f3c5d30f0297a827ba3eb9de4d9d">dataflash_CS_inactive</a>()
<a name="l00054"></a>00054 {
<a name="l00055"></a>00055 digitalWrite(<a class="code" href="_data_flash_8h.html#a3d4144bb59959e2dbd29c59ffa7929c4">DF_SLAVESELECT</a>,HIGH); <span class="comment">//disable device</span>
<a name="l00056"></a>00056 }
<a name="l00057"></a>00057
<a name="l00058"></a><a class="code" href="_data_flash_8cpp.html#acdfe2e3e0fbee9d5002bdbd5e5790f07">00058</a> <span class="keywordtype">void</span> <a class="code" href="_data_flash_8cpp.html#acdfe2e3e0fbee9d5002bdbd5e5790f07">dataflash_CS_active</a>()
<a name="l00059"></a>00059 {
<a name="l00060"></a>00060 digitalWrite(<a class="code" href="_data_flash_8h.html#a3d4144bb59959e2dbd29c59ffa7929c4">DF_SLAVESELECT</a>,LOW); <span class="comment">//enable device</span>
<a name="l00061"></a>00061 }
<a name="l00062"></a>00062
<a name="l00063"></a>00063 <span class="comment">// Constructors ////////////////////////////////////////////////////////////////</span>
<a name="l00064"></a><a class="code" href="class_data_flash___class.html#abcc7740c0c53f4594363724b8d11507e">00064</a> <a class="code" href="class_data_flash___class.html#abcc7740c0c53f4594363724b8d11507e">DataFlash_Class::DataFlash_Class</a>()
<a name="l00065"></a>00065 {
<a name="l00066"></a>00066 }
<a name="l00067"></a>00067
<a name="l00068"></a>00068 <span class="comment">// Public Methods //////////////////////////////////////////////////////////////</span>
<a name="l00069"></a><a class="code" href="class_data_flash___class.html#a5fdc7b891bfc48371cc07cf0fa659a71">00069</a> <span class="keywordtype">void</span> <a class="code" href="class_data_flash___class.html#a5fdc7b891bfc48371cc07cf0fa659a71">DataFlash_Class::Init</a>(<span class="keywordtype">void</span>)
<a name="l00070"></a>00070 {
<a name="l00071"></a>00071 byte tmp;
<a name="l00072"></a>00072
<a name="l00073"></a>00073 pinMode(<a class="code" href="_data_flash_8h.html#aaa2878b0f1626b886a345091dba1b092">DF_DATAOUT</a>, OUTPUT);
<a name="l00074"></a>00074 pinMode(<a class="code" href="_data_flash_8h.html#a6419289dfca78751031fc7b4ed09bd92">DF_DATAIN</a>, INPUT);
<a name="l00075"></a>00075 pinMode(<a class="code" href="_data_flash_8h.html#a1489251f9709f3a899f66dbcb9a03580">DF_SPICLOCK</a>,OUTPUT);
<a name="l00076"></a>00076 pinMode(<a class="code" href="_data_flash_8h.html#a3d4144bb59959e2dbd29c59ffa7929c4">DF_SLAVESELECT</a>,OUTPUT);
<a name="l00077"></a>00077 <span class="preprocessor"> #if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)</span>
<a name="l00078"></a>00078 <span class="preprocessor"></span> pinMode(DF_RESET,OUTPUT);
<a name="l00079"></a>00079 <span class="comment">// Reset the chip</span>
<a name="l00080"></a>00080 digitalWrite(DF_RESET,LOW);
<a name="l00081"></a>00081 delay(1);
<a name="l00082"></a>00082 digitalWrite(DF_RESET,HIGH);
<a name="l00083"></a>00083 <span class="preprocessor"> #endif</span>
<a name="l00084"></a>00084 <span class="preprocessor"></span>
<a name="l00085"></a>00085 df_Read_END=<span class="keyword">false</span>;
<a name="l00086"></a>00086
<a name="l00087"></a>00087 <a class="code" href="_data_flash_8cpp.html#a9a80f3c5d30f0297a827ba3eb9de4d9d">dataflash_CS_inactive</a>(); <span class="comment">//disable device</span>
<a name="l00088"></a>00088
<a name="l00089"></a>00089 <span class="comment">// Setup SPI Master, Mode 3, fosc/4 = 4MHz</span>
<a name="l00090"></a>00090 SPCR = (1&lt;&lt;SPE)|(1&lt;&lt;MSTR)|(1&lt;&lt;CPHA)|(1&lt;&lt;CPOL);
<a name="l00091"></a>00091 <span class="comment">// Setup SPI Master, Mode 3, 2MHz</span>
<a name="l00092"></a>00092 <span class="comment">//SPCR = (1&lt;&lt;SPE)|(1&lt;&lt;MSTR)|(1&lt;&lt;CPHA)|(1&lt;&lt;CPOL)|(1&lt;&lt;SPR0);</span>
<a name="l00093"></a>00093 <span class="comment">//SPSR = (1&lt;&lt;SPI2X);</span>
<a name="l00094"></a>00094 <span class="comment">// Cleanup registers...</span>
<a name="l00095"></a>00095 tmp=SPSR;
<a name="l00096"></a>00096 tmp=SPDR;
<a name="l00097"></a>00097 }
<a name="l00098"></a>00098
<a name="l00099"></a>00099 <span class="comment">// This function is mainly to test the device</span>
<a name="l00100"></a><a class="code" href="class_data_flash___class.html#a213908bcc4846bb7425a910da9295d44">00100</a> <span class="keywordtype">void</span> <a class="code" href="class_data_flash___class.html#a213908bcc4846bb7425a910da9295d44">DataFlash_Class::ReadManufacturerID</a>()
<a name="l00101"></a>00101 {
<a name="l00102"></a>00102 byte tmp;
<a name="l00103"></a>00103
<a name="l00104"></a>00104 <a class="code" href="_data_flash_8cpp.html#a9a80f3c5d30f0297a827ba3eb9de4d9d">dataflash_CS_inactive</a>(); <span class="comment">// Reset dataflash command decoder</span>
<a name="l00105"></a>00105 <a class="code" href="_data_flash_8cpp.html#acdfe2e3e0fbee9d5002bdbd5e5790f07">dataflash_CS_active</a>();
<a name="l00106"></a>00106
<a name="l00107"></a>00107 <span class="comment">// Read manufacturer and ID command...</span>
<a name="l00108"></a>00108 <a class="code" href="_data_flash_8cpp.html#aae4ffcc0a2fcb9d9c0c4ad4c9f6b89e2">dataflash_SPI_transfer</a>(<a class="code" href="_data_flash_8h.html#a6eb7b731278d544c706f0d2f5751b93f">DF_READ_MANUFACTURER_AND_DEVICE_ID</a>);
<a name="l00109"></a>00109
<a name="l00110"></a>00110 <a class="code" href="class_data_flash___class.html#ad575934014354e081340a96073159d79">df_manufacturer</a> = <a class="code" href="_data_flash_8cpp.html#aae4ffcc0a2fcb9d9c0c4ad4c9f6b89e2">dataflash_SPI_transfer</a>(0xff);
<a name="l00111"></a>00111 <a class="code" href="class_data_flash___class.html#a59c96ff23d9ae8c64b76f1a41b0a82c0">df_device_0</a> = <a class="code" href="_data_flash_8cpp.html#aae4ffcc0a2fcb9d9c0c4ad4c9f6b89e2">dataflash_SPI_transfer</a>(0xff);
<a name="l00112"></a>00112 <a class="code" href="class_data_flash___class.html#acacd168d6bf0cf536492ec857d134b40">df_device_1</a> = <a class="code" href="_data_flash_8cpp.html#aae4ffcc0a2fcb9d9c0c4ad4c9f6b89e2">dataflash_SPI_transfer</a>(0xff);
<a name="l00113"></a>00113 tmp = <a class="code" href="_data_flash_8cpp.html#aae4ffcc0a2fcb9d9c0c4ad4c9f6b89e2">dataflash_SPI_transfer</a>(0xff);
<a name="l00114"></a>00114 }
<a name="l00115"></a>00115
<a name="l00116"></a>00116 <span class="comment">// Read the status of the DataFlash</span>
<a name="l00117"></a>00117 byte DataFlash_Class::ReadStatus()
<a name="l00118"></a>00118 {
<a name="l00119"></a>00119 byte tmp;
<a name="l00120"></a>00120
<a name="l00121"></a>00121 <a class="code" href="_data_flash_8cpp.html#a9a80f3c5d30f0297a827ba3eb9de4d9d">dataflash_CS_inactive</a>(); <span class="comment">// Reset dataflash command decoder</span>
<a name="l00122"></a>00122 <a class="code" href="_data_flash_8cpp.html#acdfe2e3e0fbee9d5002bdbd5e5790f07">dataflash_CS_active</a>();
<a name="l00123"></a>00123
<a name="l00124"></a>00124 <span class="comment">// Read status command</span>
<a name="l00125"></a>00125 <a class="code" href="_data_flash_8cpp.html#aae4ffcc0a2fcb9d9c0c4ad4c9f6b89e2">dataflash_SPI_transfer</a>(<a class="code" href="_data_flash_8h.html#a301281323b66b8625e78b7888032534d">DF_STATUS_REGISTER_READ</a>);
<a name="l00126"></a>00126 tmp = <a class="code" href="_data_flash_8cpp.html#aae4ffcc0a2fcb9d9c0c4ad4c9f6b89e2">dataflash_SPI_transfer</a>(0x00);
<a name="l00127"></a>00127 <span class="keywordflow">return</span>(tmp&amp;0x80); <span class="comment">// We only want to extract the READY/BUSY bit</span>
<a name="l00128"></a>00128 }
<a name="l00129"></a>00129
<a name="l00130"></a>00130 <span class="comment">// Wait until DataFlash is in ready state...</span>
<a name="l00131"></a>00131 <span class="keywordtype">void</span> DataFlash_Class::WaitReady()
<a name="l00132"></a>00132 {
<a name="l00133"></a>00133 <span class="keywordflow">while</span>(!ReadStatus());
<a name="l00134"></a>00134 }
<a name="l00135"></a>00135
<a name="l00136"></a>00136 <span class="keywordtype">void</span> DataFlash_Class::PageToBuffer(<span class="keywordtype">unsigned</span> <span class="keywordtype">char</span> BufferNum, <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> PageAdr)
<a name="l00137"></a>00137 {
<a name="l00138"></a>00138 <a class="code" href="_data_flash_8cpp.html#a9a80f3c5d30f0297a827ba3eb9de4d9d">dataflash_CS_inactive</a>();
<a name="l00139"></a>00139 <a class="code" href="_data_flash_8cpp.html#acdfe2e3e0fbee9d5002bdbd5e5790f07">dataflash_CS_active</a>();
<a name="l00140"></a>00140 <span class="keywordflow">if</span> (BufferNum==1)
<a name="l00141"></a>00141 <a class="code" href="_data_flash_8cpp.html#aae4ffcc0a2fcb9d9c0c4ad4c9f6b89e2">dataflash_SPI_transfer</a>(<a class="code" href="_data_flash_8h.html#aa2b2a3b0192a2a9575da517fe7b35139">DF_TRANSFER_PAGE_TO_BUFFER_1</a>);
<a name="l00142"></a>00142 <span class="keywordflow">else</span>
<a name="l00143"></a>00143 <a class="code" href="_data_flash_8cpp.html#aae4ffcc0a2fcb9d9c0c4ad4c9f6b89e2">dataflash_SPI_transfer</a>(<a class="code" href="_data_flash_8h.html#a4af5551c8aff40af21b589e979620997">DF_TRANSFER_PAGE_TO_BUFFER_2</a>);
<a name="l00144"></a>00144 <a class="code" href="_data_flash_8cpp.html#aae4ffcc0a2fcb9d9c0c4ad4c9f6b89e2">dataflash_SPI_transfer</a>((<span class="keywordtype">unsigned</span> <span class="keywordtype">char</span>)(PageAdr &gt;&gt; 6));
<a name="l00145"></a>00145 <a class="code" href="_data_flash_8cpp.html#aae4ffcc0a2fcb9d9c0c4ad4c9f6b89e2">dataflash_SPI_transfer</a>((<span class="keywordtype">unsigned</span> <span class="keywordtype">char</span>)(PageAdr &lt;&lt; 2));
<a name="l00146"></a>00146 <a class="code" href="_data_flash_8cpp.html#aae4ffcc0a2fcb9d9c0c4ad4c9f6b89e2">dataflash_SPI_transfer</a>(0x00); <span class="comment">// don´t care bytes </span>
<a name="l00147"></a>00147
<a name="l00148"></a>00148 <a class="code" href="_data_flash_8cpp.html#a9a80f3c5d30f0297a827ba3eb9de4d9d">dataflash_CS_inactive</a>(); <span class="comment">//initiate the transfer</span>
<a name="l00149"></a>00149 <a class="code" href="_data_flash_8cpp.html#acdfe2e3e0fbee9d5002bdbd5e5790f07">dataflash_CS_active</a>();
<a name="l00150"></a>00150
<a name="l00151"></a>00151 <span class="keywordflow">while</span>(!ReadStatus()); <span class="comment">//monitor the status register, wait until busy-flag is high</span>
<a name="l00152"></a>00152 }
<a name="l00153"></a>00153
<a name="l00154"></a>00154 <span class="keywordtype">void</span> DataFlash_Class::BufferToPage (<span class="keywordtype">unsigned</span> <span class="keywordtype">char</span> BufferNum, <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> PageAdr, <span class="keywordtype">unsigned</span> <span class="keywordtype">char</span> wait)
<a name="l00155"></a>00155 {
<a name="l00156"></a>00156 <a class="code" href="_data_flash_8cpp.html#a9a80f3c5d30f0297a827ba3eb9de4d9d">dataflash_CS_inactive</a>(); <span class="comment">// Reset dataflash command decoder</span>
<a name="l00157"></a>00157 <a class="code" href="_data_flash_8cpp.html#acdfe2e3e0fbee9d5002bdbd5e5790f07">dataflash_CS_active</a>();
<a name="l00158"></a>00158
<a name="l00159"></a>00159 <span class="keywordflow">if</span> (BufferNum==1)
<a name="l00160"></a>00160 <a class="code" href="_data_flash_8cpp.html#aae4ffcc0a2fcb9d9c0c4ad4c9f6b89e2">dataflash_SPI_transfer</a>(<a class="code" href="_data_flash_8h.html#a459772a80f5fb0fbb18be7a0b5569cf5">DF_BUFFER_1_TO_PAGE_WITH_ERASE</a>);
<a name="l00161"></a>00161 <span class="keywordflow">else</span>
<a name="l00162"></a>00162 <a class="code" href="_data_flash_8cpp.html#aae4ffcc0a2fcb9d9c0c4ad4c9f6b89e2">dataflash_SPI_transfer</a>(<a class="code" href="_data_flash_8h.html#a4c5025dd00c27c948575fde479403317">DF_BUFFER_2_TO_PAGE_WITH_ERASE</a>);
<a name="l00163"></a>00163 <a class="code" href="_data_flash_8cpp.html#aae4ffcc0a2fcb9d9c0c4ad4c9f6b89e2">dataflash_SPI_transfer</a>((<span class="keywordtype">unsigned</span> <span class="keywordtype">char</span>)(PageAdr &gt;&gt; 6));
<a name="l00164"></a>00164 <a class="code" href="_data_flash_8cpp.html#aae4ffcc0a2fcb9d9c0c4ad4c9f6b89e2">dataflash_SPI_transfer</a>((<span class="keywordtype">unsigned</span> <span class="keywordtype">char</span>)(PageAdr &lt;&lt; 2));
<a name="l00165"></a>00165 <a class="code" href="_data_flash_8cpp.html#aae4ffcc0a2fcb9d9c0c4ad4c9f6b89e2">dataflash_SPI_transfer</a>(0x00); <span class="comment">// don´t care bytes </span>
<a name="l00166"></a>00166
<a name="l00167"></a>00167 <a class="code" href="_data_flash_8cpp.html#a9a80f3c5d30f0297a827ba3eb9de4d9d">dataflash_CS_inactive</a>(); <span class="comment">//initiate the transfer</span>
<a name="l00168"></a>00168 <a class="code" href="_data_flash_8cpp.html#acdfe2e3e0fbee9d5002bdbd5e5790f07">dataflash_CS_active</a>();
<a name="l00169"></a>00169
<a name="l00170"></a>00170 <span class="comment">// Check if we need to wait to write the buffer to memory or we can continue...</span>
<a name="l00171"></a>00171 <span class="keywordflow">if</span> (wait)
<a name="l00172"></a>00172 <span class="keywordflow">while</span>(!ReadStatus()); <span class="comment">//monitor the status register, wait until busy-flag is high</span>
<a name="l00173"></a>00173 }
<a name="l00174"></a>00174
<a name="l00175"></a>00175 <span class="keywordtype">void</span> DataFlash_Class::BufferWrite (<span class="keywordtype">unsigned</span> <span class="keywordtype">char</span> BufferNum, <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> IntPageAdr, <span class="keywordtype">unsigned</span> <span class="keywordtype">char</span> Data)
<a name="l00176"></a>00176 {
<a name="l00177"></a>00177 <a class="code" href="_data_flash_8cpp.html#a9a80f3c5d30f0297a827ba3eb9de4d9d">dataflash_CS_inactive</a>(); <span class="comment">// Reset dataflash command decoder</span>
<a name="l00178"></a>00178 <a class="code" href="_data_flash_8cpp.html#acdfe2e3e0fbee9d5002bdbd5e5790f07">dataflash_CS_active</a>();
<a name="l00179"></a>00179
<a name="l00180"></a>00180 <span class="keywordflow">if</span> (BufferNum==1)
<a name="l00181"></a>00181 <a class="code" href="_data_flash_8cpp.html#aae4ffcc0a2fcb9d9c0c4ad4c9f6b89e2">dataflash_SPI_transfer</a>(<a class="code" href="_data_flash_8h.html#aa11f0619bf3eb94dc1cd4bc85de77c78">DF_BUFFER_1_WRITE</a>);
<a name="l00182"></a>00182 <span class="keywordflow">else</span>
<a name="l00183"></a>00183 <a class="code" href="_data_flash_8cpp.html#aae4ffcc0a2fcb9d9c0c4ad4c9f6b89e2">dataflash_SPI_transfer</a>(<a class="code" href="_data_flash_8h.html#a21aa2e058c89c08ca202b67488bffc24">DF_BUFFER_2_WRITE</a>);
<a name="l00184"></a>00184 <a class="code" href="_data_flash_8cpp.html#aae4ffcc0a2fcb9d9c0c4ad4c9f6b89e2">dataflash_SPI_transfer</a>(0x00); <span class="comment">//don&#39;t cares</span>
<a name="l00185"></a>00185 <a class="code" href="_data_flash_8cpp.html#aae4ffcc0a2fcb9d9c0c4ad4c9f6b89e2">dataflash_SPI_transfer</a>((<span class="keywordtype">unsigned</span> <span class="keywordtype">char</span>)(IntPageAdr&gt;&gt;8)); <span class="comment">//upper part of internal buffer address</span>
<a name="l00186"></a>00186 <a class="code" href="_data_flash_8cpp.html#aae4ffcc0a2fcb9d9c0c4ad4c9f6b89e2">dataflash_SPI_transfer</a>((<span class="keywordtype">unsigned</span> <span class="keywordtype">char</span>)(IntPageAdr)); <span class="comment">//lower part of internal buffer address</span>
<a name="l00187"></a>00187 <a class="code" href="_data_flash_8cpp.html#aae4ffcc0a2fcb9d9c0c4ad4c9f6b89e2">dataflash_SPI_transfer</a>(Data); <span class="comment">//write data byte</span>
<a name="l00188"></a>00188 }
<a name="l00189"></a>00189
<a name="l00190"></a>00190 <span class="keywordtype">unsigned</span> <span class="keywordtype">char</span> DataFlash_Class::BufferRead (<span class="keywordtype">unsigned</span> <span class="keywordtype">char</span> BufferNum, <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> IntPageAdr)
<a name="l00191"></a>00191 {
<a name="l00192"></a>00192 byte tmp;
<a name="l00193"></a>00193
<a name="l00194"></a>00194 <a class="code" href="_data_flash_8cpp.html#a9a80f3c5d30f0297a827ba3eb9de4d9d">dataflash_CS_inactive</a>(); <span class="comment">// Reset dataflash command decoder</span>
<a name="l00195"></a>00195 <a class="code" href="_data_flash_8cpp.html#acdfe2e3e0fbee9d5002bdbd5e5790f07">dataflash_CS_active</a>();
<a name="l00196"></a>00196
<a name="l00197"></a>00197 <span class="keywordflow">if</span> (BufferNum==1)
<a name="l00198"></a>00198 <a class="code" href="_data_flash_8cpp.html#aae4ffcc0a2fcb9d9c0c4ad4c9f6b89e2">dataflash_SPI_transfer</a>(<a class="code" href="_data_flash_8h.html#a19df818e83558b75d9e61f740bb346db">DF_BUFFER_1_READ</a>);
<a name="l00199"></a>00199 <span class="keywordflow">else</span>
<a name="l00200"></a>00200 <a class="code" href="_data_flash_8cpp.html#aae4ffcc0a2fcb9d9c0c4ad4c9f6b89e2">dataflash_SPI_transfer</a>(<a class="code" href="_data_flash_8h.html#a289a660c7c5cd95f0cea2ad1911bf8d6">DF_BUFFER_2_READ</a>);
<a name="l00201"></a>00201 <a class="code" href="_data_flash_8cpp.html#aae4ffcc0a2fcb9d9c0c4ad4c9f6b89e2">dataflash_SPI_transfer</a>(0x00); <span class="comment">//don&#39;t cares</span>
<a name="l00202"></a>00202 <a class="code" href="_data_flash_8cpp.html#aae4ffcc0a2fcb9d9c0c4ad4c9f6b89e2">dataflash_SPI_transfer</a>((<span class="keywordtype">unsigned</span> <span class="keywordtype">char</span>)(IntPageAdr&gt;&gt;8)); <span class="comment">//upper part of internal buffer address</span>
<a name="l00203"></a>00203 <a class="code" href="_data_flash_8cpp.html#aae4ffcc0a2fcb9d9c0c4ad4c9f6b89e2">dataflash_SPI_transfer</a>((<span class="keywordtype">unsigned</span> <span class="keywordtype">char</span>)(IntPageAdr)); <span class="comment">//lower part of internal buffer address</span>
<a name="l00204"></a>00204 <a class="code" href="_data_flash_8cpp.html#aae4ffcc0a2fcb9d9c0c4ad4c9f6b89e2">dataflash_SPI_transfer</a>(0x00); <span class="comment">//don&#39;t cares</span>
<a name="l00205"></a>00205 tmp = <a class="code" href="_data_flash_8cpp.html#aae4ffcc0a2fcb9d9c0c4ad4c9f6b89e2">dataflash_SPI_transfer</a>(0x00); <span class="comment">//read data byte</span>
<a name="l00206"></a>00206
<a name="l00207"></a>00207 <span class="keywordflow">return</span> (tmp);
<a name="l00208"></a>00208 }
<a name="l00209"></a>00209 <span class="comment">// *** END OF INTERNAL FUNCTIONS ***</span>
<a name="l00210"></a>00210
<a name="l00211"></a><a class="code" href="class_data_flash___class.html#ab311b3c84c326b3164f6669e94644866">00211</a> <span class="keywordtype">void</span> <a class="code" href="class_data_flash___class.html#ab311b3c84c326b3164f6669e94644866">DataFlash_Class::PageErase</a> (<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> PageAdr)
<a name="l00212"></a>00212 {
<a name="l00213"></a>00213 <a class="code" href="_data_flash_8cpp.html#a9a80f3c5d30f0297a827ba3eb9de4d9d">dataflash_CS_inactive</a>(); <span class="comment">//make sure to toggle CS signal in order</span>
<a name="l00214"></a>00214 <a class="code" href="_data_flash_8cpp.html#acdfe2e3e0fbee9d5002bdbd5e5790f07">dataflash_CS_active</a>(); <span class="comment">//to reset Dataflash command decoder</span>
<a name="l00215"></a>00215 <a class="code" href="_data_flash_8cpp.html#aae4ffcc0a2fcb9d9c0c4ad4c9f6b89e2">dataflash_SPI_transfer</a>(<a class="code" href="_data_flash_8h.html#a51f149e02b27e8fa6b1a3e7140d95dcd">DF_PAGE_ERASE</a>); <span class="comment">// Command</span>
<a name="l00216"></a>00216 <a class="code" href="_data_flash_8cpp.html#aae4ffcc0a2fcb9d9c0c4ad4c9f6b89e2">dataflash_SPI_transfer</a>((<span class="keywordtype">unsigned</span> <span class="keywordtype">char</span>)(PageAdr &gt;&gt; 6)); <span class="comment">//upper part of page address</span>
<a name="l00217"></a>00217 <a class="code" href="_data_flash_8cpp.html#aae4ffcc0a2fcb9d9c0c4ad4c9f6b89e2">dataflash_SPI_transfer</a>((<span class="keywordtype">unsigned</span> <span class="keywordtype">char</span>)(PageAdr &lt;&lt; 2)); <span class="comment">//lower part of page address and MSB of int.page adr.</span>
<a name="l00218"></a>00218 <a class="code" href="_data_flash_8cpp.html#aae4ffcc0a2fcb9d9c0c4ad4c9f6b89e2">dataflash_SPI_transfer</a>(0x00); <span class="comment">// &quot;dont cares&quot;</span>
<a name="l00219"></a>00219 <a class="code" href="_data_flash_8cpp.html#a9a80f3c5d30f0297a827ba3eb9de4d9d">dataflash_CS_inactive</a>(); <span class="comment">//initiate flash page erase</span>
<a name="l00220"></a>00220 <a class="code" href="_data_flash_8cpp.html#acdfe2e3e0fbee9d5002bdbd5e5790f07">dataflash_CS_active</a>();
<a name="l00221"></a>00221 <span class="keywordflow">while</span>(!ReadStatus());
<a name="l00222"></a>00222 }
<a name="l00223"></a>00223
<a name="l00224"></a>00224 <span class="comment">// *** DATAFLASH PUBLIC FUNCTIONS ***</span>
<a name="l00225"></a><a class="code" href="class_data_flash___class.html#a2fcdc28eaa3667bb47f93a23bdc8855d">00225</a> <span class="keywordtype">void</span> <a class="code" href="class_data_flash___class.html#a2fcdc28eaa3667bb47f93a23bdc8855d">DataFlash_Class::StartWrite</a>(<span class="keywordtype">int</span> PageAdr)
<a name="l00226"></a>00226 {
<a name="l00227"></a>00227 df_BufferNum=1;
<a name="l00228"></a>00228 df_BufferIdx=0;
<a name="l00229"></a>00229 df_PageAdr=PageAdr;
<a name="l00230"></a>00230 df_Stop_Write=0;
<a name="l00231"></a>00231 WaitReady();
<a name="l00232"></a>00232 }
<a name="l00233"></a>00233
<a name="l00234"></a>00234 <span class="keywordtype">void</span> <a class="code" href="class_data_flash___class.html#a8c6c11c560d68667b326e52cc982d370">DataFlash_Class::WriteByte</a>(byte data)
<a name="l00235"></a>00235 {
<a name="l00236"></a>00236 <span class="keywordflow">if</span> (!df_Stop_Write)
<a name="l00237"></a>00237 {
<a name="l00238"></a>00238 BufferWrite(df_BufferNum,df_BufferIdx,data);
<a name="l00239"></a>00239 df_BufferIdx++;
<a name="l00240"></a>00240 <span class="keywordflow">if</span> (df_BufferIdx &gt;= 512) <span class="comment">// End of buffer?</span>
<a name="l00241"></a>00241 {
<a name="l00242"></a>00242 df_BufferIdx=0;
<a name="l00243"></a>00243 BufferToPage(df_BufferNum,df_PageAdr,0); <span class="comment">// Write Buffer to memory, NO WAIT</span>
<a name="l00244"></a>00244 df_PageAdr++;
<a name="l00245"></a>00245 <span class="keywordflow">if</span> (<a class="code" href="_data_flash_8cpp.html#ad98bf7aeba8d826f4a6fa582cf3db870">OVERWRITE_DATA</a>==1)
<a name="l00246"></a>00246 {
<a name="l00247"></a>00247 <span class="keywordflow">if</span> (df_PageAdr&gt;=4096) <span class="comment">// If we reach the end of the memory, start from the begining</span>
<a name="l00248"></a>00248 df_PageAdr = 1;
<a name="l00249"></a>00249 }
<a name="l00250"></a>00250 <span class="keywordflow">else</span>
<a name="l00251"></a>00251 {
<a name="l00252"></a>00252 <span class="keywordflow">if</span> (df_PageAdr&gt;=4096) <span class="comment">// If we reach the end of the memory, stop here</span>
<a name="l00253"></a>00253 df_Stop_Write=1;
<a name="l00254"></a>00254 }
<a name="l00255"></a>00255
<a name="l00256"></a>00256 <span class="keywordflow">if</span> (df_BufferNum==1) <span class="comment">// Change buffer to continue writing...</span>
<a name="l00257"></a>00257 df_BufferNum=2;
<a name="l00258"></a>00258 <span class="keywordflow">else</span>
<a name="l00259"></a>00259 df_BufferNum=1;
<a name="l00260"></a>00260 }
<a name="l00261"></a>00261 }
<a name="l00262"></a>00262 }
<a name="l00263"></a>00263
<a name="l00264"></a><a class="code" href="class_data_flash___class.html#ad2cb46986e1be119087204ca546ef5a2">00264</a> <span class="keywordtype">void</span> <a class="code" href="class_data_flash___class.html#ad2cb46986e1be119087204ca546ef5a2">DataFlash_Class::WriteInt</a>(<span class="keywordtype">int</span> data)
<a name="l00265"></a>00265 {
<a name="l00266"></a>00266 <a class="code" href="class_data_flash___class.html#a8c6c11c560d68667b326e52cc982d370">WriteByte</a>(data&gt;&gt;8); <span class="comment">// High byte</span>
<a name="l00267"></a>00267 <a class="code" href="class_data_flash___class.html#a8c6c11c560d68667b326e52cc982d370">WriteByte</a>(data&amp;0xFF); <span class="comment">// Low byte</span>
<a name="l00268"></a>00268 }
<a name="l00269"></a>00269
<a name="l00270"></a><a class="code" href="class_data_flash___class.html#aea5b8b87899d47b1daabe5e75204f8e9">00270</a> <span class="keywordtype">void</span> <a class="code" href="class_data_flash___class.html#aea5b8b87899d47b1daabe5e75204f8e9">DataFlash_Class::WriteLong</a>(<span class="keywordtype">long</span> data)
<a name="l00271"></a>00271 {
<a name="l00272"></a>00272 <a class="code" href="class_data_flash___class.html#a8c6c11c560d68667b326e52cc982d370">WriteByte</a>(data&gt;&gt;24); <span class="comment">// First byte</span>
<a name="l00273"></a>00273 <a class="code" href="class_data_flash___class.html#a8c6c11c560d68667b326e52cc982d370">WriteByte</a>(data&gt;&gt;16);
<a name="l00274"></a>00274 <a class="code" href="class_data_flash___class.html#a8c6c11c560d68667b326e52cc982d370">WriteByte</a>(data&gt;&gt;8);
<a name="l00275"></a>00275 <a class="code" href="class_data_flash___class.html#a8c6c11c560d68667b326e52cc982d370">WriteByte</a>(data&amp;0xFF); <span class="comment">// Last byte</span>
<a name="l00276"></a>00276 }
<a name="l00277"></a>00277
<a name="l00278"></a>00278 <span class="comment">// Get the last page written to</span>
<a name="l00279"></a><a class="code" href="class_data_flash___class.html#a8aa52719daf5fa94306eb0f4d6ff7f28">00279</a> <span class="keywordtype">int</span> <a class="code" href="class_data_flash___class.html#a8aa52719daf5fa94306eb0f4d6ff7f28">DataFlash_Class::GetWritePage</a>()
<a name="l00280"></a>00280 {
<a name="l00281"></a>00281 <span class="keywordflow">return</span>(df_PageAdr);
<a name="l00282"></a>00282 }
<a name="l00283"></a>00283
<a name="l00284"></a>00284 <span class="comment">// Get the last page read</span>
<a name="l00285"></a><a class="code" href="class_data_flash___class.html#a113d7be25c6f015b6a8bb3f909771281">00285</a> <span class="keywordtype">int</span> <a class="code" href="class_data_flash___class.html#a113d7be25c6f015b6a8bb3f909771281">DataFlash_Class::GetPage</a>()
<a name="l00286"></a>00286 {
<a name="l00287"></a>00287 <span class="keywordflow">return</span>(df_Read_PageAdr-1);
<a name="l00288"></a>00288 }
<a name="l00289"></a>00289
<a name="l00290"></a><a class="code" href="class_data_flash___class.html#af5e4a1c7035f798620666eb58ea29e96">00290</a> <span class="keywordtype">void</span> <a class="code" href="class_data_flash___class.html#af5e4a1c7035f798620666eb58ea29e96">DataFlash_Class::StartRead</a>(<span class="keywordtype">int</span> PageAdr)
<a name="l00291"></a>00291 {
<a name="l00292"></a>00292 df_Read_BufferNum=1;
<a name="l00293"></a>00293 df_Read_BufferIdx=0;
<a name="l00294"></a>00294 df_Read_PageAdr=PageAdr;
<a name="l00295"></a>00295 WaitReady();
<a name="l00296"></a>00296 PageToBuffer(df_Read_BufferNum,df_Read_PageAdr); <span class="comment">// Write Memory page to buffer</span>
<a name="l00297"></a>00297 df_Read_PageAdr++;
<a name="l00298"></a>00298 }
<a name="l00299"></a>00299
<a name="l00300"></a><a class="code" href="class_data_flash___class.html#afc7e765678010e275d581746bb25cd6f">00300</a> byte <a class="code" href="class_data_flash___class.html#afc7e765678010e275d581746bb25cd6f">DataFlash_Class::ReadByte</a>()
<a name="l00301"></a>00301 {
<a name="l00302"></a>00302 byte result;
<a name="l00303"></a>00303
<a name="l00304"></a>00304 WaitReady();
<a name="l00305"></a>00305 result = BufferRead(df_Read_BufferNum,df_Read_BufferIdx);
<a name="l00306"></a>00306 df_Read_BufferIdx++;
<a name="l00307"></a>00307 <span class="keywordflow">if</span> (df_Read_BufferIdx &gt;= 512) <span class="comment">// End of buffer?</span>
<a name="l00308"></a>00308 {
<a name="l00309"></a>00309 df_Read_BufferIdx=0;
<a name="l00310"></a>00310 PageToBuffer(df_Read_BufferNum,df_Read_PageAdr); <span class="comment">// Write memory page to Buffer</span>
<a name="l00311"></a>00311 df_Read_PageAdr++;
<a name="l00312"></a>00312 <span class="keywordflow">if</span> (df_Read_PageAdr&gt;=4096) <span class="comment">// If we reach the end of the memory, start from the begining</span>
<a name="l00313"></a>00313 {
<a name="l00314"></a>00314 df_Read_PageAdr = 0;
<a name="l00315"></a>00315 df_Read_END = <span class="keyword">true</span>;
<a name="l00316"></a>00316 }
<a name="l00317"></a>00317 }
<a name="l00318"></a>00318 <span class="keywordflow">return</span> result;
<a name="l00319"></a>00319 }
<a name="l00320"></a>00320
<a name="l00321"></a><a class="code" href="class_data_flash___class.html#a3da4020c0dab08fba5d1040c98d1adcc">00321</a> <span class="keywordtype">int</span> <a class="code" href="class_data_flash___class.html#a3da4020c0dab08fba5d1040c98d1adcc">DataFlash_Class::ReadInt</a>()
<a name="l00322"></a>00322 {
<a name="l00323"></a>00323 <span class="keywordtype">int</span> result;
<a name="l00324"></a>00324
<a name="l00325"></a>00325 result = <a class="code" href="class_data_flash___class.html#afc7e765678010e275d581746bb25cd6f">ReadByte</a>(); <span class="comment">// High byte</span>
<a name="l00326"></a>00326 result = (result&lt;&lt;8) | <a class="code" href="class_data_flash___class.html#afc7e765678010e275d581746bb25cd6f">ReadByte</a>(); <span class="comment">// Low byte</span>
<a name="l00327"></a>00327 <span class="keywordflow">return</span> result;
<a name="l00328"></a>00328 }
<a name="l00329"></a>00329
<a name="l00330"></a><a class="code" href="class_data_flash___class.html#a389c31bb2e704bf92af0d168021cdaa1">00330</a> <span class="keywordtype">long</span> <a class="code" href="class_data_flash___class.html#a389c31bb2e704bf92af0d168021cdaa1">DataFlash_Class::ReadLong</a>()
<a name="l00331"></a>00331 {
<a name="l00332"></a>00332 <span class="keywordtype">long</span> result;
<a name="l00333"></a>00333
<a name="l00334"></a>00334 result = <a class="code" href="class_data_flash___class.html#afc7e765678010e275d581746bb25cd6f">ReadByte</a>(); <span class="comment">// First byte</span>
<a name="l00335"></a>00335 result = (result&lt;&lt;8) | <a class="code" href="class_data_flash___class.html#afc7e765678010e275d581746bb25cd6f">ReadByte</a>();
<a name="l00336"></a>00336 result = (result&lt;&lt;8) | <a class="code" href="class_data_flash___class.html#afc7e765678010e275d581746bb25cd6f">ReadByte</a>();
<a name="l00337"></a>00337 result = (result&lt;&lt;8) | <a class="code" href="class_data_flash___class.html#afc7e765678010e275d581746bb25cd6f">ReadByte</a>(); <span class="comment">// Last byte</span>
<a name="l00338"></a>00338 <span class="keywordflow">return</span> result;
<a name="l00339"></a>00339 }
<a name="l00340"></a>00340
<a name="l00341"></a>00341 <span class="comment">// make one instance for the user to use</span>
<a name="l00342"></a><a class="code" href="_data_flash_8h.html#aa1b5aafe46e4156944e292005b7020fd">00342</a> <a class="code" href="class_data_flash___class.html">DataFlash_Class</a> <a class="code" href="_data_flash_8cpp.html#aa1b5aafe46e4156944e292005b7020fd">DataFlash</a>;
</pre></div></div>
</div>
<hr class="footer"/><address class="footer"><small>Generated on Sun Dec 26 2010 19:58:34 for ArduPilot Libraries by&nbsp;
<a href="http://www.doxygen.org/index.html">
<img class="footer" src="doxygen.png" alt="doxygen"/></a> 1.7.1 </small></address>
</body>
</html>