Rev 118 | Rev 121 | Go to most recent revision | Details | Compare with Previous | Last modification | View Log | RSS feed
Rev | Author | Line No. | Line |
---|---|---|---|
1 | ingob | 1 | /*#######################################################################################*/ |
2 | /* !!! THIS IS NOT FREE SOFTWARE !!! */ |
||
3 | /*#######################################################################################*/ |
||
4 | // ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ |
||
5 | // + Copyright (c) 2008 Ingo Busker, Holger Buss |
||
6 | // + Nur für den privaten Gebrauch |
||
7 | // + FOR NON COMMERCIAL USE ONLY |
||
8 | // + www.MikroKopter.com |
||
9 | // ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ |
||
41 | ingob | 10 | // + Es gilt für das gesamte Projekt (Hardware, Software, Binärfiles, Sourcecode und Dokumentation), |
11 | // + dass eine Nutzung (auch auszugsweise) nur für den privaten (nicht-kommerziellen) Gebrauch zulässig ist. |
||
12 | // + Sollten direkte oder indirekte kommerzielle Absichten verfolgt werden, ist mit uns (info@mikrokopter.de) Kontakt |
||
13 | // + bzgl. der Nutzungsbedingungen aufzunehmen. |
||
1 | ingob | 14 | // + Eine kommerzielle Nutzung ist z.B.Verkauf von MikroKoptern, Bestückung und Verkauf von Platinen oder Bausätzen, |
15 | // + Verkauf von Luftbildaufnahmen, usw. |
||
16 | // ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ |
||
41 | ingob | 17 | // + Werden Teile des Quellcodes (mit oder ohne Modifikation) weiterverwendet oder veröffentlicht, |
1 | ingob | 18 | // + unterliegen sie auch diesen Nutzungsbedingungen und diese Nutzungsbedingungen incl. Copyright müssen dann beiliegen |
19 | // ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ |
||
20 | // + Sollte die Software (auch auszugesweise) oder sonstige Informationen des MikroKopter-Projekts |
||
21 | // + auf anderen Webseiten oder sonstigen Medien veröffentlicht werden, muss unsere Webseite "http://www.mikrokopter.de" |
||
22 | // + eindeutig als Ursprung verlinkt werden |
||
23 | // ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ |
||
24 | // + Keine Gewähr auf Fehlerfreiheit, Vollständigkeit oder Funktion |
||
25 | // + Benutzung auf eigene Gefahr |
||
26 | // + Wir übernehmen keinerlei Haftung für direkte oder indirekte Personen- oder Sachschäden |
||
27 | // ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ |
||
41 | ingob | 28 | // + Die PORTIERUNG der Software (oder Teile davon) auf andere Systeme (ausser der Hardware von www.mikrokopter.de) ist nur |
1 | ingob | 29 | // + mit unserer Zustimmung zulässig |
30 | // ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ |
||
31 | // + Die Funktion printf_P() unterliegt ihrer eigenen Lizenz und ist hiervon nicht betroffen |
||
32 | // ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ |
||
41 | ingob | 33 | // + Redistributions of source code (with or without modifications) must retain the above copyright notice, |
1 | ingob | 34 | // + this list of conditions and the following disclaimer. |
35 | // + * Neither the name of the copyright holders nor the names of contributors may be used to endorse or promote products derived |
||
36 | // + from this software without specific prior written permission. |
||
41 | ingob | 37 | // + * The use of this project (hardware, software, binary files, sources and documentation) is only permitted |
1 | ingob | 38 | // + for non-commercial use (directly or indirectly) |
41 | ingob | 39 | // + Commercial use (for excample: selling of MikroKopters, selling of PCBs, assembly, ...) is only permitted |
1 | ingob | 40 | // + with our written permission |
41 | ingob | 41 | // + * If sources or documentations are redistributet on other webpages, out webpage (http://www.MikroKopter.de) must be |
42 | // + clearly linked as origin |
||
1 | ingob | 43 | // + * PORTING this software (or part of it) to systems (other than hardware from www.mikrokopter.de) is NOT allowed |
44 | // |
||
45 | // + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" |
||
46 | // + AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE |
||
47 | // + IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE |
||
48 | // + ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE |
||
49 | // + LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR |
||
50 | // + CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF |
||
51 | // + SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS |
||
52 | // + INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN |
||
53 | // + CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) |
||
54 | // + ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
||
41 | ingob | 55 | // + POSSIBILITY OF SUCH DAMAGE. |
1 | ingob | 56 | // ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ |
41 | ingob | 57 | |
58 | #include <string.h> |
||
59 | #include "91x_lib.h" |
||
60 | #include "led.h" |
||
61 | #include "GPS.h" |
||
62 | #include "uart1.h" |
||
63 | #include "spi_slave.h" |
||
64 | #include "i2c.h" |
||
119 | killagreg | 65 | #include "timer1.h" |
66 | #include "timer2.h" |
||
1 | ingob | 67 | #include "main.h" |
41 | ingob | 68 | #include "fifo.h" |
1 | ingob | 69 | |
70 | |||
41 | ingob | 71 | #define SPI_RXSYNCBYTE1 0xAA |
72 | #define SPI_RXSYNCBYTE2 0x83 |
||
73 | #define SPI_TXSYNCBYTE1 0x81 |
||
74 | #define SPI_TXSYNCBYTE2 0x55 |
||
1 | ingob | 75 | |
41 | ingob | 76 | typedef enum |
77 | { |
||
78 | SPI_SYNC1, |
||
79 | SPI_SYNC2, |
||
80 | SPI_DATA |
||
81 | } SPI_State_t; |
||
1 | ingob | 82 | |
41 | ingob | 83 | //communication packets |
84 | volatile FromFlightCtrl_t FromFlightCtrl; |
||
85 | volatile ToFlightCtrl_t ToFlightCtrl; |
||
1 | ingob | 86 | |
41 | ingob | 87 | // tx packet buffer |
88 | #define SPI_TXBUFFER_LEN (2 + sizeof(ToFlightCtrl)) // 2 bytes at start are for synchronization |
||
89 | volatile u8 SPI_TxBuffer[SPI_TXBUFFER_LEN]; |
||
90 | volatile u8 SPI_TxBufferIndex = 0; |
||
91 | u8 *Ptr_TxChksum = NULL ; // pointer to checksum in TxBuffer |
||
1 | ingob | 92 | |
41 | ingob | 93 | // rx packet buffer |
94 | #define SPI_RXBUFFER_LEN sizeof(FromFlightCtrl) |
||
95 | volatile u8 SPI_RxBuffer[SPI_RXBUFFER_LEN]; |
||
96 | volatile u8 SPI_RxBufferIndex = 0; |
||
97 | volatile u8 SPI_RxBuffer_Request = 0; |
||
1 | ingob | 98 | #define SPI_COMMAND_INDEX 0 |
99 | |||
41 | ingob | 100 | s32 FC_Kalman_K = 32; |
101 | s32 Kalman_MaxDrift = 5 * 16; |
||
102 | s32 Kalman_MaxFusion = 64; |
||
103 | u32 CheckSPIOkay = 0; |
||
1 | ingob | 104 | |
118 | killagreg | 105 | u8 SPI_CommandSequence[] = { SPI_KALMAN, SPI_EXTCTRL }; |
41 | ingob | 106 | u8 SPI_CommandCounter = 0; |
58 | killagreg | 107 | |
41 | ingob | 108 | SPI_Version_t FC_Version; |
1 | ingob | 109 | |
41 | ingob | 110 | u8 CompassCalStateQueue[10]; |
111 | fifo_t CompassCalcStateFiFo; |
||
1 | ingob | 112 | |
41 | ingob | 113 | u8 CompassCalState = 0; |
1 | ingob | 114 | |
41 | ingob | 115 | //-------------------------------------------------------------- |
116 | void SSP0_IRQHandler(void) |
||
117 | { |
||
118 | static u8 rxchksum = 0; |
||
119 | u8 rxdata; |
||
120 | static SPI_State_t SPI_State = SPI_SYNC1; |
||
1 | ingob | 121 | |
41 | ingob | 122 | // clear pending bit |
123 | SSP_ClearITPendingBit(SSP0, SSP_IT_RxTimeOut); |
||
124 | // Fill TxFIFO while its not full or end of packet is reached |
||
125 | while (SSP_GetFlagStatus(SSP0, SSP_FLAG_TxFifoNotFull) == SET) |
||
126 | { |
||
127 | if (SPI_TxBufferIndex < SPI_TXBUFFER_LEN) // still data to send ? |
||
128 | { |
||
129 | SSP0->DR = SPI_TxBuffer[SPI_TxBufferIndex]; // send a byte |
||
130 | *Ptr_TxChksum += SPI_TxBuffer[SPI_TxBufferIndex]; // update checksum |
||
131 | SPI_TxBufferIndex++; // pointer to next byte |
||
132 | } |
||
133 | else // TxBuffer end is reached then reset and copy data to tx buffer |
||
134 | { |
||
135 | SPI_TxBufferIndex = 0; // reset buffer index |
||
136 | ToFlightCtrl.Chksum = 0; // initialize checksum |
||
137 | ToFlightCtrl.BeepTime = BeepTime; // set beeptime |
||
138 | BeepTime = 0; // reset local beeptime |
||
139 | // copy contents of ToFlightCtrl->SPI_TxBuffer |
||
140 | memcpy( (u8 *) &(SPI_TxBuffer[2]), (u8 *) &ToFlightCtrl, sizeof(ToFlightCtrl)); |
||
141 | } |
||
79 | killagreg | 142 | } |
143 | // while RxFIFO not empty |
||
144 | while (SSP_GetFlagStatus(SSP0, SSP_FLAG_RxFifoNotEmpty) == SET) |
||
145 | { |
||
41 | ingob | 146 | rxdata = SSP0->DR; // catch the received byte |
147 | // Fill TxFIFO while its not full or end of packet is reached |
||
79 | killagreg | 148 | while (SSP_GetFlagStatus(SSP0, SSP_FLAG_TxFifoNotFull) == SET) |
41 | ingob | 149 | { |
79 | killagreg | 150 | if (SPI_TxBufferIndex < SPI_TXBUFFER_LEN) // still data to send ? |
151 | { |
||
41 | ingob | 152 | SSP0->DR = SPI_TxBuffer[SPI_TxBufferIndex]; // send a byte |
79 | killagreg | 153 | *Ptr_TxChksum += SPI_TxBuffer[SPI_TxBufferIndex]; // update checksum |
154 | SPI_TxBufferIndex++; // pointer to next byte |
||
155 | } |
||
156 | else // end of packet is reached reset and copy data to tx buffer |
||
157 | { |
||
158 | SPI_TxBufferIndex = 0; // reset buffer index |
||
159 | ToFlightCtrl.Chksum = 0; // initialize checksum |
||
160 | ToFlightCtrl.BeepTime = BeepTime; // set beeptime |
||
161 | BeepTime = 0; // reset local beeptime |
||
41 | ingob | 162 | // copy contents of ToFlightCtrl->SPI_TxBuffer |
79 | killagreg | 163 | memcpy((u8 *) &(SPI_TxBuffer[2]), (u8 *) &ToFlightCtrl, sizeof(ToFlightCtrl)); |
164 | } |
||
41 | ingob | 165 | } |
166 | switch (SPI_State) |
||
167 | { |
||
168 | case SPI_SYNC1: |
||
169 | SPI_RxBufferIndex = 0; // reset buffer index |
||
170 | rxchksum = rxdata; // init checksum |
||
171 | if (rxdata == SPI_RXSYNCBYTE1) |
||
172 | { // 1st syncbyte ok |
||
173 | SPI_State = SPI_SYNC2; // step to sync2 |
||
174 | } |
||
175 | break; |
||
79 | killagreg | 176 | case SPI_SYNC2: |
41 | ingob | 177 | if (rxdata == SPI_RXSYNCBYTE2) |
178 | { // 2nd Syncbyte ok |
||
179 | rxchksum += rxdata; |
||
180 | SPI_State = SPI_DATA; |
||
181 | } // 2nd Syncbyte does not match |
||
182 | else |
||
183 | { |
||
184 | SPI_State = SPI_SYNC1; //jump back to sync1 |
||
185 | } |
||
186 | break; |
||
187 | case SPI_DATA: |
||
188 | SPI_RxBuffer[SPI_RxBufferIndex++]= rxdata; // copy databyte to rx buffer |
||
189 | if (SPI_RxBufferIndex >= SPI_RXBUFFER_LEN) // end of packet is reached |
||
190 | { |
||
191 | if (rxdata == rxchksum) // verify checksum byte |
||
192 | { |
||
193 | // copy SPI_RxBuffer -> FromFlightCtrl |
||
194 | if(!SPI_RxBuffer_Request) // block writing to FromFlightCtrl on reading access |
||
195 | { |
||
196 | memcpy((u8 *) &FromFlightCtrl, (u8 *) SPI_RxBuffer, sizeof(FromFlightCtrl)); |
||
197 | SPI_RxBuffer_Request = 1; |
||
198 | } |
||
199 | CheckSPIOkay++; |
||
200 | DebugOut.Analog[13]++; |
||
201 | } |
||
202 | else // bad checksum byte |
||
203 | { |
||
204 | DebugOut.Analog[12]++; // increase SPI chksum error counter |
||
205 | } |
||
206 | SPI_State = SPI_SYNC1; // reset state |
||
207 | } |
||
208 | else // end of packet not reached |
||
209 | { |
||
210 | rxchksum += rxdata; // update checksum |
||
211 | } |
||
212 | break; |
||
213 | default: |
||
214 | SPI_State = SPI_SYNC1; |
||
215 | break; |
||
216 | } |
||
217 | } |
||
1 | ingob | 218 | } |
219 | |||
220 | //-------------------------------------------------------------- |
||
221 | void SPI0_Init(void) |
||
222 | { |
||
41 | ingob | 223 | GPIO_InitTypeDef GPIO_InitStructure; |
224 | SSP_InitTypeDef SSP_InitStructure; |
||
1 | ingob | 225 | |
110 | killagreg | 226 | UART1_PutString("\r\n SPI init..."); |
1 | ingob | 227 | |
41 | ingob | 228 | SCU_APBPeriphClockConfig(__GPIO2 ,ENABLE); |
229 | SCU_APBPeriphClockConfig(__SSP0 ,ENABLE); |
||
1 | ingob | 230 | |
41 | ingob | 231 | GPIO_DeInit(GPIO2); |
232 | //SSP0_CLK, SSP0_MOSI, SSP0_NSS pins |
||
233 | GPIO_StructInit(&GPIO_InitStructure); |
||
234 | GPIO_InitStructure.GPIO_Direction = GPIO_PinInput; |
||
235 | GPIO_InitStructure.GPIO_Pin = GPIO_Pin_4 | GPIO_Pin_5 | GPIO_Pin_7; |
||
236 | GPIO_InitStructure.GPIO_Type = GPIO_Type_PushPull ; |
||
237 | GPIO_InitStructure.GPIO_IPConnected = GPIO_IPConnected_Enable; |
||
238 | GPIO_InitStructure.GPIO_Alternate = GPIO_InputAlt1; //SSP0_SCLK, SSP0_MOSI, SSP0_NSS |
||
239 | GPIO_Init (GPIO2, &GPIO_InitStructure); |
||
1 | ingob | 240 | |
41 | ingob | 241 | // SSP0_MISO pin GPIO2.6 |
242 | GPIO_StructInit(&GPIO_InitStructure); |
||
243 | GPIO_InitStructure.GPIO_Direction = GPIO_PinOutput; |
||
244 | GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6; |
||
245 | GPIO_InitStructure.GPIO_Type = GPIO_Type_PushPull ; |
||
246 | GPIO_InitStructure.GPIO_IPConnected = GPIO_IPConnected_Enable; |
||
247 | GPIO_InitStructure.GPIO_Alternate = GPIO_OutputAlt2; //SSP0_MISO |
||
248 | GPIO_Init (GPIO2, &GPIO_InitStructure); |
||
1 | ingob | 249 | |
41 | ingob | 250 | SSP_DeInit(SSP0); |
251 | SSP_StructInit(&SSP_InitStructure); |
||
252 | SSP_InitStructure.SSP_FrameFormat = SSP_FrameFormat_Motorola; |
||
253 | SSP_InitStructure.SSP_Mode = SSP_Mode_Slave; |
||
254 | SSP_InitStructure.SSP_SlaveOutput = SSP_SlaveOutput_Enable; |
||
255 | SSP_InitStructure.SSP_CPHA = SSP_CPHA_1Edge; |
||
256 | SSP_InitStructure.SSP_CPOL = SSP_CPOL_Low; |
||
257 | SSP_InitStructure.SSP_ClockRate = 0; |
||
1 | ingob | 258 | |
41 | ingob | 259 | SSP_Init(SSP0, &SSP_InitStructure); |
1 | ingob | 260 | |
41 | ingob | 261 | SSP_ITConfig(SSP0, SSP_IT_RxFifo | SSP_IT_TxFifo | SSP_IT_RxTimeOut, ENABLE); |
1 | ingob | 262 | |
41 | ingob | 263 | fifo_init(&CompassCalcStateFiFo, CompassCalStateQueue, sizeof(CompassCalStateQueue)); |
264 | |||
265 | SSP_Cmd(SSP0, ENABLE); |
||
266 | // initialize the syncbytes in the tx buffer |
||
267 | SPI_TxBuffer[0] = SPI_TXSYNCBYTE1; |
||
268 | SPI_TxBuffer[1] = SPI_TXSYNCBYTE2; |
||
269 | // set the pointer to the checksum byte in the tx buffer |
||
270 | Ptr_TxChksum = (u8 *) &(((ToFlightCtrl_t *) &(SPI_TxBuffer[2]))->Chksum); |
||
271 | |||
272 | VIC_Config(SSP0_ITLine, VIC_IRQ, 1); |
||
273 | VIC_ITCmd(SSP0_ITLine, ENABLE); |
||
274 | |||
110 | killagreg | 275 | UART1_PutString("ok"); |
1 | ingob | 276 | } |
41 | ingob | 277 | |
1 | ingob | 278 | //------------------------------------------------------ |
41 | ingob | 279 | void SPI0_UpdateBuffer(void) |
1 | ingob | 280 | { |
41 | ingob | 281 | if (SPI_RxBuffer_Request) |
282 | { |
||
283 | // avoid sending data via SPI during the update of the ToFlightCtrl structure |
||
284 | VIC_ITCmd(SSP0_ITLine, DISABLE); // disable SPI interrupt |
||
1 | ingob | 285 | |
41 | ingob | 286 | ToFlightCtrl.CompassHeading = I2C_Heading.Heading; |
287 | ToFlightCtrl.GPS_Nick = GPS_Stick.Nick; |
||
288 | ToFlightCtrl.GPS_Roll = GPS_Stick.Roll; |
||
289 | ToFlightCtrl.GPS_Yaw = GPS_Stick.Yaw; |
||
290 | // cycle spi commands |
||
291 | ToFlightCtrl.Command = SPI_CommandSequence[SPI_CommandCounter++]; |
||
118 | killagreg | 292 | if(ToFlightCtrl.Command == SPI_EXTCTRL) |
293 | { |
||
294 | // if no new data are available skip this command in sequence |
||
295 | if(ExternControl.Status != NEWDATA) ToFlightCtrl.Command = SPI_CommandSequence[SPI_CommandCounter++]; |
||
296 | } |
||
297 | // restart command cycle at the end |
||
41 | ingob | 298 | if (SPI_CommandCounter >= sizeof(SPI_CommandSequence)) SPI_CommandCounter = 0; |
1 | ingob | 299 | |
41 | ingob | 300 | switch (ToFlightCtrl.Command) |
301 | { |
||
302 | case SPI_KALMAN: |
||
92 | killagreg | 303 | ToFlightCtrl.Param.sByte[0] = (s8) FC_Kalman_K; |
304 | ToFlightCtrl.Param.sByte[1] = (s8) Kalman_MaxFusion; |
||
305 | ToFlightCtrl.Param.sByte[2] = (s8) Kalman_MaxDrift; |
||
118 | killagreg | 306 | ToFlightCtrl.Param.Byte[3] = (u8) SerialLinkOkay; |
41 | ingob | 307 | break; |
58 | killagreg | 308 | |
118 | killagreg | 309 | case SPI_EXTCTRL: |
310 | ToFlightCtrl.Param.Byte[0] = ExternControl.Digital[0]; |
||
311 | ToFlightCtrl.Param.Byte[1] = ExternControl.Digital[1]; |
||
312 | ToFlightCtrl.Param.Byte[2] = ExternControl.RemoteButtons; |
||
313 | ToFlightCtrl.Param.sByte[3] = ExternControl.Nick; |
||
314 | ToFlightCtrl.Param.sByte[4] = ExternControl.Roll; |
||
315 | ToFlightCtrl.Param.sByte[5] = ExternControl.Yaw; |
||
316 | ToFlightCtrl.Param.Byte[6] = ExternControl.Gas; |
||
317 | ToFlightCtrl.Param.sByte[7] = ExternControl.Height; |
||
318 | ToFlightCtrl.Param.Byte[8] = ExternControl.free; |
||
319 | ToFlightCtrl.Param.Byte[9] = ExternControl.Frame; |
||
320 | ToFlightCtrl.Param.Byte[10] = ExternControl.Config; |
||
321 | ExternControl.Status = PROCESSED; |
||
322 | break; |
||
323 | |||
41 | ingob | 324 | default: |
325 | break; |
||
326 | } |
||
327 | VIC_ITCmd(SSP0_ITLine, ENABLE); // enable SPI interrupt |
||
1 | ingob | 328 | |
329 | |||
41 | ingob | 330 | switch(FromFlightCtrl.Command) |
331 | { |
||
332 | case SPI_CMD_USER: |
||
333 | Parameter.User1 = FromFlightCtrl.Param.Byte[0]; |
||
334 | Parameter.User2 = FromFlightCtrl.Param.Byte[1]; |
||
335 | Parameter.User3 = FromFlightCtrl.Param.Byte[2]; |
||
336 | Parameter.User4 = FromFlightCtrl.Param.Byte[3]; |
||
337 | Parameter.User5 = FromFlightCtrl.Param.Byte[4]; |
||
338 | Parameter.User6 = FromFlightCtrl.Param.Byte[5]; |
||
339 | Parameter.User7 = FromFlightCtrl.Param.Byte[6]; |
||
340 | Parameter.User8 = FromFlightCtrl.Param.Byte[7]; |
||
341 | if(ClearMKFlags) |
||
342 | { |
||
343 | FC.MKFlags = 0; |
||
344 | ClearMKFlags = 0; |
||
345 | } |
||
346 | FC.MKFlags |= FromFlightCtrl.Param.Byte[8]; |
||
347 | FC.UBat = FromFlightCtrl.Param.Byte[9]; |
||
348 | Parameter.LowVoltageWarning = FromFlightCtrl.Param.Byte[10]; |
||
349 | Parameter.ActiveSetting = FromFlightCtrl.Param.Byte[11]; |
||
79 | killagreg | 350 | DebugOut.Analog[5] = FC.MKFlags; |
41 | ingob | 351 | break; |
1 | ingob | 352 | |
41 | ingob | 353 | #define CHK_POTI_MM(b,a,min,max) { if(a > 250) { if(a == 251) b = FC.Poti1; else if(a == 252) b = FC.Poti2; else if(a == 253) b = FC.Poti3; else if(a == 254) b = FC.Poti4;} else b = a; if(b <= min) b = min; else if(b >= max) b = max;} |
354 | case SPI_CMD_PARAMETER1: |
||
355 | CHK_POTI_MM(Parameter.NaviGpsModeControl,FromFlightCtrl.Param.Byte[0],0,255); |
||
356 | CHK_POTI_MM(Parameter.NaviGpsGain,FromFlightCtrl.Param.Byte[1],0,255); |
||
357 | CHK_POTI_MM(Parameter.NaviGpsP,FromFlightCtrl.Param.Byte[2],0,255); |
||
358 | CHK_POTI_MM(Parameter.NaviGpsI,FromFlightCtrl.Param.Byte[3],0,255); |
||
359 | CHK_POTI_MM(Parameter.NaviGpsD,FromFlightCtrl.Param.Byte[4],0,255); |
||
360 | CHK_POTI_MM(Parameter.NaviGpsACC,FromFlightCtrl.Param.Byte[5],0,255); |
||
361 | Parameter.NaviGpsMinSat = FromFlightCtrl.Param.Byte[6]; |
||
362 | Parameter.NaviStickThreshold = FromFlightCtrl.Param.Byte[7]; |
||
103 | killagreg | 363 | CHK_POTI_MM(Parameter.NaviOperatingRadius,FromFlightCtrl.Param.Byte[8],0,255); |
41 | ingob | 364 | CHK_POTI_MM(Parameter.NaviWindCorrection,FromFlightCtrl.Param.Byte[9],0,255); |
365 | CHK_POTI_MM(Parameter.NaviSpeedCompensation,FromFlightCtrl.Param.Byte[10],0,255); |
||
366 | CHK_POTI_MM(Parameter.NaviAngleLimitation,FromFlightCtrl.Param.Byte[11],0,255); |
||
367 | // DebugOut.Analog[4] = Parameter.NaviRadiusAlert; |
||
368 | // DebugOut.Analog[5] = Parameter.NaviWindCorrection; |
||
369 | // DebugOut.Analog[6] = Parameter.NaviSpeedCompensation; |
||
370 | break; |
||
1 | ingob | 371 | |
41 | ingob | 372 | case SPI_CMD_STICK: |
373 | FC.StickGas = FromFlightCtrl.Param.sByte[0]; |
||
374 | FC.StickYaw = FromFlightCtrl.Param.sByte[1]; |
||
375 | FC.StickRoll = FromFlightCtrl.Param.sByte[2]; |
||
376 | FC.StickNick = FromFlightCtrl.Param.sByte[3]; |
||
377 | FC.Poti1 = FromFlightCtrl.Param.Byte[4]; |
||
378 | FC.Poti2 = FromFlightCtrl.Param.Byte[5]; |
||
379 | FC.Poti3 = FromFlightCtrl.Param.Byte[6]; |
||
380 | FC.Poti4 = FromFlightCtrl.Param.Byte[7]; |
||
381 | FC.RC_Quality = FromFlightCtrl.Param.Byte[8]; |
||
382 | break; |
||
27 | holgerb | 383 | |
41 | ingob | 384 | case SPI_CMD_MISC: |
385 | if(CompassCalState != FromFlightCtrl.Param.Byte[0]) |
||
386 | { // put only new CompassCalState into queue to send via I2C |
||
387 | CompassCalState = FromFlightCtrl.Param.Byte[0]; |
||
388 | fifo_put(&CompassCalcStateFiFo, CompassCalState); |
||
389 | } |
||
58 | killagreg | 390 | Parameter.NaviPH_LoginTime = FromFlightCtrl.Param.Byte[1]; |
79 | killagreg | 391 | NaviData.Variometer = (NaviData.Variometer + 2 * ((s16) FromFlightCtrl.Param.Int[1] - NaviData.Altimeter)) / 2; // provisorisch |
58 | killagreg | 392 | NaviData.Altimeter = (s16) FromFlightCtrl.Param.Int[1]; // is located at byte 2 and 3 |
79 | killagreg | 393 | CHK_POTI_MM(Parameter.NaviGpsPLimit,FromFlightCtrl.Param.Byte[4],0,255); |
394 | CHK_POTI_MM(Parameter.NaviGpsILimit,FromFlightCtrl.Param.Byte[5],0,255); |
||
395 | CHK_POTI_MM(Parameter.NaviGpsDLimit,FromFlightCtrl.Param.Byte[6],0,255); |
||
41 | ingob | 396 | break; |
119 | killagreg | 397 | |
398 | case SPI_CMD_SERVO: |
||
399 | ServoParams.Refresh = FromFlightCtrl.Param.Byte[0]; |
||
400 | ServoParams.NickOffset = FromFlightCtrl.Param.Byte[1]; |
||
401 | ServoParams.NickComp = FromFlightCtrl.Param.sByte[2]; |
||
402 | ServoParams.NickMin = FromFlightCtrl.Param.Byte[3]; |
||
403 | ServoParams.NickMax = FromFlightCtrl.Param.Byte[4]; |
||
404 | ServoParams.RollOffset = FromFlightCtrl.Param.Byte[5]; |
||
405 | ServoParams.RollComp = FromFlightCtrl.Param.sByte[6]; |
||
406 | ServoParams.RollMin = FromFlightCtrl.Param.Byte[7]; |
||
407 | ServoParams.RollMax = FromFlightCtrl.Param.Byte[8]; |
||
408 | break; |
||
1 | ingob | 409 | |
41 | ingob | 410 | case SPI_CMD_VERSION: |
119 | killagreg | 411 | FC_Version.Major = FromFlightCtrl.Param.Byte[0]; |
412 | FC_Version.Minor = FromFlightCtrl.Param.Byte[1]; |
||
413 | FC_Version.Patch = FromFlightCtrl.Param.Byte[2]; |
||
414 | FC_Version.Compatible = FromFlightCtrl.Param.Byte[3]; |
||
415 | FC_Version.Hardware = FromFlightCtrl.Param.Byte[4]; |
||
41 | ingob | 416 | break; |
1 | ingob | 417 | |
41 | ingob | 418 | default: |
419 | break; |
||
420 | } |
||
1 | ingob | 421 | |
41 | ingob | 422 | // every time we got new data from the FC via SPI call the navigation routine |
423 | GPS_Navigation(); |
||
424 | ClearMKFlags = 1; |
||
1 | ingob | 425 | |
41 | ingob | 426 | SPI_RxBuffer_Request = 0; |
1 | ingob | 427 | |
62 | killagreg | 428 | DebugOut.Analog[0] = FromFlightCtrl.AngleNick; |
429 | DebugOut.Analog[1] = FromFlightCtrl.AngleRoll; |
||
61 | holgerb | 430 | DebugOut.Analog[2] = FromFlightCtrl.AccNick; |
431 | DebugOut.Analog[3] = FromFlightCtrl.AccRoll; |
||
62 | killagreg | 432 | DebugOut.Analog[11] = FromFlightCtrl.GyroHeading/10;// in deg |
79 | killagreg | 433 | Data3D.AngleNick = FromFlightCtrl.AngleNick; // in 0.1 deg |
434 | Data3D.AngleRoll = FromFlightCtrl.AngleRoll; // in 0.1 deg |
||
435 | Data3D.Heading = FromFlightCtrl.GyroHeading; // in 0.1 deg |
||
436 | } // EOF if(SPI_RxBuffer_Request) |
||
1 | ingob | 437 | } |
438 | |||
41 | ingob | 439 | //------------------------------------------------------ |
440 | void SPI0_GetFlightCtrlVersion(void) |
||
441 | { |
||
442 | u16 timeout; |
||
78 | holgerb | 443 | u8 msg[64]; |
41 | ingob | 444 | |
445 | FC_Version.Major = 0xFF; |
||
446 | FC_Version.Minor = 0xFF; |
||
447 | FC_Version.Patch = 0xFF; |
||
448 | FC_Version.Compatible = 0xFF; |
||
449 | |||
450 | // polling FC version info for 2 second |
||
451 | timeout = SetDelay(2000); |
||
452 | do |
||
453 | { |
||
454 | SPI0_UpdateBuffer(); |
||
455 | if (FC_Version.Major != 0xFF) break; |
||
456 | }while (!CheckDelay(timeout)); |
||
457 | // if we got it |
||
458 | if (FC_Version.Major != 0xFF) |
||
459 | { |
||
61 | holgerb | 460 | sprintf(msg, "\n\r FlightCtrl V%d.%d%c HW:%d.%d", FC_Version.Major, FC_Version.Minor, 'a'+FC_Version.Patch, FC_Version.Hardware/10,FC_Version.Hardware%10); |
110 | killagreg | 461 | UART1_PutString(msg); |
41 | ingob | 462 | sprintf(msg, " Compatible: %d", FC_Version.Compatible); |
110 | killagreg | 463 | UART1_PutString(msg); |
41 | ingob | 464 | } |
110 | killagreg | 465 | else UART1_PutString("\n\r No version information from FlightCtrl."); |
41 | ingob | 466 | } |
467 | |||
468 |