Rev 215 | Rev 225 | Go to most recent revision | Only display areas with differences | Ignore whitespace | Details | Blame | Last modification | View Log | RSS feed
Rev 215 | Rev 224 | ||
---|---|---|---|
1 | /*#######################################################################################*/ |
1 | /*#######################################################################################*/ |
2 | /* !!! THIS IS NOT FREE SOFTWARE !!! */ |
2 | /* !!! THIS IS NOT FREE SOFTWARE !!! */ |
3 | /*#######################################################################################*/ |
3 | /*#######################################################################################*/ |
4 | // ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ |
4 | // ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ |
5 | // + Copyright (c) 2008 Ingo Busker, Holger Buss |
5 | // + Copyright (c) 2008 Ingo Busker, Holger Buss |
6 | // + Nur für den privaten Gebrauch / NON-COMMERCIAL USE ONLY |
6 | // + Nur für den privaten Gebrauch / NON-COMMERCIAL USE ONLY |
7 | // + FOR NON COMMERCIAL USE ONLY |
7 | // + FOR NON COMMERCIAL USE ONLY |
8 | // + www.MikroKopter.com |
8 | // + www.MikroKopter.com |
9 | // ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ |
9 | // ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ |
10 | // + Es gilt für das gesamte Projekt (Hardware, Software, Binärfiles, Sourcecode und Dokumentation), |
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. |
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 |
12 | // + Sollten direkte oder indirekte kommerzielle Absichten verfolgt werden, ist mit uns (info@mikrokopter.de) Kontakt |
13 | // + bzgl. der Nutzungsbedingungen aufzunehmen. |
13 | // + bzgl. der Nutzungsbedingungen aufzunehmen. |
14 | // + Eine kommerzielle Nutzung ist z.B.Verkauf von MikroKoptern, Bestückung und Verkauf von Platinen oder Bausätzen, |
14 | // + Eine kommerzielle Nutzung ist z.B.Verkauf von MikroKoptern, Bestückung und Verkauf von Platinen oder Bausätzen, |
15 | // + Verkauf von Luftbildaufnahmen, usw. |
15 | // + Verkauf von Luftbildaufnahmen, usw. |
16 | // ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ |
16 | // ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ |
17 | // + Werden Teile des Quellcodes (mit oder ohne Modifikation) weiterverwendet oder veröffentlicht, |
17 | // + Werden Teile des Quellcodes (mit oder ohne Modifikation) weiterverwendet oder veröffentlicht, |
18 | // + unterliegen sie auch diesen Nutzungsbedingungen und diese Nutzungsbedingungen incl. Copyright müssen dann beiliegen |
18 | // + unterliegen sie auch diesen Nutzungsbedingungen und diese Nutzungsbedingungen incl. Copyright müssen dann beiliegen |
19 | // ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ |
19 | // ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ |
20 | // + Sollte die Software (auch auszugesweise) oder sonstige Informationen des MikroKopter-Projekts |
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" |
21 | // + auf anderen Webseiten oder sonstigen Medien veröffentlicht werden, muss unsere Webseite "http://www.mikrokopter.de" |
22 | // + eindeutig als Ursprung verlinkt werden |
22 | // + eindeutig als Ursprung verlinkt werden |
23 | // ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ |
23 | // ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ |
24 | // + Keine Gewähr auf Fehlerfreiheit, Vollständigkeit oder Funktion |
24 | // + Keine Gewähr auf Fehlerfreiheit, Vollständigkeit oder Funktion |
25 | // + Benutzung auf eigene Gefahr |
25 | // + Benutzung auf eigene Gefahr |
26 | // + Wir übernehmen keinerlei Haftung für direkte oder indirekte Personen- oder Sachschäden |
26 | // + Wir übernehmen keinerlei Haftung für direkte oder indirekte Personen- oder Sachschäden |
27 | // ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ |
27 | // ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ |
28 | // + Die Portierung oder Nutzung der Software (oder Teile davon) auf andere Systeme (ausser der Hardware von www.mikrokopter.de) ist nur |
28 | // + Die Portierung oder Nutzung der Software (oder Teile davon) auf andere Systeme (ausser der Hardware von www.mikrokopter.de) ist nur |
29 | // + mit unserer Zustimmung zulässig |
29 | // + mit unserer Zustimmung zulässig |
30 | // ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ |
30 | // ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ |
31 | // + Die Funktion printf_P() unterliegt ihrer eigenen Lizenz und ist hiervon nicht betroffen |
31 | // + Die Funktion printf_P() unterliegt ihrer eigenen Lizenz und ist hiervon nicht betroffen |
32 | // ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ |
32 | // ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ |
33 | // + Redistributions of source code (with or without modifications) must retain the above copyright notice, |
33 | // + Redistributions of source code (with or without modifications) must retain the above copyright notice, |
34 | // + this list of conditions and the following disclaimer. |
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 |
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. |
36 | // + from this software without specific prior written permission. |
37 | // + * The use of this project (hardware, software, binary files, sources and documentation) is only permitted |
37 | // + * The use of this project (hardware, software, binary files, sources and documentation) is only permitted |
38 | // + for non-commercial use (directly or indirectly) |
38 | // + for non-commercial use (directly or indirectly) |
39 | // + Commercial use (for excample: selling of MikroKopters, selling of PCBs, assembly, ...) is only permitted |
39 | // + Commercial use (for excample: selling of MikroKopters, selling of PCBs, assembly, ...) is only permitted |
40 | // + with our written permission |
40 | // + with our written permission |
41 | // + * If sources or documentations are redistributet on other webpages, out webpage (http://www.MikroKopter.de) must be |
41 | // + * If sources or documentations are redistributet on other webpages, out webpage (http://www.MikroKopter.de) must be |
42 | // + clearly linked as origin |
42 | // + clearly linked as origin |
43 | // + * porting the sources to other systems or using the software on other systems (except hardware from www.mikrokopter.de) is not allowed |
43 | // + * porting the sources to other systems or using the software on other systems (except hardware from www.mikrokopter.de) is not allowed |
44 | // |
44 | // |
45 | // + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" |
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 |
46 | // + AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE |
47 | // + IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE |
47 | // + IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE |
48 | // + ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE |
48 | // + ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE |
49 | // + LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR |
49 | // + LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR |
50 | // + CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF |
50 | // + CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF |
51 | // + SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS |
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 |
52 | // + INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN |
53 | // + CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) |
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 |
54 | // + ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
55 | // + POSSIBILITY OF SUCH DAMAGE. |
55 | // + POSSIBILITY OF SUCH DAMAGE. |
56 | // ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ |
56 | // ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ |
57 | #include <stdio.h> |
57 | #include <stdio.h> |
58 | #include <stdarg.h> |
58 | #include <stdarg.h> |
59 | #include <string.h> |
59 | #include <string.h> |
60 | 60 | ||
61 | #include "91x_lib.h" |
61 | #include "91x_lib.h" |
62 | #include "config.h" |
62 | #include "config.h" |
63 | #include "menu.h" |
63 | #include "menu.h" |
64 | #include "GPS.h" |
64 | #include "GPS.h" |
65 | #include "i2c.h" |
65 | #include "i2c.h" |
66 | #include "uart0.h" |
66 | #include "uart0.h" |
67 | #include "uart1.h" |
67 | #include "uart1.h" |
68 | #include "uart2.h" |
68 | #include "uart2.h" |
69 | #include "timer1.h" |
69 | #include "timer1.h" |
70 | #include "timer2.h" |
70 | #include "timer2.h" |
71 | #include "analog.h" |
71 | #include "analog.h" |
72 | #include "main.h" |
72 | #include "main.h" |
73 | #include "waypoints.h" |
73 | #include "waypoints.h" |
74 | #include "mkprotocol.h" |
74 | #include "mkprotocol.h" |
75 | #include "params.h" |
75 | #include "params.h" |
76 | #include "fifo.h" |
76 | #include "fifo.h" |
77 | 77 | ||
78 | #define FALSE 0 |
78 | #define FALSE 0 |
79 | #define TRUE 1 |
79 | #define TRUE 1 |
80 | 80 | ||
81 | #define ABO_TIMEOUT 4000 // disable abo after 4 seconds |
81 | #define ABO_TIMEOUT 4000 // disable abo after 4 seconds |
82 | u32 UART1_AboTimeOut = 0; |
82 | u32 UART1_AboTimeOut = 0; |
83 | 83 | ||
84 | u8 UART1_Request_VersionInfo = FALSE; |
84 | u8 UART1_Request_VersionInfo = FALSE; |
85 | u8 UART1_Request_ExternalControl= FALSE; |
85 | u8 UART1_Request_ExternalControl= FALSE; |
86 | u8 UART1_Request_Display = FALSE; |
86 | u8 UART1_Request_Display = FALSE; |
87 | u8 UART1_Request_Display1 = FALSE; |
87 | u8 UART1_Request_Display1 = FALSE; |
88 | u8 UART1_Request_DebugData = FALSE; |
88 | u8 UART1_Request_DebugData = FALSE; |
89 | u8 UART1_Request_DebugLabel = 255; |
89 | u8 UART1_Request_DebugLabel = 255; |
90 | u8 UART1_Request_NaviData = FALSE; |
90 | u8 UART1_Request_NaviData = FALSE; |
91 | u8 UART1_Request_ErrorMessage = FALSE; |
91 | u8 UART1_Request_ErrorMessage = FALSE; |
92 | u8 UART1_Request_NewWaypoint = FALSE; |
92 | u8 UART1_Request_NewWaypoint = FALSE; |
93 | u8 UART1_Request_ReadWaypoint = 255; |
93 | u8 UART1_Request_ReadWaypoint = 255; |
94 | u8 UART1_Request_Data3D = FALSE; |
94 | u8 UART1_Request_Data3D = FALSE; |
95 | u8 UART1_Request_Echo = FALSE; |
95 | u8 UART1_Request_Echo = FALSE; |
96 | u8 UART1_Request_ParameterId = 0; |
96 | u8 UART1_Request_ParameterId = 0; |
97 | u8 UART1_Request_Parameter = FALSE; |
97 | u8 UART1_Request_Parameter = FALSE; |
98 | u8 UART1_DisplayKeys = 0; |
98 | u8 UART1_DisplayKeys = 0; |
99 | u8 UART1_DisplayLine = 0; |
99 | u8 UART1_DisplayLine = 0; |
100 | u8 UART1_ConfirmFrame = 0; |
100 | u8 UART1_ConfirmFrame = 0; |
101 | 101 | ||
102 | UART_TypeDef *DebugUART = UART1; |
102 | UART_TypeDef *DebugUART = UART1; |
103 | 103 | ||
104 | // the primary rx fifo |
104 | // the primary rx fifo |
105 | #define UART1_RX_FIFO_LEN 1024 |
105 | #define UART1_RX_FIFO_LEN 1024 |
106 | u8 UART1_rxfifobuffer[UART1_RX_FIFO_LEN]; |
106 | u8 UART1_rxfifobuffer[UART1_RX_FIFO_LEN]; |
107 | fifo_t UART1_rx_fifo; |
107 | fifo_t UART1_rx_fifo; |
108 | 108 | ||
109 | // the rx buffer |
109 | // the rx buffer |
110 | #define UART1_RX_BUFFER_LEN 150 |
110 | #define UART1_RX_BUFFER_LEN 150 |
111 | u8 UART1_rbuffer[UART1_RX_BUFFER_LEN]; |
111 | u8 UART1_rbuffer[UART1_RX_BUFFER_LEN]; |
112 | Buffer_t UART1_rx_buffer; |
112 | Buffer_t UART1_rx_buffer; |
113 | 113 | ||
114 | // the tx buffer |
114 | // the tx buffer |
115 | #define UART1_TX_BUFFER_LEN 150 |
115 | #define UART1_TX_BUFFER_LEN 150 |
116 | u8 UART1_tbuffer[UART1_TX_BUFFER_LEN]; |
116 | u8 UART1_tbuffer[UART1_TX_BUFFER_LEN]; |
117 | Buffer_t UART1_tx_buffer; |
117 | Buffer_t UART1_tx_buffer; |
118 | 118 | ||
119 | 119 | ||
120 | 120 | ||
121 | volatile u8 SerialLinkOkay = 0; |
121 | volatile u8 SerialLinkOkay = 0; |
122 | 122 | ||
123 | u8 text[200]; |
123 | u8 text[200]; |
124 | 124 | ||
125 | const u8 ANALOG_LABEL[32][16] = |
125 | const u8 ANALOG_LABEL[32][16] = |
126 | { |
126 | { |
127 | //1234567890123456 |
127 | //1234567890123456 |
128 | "AngleNick ", //0 |
128 | "AngleNick ", //0 |
129 | "AngleRoll ", |
129 | "AngleRoll ", |
130 | "AccNick ", |
130 | "AccNick ", |
131 | "AccRoll ", |
131 | "AccRoll ", |
132 | "OperatingRadius ", |
132 | "OperatingRadius ", |
133 | "FC-Flags ", //5 |
133 | "FC-Flags ", //5 |
134 | "NC-Flags ", |
134 | "NC-Flags ", |
135 | "NickServo ", |
135 | "NickServo ", |
136 | "RollServo ", |
136 | "RollServo ", |
137 | "GPS Data ", |
137 | "GPS Data ", |
138 | "CompassHeading ", //10 |
138 | "CompassHeading ", //10 |
139 | "GyroHeading ", |
139 | "GyroHeading ", |
140 | "SPI Error ", |
140 | "SPI Error ", |
141 | "SPI Okay ", |
141 | "SPI Okay ", |
142 | "I2C Error ", |
142 | "I2C Error ", |
143 | "I2C Okay ", //15 |
143 | "I2C Okay ", //15 |
144 | " ",// "Kalman_K ", |
144 | " ",// "Kalman_K ", |
145 | "ACC_Speed_N ", |
145 | "ACC_Speed_N ", |
146 | "ACC_Speed_E ", |
146 | "ACC_Speed_E ", |
147 | "Speed_z ",// "GPS ACC ", |
147 | "Speed_z ",// "GPS ACC ", |
148 | " ",// "MAXDrift ", //20 |
148 | " ",// "MAXDrift ", //20 |
149 | "N_Speed ", |
149 | "N_Speed ", |
150 | "E_Speed ", |
150 | "E_Speed ", |
151 | "P-Part ", |
151 | "P-Part ", |
152 | "I-Part ", |
152 | "I-Part ", |
153 | "D-Part ",//25 |
153 | "D-Part ",//25 |
154 | "PID-Part ", |
154 | "PID-Part ", |
155 | "Distance N ", |
155 | "Distance N ", |
156 | "Distance E ", |
156 | "Distance E ", |
157 | "GPS_Nick ", |
157 | "GPS_Nick ", |
158 | "GPS_Roll ", //30 |
158 | "GPS_Roll ", //30 |
159 | "Used_Sats " |
159 | "Used_Sats " |
160 | }; |
160 | }; |
161 | 161 | ||
162 | DebugOut_t DebugOut; |
162 | DebugOut_t DebugOut; |
163 | ExternControl_t ExternControl; |
163 | ExternControl_t ExternControl; |
164 | UART_VersionInfo_t UART_VersionInfo; |
164 | UART_VersionInfo_t UART_VersionInfo; |
165 | NaviData_t NaviData; |
165 | NaviData_t NaviData; |
166 | Data3D_t Data3D; |
166 | Data3D_t Data3D; |
167 | u16 Echo; // 2 bytes recieved will be sent back as echo |
167 | u16 Echo; // 2 bytes recieved will be sent back as echo |
168 | 168 | ||
169 | u32 UART1_DebugData_Timer = 0; |
169 | u32 UART1_DebugData_Timer = 0; |
170 | u32 UART1_DebugData_Interval = 0; // in ms |
170 | u32 UART1_DebugData_Interval = 0; // in ms |
171 | u32 UART1_NaviData_Timer = 0; |
171 | u32 UART1_NaviData_Timer = 0; |
172 | u32 UART1_NaviData_Interval = 0; // in ms |
172 | u32 UART1_NaviData_Interval = 0; // in ms |
173 | u32 UART1_Data3D_Timer = 0; |
173 | u32 UART1_Data3D_Timer = 0; |
174 | u32 UART1_Data3D_Interval = 0; // in ms |
174 | u32 UART1_Data3D_Interval = 0; // in ms |
175 | u32 UART1_Display_Timer = 0; |
175 | u32 UART1_Display_Timer = 0; |
176 | u32 UART1_Display_Interval = 0; // in ms |
176 | u32 UART1_Display_Interval = 0; // in ms |
177 | 177 | ||
178 | /********************************************************/ |
178 | /********************************************************/ |
179 | /* Initialization the UART1 */ |
179 | /* Initialization the UART1 */ |
180 | /********************************************************/ |
180 | /********************************************************/ |
181 | void UART1_Init (void) |
181 | void UART1_Init (void) |
182 | { |
182 | { |
183 | GPIO_InitTypeDef GPIO_InitStructure; |
183 | GPIO_InitTypeDef GPIO_InitStructure; |
184 | UART_InitTypeDef UART_InitStructure; |
184 | UART_InitTypeDef UART_InitStructure; |
185 | 185 | ||
186 | // initialize txd buffer |
186 | // initialize txd buffer |
187 | Buffer_Init(&UART1_tx_buffer, UART1_tbuffer, UART1_TX_BUFFER_LEN); |
187 | Buffer_Init(&UART1_tx_buffer, UART1_tbuffer, UART1_TX_BUFFER_LEN); |
188 | 188 | ||
189 | // initialize rxd buffer |
189 | // initialize rxd buffer |
190 | Buffer_Init(&UART1_rx_buffer, UART1_rbuffer, UART1_RX_BUFFER_LEN); |
190 | Buffer_Init(&UART1_rx_buffer, UART1_rbuffer, UART1_RX_BUFFER_LEN); |
191 | 191 | ||
192 | // initialize the rx fifo |
192 | // initialize the rx fifo |
193 | fifo_init(&UART1_rx_fifo, UART1_rxfifobuffer, UART1_RX_FIFO_LEN); |
193 | fifo_init(&UART1_rx_fifo, UART1_rxfifobuffer, UART1_RX_FIFO_LEN); |
194 | 194 | ||
195 | SCU_APBPeriphClockConfig(__UART1, ENABLE); // Enable the UART1 Clock |
195 | SCU_APBPeriphClockConfig(__UART1, ENABLE); // Enable the UART1 Clock |
196 | SCU_APBPeriphClockConfig(__GPIO3, ENABLE); // Enable the GPIO3 Clock |
196 | SCU_APBPeriphClockConfig(__GPIO3, ENABLE); // Enable the GPIO3 Clock |
197 | 197 | ||
198 | /*Configure UART1_Rx pin GPIO3.2*/ |
198 | /*Configure UART1_Rx pin GPIO3.2*/ |
199 | GPIO_StructInit(&GPIO_InitStructure); |
199 | GPIO_StructInit(&GPIO_InitStructure); |
200 | GPIO_InitStructure.GPIO_Direction = GPIO_PinInput; |
200 | GPIO_InitStructure.GPIO_Direction = GPIO_PinInput; |
201 | GPIO_InitStructure.GPIO_Pin = GPIO_Pin_2; |
201 | GPIO_InitStructure.GPIO_Pin = GPIO_Pin_2; |
202 | GPIO_InitStructure.GPIO_Type = GPIO_Type_PushPull; |
202 | GPIO_InitStructure.GPIO_Type = GPIO_Type_PushPull; |
203 | GPIO_InitStructure.GPIO_IPInputConnected = GPIO_IPInputConnected_Enable; |
203 | GPIO_InitStructure.GPIO_IPInputConnected = GPIO_IPInputConnected_Enable; |
204 | GPIO_InitStructure.GPIO_Alternate = GPIO_InputAlt1; // UART1_RxD |
204 | GPIO_InitStructure.GPIO_Alternate = GPIO_InputAlt1; // UART1_RxD |
205 | GPIO_Init(GPIO3, &GPIO_InitStructure); |
205 | GPIO_Init(GPIO3, &GPIO_InitStructure); |
206 | 206 | ||
207 | /*Configure UART1_Tx pin GPIO3.3*/ |
207 | /*Configure UART1_Tx pin GPIO3.3*/ |
208 | GPIO_StructInit(&GPIO_InitStructure); |
208 | GPIO_StructInit(&GPIO_InitStructure); |
209 | GPIO_InitStructure.GPIO_Direction = GPIO_PinOutput; |
209 | GPIO_InitStructure.GPIO_Direction = GPIO_PinOutput; |
210 | GPIO_InitStructure.GPIO_Pin = GPIO_Pin_3; |
210 | GPIO_InitStructure.GPIO_Pin = GPIO_Pin_3; |
211 | GPIO_InitStructure.GPIO_Type = GPIO_Type_PushPull; |
211 | GPIO_InitStructure.GPIO_Type = GPIO_Type_PushPull; |
212 | GPIO_InitStructure.GPIO_Alternate = GPIO_OutputAlt2; // UART1_TX |
212 | GPIO_InitStructure.GPIO_Alternate = GPIO_OutputAlt2; // UART1_TX |
213 | GPIO_Init(GPIO3, &GPIO_InitStructure); |
213 | GPIO_Init(GPIO3, &GPIO_InitStructure); |
214 | 214 | ||
215 | /* UART1 configured as follow: |
215 | /* UART1 configured as follow: |
216 | - Word Length = 8 Bits |
216 | - Word Length = 8 Bits |
217 | - One Stop Bit |
217 | - One Stop Bit |
218 | - No parity |
218 | - No parity |
219 | - BaudRate = 57600 baud |
219 | - BaudRate = 57600 baud |
220 | - Hardware flow control Disabled |
220 | - Hardware flow control Disabled |
221 | - Receive and transmit enabled |
221 | - Receive and transmit enabled |
222 | - Receive and transmit FIFOs are Disabled |
222 | - Receive and transmit FIFOs are Disabled |
223 | */ |
223 | */ |
224 | UART_StructInit(&UART_InitStructure); |
224 | UART_StructInit(&UART_InitStructure); |
225 | UART_InitStructure.UART_WordLength = UART_WordLength_8D; |
225 | UART_InitStructure.UART_WordLength = UART_WordLength_8D; |
226 | UART_InitStructure.UART_StopBits = UART_StopBits_1; |
226 | UART_InitStructure.UART_StopBits = UART_StopBits_1; |
227 | UART_InitStructure.UART_Parity = UART_Parity_No ; |
227 | UART_InitStructure.UART_Parity = UART_Parity_No ; |
228 | UART_InitStructure.UART_BaudRate = UART1_BAUD_RATE; |
228 | UART_InitStructure.UART_BaudRate = UART1_BAUD_RATE; |
229 | UART_InitStructure. UART_HardwareFlowControl = UART_HardwareFlowControl_None; |
229 | UART_InitStructure. UART_HardwareFlowControl = UART_HardwareFlowControl_None; |
230 | UART_InitStructure.UART_Mode = UART_Mode_Tx_Rx; |
230 | UART_InitStructure.UART_Mode = UART_Mode_Tx_Rx; |
231 | UART_InitStructure.UART_FIFO = UART_FIFO_Enable; |
231 | UART_InitStructure.UART_FIFO = UART_FIFO_Enable; |
232 | UART_InitStructure.UART_TxFIFOLevel = UART_FIFOLevel_1_2; |
232 | UART_InitStructure.UART_TxFIFOLevel = UART_FIFOLevel_1_2; |
233 | UART_InitStructure.UART_RxFIFOLevel = UART_FIFOLevel_1_2; |
233 | UART_InitStructure.UART_RxFIFOLevel = UART_FIFOLevel_1_2; |
234 | 234 | ||
235 | UART_DeInit(UART1); // reset uart 1 to default |
235 | UART_DeInit(UART1); // reset uart 1 to default |
236 | UART_Init(UART1, &UART_InitStructure); // initialize uart 1 |
236 | UART_Init(UART1, &UART_InitStructure); // initialize uart 1 |
237 | // enable uart 1 interrupts selective |
237 | // enable uart 1 interrupts selective |
238 | UART_ITConfig(UART1, UART_IT_Receive | UART_IT_ReceiveTimeOut, ENABLE); |
238 | UART_ITConfig(UART1, UART_IT_Receive | UART_IT_ReceiveTimeOut, ENABLE); |
239 | UART_Cmd(UART1, ENABLE); // enable uart 1 |
239 | UART_Cmd(UART1, ENABLE); // enable uart 1 |
240 | // configure the uart 1 interupt line |
240 | // configure the uart 1 interupt line |
241 | VIC_Config(UART1_ITLine, VIC_IRQ, PRIORITY_UART1); |
241 | VIC_Config(UART1_ITLine, VIC_IRQ, PRIORITY_UART1); |
242 | // enable the uart 1 IRQ |
242 | // enable the uart 1 IRQ |
243 | VIC_ITCmd(UART1_ITLine, ENABLE); |
243 | VIC_ITCmd(UART1_ITLine, ENABLE); |
244 | 244 | ||
245 | // initialize the debug timer |
245 | // initialize the debug timer |
246 | UART1_DebugData_Timer = SetDelay(UART1_DebugData_Interval); |
246 | UART1_DebugData_Timer = SetDelay(UART1_DebugData_Interval); |
247 | UART1_NaviData_Timer = SetDelay(UART1_NaviData_Interval)+500; |
247 | UART1_NaviData_Timer = SetDelay(UART1_NaviData_Interval)+500; |
248 | 248 | ||
249 | // Fill Version Info Structure |
249 | // Fill Version Info Structure |
250 | UART_VersionInfo.SWMajor = VERSION_MAJOR; |
250 | UART_VersionInfo.SWMajor = VERSION_MAJOR; |
251 | UART_VersionInfo.SWMinor = VERSION_MINOR; |
251 | UART_VersionInfo.SWMinor = VERSION_MINOR; |
252 | UART_VersionInfo.SWPatch = VERSION_PATCH; |
252 | UART_VersionInfo.SWPatch = VERSION_PATCH; |
253 | UART_VersionInfo.ProtoMajor = VERSION_SERIAL_MAJOR; |
253 | UART_VersionInfo.ProtoMajor = VERSION_SERIAL_MAJOR; |
254 | UART_VersionInfo.ProtoMinor = VERSION_SERIAL_MINOR; |
254 | UART_VersionInfo.ProtoMinor = VERSION_SERIAL_MINOR; |
255 | 255 | ||
256 | NaviData.Version = NAVIDATA_VERSION; |
256 | NaviData.Version = NAVIDATA_VERSION; |
257 | 257 | ||
258 | UART1_PutString("\r\n UART1 init...ok"); |
258 | UART1_PutString("\r\n UART1 init...ok"); |
259 | } |
259 | } |
260 | 260 | ||
261 | 261 | ||
262 | /****************************************************************/ |
262 | /****************************************************************/ |
263 | /* USART1 receiver ISR */ |
263 | /* USART1 receiver ISR */ |
264 | /****************************************************************/ |
264 | /****************************************************************/ |
265 | void UART1_IRQHandler(void) |
265 | void UART1_IRQHandler(void) |
266 | { |
266 | { |
267 | static u8 abortState = 0; |
267 | static u8 abortState = 0; |
268 | u8 c; |
268 | u8 c; |
269 | 269 | ||
270 | IENABLE; |
270 | IENABLE; |
271 | 271 | ||
272 | if((UART_GetITStatus(UART1, UART_IT_Receive) != RESET) || (UART_GetITStatus(UART1, UART_IT_ReceiveTimeOut) != RESET) ) |
272 | if((UART_GetITStatus(UART1, UART_IT_Receive) != RESET) || (UART_GetITStatus(UART1, UART_IT_ReceiveTimeOut) != RESET) ) |
273 | { |
273 | { |
274 | // clear the pending bits! |
274 | // clear the pending bits! |
275 | UART_ClearITPendingBit(UART1, UART_IT_Receive); |
275 | UART_ClearITPendingBit(UART1, UART_IT_Receive); |
276 | UART_ClearITPendingBit(UART1, UART_IT_ReceiveTimeOut); |
276 | UART_ClearITPendingBit(UART1, UART_IT_ReceiveTimeOut); |
277 | // if debug UART is not UART1 |
277 | // if debug UART is not UART1 |
278 | if (DebugUART != UART1) |
278 | if (DebugUART != UART1) |
279 | { // forward received data to the debug UART tx buffer |
279 | { // forward received data to the debug UART tx buffer |
280 | while(UART_GetFlagStatus(UART1, UART_FLAG_RxFIFOEmpty) != SET) |
280 | while(UART_GetFlagStatus(UART1, UART_FLAG_RxFIFOEmpty) != SET) |
281 | { |
281 | { |
282 | // move the byte from the rx buffer of UART1 to the tx buffer of DebugUART |
282 | // move the byte from the rx buffer of UART1 to the tx buffer of DebugUART |
283 | c = UART_ReceiveData(UART1); |
283 | c = UART_ReceiveData(UART1); |
284 | 284 | ||
285 | // check for abort condition (ESC ESC 0x55 0xAA 0x00) |
285 | // check for abort condition (ESC ESC 0x55 0xAA 0x00) |
286 | switch (abortState) |
286 | switch (abortState) |
287 | { |
287 | { |
288 | case 0: |
288 | case 0: |
289 | if (c == 27) abortState++; |
289 | if (c == 27) abortState++; |
290 | break; |
290 | break; |
291 | case 1: |
291 | case 1: |
292 | if (c == 27) abortState++; |
292 | if (c == 27) abortState++; |
293 | else abortState = 0; |
293 | else abortState = 0; |
294 | break; |
294 | break; |
295 | case 2: |
295 | case 2: |
296 | if (c == 0x55) abortState++; |
296 | if (c == 0x55) abortState++; |
297 | else abortState = 0; |
297 | else abortState = 0; |
298 | break; |
298 | break; |
299 | case 3: |
299 | case 3: |
300 | if (c == 0xAA) abortState++; |
300 | if (c == 0xAA) abortState++; |
301 | else abortState = 0; |
301 | else abortState = 0; |
302 | break; |
302 | break; |
303 | case 4: |
303 | case 4: |
304 | if (c == 0x00) |
304 | if (c == 0x00) |
305 | { |
305 | { |
306 | if(DebugUART == UART0) |
306 | if(DebugUART == UART0) |
307 | { |
307 | { |
308 | UART0_Connect_to_MKGPS(); |
308 | UART0_Connect_to_MKGPS(); |
309 | TIMER2_Init(); // enbable servo outputs |
309 | TIMER2_Init(); // enbable servo outputs |
310 | fifo_purge(&UART1_rx_fifo); // flush the whole fifo init buffer |
310 | fifo_purge(&UART1_rx_fifo); // flush the whole fifo init buffer |
311 | } |
311 | } |
312 | DebugUART = UART1; |
312 | DebugUART = UART1; |
313 | } |
313 | } |
314 | abortState = 0; |
314 | abortState = 0; |
315 | break; |
315 | break; |
316 | } // end switch abort state |
316 | } // end switch abort state |
317 | // if the Debug uart is not UART1, redirect input to the Debug UART |
317 | // if the Debug uart is not UART1, redirect input to the Debug UART |
318 | if (DebugUART != UART1) |
318 | if (DebugUART != UART1) |
319 | { |
319 | { |
320 | // wait for space in the tx buffer of the DebugUART |
320 | // wait for space in the tx buffer of the DebugUART |
321 | while(UART_GetFlagStatus(DebugUART, UART_FLAG_TxFIFOFull) == SET) {}; |
321 | while(UART_GetFlagStatus(DebugUART, UART_FLAG_TxFIFOFull) == SET) {}; |
322 | // move byte to the tx fifo of the debug uart |
322 | // move byte to the tx fifo of the debug uart |
323 | UART_SendData(DebugUART, c); |
323 | UART_SendData(DebugUART, c); |
324 | } |
324 | } |
325 | } |
325 | } |
326 | } |
326 | } |
327 | else // DebugUART == UART1 (normal operation) |
327 | else // DebugUART == UART1 (normal operation) |
328 | { |
328 | { |
329 | while(UART_GetFlagStatus(UART1, UART_FLAG_RxFIFOEmpty) != SET) |
329 | while(UART_GetFlagStatus(UART1, UART_FLAG_RxFIFOEmpty) != SET) |
330 | { // some byes in the hardware fifo |
330 | { // some byes in the hardware fifo |
331 | // get byte from hardware fifo |
331 | // get byte from hardware fifo |
332 | c = UART_ReceiveData(UART1); |
332 | c = UART_ReceiveData(UART1); |
333 | // put into the software fifo |
333 | // put into the software fifo |
334 | if(!fifo_put(&UART1_rx_fifo, c)) |
334 | if(!fifo_put(&UART1_rx_fifo, c)) |
335 | { // fifo overflow |
335 | { // fifo overflow |
336 | //fifo_purge(&UART1_rx_fifo); // flush the whole buffer |
336 | //fifo_purge(&UART1_rx_fifo); // flush the whole buffer |
337 | } |
337 | } |
338 | } // EOF while some byes in the hardware fifo |
338 | } // EOF while some byes in the hardware fifo |
339 | } // eof DebugUart = UART1 |
339 | } // eof DebugUart = UART1 |
340 | } |
340 | } |
341 | 341 | ||
342 | IDISABLE; |
342 | IDISABLE; |
343 | } |
343 | } |
344 | 344 | ||
345 | /**************************************************************/ |
345 | /**************************************************************/ |
346 | /* Process incomming data from debug uart */ |
346 | /* Process incomming data from debug uart */ |
347 | /**************************************************************/ |
347 | /**************************************************************/ |
348 | void UART1_ProcessRxData(void) |
348 | void UART1_ProcessRxData(void) |
349 | { |
349 | { |
350 | // return on forwarding uart or unlocked rx buffer |
350 | // return on forwarding uart or unlocked rx buffer |
351 | if(DebugUART != UART1) return; |
351 | if(DebugUART != UART1) return; |
352 | 352 | ||
353 | u8 c; |
353 | u8 c; |
354 | // if rx buffer is not locked |
354 | // if rx buffer is not locked |
355 | if(UART1_rx_buffer.Locked == FALSE) |
355 | if(UART1_rx_buffer.Locked == FALSE) |
356 | { //collect data from primary rx fifo |
356 | { //collect data from primary rx fifo |
357 | while(fifo_get(&UART1_rx_fifo, &c)) |
357 | while(fifo_get(&UART1_rx_fifo, &c)) |
358 | { // break if complete frame is collected |
358 | { // break if complete frame is collected |
359 | if(MKProtocol_CollectSerialFrame(&UART1_rx_buffer, c)) break; |
359 | if(MKProtocol_CollectSerialFrame(&UART1_rx_buffer, c)) break; |
360 | } |
360 | } |
361 | } |
361 | } |
362 | if(UART1_rx_buffer.Locked == FALSE) return; |
362 | if(UART1_rx_buffer.Locked == FALSE) return; |
363 | 363 | ||
364 | Waypoint_t * pWaypoint = NULL; |
364 | Waypoint_t * pWaypoint = NULL; |
365 | SerialMsg_t SerialMsg; |
365 | SerialMsg_t SerialMsg; |
366 | 366 | ||
367 | // analyze header first |
367 | // analyze header first |
368 | MKProtocol_DecodeSerialFrameHeader(&UART1_rx_buffer, &SerialMsg); |
368 | MKProtocol_DecodeSerialFrameHeader(&UART1_rx_buffer, &SerialMsg); |
369 | if( SerialMsg.Address == FC_ADDRESS ) |
369 | if( SerialMsg.Address == FC_ADDRESS ) |
370 | { |
370 | { |
371 | switch(SerialMsg.CmdID) |
371 | switch(SerialMsg.CmdID) |
372 | { |
372 | { |
373 | case 'y': // serial poti values |
373 | case 'y': // serial poti values |
374 | case 'b': // extern control |
374 | case 'b': // extern control |
375 | Buffer_Copy(&UART1_rx_buffer, &UART2_tx_buffer); //forward to FC |
375 | Buffer_Copy(&UART1_rx_buffer, &UART2_tx_buffer); //forward to FC |
376 | Buffer_Clear(&UART1_rx_buffer); // free rc buffer for next frame |
376 | Buffer_Clear(&UART1_rx_buffer); // free rc buffer for next frame |
377 | return; //end process rx data |
377 | return; //end process rx data |
378 | break; |
378 | break; |
379 | } |
379 | } |
380 | } |
380 | } |
381 | 381 | ||
382 | MKProtocol_DecodeSerialFrameData(&UART1_rx_buffer, &SerialMsg); // decode serial frame in rxd buffer |
382 | MKProtocol_DecodeSerialFrameData(&UART1_rx_buffer, &SerialMsg); // decode serial frame in rxd buffer |
383 | if(SerialMsg.CmdID != 'z') SerialLinkOkay = 250; // reset SerialTimeout, but not in case of the "ping" |
383 | if(SerialMsg.CmdID != 'z') SerialLinkOkay = 250; // reset SerialTimeout, but not in case of the "ping" |
384 | switch(SerialMsg.Address) // check for Slave Address |
384 | switch(SerialMsg.Address) // check for Slave Address |
385 | { |
385 | { |
386 | case NC_ADDRESS: // own Slave Address |
386 | case NC_ADDRESS: // own Slave Address |
387 | switch(SerialMsg.CmdID) |
387 | switch(SerialMsg.CmdID) |
388 | { |
388 | { |
389 | case 'z': // connection checker |
389 | case 'z': // connection checker |
390 | memcpy(&Echo, SerialMsg.pData, sizeof(Echo)); // copy echo pattern |
390 | memcpy(&Echo, SerialMsg.pData, sizeof(Echo)); // copy echo pattern |
391 | UART1_Request_Echo = TRUE; |
391 | UART1_Request_Echo = TRUE; |
392 | break; |
392 | break; |
393 | 393 | ||
394 | case 'e': // request for the text of the error status |
394 | case 'e': // request for the text of the error status |
395 | UART1_Request_ErrorMessage = TRUE; |
395 | UART1_Request_ErrorMessage = TRUE; |
396 | break; |
396 | break; |
397 | 397 | ||
398 | case 's':// new target position |
398 | case 's':// new target position |
399 | pWaypoint = (Waypoint_t*)SerialMsg.pData; |
399 | pWaypoint = (Waypoint_t*)SerialMsg.pData; |
400 | BeepTime = 300; |
400 | BeepTime = 300; |
401 | if(pWaypoint->Position.Status == NEWDATA) |
401 | if(pWaypoint->Position.Status == NEWDATA) |
402 | { |
402 | { |
403 | WPList_Clear(); // empty WPList |
403 | WPList_Clear(); // empty WPList |
404 | WPList_Append(pWaypoint); |
404 | WPList_Append(pWaypoint); |
405 | GPS_pWaypoint = WPList_Begin(); |
405 | GPS_pWaypoint = WPList_Begin(); |
406 | } |
406 | } |
407 | break; |
407 | break; |
408 | 408 | ||
409 | case 'u': // redirect debug uart |
409 | case 'u': // redirect debug uart |
410 | switch(SerialMsg.pData[0]) |
410 | switch(SerialMsg.pData[0]) |
411 | { |
411 | { |
412 | case UART_FLIGHTCTRL: |
412 | case UART_FLIGHTCTRL: |
413 | UART2_Init(); // initialize UART2 to FC pins |
413 | UART2_Init(); // initialize UART2 to FC pins |
414 | fifo_purge(&UART1_rx_fifo); |
414 | fifo_purge(&UART1_rx_fifo); |
415 | TIMER2_Deinit(); // reduce irq load |
415 | TIMER2_Deinit(); // reduce irq load |
416 | DebugUART = UART2; |
416 | DebugUART = UART2; |
417 | break; |
417 | break; |
418 | case UART_MK3MAG: |
418 | case UART_MK3MAG: |
419 | if(FC.Flags & FCFLAG_MOTOR_RUN) break; // not if the motors are running |
419 | if(FC.Flags & FCFLAG_MOTOR_RUN) break; // not if the motors are running |
420 | UART0_Connect_to_MK3MAG(); // mux UART0 to MK3MAG pins |
420 | UART0_Connect_to_MK3MAG(); // mux UART0 to MK3MAG pins |
421 | GPSData.Status = INVALID; |
421 | GPSData.Status = INVALID; |
422 | fifo_purge(&UART1_rx_fifo); |
422 | fifo_purge(&UART1_rx_fifo); |
423 | DebugUART = UART0; |
423 | DebugUART = UART0; |
424 | break; |
424 | break; |
425 | case UART_MKGPS: |
425 | case UART_MKGPS: |
426 | if(FC.Flags & FCFLAG_MOTOR_RUN) break; // not if the motors are running |
426 | if(FC.Flags & FCFLAG_MOTOR_RUN) break; // not if the motors are running |
427 | TIMER2_Deinit(); // disable servo outputs to reduce irq load |
427 | TIMER2_Deinit(); // disable servo outputs to reduce irq load |
428 | UART0_Connect_to_MKGPS(); // connect UART0 to MKGPS pins |
428 | UART0_Connect_to_MKGPS(); // connect UART0 to MKGPS pins |
429 | GPSData.Status = INVALID; |
429 | GPSData.Status = INVALID; |
430 | fifo_purge(&UART1_rx_fifo); |
430 | fifo_purge(&UART1_rx_fifo); |
431 | DebugUART = UART0; |
431 | DebugUART = UART0; |
432 | break; |
432 | break; |
433 | default: |
433 | default: |
434 | break; |
434 | break; |
435 | } |
435 | } |
436 | break; |
436 | break; |
437 | 437 | ||
438 | case 'w':// Append Waypoint to List |
438 | case 'w':// Append Waypoint to List |
439 | { |
439 | { |
440 | static u8 oldIndex = 0x00; |
440 | static u8 nextIndex = 0x00; |
441 | 441 | ||
- | 442 | pWaypoint = (Waypoint_t*)SerialMsg.pData; |
|
442 | pWaypoint = (Waypoint_t*)SerialMsg.pData; |
443 | |
443 | if(pWaypoint->Position.Status == INVALID) |
444 | if (pWaypoint->Index == 0) // is the POI |
444 | { // clear WP List |
445 | { |
445 | WPList_Clear(); |
446 | WPList_SetPOI(pWaypoint); //update POI also when invalid |
446 | oldIndex = 0x00; |
447 | WPList_Clear(); //delete the WP List |
- | 448 | GPS_pWaypoint = WPList_Begin(); |
|
- | 449 | nextIndex = 0x01; |
|
447 | GPS_pWaypoint = WPList_Begin(); |
450 | BeepTime = 300; |
- | 451 | UART1_Request_NewWaypoint = TRUE; |
|
- | 452 | // the POI is not a WP therefore the WPNumber is not increased |
|
448 | UART1_Request_NewWaypoint = TRUE; |
453 | // and the command returns a 0 as WP number |
- | 454 | } |
|
- | 455 | else // normal WP |
|
449 | } |
456 | { |
450 | else if (pWaypoint->Position.Status == NEWDATA) |
457 | if (pWaypoint->Position.Status == NEWDATA) |
451 | { // app current WP to the list |
458 | { // app current WP to the list |
452 | if (pWaypoint->Index == oldIndex + 1) |
459 | if (pWaypoint->Index == nextIndex) |
453 | { |
460 | { |
454 | WPList_Append(pWaypoint); |
461 | WPList_Append(pWaypoint); |
455 | BeepTime = 500; |
462 | BeepTime = 500; |
456 | oldIndex = pWaypoint->Index; |
463 | nextIndex = pWaypoint->Index+1; |
- | 464 | UART1_Request_NewWaypoint = TRUE; // return new WP number |
|
457 | UART1_Request_NewWaypoint = TRUE; |
465 | } |
458 | } |
466 | } |
459 | } |
467 | } |
460 | } |
468 | } |
461 | break; |
469 | break; |
462 | 470 | ||
463 | case 'x':// Read Waypoint from List |
471 | case 'x':// Read Waypoint from List |
464 | UART1_Request_ReadWaypoint = SerialMsg.pData[0]; |
472 | UART1_Request_ReadWaypoint = SerialMsg.pData[0]; |
465 | break; |
473 | break; |
466 | 474 | ||
467 | case 'j':// Set/Get NC-Parameter |
475 | case 'j':// Set/Get NC-Parameter |
468 | switch(SerialMsg.pData[0]) |
476 | switch(SerialMsg.pData[0]) |
469 | { |
477 | { |
470 | case 0: // get |
478 | case 0: // get |
471 | break; |
479 | break; |
472 | 480 | ||
473 | case 1: // set |
481 | case 1: // set |
474 | { |
482 | { |
475 | s16 value; |
483 | s16 value; |
476 | value = SerialMsg.pData[2] + (s16)SerialMsg.pData[3] * 0x0100; |
484 | value = SerialMsg.pData[2] + (s16)SerialMsg.pData[3] * 0x0100; |
477 | NCParams_SetValue(SerialMsg.pData[1], &value); |
485 | NCParams_SetValue(SerialMsg.pData[1], &value); |
478 | } |
486 | } |
479 | break; |
487 | break; |
480 | 488 | ||
481 | default: |
489 | default: |
482 | break; |
490 | break; |
483 | } |
491 | } |
484 | UART1_Request_ParameterId = SerialMsg.pData[1]; |
492 | UART1_Request_ParameterId = SerialMsg.pData[1]; |
485 | UART1_Request_Parameter = TRUE; |
493 | UART1_Request_Parameter = TRUE; |
486 | break; |
494 | break; |
487 | default: |
495 | default: |
488 | // unsupported command recieved |
496 | // unsupported command recieved |
489 | break; |
497 | break; |
490 | } // case NC_ADDRESS |
498 | } // case NC_ADDRESS |
491 | // "break;" is missing here to fall thru to the common commands |
499 | // "break;" is missing here to fall thru to the common commands |
492 | 500 | ||
493 | default: // and any other Slave Address |
501 | default: // and any other Slave Address |
494 | 502 | ||
495 | switch(SerialMsg.CmdID) // check CmdID |
503 | switch(SerialMsg.CmdID) // check CmdID |
496 | { |
504 | { |
497 | case 'a':// request for the labels of the analog debug outputs |
505 | case 'a':// request for the labels of the analog debug outputs |
498 | UART1_Request_DebugLabel = SerialMsg.pData[0]; |
506 | UART1_Request_DebugLabel = SerialMsg.pData[0]; |
499 | if(UART1_Request_DebugLabel > 31) UART1_Request_DebugLabel = 31; |
507 | if(UART1_Request_DebugLabel > 31) UART1_Request_DebugLabel = 31; |
500 | break; |
508 | break; |
501 | /* |
509 | /* |
502 | case 'b': // submit extern control |
510 | case 'b': // submit extern control |
503 | memcpy(&ExternControl, SerialMsg.pData, sizeof(ExternControl)); |
511 | memcpy(&ExternControl, SerialMsg.pData, sizeof(ExternControl)); |
504 | UART1_ConfirmFrame = ExternControl.Frame; |
512 | UART1_ConfirmFrame = ExternControl.Frame; |
505 | break; |
513 | break; |
506 | */ |
514 | */ |
507 | case 'd': // request for debug data; |
515 | case 'd': // request for debug data; |
508 | UART1_DebugData_Interval = (u32) SerialMsg.pData[0] * 10; |
516 | UART1_DebugData_Interval = (u32) SerialMsg.pData[0] * 10; |
509 | if(UART1_DebugData_Interval > 0) UART1_Request_DebugData = TRUE; |
517 | if(UART1_DebugData_Interval > 0) UART1_Request_DebugData = TRUE; |
510 | UART1_AboTimeOut = SetDelay(ABO_TIMEOUT); |
518 | UART1_AboTimeOut = SetDelay(ABO_TIMEOUT); |
511 | break; |
519 | break; |
512 | 520 | ||
513 | case 'c': // request for 3D data; |
521 | case 'c': // request for 3D data; |
514 | UART1_Data3D_Interval = (u32) SerialMsg.pData[0] * 10; |
522 | UART1_Data3D_Interval = (u32) SerialMsg.pData[0] * 10; |
515 | if(UART1_Data3D_Interval > 0) UART1_Request_Data3D = TRUE; |
523 | if(UART1_Data3D_Interval > 0) UART1_Request_Data3D = TRUE; |
516 | UART1_AboTimeOut = SetDelay(ABO_TIMEOUT); |
524 | UART1_AboTimeOut = SetDelay(ABO_TIMEOUT); |
517 | break; |
525 | break; |
518 | /* |
526 | /* |
519 | case 'g':// request for external control data |
527 | case 'g':// request for external control data |
520 | UART1_Request_ExternalControl = TRUE; |
528 | UART1_Request_ExternalControl = TRUE; |
521 | break; |
529 | break; |
522 | */ |
530 | */ |
523 | case 'h':// reqest for display line |
531 | case 'h':// reqest for display line |
524 | if((SerialMsg.pData[0]& 0x80) == 0x00)// old format |
532 | if((SerialMsg.pData[0]& 0x80) == 0x00)// old format |
525 | { |
533 | { |
526 | UART1_DisplayLine = 2; |
534 | UART1_DisplayLine = 2; |
527 | UART1_Display_Interval = 0; |
535 | UART1_Display_Interval = 0; |
528 | } |
536 | } |
529 | else |
537 | else |
530 | { |
538 | { |
531 | UART1_DisplayKeys |= ~SerialMsg.pData[0]; |
539 | UART1_DisplayKeys |= ~SerialMsg.pData[0]; |
532 | UART1_Display_Interval = (u32) SerialMsg.pData[1] * 10; |
540 | UART1_Display_Interval = (u32) SerialMsg.pData[1] * 10; |
533 | UART1_DisplayLine = 4; |
541 | UART1_DisplayLine = 4; |
534 | UART1_AboTimeOut = SetDelay(ABO_TIMEOUT); |
542 | UART1_AboTimeOut = SetDelay(ABO_TIMEOUT); |
535 | } |
543 | } |
536 | UART1_Request_Display = TRUE; |
544 | UART1_Request_Display = TRUE; |
537 | break; |
545 | break; |
538 | 546 | ||
539 | case 'l':// reqest for display columns |
547 | case 'l':// reqest for display columns |
540 | MenuItem = SerialMsg.pData[0]; |
548 | MenuItem = SerialMsg.pData[0]; |
541 | UART1_Request_Display1 = TRUE; |
549 | UART1_Request_Display1 = TRUE; |
542 | break; |
550 | break; |
543 | 551 | ||
544 | case 'o': // request for navigation information |
552 | case 'o': // request for navigation information |
545 | UART1_NaviData_Interval = (u32) SerialMsg.pData[0] * 10; |
553 | UART1_NaviData_Interval = (u32) SerialMsg.pData[0] * 10; |
546 | if(UART1_NaviData_Interval > 0) UART1_Request_NaviData = TRUE; |
554 | if(UART1_NaviData_Interval > 0) UART1_Request_NaviData = TRUE; |
547 | UART1_AboTimeOut = SetDelay(ABO_TIMEOUT); |
555 | UART1_AboTimeOut = SetDelay(ABO_TIMEOUT); |
548 | break; |
556 | break; |
549 | 557 | ||
550 | case 'v': // request for version info |
558 | case 'v': // request for version info |
551 | UART1_Request_VersionInfo = TRUE; |
559 | UART1_Request_VersionInfo = TRUE; |
552 | break; |
560 | break; |
553 | default: |
561 | default: |
554 | // unsupported command recieved |
562 | // unsupported command recieved |
555 | break; |
563 | break; |
556 | } |
564 | } |
557 | break; // default: |
565 | break; // default: |
558 | } |
566 | } |
559 | Buffer_Clear(&UART1_rx_buffer); // free rc buffer for next frame |
567 | Buffer_Clear(&UART1_rx_buffer); // free rc buffer for next frame |
560 | } |
568 | } |
561 | 569 | ||
562 | 570 | ||
563 | /*****************************************************/ |
571 | /*****************************************************/ |
564 | /* Send a character */ |
572 | /* Send a character */ |
565 | /*****************************************************/ |
573 | /*****************************************************/ |
566 | s16 UART1_Putchar(char c) |
574 | s16 UART1_Putchar(char c) |
567 | { |
575 | { |
568 | if (c == '\n') UART1_Putchar('\r'); |
576 | if (c == '\n') UART1_Putchar('\r'); |
569 | // wait until txd fifo is not full |
577 | // wait until txd fifo is not full |
570 | while (UART_GetFlagStatus(UART1, UART_FLAG_TxFIFOFull) != RESET); |
578 | while (UART_GetFlagStatus(UART1, UART_FLAG_TxFIFOFull) != RESET); |
571 | // transmit byte |
579 | // transmit byte |
572 | UART_SendData(UART1, c); |
580 | UART_SendData(UART1, c); |
573 | return (0); |
581 | return (0); |
574 | } |
582 | } |
575 | 583 | ||
576 | /*****************************************************/ |
584 | /*****************************************************/ |
577 | /* Send a string to the debug uart */ |
585 | /* Send a string to the debug uart */ |
578 | /*****************************************************/ |
586 | /*****************************************************/ |
579 | void UART1_PutString(u8 *s) |
587 | void UART1_PutString(u8 *s) |
580 | { |
588 | { |
581 | if(s == NULL) return; |
589 | if(s == NULL) return; |
582 | while (*s != '\0' && DebugUART == UART1) |
590 | while (*s != '\0' && DebugUART == UART1) |
583 | { |
591 | { |
584 | UART1_Putchar(*s); |
592 | UART1_Putchar(*s); |
585 | s ++; |
593 | s ++; |
586 | } |
594 | } |
587 | } |
595 | } |
588 | 596 | ||
589 | 597 | ||
590 | /**************************************************************/ |
598 | /**************************************************************/ |
591 | /* Transmit tx buffer via debug uart */ |
599 | /* Transmit tx buffer via debug uart */ |
592 | /**************************************************************/ |
600 | /**************************************************************/ |
593 | void UART1_Transmit(void) |
601 | void UART1_Transmit(void) |
594 | { |
602 | { |
595 | u8 tmp_tx; |
603 | u8 tmp_tx; |
596 | if(DebugUART != UART1) return; |
604 | if(DebugUART != UART1) return; |
597 | // if something has to be send and the txd fifo is not full |
605 | // if something has to be send and the txd fifo is not full |
598 | if(UART1_tx_buffer.Locked == TRUE) |
606 | if(UART1_tx_buffer.Locked == TRUE) |
599 | { |
607 | { |
600 | // while there is some space in the tx fifo |
608 | // while there is some space in the tx fifo |
601 | while(UART_GetFlagStatus(UART1, UART_FLAG_TxFIFOFull) != SET) |
609 | while(UART_GetFlagStatus(UART1, UART_FLAG_TxFIFOFull) != SET) |
602 | { |
610 | { |
603 | tmp_tx = UART1_tx_buffer.pData[UART1_tx_buffer.Position++]; // read next byte from txd buffer |
611 | tmp_tx = UART1_tx_buffer.pData[UART1_tx_buffer.Position++]; // read next byte from txd buffer |
604 | UART_SendData(UART1, tmp_tx); // put character to txd fifo |
612 | UART_SendData(UART1, tmp_tx); // put character to txd fifo |
605 | // if terminating character or end of txd buffer reached |
613 | // if terminating character or end of txd buffer reached |
606 | if((tmp_tx == '\r') || (UART1_tx_buffer.Position == UART1_tx_buffer.DataBytes)) |
614 | if((tmp_tx == '\r') || (UART1_tx_buffer.Position == UART1_tx_buffer.DataBytes)) |
607 | { |
615 | { |
608 | Buffer_Clear(&UART1_tx_buffer); // clear txd buffer |
616 | Buffer_Clear(&UART1_tx_buffer); // clear txd buffer |
609 | break; // end while loop |
617 | break; // end while loop |
610 | } |
618 | } |
611 | } |
619 | } |
612 | } |
620 | } |
613 | } |
621 | } |
614 | 622 | ||
615 | /**************************************************************/ |
623 | /**************************************************************/ |
616 | /* Send the answers to incomming commands at the debug uart */ |
624 | /* Send the answers to incomming commands at the debug uart */ |
617 | /**************************************************************/ |
625 | /**************************************************************/ |
618 | void UART1_TransmitTxData(void) |
626 | void UART1_TransmitTxData(void) |
619 | { |
627 | { |
620 | if(DebugUART != UART1) return; |
628 | if(DebugUART != UART1) return; |
621 | 629 | ||
622 | if(CheckDelay(UART1_AboTimeOut)) |
630 | if(CheckDelay(UART1_AboTimeOut)) |
623 | { |
631 | { |
624 | UART1_DebugData_Interval = 0; |
632 | UART1_DebugData_Interval = 0; |
625 | UART1_NaviData_Interval = 0; |
633 | UART1_NaviData_Interval = 0; |
626 | UART1_Data3D_Interval = 0; |
634 | UART1_Data3D_Interval = 0; |
627 | UART1_Display_Interval = 0; |
635 | UART1_Display_Interval = 0; |
628 | } |
636 | } |
629 | 637 | ||
630 | UART1_Transmit(); // output pending bytes in tx buffer |
638 | UART1_Transmit(); // output pending bytes in tx buffer |
631 | if((UART1_tx_buffer.Locked == TRUE)) return; |
639 | if((UART1_tx_buffer.Locked == TRUE)) return; |
632 | 640 | ||
633 | if(UART1_Request_Parameter && (UART1_tx_buffer.Locked == FALSE)) |
641 | if(UART1_Request_Parameter && (UART1_tx_buffer.Locked == FALSE)) |
634 | { |
642 | { |
635 | s16 ParamValue; |
643 | s16 ParamValue; |
636 | NCParams_GetValue(UART1_Request_ParameterId, &ParamValue); |
644 | NCParams_GetValue(UART1_Request_ParameterId, &ParamValue); |
637 | //sprintf(text, "\r\nId=%d, value = %d\r\n", UART1_Request_ParameterId, ParamValue); |
645 | //sprintf(text, "\r\nId=%d, value = %d\r\n", UART1_Request_ParameterId, ParamValue); |
638 | //UART1_PutString(text); |
646 | //UART1_PutString(text); |
639 | MKProtocol_CreateSerialFrame(&UART1_tx_buffer, 'J', NC_ADDRESS, 2, &UART1_Request_ParameterId, sizeof(UART1_Request_ParameterId), &ParamValue, sizeof(ParamValue)); // answer the param request |
647 | MKProtocol_CreateSerialFrame(&UART1_tx_buffer, 'J', NC_ADDRESS, 2, &UART1_Request_ParameterId, sizeof(UART1_Request_ParameterId), &ParamValue, sizeof(ParamValue)); // answer the param request |
640 | UART1_Request_Parameter = FALSE; |
648 | UART1_Request_Parameter = FALSE; |
641 | } |
649 | } |
642 | else if(UART1_Request_Echo && (UART1_tx_buffer.Locked == FALSE)) |
650 | else if(UART1_Request_Echo && (UART1_tx_buffer.Locked == FALSE)) |
643 | { |
651 | { |
644 | MKProtocol_CreateSerialFrame(&UART1_tx_buffer, 'Z', NC_ADDRESS, 1, &Echo, sizeof(Echo)); // answer the echo request |
652 | MKProtocol_CreateSerialFrame(&UART1_tx_buffer, 'Z', NC_ADDRESS, 1, &Echo, sizeof(Echo)); // answer the echo request |
645 | Echo = 0; // reset echo value |
653 | Echo = 0; // reset echo value |
646 | UART1_Request_Echo = FALSE; |
654 | UART1_Request_Echo = FALSE; |
647 | } |
655 | } |
648 | else if(UART1_Request_NewWaypoint && (UART1_tx_buffer.Locked == FALSE)) |
656 | else if(UART1_Request_NewWaypoint && (UART1_tx_buffer.Locked == FALSE)) |
649 | { |
657 | { |
650 | u8 WPNumber = WPList_GetCount(); |
658 | u8 WPNumber = WPList_GetCount(); |
651 | MKProtocol_CreateSerialFrame(&UART1_tx_buffer, 'W', NC_ADDRESS, 1, &WPNumber, sizeof(WPNumber)); |
659 | MKProtocol_CreateSerialFrame(&UART1_tx_buffer, 'W', NC_ADDRESS, 1, &WPNumber, sizeof(WPNumber)); |
652 | UART1_Request_NewWaypoint = FALSE; |
660 | UART1_Request_NewWaypoint = FALSE; |
653 | } |
661 | } |
654 | else if((UART1_Request_ReadWaypoint != 0xFF) && (UART1_tx_buffer.Locked == FALSE)) |
662 | else if((UART1_Request_ReadWaypoint != 0xFF) && (UART1_tx_buffer.Locked == FALSE)) |
655 | { |
663 | { |
656 | u8 WPNumber = WPList_GetCount(); |
664 | u8 WPNumber = WPList_GetCount(); |
657 | if (UART1_Request_ReadWaypoint < WPNumber) |
665 | if (UART1_Request_ReadWaypoint < WPNumber) |
658 | { |
666 | { |
659 | MKProtocol_CreateSerialFrame(&UART1_tx_buffer, 'X', NC_ADDRESS, 3, &WPNumber, 1, &UART1_Request_ReadWaypoint, 1, WPList_GetAt(UART1_Request_ReadWaypoint), sizeof(Waypoint_t)); |
667 | MKProtocol_CreateSerialFrame(&UART1_tx_buffer, 'X', NC_ADDRESS, 3, &WPNumber, 1, &UART1_Request_ReadWaypoint, 1, WPList_GetAt(UART1_Request_ReadWaypoint), sizeof(Waypoint_t)); |
660 | } |
668 | } |
661 | else |
669 | else |
662 | { |
670 | { |
663 | MKProtocol_CreateSerialFrame(&UART1_tx_buffer,'X', NC_ADDRESS, 1, &WPNumber, sizeof(WPNumber)); |
671 | MKProtocol_CreateSerialFrame(&UART1_tx_buffer,'X', NC_ADDRESS, 1, &WPNumber, sizeof(WPNumber)); |
664 | } |
672 | } |
665 | UART1_Request_ReadWaypoint = 0xFF; |
673 | UART1_Request_ReadWaypoint = 0xFF; |
666 | } |
674 | } |
667 | else if((UART1_Request_DebugLabel != 0xFF) && (UART1_tx_buffer.Locked == FALSE)) |
675 | else if((UART1_Request_DebugLabel != 0xFF) && (UART1_tx_buffer.Locked == FALSE)) |
668 | { |
676 | { |
669 | MKProtocol_CreateSerialFrame(&UART1_tx_buffer, 'A', NC_ADDRESS, 2, &UART1_Request_DebugLabel, sizeof(UART1_Request_DebugLabel), (u8 *) ANALOG_LABEL[UART1_Request_DebugLabel], 16); |
677 | MKProtocol_CreateSerialFrame(&UART1_tx_buffer, 'A', NC_ADDRESS, 2, &UART1_Request_DebugLabel, sizeof(UART1_Request_DebugLabel), (u8 *) ANALOG_LABEL[UART1_Request_DebugLabel], 16); |
670 | UART1_Request_DebugLabel = 0xFF; |
678 | UART1_Request_DebugLabel = 0xFF; |
671 | } |
679 | } |
672 | else if(( ((UART1_NaviData_Interval > 0) && CheckDelay(UART1_NaviData_Timer) ) || UART1_Request_NaviData) && (UART1_tx_buffer.Locked == FALSE)) |
680 | else if(( ((UART1_NaviData_Interval > 0) && CheckDelay(UART1_NaviData_Timer) ) || UART1_Request_NaviData) && (UART1_tx_buffer.Locked == FALSE)) |
673 | { |
681 | { |
674 | NaviData.Errorcode = ErrorCode; |
682 | NaviData.Errorcode = ErrorCode; |
675 | MKProtocol_CreateSerialFrame(&UART1_tx_buffer, 'O', NC_ADDRESS,1, (u8 *)&NaviData, sizeof(NaviData)); |
683 | MKProtocol_CreateSerialFrame(&UART1_tx_buffer, 'O', NC_ADDRESS,1, (u8 *)&NaviData, sizeof(NaviData)); |
676 | UART1_NaviData_Timer = SetDelay(UART1_NaviData_Interval); |
684 | UART1_NaviData_Timer = SetDelay(UART1_NaviData_Interval); |
677 | UART1_Request_NaviData = FALSE; |
685 | UART1_Request_NaviData = FALSE; |
678 | } |
686 | } |
679 | else if( (( (UART1_DebugData_Interval > 0) && CheckDelay(UART1_DebugData_Timer)) || UART1_Request_DebugData) && (UART1_tx_buffer.Locked == FALSE)) |
687 | else if( (( (UART1_DebugData_Interval > 0) && CheckDelay(UART1_DebugData_Timer)) || UART1_Request_DebugData) && (UART1_tx_buffer.Locked == FALSE)) |
680 | { |
688 | { |
681 | MKProtocol_CreateSerialFrame(&UART1_tx_buffer, 'D', NC_ADDRESS, 1,(u8 *)&DebugOut, sizeof(DebugOut)); |
689 | MKProtocol_CreateSerialFrame(&UART1_tx_buffer, 'D', NC_ADDRESS, 1,(u8 *)&DebugOut, sizeof(DebugOut)); |
682 | UART1_DebugData_Timer = SetDelay(UART1_DebugData_Interval); |
690 | UART1_DebugData_Timer = SetDelay(UART1_DebugData_Interval); |
683 | UART1_Request_DebugData = FALSE; |
691 | UART1_Request_DebugData = FALSE; |
684 | } |
692 | } |
685 | else if((( (UART1_Data3D_Interval > 0) && CheckDelay(UART1_Data3D_Timer) ) || UART1_Request_Data3D) && (UART1_tx_buffer.Locked == FALSE)) |
693 | else if((( (UART1_Data3D_Interval > 0) && CheckDelay(UART1_Data3D_Timer) ) || UART1_Request_Data3D) && (UART1_tx_buffer.Locked == FALSE)) |
686 | { |
694 | { |
687 | MKProtocol_CreateSerialFrame(&UART1_tx_buffer, 'C', NC_ADDRESS, 1,(u8 *)&Data3D, sizeof(Data3D)); |
695 | MKProtocol_CreateSerialFrame(&UART1_tx_buffer, 'C', NC_ADDRESS, 1,(u8 *)&Data3D, sizeof(Data3D)); |
688 | UART1_Data3D_Timer = SetDelay(UART1_Data3D_Interval); |
696 | UART1_Data3D_Timer = SetDelay(UART1_Data3D_Interval); |
689 | UART1_Request_Data3D = FALSE; |
697 | UART1_Request_Data3D = FALSE; |
690 | } |
698 | } |
691 | /* |
699 | /* |
692 | else if(UART1_ConfirmFrame && (UART1_tx_buffer.Locked == FALSE)) |
700 | else if(UART1_ConfirmFrame && (UART1_tx_buffer.Locked == FALSE)) |
693 | { |
701 | { |
694 | MKProtocol_CreateSerialFrame(&UART1_tx_buffer, 'B', NC_ADDRESS, 1, &UART1_ConfirmFrame, sizeof(UART1_ConfirmFrame)); |
702 | MKProtocol_CreateSerialFrame(&UART1_tx_buffer, 'B', NC_ADDRESS, 1, &UART1_ConfirmFrame, sizeof(UART1_ConfirmFrame)); |
695 | UART1_ConfirmFrame = 0; |
703 | UART1_ConfirmFrame = 0; |
696 | } |
704 | } |
697 | */ |
705 | */ |
698 | /* |
706 | /* |
699 | else if(UART1_Request_ExternalControl && (UART1_tx_buffer.Locked == FALSE)) |
707 | else if(UART1_Request_ExternalControl && (UART1_tx_buffer.Locked == FALSE)) |
700 | { |
708 | { |
701 | MKProtocol_CreateSerialFrame(&UART1_tx_buffer, 'G', NC_ADDRESS, 1, (u8 *)&ExternControl, sizeof(ExternControl)); |
709 | MKProtocol_CreateSerialFrame(&UART1_tx_buffer, 'G', NC_ADDRESS, 1, (u8 *)&ExternControl, sizeof(ExternControl)); |
702 | UART1_Request_ExternalControl = FALSE; |
710 | UART1_Request_ExternalControl = FALSE; |
703 | } |
711 | } |
704 | */ |
712 | */ |
705 | else if( (( (UART1_Display_Interval > 0) && CheckDelay(UART1_Display_Timer)) || UART1_Request_Display) && (UART1_tx_buffer.Locked == FALSE)) |
713 | else if( (( (UART1_Display_Interval > 0) && CheckDelay(UART1_Display_Timer)) || UART1_Request_Display) && (UART1_tx_buffer.Locked == FALSE)) |
706 | { |
714 | { |
707 | if(UART1_DisplayLine > 3) |
715 | if(UART1_DisplayLine > 3) |
708 | { |
716 | { |
709 | Menu_Update(UART1_DisplayKeys); |
717 | Menu_Update(UART1_DisplayKeys); |
710 | UART1_DisplayKeys = 0; |
718 | UART1_DisplayKeys = 0; |
711 | MKProtocol_CreateSerialFrame(&UART1_tx_buffer, 'H', NC_ADDRESS, 1, (u8*)DisplayBuff, sizeof(DisplayBuff)); |
719 | MKProtocol_CreateSerialFrame(&UART1_tx_buffer, 'H', NC_ADDRESS, 1, (u8*)DisplayBuff, sizeof(DisplayBuff)); |
712 | } |
720 | } |
713 | else |
721 | else |
714 | { |
722 | { |
715 | UART1_DisplayLine = 2; |
723 | UART1_DisplayLine = 2; |
716 | sprintf(text,"!!! incompatible !!!"); |
724 | sprintf(text,"!!! incompatible !!!"); |
717 | MKProtocol_CreateSerialFrame(&UART1_tx_buffer, 'H', NC_ADDRESS, 2, &UART1_DisplayLine, sizeof(UART1_DisplayLine), (u8*)&text, 20); |
725 | MKProtocol_CreateSerialFrame(&UART1_tx_buffer, 'H', NC_ADDRESS, 2, &UART1_DisplayLine, sizeof(UART1_DisplayLine), (u8*)&text, 20); |
718 | if(UART1_DisplayLine++ > 3) UART1_DisplayLine = 0; |
726 | if(UART1_DisplayLine++ > 3) UART1_DisplayLine = 0; |
719 | } |
727 | } |
720 | UART1_Display_Timer = SetDelay(UART1_Display_Interval); |
728 | UART1_Display_Timer = SetDelay(UART1_Display_Interval); |
721 | UART1_Request_Display = FALSE; |
729 | UART1_Request_Display = FALSE; |
722 | } |
730 | } |
723 | else if(UART1_Request_Display1 && (UART1_tx_buffer.Locked == FALSE)) |
731 | else if(UART1_Request_Display1 && (UART1_tx_buffer.Locked == FALSE)) |
724 | { |
732 | { |
725 | Menu_Update(0); |
733 | Menu_Update(0); |
726 | MKProtocol_CreateSerialFrame(&UART1_tx_buffer, 'L', NC_ADDRESS, 3, (u8*)&MenuItem, sizeof(MenuItem), (u8*)&MaxMenuItem, sizeof(MaxMenuItem),(u8*)DisplayBuff, sizeof(DisplayBuff)); |
734 | MKProtocol_CreateSerialFrame(&UART1_tx_buffer, 'L', NC_ADDRESS, 3, (u8*)&MenuItem, sizeof(MenuItem), (u8*)&MaxMenuItem, sizeof(MaxMenuItem),(u8*)DisplayBuff, sizeof(DisplayBuff)); |
727 | UART1_Request_Display1 = FALSE; |
735 | UART1_Request_Display1 = FALSE; |
728 | } |
736 | } |
729 | else if(UART1_Request_VersionInfo && (UART1_tx_buffer.Locked == FALSE)) |
737 | else if(UART1_Request_VersionInfo && (UART1_tx_buffer.Locked == FALSE)) |
730 | { |
738 | { |
731 | MKProtocol_CreateSerialFrame(&UART1_tx_buffer, 'V', NC_ADDRESS,1, (u8 *)&UART_VersionInfo, sizeof(UART_VersionInfo)); |
739 | MKProtocol_CreateSerialFrame(&UART1_tx_buffer, 'V', NC_ADDRESS,1, (u8 *)&UART_VersionInfo, sizeof(UART_VersionInfo)); |
732 | UART1_Request_VersionInfo = FALSE; |
740 | UART1_Request_VersionInfo = FALSE; |
733 | } |
741 | } |
734 | else if(UART1_Request_ErrorMessage && (UART1_tx_buffer.Locked == FALSE)) |
742 | else if(UART1_Request_ErrorMessage && (UART1_tx_buffer.Locked == FALSE)) |
735 | { |
743 | { |
736 | MKProtocol_CreateSerialFrame(&UART1_tx_buffer, 'E', NC_ADDRESS, 1, (u8 *)&ErrorMSG, sizeof(ErrorMSG)); |
744 | MKProtocol_CreateSerialFrame(&UART1_tx_buffer, 'E', NC_ADDRESS, 1, (u8 *)&ErrorMSG, sizeof(ErrorMSG)); |
737 | UART1_Request_ErrorMessage = FALSE; |
745 | UART1_Request_ErrorMessage = FALSE; |
738 | } |
746 | } |
739 | UART1_Transmit(); // output pending bytes in tx buffer |
747 | UART1_Transmit(); // output pending bytes in tx buffer |
740 | } |
748 | } |
741 | 749 | ||
742 | 750 |