Rev 298 | Rev 300 | 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" |
||
215 | killagreg | 61 | #include "gps.h" |
41 | ingob | 62 | #include "uart1.h" |
63 | #include "spi_slave.h" |
||
242 | killagreg | 64 | #include "compass.h" |
119 | killagreg | 65 | #include "timer1.h" |
66 | #include "timer2.h" |
||
136 | killagreg | 67 | #include "config.h" |
1 | ingob | 68 | #include "main.h" |
284 | killagreg | 69 | #include "compass.h" |
294 | holgerb | 70 | #include "params.h" |
1 | ingob | 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 |
215 | killagreg | 78 | FromFlightCtrl_t FromFlightCtrl; |
79 | 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 | |
204 | killagreg | 101 | u8 SPI_CommandSequence[] = { SPI_NCCMD_VERSION, SPI_NCCMD_KALMAN, SPI_NCCMD_GPSINFO ,SPI_NCCMD_KALMAN, SPI_NCCMD_KALMAN}; |
41 | ingob | 102 | u8 SPI_CommandCounter = 0; |
222 | holgerb | 103 | s32 ToFC_Rotate_C = 64, ToFC_Rotate_S = 0; |
104 | s32 HeadFreeStartAngle = 0; |
||
277 | killagreg | 105 | s16 FC_WP_EventChannel = 0; // gibt einen Schaltkanal an die FC weiter, wenn der Wegpunkt erreicht wurde |
286 | killagreg | 106 | u32 ToFC_AltitudeRate = 0; |
285 | holgerb | 107 | s32 ToFC_AltitudeSetpoint = 0; |
298 | holgerb | 108 | u8 FromFC_VarioCharacter = ' '; |
58 | killagreg | 109 | |
41 | ingob | 110 | SPI_Version_t FC_Version; |
1 | ingob | 111 | |
41 | ingob | 112 | //-------------------------------------------------------------- |
113 | void SSP0_IRQHandler(void) |
||
114 | { |
||
115 | static u8 rxchksum = 0; |
||
116 | u8 rxdata; |
||
1 | ingob | 117 | |
189 | killagreg | 118 | #define SPI_SYNC1 0 |
119 | #define SPI_SYNC2 1 |
||
120 | #define SPI_DATA 2 |
||
121 | static u8 SPI_State = SPI_SYNC1; |
||
122 | |||
195 | killagreg | 123 | IENABLE; |
124 | |||
161 | killagreg | 125 | // clear pending bits |
41 | ingob | 126 | SSP_ClearITPendingBit(SSP0, SSP_IT_RxTimeOut); |
144 | killagreg | 127 | SSP_ClearITPendingBit(SSP0, SSP_IT_RxFifo); |
189 | killagreg | 128 | |
79 | killagreg | 129 | // while RxFIFO not empty |
130 | while (SSP_GetFlagStatus(SSP0, SSP_FLAG_RxFifoNotEmpty) == SET) |
||
131 | { |
||
41 | ingob | 132 | rxdata = SSP0->DR; // catch the received byte |
133 | // Fill TxFIFO while its not full or end of packet is reached |
||
79 | killagreg | 134 | while (SSP_GetFlagStatus(SSP0, SSP_FLAG_TxFifoNotFull) == SET) |
161 | killagreg | 135 | { |
79 | killagreg | 136 | if (SPI_TxBufferIndex < SPI_TXBUFFER_LEN) // still data to send ? |
137 | { |
||
41 | ingob | 138 | SSP0->DR = SPI_TxBuffer[SPI_TxBufferIndex]; // send a byte |
79 | killagreg | 139 | *Ptr_TxChksum += SPI_TxBuffer[SPI_TxBufferIndex]; // update checksum |
140 | SPI_TxBufferIndex++; // pointer to next byte |
||
141 | } |
||
142 | else // end of packet is reached reset and copy data to tx buffer |
||
143 | { |
||
144 | SPI_TxBufferIndex = 0; // reset buffer index |
||
145 | ToFlightCtrl.Chksum = 0; // initialize checksum |
||
146 | ToFlightCtrl.BeepTime = BeepTime; // set beeptime |
||
147 | BeepTime = 0; // reset local beeptime |
||
41 | ingob | 148 | // copy contents of ToFlightCtrl->SPI_TxBuffer |
79 | killagreg | 149 | memcpy((u8 *) &(SPI_TxBuffer[2]), (u8 *) &ToFlightCtrl, sizeof(ToFlightCtrl)); |
150 | } |
||
41 | ingob | 151 | } |
152 | switch (SPI_State) |
||
153 | { |
||
154 | case SPI_SYNC1: |
||
155 | SPI_RxBufferIndex = 0; // reset buffer index |
||
156 | rxchksum = rxdata; // init checksum |
||
157 | if (rxdata == SPI_RXSYNCBYTE1) |
||
158 | { // 1st syncbyte ok |
||
159 | SPI_State = SPI_SYNC2; // step to sync2 |
||
160 | } |
||
161 | break; |
||
79 | killagreg | 162 | case SPI_SYNC2: |
41 | ingob | 163 | if (rxdata == SPI_RXSYNCBYTE2) |
164 | { // 2nd Syncbyte ok |
||
165 | rxchksum += rxdata; |
||
166 | SPI_State = SPI_DATA; |
||
167 | } // 2nd Syncbyte does not match |
||
168 | else |
||
169 | { |
||
170 | SPI_State = SPI_SYNC1; //jump back to sync1 |
||
171 | } |
||
172 | break; |
||
173 | case SPI_DATA: |
||
174 | SPI_RxBuffer[SPI_RxBufferIndex++]= rxdata; // copy databyte to rx buffer |
||
175 | if (SPI_RxBufferIndex >= SPI_RXBUFFER_LEN) // end of packet is reached |
||
176 | { |
||
177 | if (rxdata == rxchksum) // verify checksum byte |
||
178 | { |
||
179 | // copy SPI_RxBuffer -> FromFlightCtrl |
||
180 | if(!SPI_RxBuffer_Request) // block writing to FromFlightCtrl on reading access |
||
181 | { |
||
182 | memcpy((u8 *) &FromFlightCtrl, (u8 *) SPI_RxBuffer, sizeof(FromFlightCtrl)); |
||
183 | SPI_RxBuffer_Request = 1; |
||
184 | } |
||
146 | killagreg | 185 | // reset timeout counter on good packet |
186 | SPI0_Timeout = SetDelay(SPI0_TIMEOUT); |
||
41 | ingob | 187 | DebugOut.Analog[13]++; |
188 | } |
||
189 | else // bad checksum byte |
||
190 | { |
||
191 | DebugOut.Analog[12]++; // increase SPI chksum error counter |
||
192 | } |
||
193 | SPI_State = SPI_SYNC1; // reset state |
||
194 | } |
||
195 | else // end of packet not reached |
||
196 | { |
||
197 | rxchksum += rxdata; // update checksum |
||
198 | } |
||
199 | break; |
||
200 | default: |
||
201 | SPI_State = SPI_SYNC1; |
||
202 | break; |
||
203 | } |
||
204 | } |
||
195 | killagreg | 205 | |
206 | IDISABLE; |
||
1 | ingob | 207 | } |
208 | |||
209 | //-------------------------------------------------------------- |
||
210 | void SPI0_Init(void) |
||
211 | { |
||
41 | ingob | 212 | GPIO_InitTypeDef GPIO_InitStructure; |
213 | SSP_InitTypeDef SSP_InitStructure; |
||
1 | ingob | 214 | |
110 | killagreg | 215 | UART1_PutString("\r\n SPI init..."); |
1 | ingob | 216 | |
41 | ingob | 217 | SCU_APBPeriphClockConfig(__GPIO2 ,ENABLE); |
218 | SCU_APBPeriphClockConfig(__SSP0 ,ENABLE); |
||
1 | ingob | 219 | |
41 | ingob | 220 | GPIO_DeInit(GPIO2); |
221 | //SSP0_CLK, SSP0_MOSI, SSP0_NSS pins |
||
222 | GPIO_StructInit(&GPIO_InitStructure); |
||
223 | GPIO_InitStructure.GPIO_Direction = GPIO_PinInput; |
||
224 | GPIO_InitStructure.GPIO_Pin = GPIO_Pin_4 | GPIO_Pin_5 | GPIO_Pin_7; |
||
225 | GPIO_InitStructure.GPIO_Type = GPIO_Type_PushPull ; |
||
196 | killagreg | 226 | GPIO_InitStructure.GPIO_IPInputConnected = GPIO_IPInputConnected_Enable; |
41 | ingob | 227 | GPIO_InitStructure.GPIO_Alternate = GPIO_InputAlt1; //SSP0_SCLK, SSP0_MOSI, SSP0_NSS |
228 | GPIO_Init (GPIO2, &GPIO_InitStructure); |
||
1 | ingob | 229 | |
41 | ingob | 230 | // SSP0_MISO pin GPIO2.6 |
231 | GPIO_StructInit(&GPIO_InitStructure); |
||
232 | GPIO_InitStructure.GPIO_Direction = GPIO_PinOutput; |
||
233 | GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6; |
||
234 | GPIO_InitStructure.GPIO_Type = GPIO_Type_PushPull ; |
||
196 | killagreg | 235 | GPIO_InitStructure.GPIO_IPInputConnected = GPIO_IPInputConnected_Enable; |
41 | ingob | 236 | GPIO_InitStructure.GPIO_Alternate = GPIO_OutputAlt2; //SSP0_MISO |
237 | GPIO_Init (GPIO2, &GPIO_InitStructure); |
||
1 | ingob | 238 | |
41 | ingob | 239 | SSP_DeInit(SSP0); |
240 | SSP_StructInit(&SSP_InitStructure); |
||
241 | SSP_InitStructure.SSP_FrameFormat = SSP_FrameFormat_Motorola; |
||
242 | SSP_InitStructure.SSP_Mode = SSP_Mode_Slave; |
||
243 | SSP_InitStructure.SSP_SlaveOutput = SSP_SlaveOutput_Enable; |
||
244 | SSP_InitStructure.SSP_CPHA = SSP_CPHA_1Edge; |
||
245 | SSP_InitStructure.SSP_CPOL = SSP_CPOL_Low; |
||
246 | SSP_InitStructure.SSP_ClockRate = 0; |
||
1 | ingob | 247 | |
41 | ingob | 248 | SSP_Init(SSP0, &SSP_InitStructure); |
144 | killagreg | 249 | SSP_ITConfig(SSP0, SSP_IT_RxFifo | SSP_IT_RxTimeOut, ENABLE); |
202 | killagreg | 250 | |
41 | ingob | 251 | SSP_Cmd(SSP0, ENABLE); |
252 | // initialize the syncbytes in the tx buffer |
||
253 | SPI_TxBuffer[0] = SPI_TXSYNCBYTE1; |
||
254 | SPI_TxBuffer[1] = SPI_TXSYNCBYTE2; |
||
255 | // set the pointer to the checksum byte in the tx buffer |
||
256 | Ptr_TxChksum = (u8 *) &(((ToFlightCtrl_t *) &(SPI_TxBuffer[2]))->Chksum); |
||
257 | |||
215 | killagreg | 258 | ToFlightCtrl.GPSStick.Nick = 0; |
259 | ToFlightCtrl.GPSStick.Roll = 0; |
||
260 | ToFlightCtrl.GPSStick.Yaw = 0; |
||
261 | |||
136 | killagreg | 262 | VIC_Config(SSP0_ITLine, VIC_IRQ, PRIORITY_SPI0); |
41 | ingob | 263 | VIC_ITCmd(SSP0_ITLine, ENABLE); |
264 | |||
146 | killagreg | 265 | SPI0_Timeout = SetDelay(4*SPI0_TIMEOUT); |
266 | |||
110 | killagreg | 267 | UART1_PutString("ok"); |
1 | ingob | 268 | } |
41 | ingob | 269 | |
222 | holgerb | 270 | |
1 | ingob | 271 | //------------------------------------------------------ |
41 | ingob | 272 | void SPI0_UpdateBuffer(void) |
1 | ingob | 273 | { |
180 | killagreg | 274 | static u32 timeout = 0; |
275 | static u8 counter = 50; |
||
254 | killagreg | 276 | static u8 CompassCalState = 0; |
268 | killagreg | 277 | static u8 FCCalibActive = 0; |
299 | killagreg | 278 | s16 tmp; |
202 | killagreg | 279 | |
41 | ingob | 280 | if (SPI_RxBuffer_Request) |
281 | { |
||
282 | // avoid sending data via SPI during the update of the ToFlightCtrl structure |
||
283 | VIC_ITCmd(SSP0_ITLine, DISABLE); // disable SPI interrupt |
||
254 | killagreg | 284 | ToFlightCtrl.CompassHeading = Compass_Heading; |
189 | killagreg | 285 | DebugOut.Analog[10] = ToFlightCtrl.CompassHeading; |
228 | holgerb | 286 | if(ToFlightCtrl.CompassHeading >= 0) ToFlightCtrl.CompassHeading = (360 + ToFlightCtrl.CompassHeading + FromFlightCtrl.GyroYaw / 12) % 360; |
286 | killagreg | 287 | ToFlightCtrl.MagVecX = MagVector.X; |
288 | ToFlightCtrl.MagVecY = MagVector.Y; |
||
289 | ToFlightCtrl.MagVecZ = MagVector.Z; |
||
284 | killagreg | 290 | ToFlightCtrl.NCStatus = 0; |
41 | ingob | 291 | // cycle spi commands |
292 | ToFlightCtrl.Command = SPI_CommandSequence[SPI_CommandCounter++]; |
||
118 | killagreg | 293 | // restart command cycle at the end |
41 | ingob | 294 | if (SPI_CommandCounter >= sizeof(SPI_CommandSequence)) SPI_CommandCounter = 0; |
1 | ingob | 295 | |
41 | ingob | 296 | switch (ToFlightCtrl.Command) |
297 | { |
||
202 | killagreg | 298 | case SPI_NCCMD_KALMAN: |
223 | killagreg | 299 | CalcHeadFree(); |
149 | killagreg | 300 | ToFlightCtrl.Param.sByte[0] = (s8) Kalman_K; |
92 | killagreg | 301 | ToFlightCtrl.Param.sByte[1] = (s8) Kalman_MaxFusion; |
302 | ToFlightCtrl.Param.sByte[2] = (s8) Kalman_MaxDrift; |
||
118 | killagreg | 303 | ToFlightCtrl.Param.Byte[3] = (u8) SerialLinkOkay; |
149 | killagreg | 304 | ToFlightCtrl.Param.sByte[4] = (s8) ToFcGpsZ; |
222 | holgerb | 305 | ToFlightCtrl.Param.Byte[5] = (s8) ToFC_Rotate_C; |
223 | killagreg | 306 | ToFlightCtrl.Param.Byte[6] = (s8) ToFC_Rotate_S; |
285 | holgerb | 307 | //ToFlightCtrl.Param.Byte[7] = |
280 | killagreg | 308 | if(CAM_Orientation.UpdateMask & CAM_UPDATE_AZIMUTH) |
278 | killagreg | 309 | { |
310 | ToFlightCtrl.Param.sInt[4] = CAM_Orientation.Azimuth; |
||
280 | killagreg | 311 | CAM_Orientation.UpdateMask &= ~CAM_UPDATE_AZIMUTH; |
278 | killagreg | 312 | } |
313 | else |
||
280 | killagreg | 314 | { |
278 | killagreg | 315 | ToFlightCtrl.Param.sInt[4] = -1; |
316 | } |
||
294 | holgerb | 317 | |
299 | killagreg | 318 | if(NCRARAM_STATE_VALID == NCParams_GetValue(NCPARAMS_NEW_CAMERA_ELEVATION, &tmp)) // Elevation set via 'j' command |
295 | killagreg | 319 | { |
299 | killagreg | 320 | ToFlightCtrl.Param.sInt[5] = tmp; |
321 | } |
||
322 | else |
||
323 | { |
||
295 | killagreg | 324 | if(FC.StatusFlags2 & FC_STATUS2_CAREFREE) ToFlightCtrl.Param.sInt[5] = CAM_Orientation.Elevation; // only, if carefree is active |
325 | else ToFlightCtrl.Param.sInt[5] = 0; |
||
326 | } |
||
161 | killagreg | 327 | break; |
58 | killagreg | 328 | |
202 | killagreg | 329 | case SPI_NCCMD_VERSION: |
330 | ToFlightCtrl.Param.Byte[0] = VERSION_MAJOR; |
||
331 | ToFlightCtrl.Param.Byte[1] = VERSION_MINOR; |
||
204 | killagreg | 332 | ToFlightCtrl.Param.Byte[2] = VERSION_PATCH; |
202 | killagreg | 333 | ToFlightCtrl.Param.Byte[3] = FC_SPI_COMPATIBLE; |
264 | killagreg | 334 | ToFlightCtrl.Param.Byte[4] = Version_HW; |
231 | holgerb | 335 | ToFlightCtrl.Param.Byte[5] = DebugOut.Status[0]; |
336 | ToFlightCtrl.Param.Byte[6] = DebugOut.Status[1]; |
||
233 | holgerb | 337 | ToFlightCtrl.Param.Byte[7] = ErrorCode; |
202 | killagreg | 338 | break; |
223 | killagreg | 339 | |
204 | killagreg | 340 | case SPI_NCCMD_GPSINFO: |
341 | ToFlightCtrl.Param.Byte[0] = GPSData.Flags; |
||
342 | ToFlightCtrl.Param.Byte[1] = GPSData.NumOfSats; |
||
343 | ToFlightCtrl.Param.Byte[2] = GPSData.SatFix; |
||
232 | killagreg | 344 | ToFlightCtrl.Param.Byte[3] = GPSData.Speed_Ground / 100; // m/s |
258 | holgerb | 345 | ToFlightCtrl.Param.Int[2] = NaviData.HomePositionDeviation.Distance; // dm //4&5 |
346 | ToFlightCtrl.Param.sInt[3] = NaviData.HomePositionDeviation.Bearing; // deg //6&7 |
||
347 | ToFlightCtrl.Param.Byte[8] = (s8)(FC_WP_EventChannel - 110); |
||
299 | killagreg | 348 | |
349 | if(NCRARAM_STATE_VALID == NCParams_GetValue(NCPARAMS_ALTITUDE_RATE, &tmp)) |
||
350 | { |
||
351 | ToFlightCtrl.Param.Byte[9] = (u8)tmp; |
||
295 | killagreg | 352 | } |
299 | killagreg | 353 | else |
354 | { |
||
355 | ToFlightCtrl.Param.Byte[9] = (u8)ToFC_AltitudeRate; |
||
356 | } |
||
357 | if(NCRARAM_STATE_VALID == NCParams_GetValue(NCPARAMS_ALTITUDE_SETPOINT, &tmp)) |
||
358 | { |
||
359 | ToFlightCtrl.Param.sInt[5] = tmp; |
||
360 | } |
||
361 | else |
||
362 | { |
||
363 | ToFlightCtrl.Param.sInt[5] = (s16)ToFC_AltitudeSetpoint; |
||
364 | } |
||
365 | DebugOut.Analog[25] = (s16)ToFlightCtrl.Param.Byte[9]; |
||
366 | DebugOut.Analog[20] = ToFlightCtrl.Param.sInt[5]; |
||
204 | killagreg | 367 | break; |
299 | killagreg | 368 | |
41 | ingob | 369 | default: |
370 | break; |
||
285 | holgerb | 371 | // 0 = 0,1 |
372 | // 1 = 2,3 |
||
373 | // 2 = 4,5 |
||
374 | // 3 = 6,7 |
||
375 | // 4 = 8,9 |
||
376 | // 5 = 10,11 |
||
41 | ingob | 377 | } |
378 | VIC_ITCmd(SSP0_ITLine, ENABLE); // enable SPI interrupt |
||
1 | ingob | 379 | |
380 | |||
41 | ingob | 381 | switch(FromFlightCtrl.Command) |
382 | { |
||
202 | killagreg | 383 | case SPI_FCCMD_USER: |
41 | ingob | 384 | Parameter.User1 = FromFlightCtrl.Param.Byte[0]; |
385 | Parameter.User2 = FromFlightCtrl.Param.Byte[1]; |
||
386 | Parameter.User3 = FromFlightCtrl.Param.Byte[2]; |
||
387 | Parameter.User4 = FromFlightCtrl.Param.Byte[3]; |
||
388 | Parameter.User5 = FromFlightCtrl.Param.Byte[4]; |
||
389 | Parameter.User6 = FromFlightCtrl.Param.Byte[5]; |
||
390 | Parameter.User7 = FromFlightCtrl.Param.Byte[6]; |
||
391 | Parameter.User8 = FromFlightCtrl.Param.Byte[7]; |
||
255 | killagreg | 392 | if(ClearFCStatusFlags) |
41 | ingob | 393 | { |
255 | killagreg | 394 | FC.StatusFlags = 0; |
395 | ClearFCStatusFlags = 0; |
||
41 | ingob | 396 | } |
255 | killagreg | 397 | FC.StatusFlags |= FromFlightCtrl.Param.Byte[8]; |
284 | killagreg | 398 | if(FC.StatusFlags&FC_STATUS_CALIBRATE && !FCCalibActive) |
268 | killagreg | 399 | { |
400 | Compass_Init(); |
||
401 | FCCalibActive = 1; |
||
402 | } |
||
403 | else |
||
404 | { |
||
284 | killagreg | 405 | FCCalibActive = 0; |
268 | killagreg | 406 | } |
223 | killagreg | 407 | Parameter.ActiveSetting = FromFlightCtrl.Param.Byte[9]; |
255 | killagreg | 408 | DebugOut.Analog[5] = FC.StatusFlags; |
294 | holgerb | 409 | FC.StatusFlags2 = FromFlightCtrl.Param.Byte[11]; |
255 | killagreg | 410 | NaviData.FCStatusFlags = FC.StatusFlags; |
294 | holgerb | 411 | NaviData.FCStatusFlags2 = FC.StatusFlags2; |
223 | killagreg | 412 | HeadFreeStartAngle = (s32) FromFlightCtrl.Param.Byte[10] * 20; // convert to 0.1° |
41 | ingob | 413 | break; |
1 | ingob | 414 | |
206 | killagreg | 415 | case SPI_FCCMD_ACCU: |
223 | killagreg | 416 | FC.BAT_Current = FromFlightCtrl.Param.Int[0]; |
206 | killagreg | 417 | FC.BAT_UsedCapacity = FromFlightCtrl.Param.Int[1]; |
418 | FC.BAT_Voltage = FromFlightCtrl.Param.Byte[4]; |
||
419 | Parameter.LowVoltageWarning = FromFlightCtrl.Param.Byte[5]; |
||
298 | holgerb | 420 | FromFC_VarioCharacter = FromFlightCtrl.Param.Byte[6]; |
421 | if(FromFC_VarioCharacter == '+' || FromFC_VarioCharacter == '-') // manual setpoint clears the NC-Parameter command |
||
422 | { |
||
423 | NCParams_ClearValue(NCPARAMS_ALTITUDE_RATE); |
||
424 | } |
||
425 | |||
206 | killagreg | 426 | NaviData.UBat = FC.BAT_Voltage; |
427 | NaviData.Current = FC.BAT_Current; |
||
428 | NaviData.UsedCapacity = FC.BAT_UsedCapacity; |
||
429 | break; |
||
430 | |||
193 | killagreg | 431 | #define CHK_POTI(b,a) { if(a < 248) b = a; else b = FC.Poti[255 - a]; } |
190 | killagreg | 432 | #define CHK_POTI_MM(b,a,min,max) {CHK_POTI(b,a); LIMIT_MIN_MAX(b, min, max); } |
433 | |||
202 | killagreg | 434 | case SPI_FCCMD_PARAMETER1: |
41 | ingob | 435 | CHK_POTI_MM(Parameter.NaviGpsModeControl,FromFlightCtrl.Param.Byte[0],0,255); |
436 | CHK_POTI_MM(Parameter.NaviGpsGain,FromFlightCtrl.Param.Byte[1],0,255); |
||
437 | CHK_POTI_MM(Parameter.NaviGpsP,FromFlightCtrl.Param.Byte[2],0,255); |
||
438 | CHK_POTI_MM(Parameter.NaviGpsI,FromFlightCtrl.Param.Byte[3],0,255); |
||
439 | CHK_POTI_MM(Parameter.NaviGpsD,FromFlightCtrl.Param.Byte[4],0,255); |
||
440 | CHK_POTI_MM(Parameter.NaviGpsACC,FromFlightCtrl.Param.Byte[5],0,255); |
||
441 | Parameter.NaviGpsMinSat = FromFlightCtrl.Param.Byte[6]; |
||
442 | Parameter.NaviStickThreshold = FromFlightCtrl.Param.Byte[7]; |
||
103 | killagreg | 443 | CHK_POTI_MM(Parameter.NaviOperatingRadius,FromFlightCtrl.Param.Byte[8],0,255); |
41 | ingob | 444 | CHK_POTI_MM(Parameter.NaviWindCorrection,FromFlightCtrl.Param.Byte[9],0,255); |
445 | CHK_POTI_MM(Parameter.NaviSpeedCompensation,FromFlightCtrl.Param.Byte[10],0,255); |
||
446 | CHK_POTI_MM(Parameter.NaviAngleLimitation,FromFlightCtrl.Param.Byte[11],0,255); |
||
121 | killagreg | 447 | break; |
1 | ingob | 448 | |
202 | killagreg | 449 | case SPI_FCCMD_STICK: |
41 | ingob | 450 | FC.StickGas = FromFlightCtrl.Param.sByte[0]; |
451 | FC.StickYaw = FromFlightCtrl.Param.sByte[1]; |
||
452 | FC.StickRoll = FromFlightCtrl.Param.sByte[2]; |
||
453 | FC.StickNick = FromFlightCtrl.Param.sByte[3]; |
||
190 | killagreg | 454 | FC.Poti[0] = FromFlightCtrl.Param.Byte[4]; |
455 | FC.Poti[1] = FromFlightCtrl.Param.Byte[5]; |
||
456 | FC.Poti[2] = FromFlightCtrl.Param.Byte[6]; |
||
457 | FC.Poti[3] = FromFlightCtrl.Param.Byte[7]; |
||
458 | FC.Poti[4] = FromFlightCtrl.Param.Byte[8]; |
||
459 | FC.Poti[5] = FromFlightCtrl.Param.Byte[9]; |
||
460 | FC.Poti[6] = FromFlightCtrl.Param.Byte[10]; |
||
202 | killagreg | 461 | FC.Poti[7] = FromFlightCtrl.Param.Byte[11]; |
41 | ingob | 462 | break; |
27 | holgerb | 463 | |
202 | killagreg | 464 | case SPI_FCCMD_MISC: |
41 | ingob | 465 | if(CompassCalState != FromFlightCtrl.Param.Byte[0]) |
466 | { // put only new CompassCalState into queue to send via I2C |
||
467 | CompassCalState = FromFlightCtrl.Param.Byte[0]; |
||
254 | killagreg | 468 | Compass_SetCalState(CompassCalState); |
41 | ingob | 469 | } |
58 | killagreg | 470 | Parameter.NaviPH_LoginTime = FromFlightCtrl.Param.Byte[1]; |
205 | killagreg | 471 | NaviData.Variometer = (NaviData.Variometer + 2 * (FromFlightCtrl.Param.sInt[1] - NaviData.Altimeter)) / 2; // provisorisch |
287 | holgerb | 472 | NaviData.Altimeter = FromFlightCtrl.Param.sInt[1]; // in 5cm |
473 | NaviData.SetpointAltitude = FromFlightCtrl.Param.sInt[2]; // in 5cm |
||
160 | holgerb | 474 | CHK_POTI_MM(Parameter.NaviGpsPLimit,FromFlightCtrl.Param.Byte[6],0,255); |
475 | CHK_POTI_MM(Parameter.NaviGpsILimit,FromFlightCtrl.Param.Byte[7],0,255); |
||
476 | CHK_POTI_MM(Parameter.NaviGpsDLimit,FromFlightCtrl.Param.Byte[8],0,255); |
||
190 | killagreg | 477 | FC.RC_Quality = FromFlightCtrl.Param.Byte[9]; |
478 | FC.RC_RSSI = FromFlightCtrl.Param.Byte[10]; |
||
294 | holgerb | 479 | if(!FC.RC_RSSI) NaviData.RC_Quality = FC.RC_Quality; else NaviData.RC_Quality = FC.RC_RSSI; |
480 | // NaviData.RC_RSSI = FC.RC_RSSI; |
||
206 | killagreg | 481 | NaviData.Gas = (FC.BAT_Voltage * (u32) FromFlightCtrl.Param.Byte[11]) / (u32) Parameter.LowVoltageWarning; |
41 | ingob | 482 | break; |
161 | killagreg | 483 | |
202 | killagreg | 484 | case SPI_FCCMD_SERVOS: |
121 | killagreg | 485 | ServoParams.Refresh = FromFlightCtrl.Param.Byte[0]; |
486 | ServoParams.CompInvert = FromFlightCtrl.Param.Byte[1]; |
||
487 | ServoParams.NickControl = FromFlightCtrl.Param.Byte[2]; |
||
488 | ServoParams.NickComp = FromFlightCtrl.Param.Byte[3]; |
||
161 | killagreg | 489 | ServoParams.NickMin = FromFlightCtrl.Param.Byte[4]; |
121 | killagreg | 490 | ServoParams.NickMax = FromFlightCtrl.Param.Byte[5]; |
491 | ServoParams.RollControl = FromFlightCtrl.Param.Byte[6]; |
||
492 | ServoParams.RollComp = FromFlightCtrl.Param.Byte[7]; |
||
161 | killagreg | 493 | ServoParams.RollMin = FromFlightCtrl.Param.Byte[8]; |
494 | ServoParams.RollMax = FromFlightCtrl.Param.Byte[9]; |
||
119 | killagreg | 495 | break; |
1 | ingob | 496 | |
202 | killagreg | 497 | case SPI_FCCMD_VERSION: |
119 | killagreg | 498 | FC_Version.Major = FromFlightCtrl.Param.Byte[0]; |
499 | FC_Version.Minor = FromFlightCtrl.Param.Byte[1]; |
||
500 | FC_Version.Patch = FromFlightCtrl.Param.Byte[2]; |
||
501 | FC_Version.Compatible = FromFlightCtrl.Param.Byte[3]; |
||
502 | FC_Version.Hardware = FromFlightCtrl.Param.Byte[4]; |
||
255 | killagreg | 503 | FC.Error[0] = FromFlightCtrl.Param.Byte[5]; |
504 | FC.Error[1] = FromFlightCtrl.Param.Byte[6]; |
||
505 | FC.Error[2] = FromFlightCtrl.Param.Byte[7]; |
||
506 | FC.Error[3] = FromFlightCtrl.Param.Byte[8]; |
||
507 | FC.Error[4] = FromFlightCtrl.Param.Byte[9]; |
||
231 | holgerb | 508 | DebugOut.Status[0] |= 0x01; // status of FC Present |
232 | killagreg | 509 | DebugOut.Status[0] |= 0x02; // status of BL Present |
255 | killagreg | 510 | if(FC.Error[0] || FC.Error[1] || FC.Error[2] || FC.Error[3] || FC.Error[4]) DebugOut.Status[1] |= 0x01; |
232 | killagreg | 511 | else DebugOut.Status[1] &= ~0x01; |
41 | ingob | 512 | break; |
513 | default: |
||
204 | killagreg | 514 | break; |
41 | ingob | 515 | } |
1 | ingob | 516 | |
41 | ingob | 517 | // every time we got new data from the FC via SPI call the navigation routine |
215 | killagreg | 518 | // and update GPSStick that are returned to FC |
519 | GPS_Navigation(&GPSData, &(ToFlightCtrl.GPSStick)); |
||
255 | killagreg | 520 | ClearFCStatusFlags = 1; |
202 | killagreg | 521 | |
180 | killagreg | 522 | if(counter) |
523 | { |
||
524 | counter--; // count down to enable servo |
||
202 | killagreg | 525 | if(!counter) TIMER2_Init(); // enable Servo Output |
180 | killagreg | 526 | } |
1 | ingob | 527 | |
41 | ingob | 528 | SPI_RxBuffer_Request = 0; |
180 | killagreg | 529 | timeout = SetDelay(80); // 80 ms, new data are send every 20 ms |
1 | ingob | 530 | |
62 | killagreg | 531 | DebugOut.Analog[0] = FromFlightCtrl.AngleNick; |
532 | DebugOut.Analog[1] = FromFlightCtrl.AngleRoll; |
||
61 | holgerb | 533 | DebugOut.Analog[2] = FromFlightCtrl.AccNick; |
534 | DebugOut.Analog[3] = FromFlightCtrl.AccRoll; |
||
62 | killagreg | 535 | DebugOut.Analog[11] = FromFlightCtrl.GyroHeading/10;// in deg |
79 | killagreg | 536 | Data3D.AngleNick = FromFlightCtrl.AngleNick; // in 0.1 deg |
537 | Data3D.AngleRoll = FromFlightCtrl.AngleRoll; // in 0.1 deg |
||
538 | Data3D.Heading = FromFlightCtrl.GyroHeading; // in 0.1 deg |
||
539 | } // EOF if(SPI_RxBuffer_Request) |
||
180 | killagreg | 540 | else // no new SPI data |
202 | killagreg | 541 | { |
180 | killagreg | 542 | if(CheckDelay(timeout) && (counter == 0)) |
543 | { |
||
544 | TIMER2_Deinit(); // disable Servo Output |
||
545 | counter = 50; // reset counter for enabling Servo Output |
||
546 | } |
||
547 | } |
||
1 | ingob | 548 | } |
549 | |||
41 | ingob | 550 | //------------------------------------------------------ |
551 | void SPI0_GetFlightCtrlVersion(void) |
||
552 | { |
||
154 | killagreg | 553 | u32 timeout; |
554 | u8 repeat; |
||
78 | holgerb | 555 | u8 msg[64]; |
41 | ingob | 556 | |
297 | ingob | 557 | UART1_PutString("\r\n Looking for FlightControl"); |
41 | ingob | 558 | FC_Version.Major = 0xFF; |
559 | FC_Version.Minor = 0xFF; |
||
560 | FC_Version.Patch = 0xFF; |
||
561 | FC_Version.Compatible = 0xFF; |
||
562 | |||
165 | killagreg | 563 | // polling FC version info |
154 | killagreg | 564 | repeat = 0; |
41 | ingob | 565 | do |
566 | { |
||
154 | killagreg | 567 | timeout = SetDelay(250); |
568 | do |
||
569 | { |
||
570 | SPI0_UpdateBuffer(); |
||
571 | if (FC_Version.Major != 0xFF) break; |
||
572 | }while (!CheckDelay(timeout)); |
||
573 | UART1_PutString("."); |
||
574 | repeat++; |
||
180 | killagreg | 575 | }while((FC_Version.Major == 0xFF) && (repeat < 40)); // 40*250ms = 10s |
41 | ingob | 576 | // if we got it |
577 | if (FC_Version.Major != 0xFF) |
||
578 | { |
||
242 | killagreg | 579 | sprintf(msg, " FC 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 | 580 | UART1_PutString(msg); |
41 | ingob | 581 | } |
242 | killagreg | 582 | else UART1_PutString("\n\r not found!"); |
41 | ingob | 583 | } |
584 | |||
585 |