Rev 189 | Rev 193 | 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 |
||
171 | ingob | 6 | // + Nur für den privaten Gebrauch / NON-COMMERCIAL USE ONLY |
1 | ingob | 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 | // ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ |
||
171 | ingob | 28 | // + Die Portierung oder Nutzung 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 |
||
171 | ingob | 43 | // + * porting the sources to other systems or using the software on other systems (except hardware from www.mikrokopter.de) is not allowed |
1 | ingob | 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" |
||
136 | killagreg | 67 | #include "config.h" |
1 | ingob | 68 | #include "main.h" |
41 | ingob | 69 | #include "fifo.h" |
1 | ingob | 70 | |
71 | |||
41 | ingob | 72 | #define SPI_RXSYNCBYTE1 0xAA |
73 | #define SPI_RXSYNCBYTE2 0x83 |
||
74 | #define SPI_TXSYNCBYTE1 0x81 |
||
75 | #define SPI_TXSYNCBYTE2 0x55 |
||
1 | ingob | 76 | |
41 | ingob | 77 | //communication packets |
78 | volatile FromFlightCtrl_t FromFlightCtrl; |
||
79 | volatile ToFlightCtrl_t ToFlightCtrl; |
||
183 | killagreg | 80 | #define SPI0_TIMEOUT 500 // 500ms |
146 | killagreg | 81 | volatile u32 SPI0_Timeout = 0; |
1 | ingob | 82 | |
41 | ingob | 83 | // tx packet buffer |
84 | #define SPI_TXBUFFER_LEN (2 + sizeof(ToFlightCtrl)) // 2 bytes at start are for synchronization |
||
85 | volatile u8 SPI_TxBuffer[SPI_TXBUFFER_LEN]; |
||
86 | volatile u8 SPI_TxBufferIndex = 0; |
||
87 | u8 *Ptr_TxChksum = NULL ; // pointer to checksum in TxBuffer |
||
1 | ingob | 88 | |
41 | ingob | 89 | // rx packet buffer |
90 | #define SPI_RXBUFFER_LEN sizeof(FromFlightCtrl) |
||
91 | volatile u8 SPI_RxBuffer[SPI_RXBUFFER_LEN]; |
||
92 | volatile u8 SPI_RxBufferIndex = 0; |
||
93 | volatile u8 SPI_RxBuffer_Request = 0; |
||
1 | ingob | 94 | #define SPI_COMMAND_INDEX 0 |
95 | |||
149 | killagreg | 96 | s32 Kalman_K = 32; |
41 | ingob | 97 | s32 Kalman_MaxDrift = 5 * 16; |
98 | s32 Kalman_MaxFusion = 64; |
||
148 | holgerb | 99 | s32 ToFcGpsZ = 0; |
1 | ingob | 100 | |
121 | killagreg | 101 | u8 SPI_CommandSequence[] = { SPI_KALMAN }; |
41 | ingob | 102 | u8 SPI_CommandCounter = 0; |
58 | killagreg | 103 | |
41 | ingob | 104 | SPI_Version_t FC_Version; |
1 | ingob | 105 | |
41 | ingob | 106 | u8 CompassCalStateQueue[10]; |
107 | fifo_t CompassCalcStateFiFo; |
||
1 | ingob | 108 | |
41 | ingob | 109 | u8 CompassCalState = 0; |
1 | ingob | 110 | |
41 | ingob | 111 | //-------------------------------------------------------------- |
112 | void SSP0_IRQHandler(void) |
||
113 | { |
||
114 | static u8 rxchksum = 0; |
||
115 | u8 rxdata; |
||
1 | ingob | 116 | |
189 | killagreg | 117 | #define SPI_SYNC1 0 |
118 | #define SPI_SYNC2 1 |
||
119 | #define SPI_DATA 2 |
||
120 | static u8 SPI_State = SPI_SYNC1; |
||
121 | |||
161 | killagreg | 122 | // clear pending bits |
41 | ingob | 123 | SSP_ClearITPendingBit(SSP0, SSP_IT_RxTimeOut); |
144 | killagreg | 124 | SSP_ClearITPendingBit(SSP0, SSP_IT_RxFifo); |
189 | killagreg | 125 | |
79 | killagreg | 126 | // while RxFIFO not empty |
127 | while (SSP_GetFlagStatus(SSP0, SSP_FLAG_RxFifoNotEmpty) == SET) |
||
128 | { |
||
41 | ingob | 129 | rxdata = SSP0->DR; // catch the received byte |
130 | // Fill TxFIFO while its not full or end of packet is reached |
||
79 | killagreg | 131 | while (SSP_GetFlagStatus(SSP0, SSP_FLAG_TxFifoNotFull) == SET) |
161 | killagreg | 132 | { |
79 | killagreg | 133 | if (SPI_TxBufferIndex < SPI_TXBUFFER_LEN) // still data to send ? |
134 | { |
||
41 | ingob | 135 | SSP0->DR = SPI_TxBuffer[SPI_TxBufferIndex]; // send a byte |
79 | killagreg | 136 | *Ptr_TxChksum += SPI_TxBuffer[SPI_TxBufferIndex]; // update checksum |
137 | SPI_TxBufferIndex++; // pointer to next byte |
||
138 | } |
||
139 | else // end of packet is reached reset and copy data to tx buffer |
||
140 | { |
||
141 | SPI_TxBufferIndex = 0; // reset buffer index |
||
142 | ToFlightCtrl.Chksum = 0; // initialize checksum |
||
143 | ToFlightCtrl.BeepTime = BeepTime; // set beeptime |
||
144 | BeepTime = 0; // reset local beeptime |
||
41 | ingob | 145 | // copy contents of ToFlightCtrl->SPI_TxBuffer |
79 | killagreg | 146 | memcpy((u8 *) &(SPI_TxBuffer[2]), (u8 *) &ToFlightCtrl, sizeof(ToFlightCtrl)); |
147 | } |
||
41 | ingob | 148 | } |
149 | switch (SPI_State) |
||
150 | { |
||
151 | case SPI_SYNC1: |
||
152 | SPI_RxBufferIndex = 0; // reset buffer index |
||
153 | rxchksum = rxdata; // init checksum |
||
154 | if (rxdata == SPI_RXSYNCBYTE1) |
||
155 | { // 1st syncbyte ok |
||
156 | SPI_State = SPI_SYNC2; // step to sync2 |
||
157 | } |
||
158 | break; |
||
79 | killagreg | 159 | case SPI_SYNC2: |
41 | ingob | 160 | if (rxdata == SPI_RXSYNCBYTE2) |
161 | { // 2nd Syncbyte ok |
||
162 | rxchksum += rxdata; |
||
163 | SPI_State = SPI_DATA; |
||
164 | } // 2nd Syncbyte does not match |
||
165 | else |
||
166 | { |
||
167 | SPI_State = SPI_SYNC1; //jump back to sync1 |
||
168 | } |
||
169 | break; |
||
170 | case SPI_DATA: |
||
171 | SPI_RxBuffer[SPI_RxBufferIndex++]= rxdata; // copy databyte to rx buffer |
||
172 | if (SPI_RxBufferIndex >= SPI_RXBUFFER_LEN) // end of packet is reached |
||
173 | { |
||
174 | if (rxdata == rxchksum) // verify checksum byte |
||
175 | { |
||
176 | // copy SPI_RxBuffer -> FromFlightCtrl |
||
177 | if(!SPI_RxBuffer_Request) // block writing to FromFlightCtrl on reading access |
||
178 | { |
||
179 | memcpy((u8 *) &FromFlightCtrl, (u8 *) SPI_RxBuffer, sizeof(FromFlightCtrl)); |
||
180 | SPI_RxBuffer_Request = 1; |
||
181 | } |
||
146 | killagreg | 182 | // reset timeout counter on good packet |
183 | SPI0_Timeout = SetDelay(SPI0_TIMEOUT); |
||
41 | ingob | 184 | DebugOut.Analog[13]++; |
185 | } |
||
186 | else // bad checksum byte |
||
187 | { |
||
188 | DebugOut.Analog[12]++; // increase SPI chksum error counter |
||
189 | } |
||
190 | SPI_State = SPI_SYNC1; // reset state |
||
191 | } |
||
192 | else // end of packet not reached |
||
193 | { |
||
194 | rxchksum += rxdata; // update checksum |
||
195 | } |
||
196 | break; |
||
197 | default: |
||
198 | SPI_State = SPI_SYNC1; |
||
199 | break; |
||
200 | } |
||
201 | } |
||
1 | ingob | 202 | } |
203 | |||
204 | //-------------------------------------------------------------- |
||
205 | void SPI0_Init(void) |
||
206 | { |
||
41 | ingob | 207 | GPIO_InitTypeDef GPIO_InitStructure; |
208 | SSP_InitTypeDef SSP_InitStructure; |
||
1 | ingob | 209 | |
110 | killagreg | 210 | UART1_PutString("\r\n SPI init..."); |
1 | ingob | 211 | |
41 | ingob | 212 | SCU_APBPeriphClockConfig(__GPIO2 ,ENABLE); |
213 | SCU_APBPeriphClockConfig(__SSP0 ,ENABLE); |
||
1 | ingob | 214 | |
41 | ingob | 215 | GPIO_DeInit(GPIO2); |
216 | //SSP0_CLK, SSP0_MOSI, SSP0_NSS pins |
||
217 | GPIO_StructInit(&GPIO_InitStructure); |
||
218 | GPIO_InitStructure.GPIO_Direction = GPIO_PinInput; |
||
219 | GPIO_InitStructure.GPIO_Pin = GPIO_Pin_4 | GPIO_Pin_5 | GPIO_Pin_7; |
||
220 | GPIO_InitStructure.GPIO_Type = GPIO_Type_PushPull ; |
||
221 | GPIO_InitStructure.GPIO_IPConnected = GPIO_IPConnected_Enable; |
||
222 | GPIO_InitStructure.GPIO_Alternate = GPIO_InputAlt1; //SSP0_SCLK, SSP0_MOSI, SSP0_NSS |
||
223 | GPIO_Init (GPIO2, &GPIO_InitStructure); |
||
1 | ingob | 224 | |
41 | ingob | 225 | // SSP0_MISO pin GPIO2.6 |
226 | GPIO_StructInit(&GPIO_InitStructure); |
||
227 | GPIO_InitStructure.GPIO_Direction = GPIO_PinOutput; |
||
228 | GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6; |
||
229 | GPIO_InitStructure.GPIO_Type = GPIO_Type_PushPull ; |
||
230 | GPIO_InitStructure.GPIO_IPConnected = GPIO_IPConnected_Enable; |
||
231 | GPIO_InitStructure.GPIO_Alternate = GPIO_OutputAlt2; //SSP0_MISO |
||
232 | GPIO_Init (GPIO2, &GPIO_InitStructure); |
||
1 | ingob | 233 | |
41 | ingob | 234 | SSP_DeInit(SSP0); |
235 | SSP_StructInit(&SSP_InitStructure); |
||
236 | SSP_InitStructure.SSP_FrameFormat = SSP_FrameFormat_Motorola; |
||
237 | SSP_InitStructure.SSP_Mode = SSP_Mode_Slave; |
||
238 | SSP_InitStructure.SSP_SlaveOutput = SSP_SlaveOutput_Enable; |
||
239 | SSP_InitStructure.SSP_CPHA = SSP_CPHA_1Edge; |
||
240 | SSP_InitStructure.SSP_CPOL = SSP_CPOL_Low; |
||
241 | SSP_InitStructure.SSP_ClockRate = 0; |
||
1 | ingob | 242 | |
41 | ingob | 243 | SSP_Init(SSP0, &SSP_InitStructure); |
144 | killagreg | 244 | SSP_ITConfig(SSP0, SSP_IT_RxFifo | SSP_IT_RxTimeOut, ENABLE); |
189 | killagreg | 245 | |
41 | ingob | 246 | fifo_init(&CompassCalcStateFiFo, CompassCalStateQueue, sizeof(CompassCalStateQueue)); |
247 | |||
248 | SSP_Cmd(SSP0, ENABLE); |
||
249 | // initialize the syncbytes in the tx buffer |
||
250 | SPI_TxBuffer[0] = SPI_TXSYNCBYTE1; |
||
251 | SPI_TxBuffer[1] = SPI_TXSYNCBYTE2; |
||
252 | // set the pointer to the checksum byte in the tx buffer |
||
253 | Ptr_TxChksum = (u8 *) &(((ToFlightCtrl_t *) &(SPI_TxBuffer[2]))->Chksum); |
||
254 | |||
136 | killagreg | 255 | VIC_Config(SSP0_ITLine, VIC_IRQ, PRIORITY_SPI0); |
41 | ingob | 256 | VIC_ITCmd(SSP0_ITLine, ENABLE); |
257 | |||
146 | killagreg | 258 | SPI0_Timeout = SetDelay(4*SPI0_TIMEOUT); |
259 | |||
110 | killagreg | 260 | UART1_PutString("ok"); |
1 | ingob | 261 | } |
41 | ingob | 262 | |
1 | ingob | 263 | //------------------------------------------------------ |
41 | ingob | 264 | void SPI0_UpdateBuffer(void) |
1 | ingob | 265 | { |
180 | killagreg | 266 | static u32 timeout = 0; |
267 | static u8 counter = 50; |
||
268 | |||
41 | ingob | 269 | if (SPI_RxBuffer_Request) |
270 | { |
||
271 | // avoid sending data via SPI during the update of the ToFlightCtrl structure |
||
272 | VIC_ITCmd(SSP0_ITLine, DISABLE); // disable SPI interrupt |
||
273 | ToFlightCtrl.CompassHeading = I2C_Heading.Heading; |
||
189 | killagreg | 274 | DebugOut.Analog[10] = ToFlightCtrl.CompassHeading; |
41 | ingob | 275 | ToFlightCtrl.GPS_Nick = GPS_Stick.Nick; |
276 | ToFlightCtrl.GPS_Roll = GPS_Stick.Roll; |
||
277 | ToFlightCtrl.GPS_Yaw = GPS_Stick.Yaw; |
||
278 | // cycle spi commands |
||
279 | ToFlightCtrl.Command = SPI_CommandSequence[SPI_CommandCounter++]; |
||
118 | killagreg | 280 | // restart command cycle at the end |
41 | ingob | 281 | if (SPI_CommandCounter >= sizeof(SPI_CommandSequence)) SPI_CommandCounter = 0; |
1 | ingob | 282 | |
41 | ingob | 283 | switch (ToFlightCtrl.Command) |
284 | { |
||
285 | case SPI_KALMAN: |
||
149 | killagreg | 286 | ToFlightCtrl.Param.sByte[0] = (s8) Kalman_K; |
92 | killagreg | 287 | ToFlightCtrl.Param.sByte[1] = (s8) Kalman_MaxFusion; |
288 | ToFlightCtrl.Param.sByte[2] = (s8) Kalman_MaxDrift; |
||
118 | killagreg | 289 | ToFlightCtrl.Param.Byte[3] = (u8) SerialLinkOkay; |
149 | killagreg | 290 | ToFlightCtrl.Param.sByte[4] = (s8) ToFcGpsZ; |
161 | killagreg | 291 | break; |
58 | killagreg | 292 | |
41 | ingob | 293 | default: |
294 | break; |
||
295 | } |
||
296 | VIC_ITCmd(SSP0_ITLine, ENABLE); // enable SPI interrupt |
||
1 | ingob | 297 | |
298 | |||
41 | ingob | 299 | switch(FromFlightCtrl.Command) |
300 | { |
||
301 | case SPI_CMD_USER: |
||
302 | Parameter.User1 = FromFlightCtrl.Param.Byte[0]; |
||
303 | Parameter.User2 = FromFlightCtrl.Param.Byte[1]; |
||
304 | Parameter.User3 = FromFlightCtrl.Param.Byte[2]; |
||
305 | Parameter.User4 = FromFlightCtrl.Param.Byte[3]; |
||
306 | Parameter.User5 = FromFlightCtrl.Param.Byte[4]; |
||
307 | Parameter.User6 = FromFlightCtrl.Param.Byte[5]; |
||
308 | Parameter.User7 = FromFlightCtrl.Param.Byte[6]; |
||
309 | Parameter.User8 = FromFlightCtrl.Param.Byte[7]; |
||
310 | if(ClearMKFlags) |
||
311 | { |
||
312 | FC.MKFlags = 0; |
||
313 | ClearMKFlags = 0; |
||
314 | } |
||
315 | FC.MKFlags |= FromFlightCtrl.Param.Byte[8]; |
||
316 | FC.UBat = FromFlightCtrl.Param.Byte[9]; |
||
317 | Parameter.LowVoltageWarning = FromFlightCtrl.Param.Byte[10]; |
||
318 | Parameter.ActiveSetting = FromFlightCtrl.Param.Byte[11]; |
||
79 | killagreg | 319 | DebugOut.Analog[5] = FC.MKFlags; |
41 | ingob | 320 | break; |
1 | ingob | 321 | |
190 | killagreg | 322 | #define CHK_POTI(b,a) { if(a < 247) b = a; else b = FC.Poti[255 - a]; } |
323 | #define CHK_POTI_MM(b,a,min,max) {CHK_POTI(b,a); LIMIT_MIN_MAX(b, min, max); } |
||
324 | |||
41 | ingob | 325 | case SPI_CMD_PARAMETER1: |
326 | CHK_POTI_MM(Parameter.NaviGpsModeControl,FromFlightCtrl.Param.Byte[0],0,255); |
||
327 | CHK_POTI_MM(Parameter.NaviGpsGain,FromFlightCtrl.Param.Byte[1],0,255); |
||
328 | CHK_POTI_MM(Parameter.NaviGpsP,FromFlightCtrl.Param.Byte[2],0,255); |
||
329 | CHK_POTI_MM(Parameter.NaviGpsI,FromFlightCtrl.Param.Byte[3],0,255); |
||
330 | CHK_POTI_MM(Parameter.NaviGpsD,FromFlightCtrl.Param.Byte[4],0,255); |
||
331 | CHK_POTI_MM(Parameter.NaviGpsACC,FromFlightCtrl.Param.Byte[5],0,255); |
||
332 | Parameter.NaviGpsMinSat = FromFlightCtrl.Param.Byte[6]; |
||
333 | Parameter.NaviStickThreshold = FromFlightCtrl.Param.Byte[7]; |
||
103 | killagreg | 334 | CHK_POTI_MM(Parameter.NaviOperatingRadius,FromFlightCtrl.Param.Byte[8],0,255); |
41 | ingob | 335 | CHK_POTI_MM(Parameter.NaviWindCorrection,FromFlightCtrl.Param.Byte[9],0,255); |
336 | CHK_POTI_MM(Parameter.NaviSpeedCompensation,FromFlightCtrl.Param.Byte[10],0,255); |
||
337 | CHK_POTI_MM(Parameter.NaviAngleLimitation,FromFlightCtrl.Param.Byte[11],0,255); |
||
121 | killagreg | 338 | break; |
1 | ingob | 339 | |
41 | ingob | 340 | case SPI_CMD_STICK: |
341 | FC.StickGas = FromFlightCtrl.Param.sByte[0]; |
||
342 | FC.StickYaw = FromFlightCtrl.Param.sByte[1]; |
||
343 | FC.StickRoll = FromFlightCtrl.Param.sByte[2]; |
||
344 | FC.StickNick = FromFlightCtrl.Param.sByte[3]; |
||
190 | killagreg | 345 | FC.Poti[0] = FromFlightCtrl.Param.Byte[4]; |
346 | FC.Poti[1] = FromFlightCtrl.Param.Byte[5]; |
||
347 | FC.Poti[2] = FromFlightCtrl.Param.Byte[6]; |
||
348 | FC.Poti[3] = FromFlightCtrl.Param.Byte[7]; |
||
349 | FC.Poti[4] = FromFlightCtrl.Param.Byte[8]; |
||
350 | FC.Poti[5] = FromFlightCtrl.Param.Byte[9]; |
||
351 | FC.Poti[6] = FromFlightCtrl.Param.Byte[10]; |
||
352 | FC.Poti[7] = FromFlightCtrl.Param.Byte[11]; |
||
41 | ingob | 353 | break; |
27 | holgerb | 354 | |
41 | ingob | 355 | case SPI_CMD_MISC: |
356 | if(CompassCalState != FromFlightCtrl.Param.Byte[0]) |
||
357 | { // put only new CompassCalState into queue to send via I2C |
||
358 | CompassCalState = FromFlightCtrl.Param.Byte[0]; |
||
359 | fifo_put(&CompassCalcStateFiFo, CompassCalState); |
||
360 | } |
||
58 | killagreg | 361 | Parameter.NaviPH_LoginTime = FromFlightCtrl.Param.Byte[1]; |
79 | killagreg | 362 | NaviData.Variometer = (NaviData.Variometer + 2 * ((s16) FromFlightCtrl.Param.Int[1] - NaviData.Altimeter)) / 2; // provisorisch |
58 | killagreg | 363 | NaviData.Altimeter = (s16) FromFlightCtrl.Param.Int[1]; // is located at byte 2 and 3 |
160 | holgerb | 364 | NaviData.SetpointAltitude = (s16) FromFlightCtrl.Param.Int[2]; // is located at byte 4 and 5 |
365 | CHK_POTI_MM(Parameter.NaviGpsPLimit,FromFlightCtrl.Param.Byte[6],0,255); |
||
366 | CHK_POTI_MM(Parameter.NaviGpsILimit,FromFlightCtrl.Param.Byte[7],0,255); |
||
367 | CHK_POTI_MM(Parameter.NaviGpsDLimit,FromFlightCtrl.Param.Byte[8],0,255); |
||
190 | killagreg | 368 | FC.RC_Quality = FromFlightCtrl.Param.Byte[9]; |
369 | FC.RC_RSSI = FromFlightCtrl.Param.Byte[10]; |
||
370 | NaviData.Gas = (FC.UBat * (u32) FromFlightCtrl.Param.Byte[11]) / (u32) Parameter.LowVoltageWarning; |
||
41 | ingob | 371 | break; |
161 | killagreg | 372 | |
121 | killagreg | 373 | case SPI_CMD_SERVOS: |
374 | ServoParams.Refresh = FromFlightCtrl.Param.Byte[0]; |
||
375 | ServoParams.CompInvert = FromFlightCtrl.Param.Byte[1]; |
||
376 | ServoParams.NickControl = FromFlightCtrl.Param.Byte[2]; |
||
377 | ServoParams.NickComp = FromFlightCtrl.Param.Byte[3]; |
||
161 | killagreg | 378 | ServoParams.NickMin = FromFlightCtrl.Param.Byte[4]; |
121 | killagreg | 379 | ServoParams.NickMax = FromFlightCtrl.Param.Byte[5]; |
380 | ServoParams.RollControl = FromFlightCtrl.Param.Byte[6]; |
||
381 | ServoParams.RollComp = FromFlightCtrl.Param.Byte[7]; |
||
161 | killagreg | 382 | ServoParams.RollMin = FromFlightCtrl.Param.Byte[8]; |
383 | ServoParams.RollMax = FromFlightCtrl.Param.Byte[9]; |
||
119 | killagreg | 384 | break; |
1 | ingob | 385 | |
41 | ingob | 386 | case SPI_CMD_VERSION: |
119 | killagreg | 387 | FC_Version.Major = FromFlightCtrl.Param.Byte[0]; |
388 | FC_Version.Minor = FromFlightCtrl.Param.Byte[1]; |
||
389 | FC_Version.Patch = FromFlightCtrl.Param.Byte[2]; |
||
390 | FC_Version.Compatible = FromFlightCtrl.Param.Byte[3]; |
||
391 | FC_Version.Hardware = FromFlightCtrl.Param.Byte[4]; |
||
41 | ingob | 392 | break; |
1 | ingob | 393 | |
41 | ingob | 394 | default: |
395 | break; |
||
396 | } |
||
1 | ingob | 397 | |
41 | ingob | 398 | // every time we got new data from the FC via SPI call the navigation routine |
399 | GPS_Navigation(); |
||
400 | ClearMKFlags = 1; |
||
180 | killagreg | 401 | |
402 | if(counter) |
||
403 | { |
||
404 | counter--; // count down to enable servo |
||
405 | if(!counter) TIMER2_Init(); // enable Servo Output |
||
406 | } |
||
1 | ingob | 407 | |
41 | ingob | 408 | SPI_RxBuffer_Request = 0; |
180 | killagreg | 409 | timeout = SetDelay(80); // 80 ms, new data are send every 20 ms |
1 | ingob | 410 | |
62 | killagreg | 411 | DebugOut.Analog[0] = FromFlightCtrl.AngleNick; |
412 | DebugOut.Analog[1] = FromFlightCtrl.AngleRoll; |
||
61 | holgerb | 413 | DebugOut.Analog[2] = FromFlightCtrl.AccNick; |
414 | DebugOut.Analog[3] = FromFlightCtrl.AccRoll; |
||
62 | killagreg | 415 | DebugOut.Analog[11] = FromFlightCtrl.GyroHeading/10;// in deg |
79 | killagreg | 416 | Data3D.AngleNick = FromFlightCtrl.AngleNick; // in 0.1 deg |
417 | Data3D.AngleRoll = FromFlightCtrl.AngleRoll; // in 0.1 deg |
||
418 | Data3D.Heading = FromFlightCtrl.GyroHeading; // in 0.1 deg |
||
419 | } // EOF if(SPI_RxBuffer_Request) |
||
180 | killagreg | 420 | else // no new SPI data |
421 | { |
||
422 | if(CheckDelay(timeout) && (counter == 0)) |
||
423 | { |
||
424 | TIMER2_Deinit(); // disable Servo Output |
||
425 | counter = 50; // reset counter for enabling Servo Output |
||
426 | } |
||
427 | } |
||
1 | ingob | 428 | } |
429 | |||
41 | ingob | 430 | //------------------------------------------------------ |
431 | void SPI0_GetFlightCtrlVersion(void) |
||
432 | { |
||
154 | killagreg | 433 | u32 timeout; |
434 | u8 repeat; |
||
78 | holgerb | 435 | u8 msg[64]; |
41 | ingob | 436 | |
154 | killagreg | 437 | UART1_PutString("\r\n Getting Version from FC"); |
41 | ingob | 438 | FC_Version.Major = 0xFF; |
439 | FC_Version.Minor = 0xFF; |
||
440 | FC_Version.Patch = 0xFF; |
||
441 | FC_Version.Compatible = 0xFF; |
||
442 | |||
165 | killagreg | 443 | // polling FC version info |
154 | killagreg | 444 | repeat = 0; |
41 | ingob | 445 | do |
446 | { |
||
154 | killagreg | 447 | timeout = SetDelay(250); |
448 | do |
||
449 | { |
||
450 | SPI0_UpdateBuffer(); |
||
451 | if (FC_Version.Major != 0xFF) break; |
||
452 | }while (!CheckDelay(timeout)); |
||
453 | UART1_PutString("."); |
||
454 | repeat++; |
||
180 | killagreg | 455 | }while((FC_Version.Major == 0xFF) && (repeat < 40)); // 40*250ms = 10s |
41 | ingob | 456 | // if we got it |
457 | if (FC_Version.Major != 0xFF) |
||
458 | { |
||
61 | holgerb | 459 | 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 | 460 | UART1_PutString(msg); |
41 | ingob | 461 | sprintf(msg, " Compatible: %d", FC_Version.Compatible); |
110 | killagreg | 462 | UART1_PutString(msg); |
41 | ingob | 463 | } |
110 | killagreg | 464 | else UART1_PutString("\n\r No version information from FlightCtrl."); |
41 | ingob | 465 | } |
466 | |||
467 |