Rev 2265 | Go to most recent revision | Only display areas with differences | Ignore whitespace | Details | Blame | Last modification | View Log | RSS feed
Rev 2265 | Rev 2274 | ||
---|---|---|---|
1 | ///============================================================================ |
1 | ///============================================================================ |
2 | /// MKLiveView |
2 | /// MKLiveView |
3 | /// Copyright © 2016 Steph |
3 | /// Copyright © 2016 Steph |
4 | /// |
4 | /// |
5 | ///This file is part of MKLiveView. |
5 | ///This file is part of MKLiveView. |
6 | /// |
6 | /// |
7 | ///MKLiveView is free software: you can redistribute it and/or modify |
7 | ///MKLiveView is free software: you can redistribute it and/or modify |
8 | ///it under the terms of the GNU General Public License as published by |
8 | ///it under the terms of the GNU General Public License as published by |
9 | ///the Free Software Foundation, either version 3 of the License, or |
9 | ///the Free Software Foundation, either version 3 of the License, or |
10 | ///(at your option) any later version. |
10 | ///(at your option) any later version. |
11 | /// |
11 | /// |
12 | ///MKLiveView is distributed in the hope that it will be useful, |
12 | ///MKLiveView is distributed in the hope that it will be useful, |
13 | ///but WITHOUT ANY WARRANTY; without even the implied warranty of |
13 | ///but WITHOUT ANY WARRANTY; without even the implied warranty of |
14 | ///MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the |
14 | ///MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the |
15 | ///GNU General Public License for more details. |
15 | ///GNU General Public License for more details. |
16 | /// |
16 | /// |
17 | ///You should have received a copy of the GNU General Public License |
17 | ///You should have received a copy of the GNU General Public License |
18 | ///along with cssRcon. If not, see <http://www.gnu.org/licenses/>. |
18 | ///along with cssRcon. If not, see <http://www.gnu.org/licenses/>. |
19 | /// |
19 | /// |
20 | ///============================================================================ |
20 | ///============================================================================ |
21 | ///Credits: |
21 | ///Credits: |
22 | ///Chootair (http://www.codeproject.com/script/Membership/View.aspx?mid=3941737) |
22 | ///Chootair (http://www.codeproject.com/script/Membership/View.aspx?mid=3941737) |
23 | ///for his "C# Avionic Instrument Controls" (http://www.codeproject.com/Articles/27411/C-Avionic-Instrument-Controls) |
23 | ///for his "C# Avionic Instrument Controls" (http://www.codeproject.com/Articles/27411/C-Avionic-Instrument-Controls) |
24 | ///I used some of his code for displaying the compass |
24 | ///I used some of his code for displaying the compass |
25 | /// |
25 | /// |
26 | ///Tom Pyke (http://tom.pycke.be) |
26 | ///Tom Pyke (http://tom.pycke.be) |
27 | ///for his "Artifical horizon" (http://tom.pycke.be/mav/100/artificial-horizon) |
27 | ///for his "Artifical horizon" (http://tom.pycke.be/mav/100/artificial-horizon) |
28 | ///Great job! |
28 | ///Great job! |
29 | /// |
29 | /// |
30 | /// and last but most of all to JOHN C. MACDONALD at Ira A. Fulton College of Engineering and Technology |
30 | /// and last but most of all to JOHN C. MACDONALD at Ira A. Fulton College of Engineering and Technology |
31 | /// for his MIKROKOPTER SERIAL CONTROL TUTORIAL (http://hdl.lib.byu.edu/1877/2747) |
31 | /// for his MIKROKOPTER SERIAL CONTROL TUTORIAL (http://hdl.lib.byu.edu/1877/2747) |
32 | /// and the sourcecode (http://hdl.lib.byu.edu/1877/2748) |
32 | /// and the sourcecode (http://hdl.lib.byu.edu/1877/2748) |
33 | /// By his work I finally managed to get the communication with the Mikrokopter controllers to run |
33 | /// By his work I finally managed to get the communication with the Mikrokopter controllers to run |
34 | /// Some of his code was used in this programm like the SimpelSerialPort class (with some changes) |
34 | /// Some of his code was used in this programm like the SimpelSerialPort class (with some changes) |
35 | /// and the FilghtControllerMessage class |
35 | /// and the FilghtControllerMessage class |
36 | /// |
36 | /// |
37 | ///============================================================================ |
37 | ///============================================================================ |
38 | /// DISCLAIMER |
38 | /// DISCLAIMER |
39 | /// =========== |
39 | /// =========== |
40 | /// |
40 | /// |
41 | /// I created this software with my best knowledge and belief. |
41 | /// I created this software with my best knowledge and belief. |
42 | /// |
42 | /// |
43 | /// IN NO EVENT, UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN WRITING, |
43 | /// IN NO EVENT, UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN WRITING, |
44 | /// SHALL I, OR ANY PERSON BE LIABLE FOR ANY LOSS, EXPENSE OR DAMAGE, |
44 | /// SHALL I, OR ANY PERSON BE LIABLE FOR ANY LOSS, EXPENSE OR DAMAGE, |
45 | /// OF ANY TYPE OR NATURE ARISING OUT OF THE USE OF, |
45 | /// OF ANY TYPE OR NATURE ARISING OUT OF THE USE OF, |
46 | /// OR INABILITY TO USE THIS SOFTWARE OR PROGRAM, |
46 | /// OR INABILITY TO USE THIS SOFTWARE OR PROGRAM, |
47 | /// INCLUDING, BUT NOT LIMITED TO, CLAIMS, SUITS OR CAUSES OF ACTION |
47 | /// INCLUDING, BUT NOT LIMITED TO, CLAIMS, SUITS OR CAUSES OF ACTION |
48 | /// INVOLVING ALLEGED INFRINGEMENT OF COPYRIGHTS, |
48 | /// INVOLVING ALLEGED INFRINGEMENT OF COPYRIGHTS, |
49 | /// PATENTS, TRADEMARKS, TRADE SECRETS, OR UNFAIR COMPETITION. |
49 | /// PATENTS, TRADEMARKS, TRADE SECRETS, OR UNFAIR COMPETITION. |
50 | /// |
50 | /// |
51 | /// This means: use it & have fun (but @ Your own risk...) |
51 | /// This means: use it & have fun (but @ Your own risk...) |
52 | /// =========================================================================== |
52 | /// =========================================================================== |
53 | 53 | ||
54 | using System; |
54 | using System; |
55 | using System.Data; |
55 | using System.Data; |
56 | using System.Drawing; |
56 | using System.Drawing; |
57 | using System.Text; |
57 | using System.Text; |
58 | using System.Windows.Forms; |
58 | using System.Windows.Forms; |
59 | using System.IO; |
59 | using System.IO; |
60 | using System.Threading; |
60 | using System.Threading; |
61 | using System.Diagnostics; |
61 | using System.Diagnostics; |
62 | using System.Runtime.InteropServices; |
62 | using System.Runtime.InteropServices; |
63 | 63 | ||
64 | namespace MKLiveView |
64 | namespace MKLiveView |
65 | { |
65 | { |
66 | public partial class MainForm : Form |
66 | public partial class MainForm : Form |
67 | { |
67 | { |
68 | String[] NC_Error = new string[44] |
68 | String[] NC_Error = new string[44] |
69 | { |
69 | { |
70 | "No Error", |
70 | "No Error", |
71 | "FC not compatible" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A1_.22FC_not_compatible_.22", |
71 | "FC not compatible" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A1_.22FC_not_compatible_.22", |
72 | "MK3Mag not compatible" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A2_.22MK3Mag_not_compatible_.22", |
72 | "MK3Mag not compatible" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A2_.22MK3Mag_not_compatible_.22", |
73 | "no FC communication" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A3_.22no_FC_communication_.22", |
73 | "no FC communication" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A3_.22no_FC_communication_.22", |
74 | "no compass communication" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A4_.22no_compass_communication_.22", |
74 | "no compass communication" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A4_.22no_compass_communication_.22", |
75 | "no GPS communication" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A5_.22no_GPS_communication_.22", |
75 | "no GPS communication" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A5_.22no_GPS_communication_.22", |
76 | "bad compass value" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A6_.22bad_compass_value.22", |
76 | "bad compass value" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A6_.22bad_compass_value.22", |
77 | "RC Signal lost" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A7_.22RC_Signal_lost_.22", |
77 | "RC Signal lost" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A7_.22RC_Signal_lost_.22", |
78 | "FC spi rx error" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A8_.22FC_spi_rx_error_.22", |
78 | "FC spi rx error" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A8_.22FC_spi_rx_error_.22", |
79 | "ERR: no NC communication" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A9:_.22ERR:_no_NC_communication.22", |
79 | "ERR: no NC communication" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A9:_.22ERR:_no_NC_communication.22", |
80 | "ERR: FC Nick Gyro" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A10_.22ERR:_FC_Nick_Gyro.22", |
80 | "ERR: FC Nick Gyro" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A10_.22ERR:_FC_Nick_Gyro.22", |
81 | "ERR: FC Roll Gyro" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A11_.22ERR:_FC_Roll_Gyro.22", |
81 | "ERR: FC Roll Gyro" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A11_.22ERR:_FC_Roll_Gyro.22", |
82 | "ERR: FC Yaw Gyro" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A12_.22ERR:_FC_Yaw_Gyro.22", |
82 | "ERR: FC Yaw Gyro" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A12_.22ERR:_FC_Yaw_Gyro.22", |
83 | "ERR: FC Nick ACC" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A13_.22ERR:_FC_Nick_ACC.22", |
83 | "ERR: FC Nick ACC" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A13_.22ERR:_FC_Nick_ACC.22", |
84 | "ERR: FC Roll ACC" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A14_.22ERR:_FC_Roll_ACC.22", |
84 | "ERR: FC Roll ACC" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A14_.22ERR:_FC_Roll_ACC.22", |
85 | "ERR: FC Z-ACC" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A15_.22ERR:_FC_Z-ACC.22", |
85 | "ERR: FC Z-ACC" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A15_.22ERR:_FC_Z-ACC.22", |
86 | "ERR: Pressure sensor" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A16_.22ERR:_Pressure_sensor.22", |
86 | "ERR: Pressure sensor" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A16_.22ERR:_Pressure_sensor.22", |
87 | "ERR: FC I2C" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A17_.22ERR:_FC_I2C.22", |
87 | "ERR: FC I2C" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A17_.22ERR:_FC_I2C.22", |
88 | "ERR: Bl Missing" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A18_.22ERR:_Bl_Missing.22", |
88 | "ERR: Bl Missing" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A18_.22ERR:_Bl_Missing.22", |
89 | "Mixer Error" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A19_.22Mixer_Error.22", |
89 | "Mixer Error" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A19_.22Mixer_Error.22", |
90 | "FC: Carefree Error" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A20_.22FC:_Carefree_Error.22", |
90 | "FC: Carefree Error" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A20_.22FC:_Carefree_Error.22", |
91 | "ERR: GPS lost" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A21_.22ERR:_GPS_lost.22", |
91 | "ERR: GPS lost" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A21_.22ERR:_GPS_lost.22", |
92 | "ERR: Magnet Error" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A22_.22ERR:_Magnet_Error.22", |
92 | "ERR: Magnet Error" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A22_.22ERR:_Magnet_Error.22", |
93 | "Motor restart" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A23_.22Motor_restart.22", |
93 | "Motor restart" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A23_.22Motor_restart.22", |
94 | "BL Limitation" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A24_.22BL_Limitation.22", |
94 | "BL Limitation" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A24_.22BL_Limitation.22", |
95 | "Waypoint range" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A25_.22Waypoint_range.22", |
95 | "Waypoint range" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A25_.22Waypoint_range.22", |
96 | "ERR:No SD-Card" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A26_.22ERR:No_SD-Card.22", |
96 | "ERR:No SD-Card" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A26_.22ERR:No_SD-Card.22", |
97 | "ERR:SD Logging aborted" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A27_.22ERR:SD_Logging_aborted.22", |
97 | "ERR:SD Logging aborted" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A27_.22ERR:SD_Logging_aborted.22", |
98 | "ERR:Flying range!" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A28_.22ERR:Flying_range.21.22", |
98 | "ERR:Flying range!" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A28_.22ERR:Flying_range.21.22", |
99 | "ERR:Max Altitude" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A29_.22ERR:Max_Altitude.22", |
99 | "ERR:Max Altitude" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A29_.22ERR:Max_Altitude.22", |
100 | "No GPS Fix" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A30_.22No_GPS_Fix.22", |
100 | "No GPS Fix" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A30_.22No_GPS_Fix.22", |
101 | "compass not calibrated" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A31_.22compass_not_calibrated.22", |
101 | "compass not calibrated" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A31_.22compass_not_calibrated.22", |
102 | "ERR:BL selftest" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A32_.22ERR:BL_selftest.22", |
102 | "ERR:BL selftest" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A32_.22ERR:BL_selftest.22", |
103 | "no ext. compass" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A33_.22no_ext._compass.22", |
103 | "no ext. compass" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A33_.22no_ext._compass.22", |
104 | "compass sensor" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A34_.22compass_sensor.22", |
104 | "compass sensor" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A34_.22compass_sensor.22", |
105 | "FAILSAFE pos.!" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A35_.22FAILSAFE_pos..21__.22", |
105 | "FAILSAFE pos.!" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A35_.22FAILSAFE_pos..21__.22", |
106 | "ERR:Redundancy" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A36_.22ERR:Redundancy__.22", |
106 | "ERR:Redundancy" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A36_.22ERR:Redundancy__.22", |
107 | "Redundancy test" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A37_.22Redundancy_test_.22", |
107 | "Redundancy test" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A37_.22Redundancy_test_.22", |
108 | "GPS Update rate" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A38_.22GPS_Update_rate.22", |
108 | "GPS Update rate" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A38_.22GPS_Update_rate.22", |
109 | "ERR:Canbus" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A39_.22ERR:Canbus.22", |
109 | "ERR:Canbus" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A39_.22ERR:Canbus.22", |
110 | "ERR: 5V RC-Supply" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A40_.22ERR:_5V_RC-Supply.22", |
110 | "ERR: 5V RC-Supply" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A40_.22ERR:_5V_RC-Supply.22", |
111 | "ERR:Power-Supply" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A41_.22ERR:Power-Supply.22", |
111 | "ERR:Power-Supply" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A41_.22ERR:Power-Supply.22", |
112 | "ACC not calibr." + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A42_.22ACC_not_calibr..22", |
112 | "ACC not calibr." + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A42_.22ACC_not_calibr..22", |
113 | "ERR:Parachute!" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A43_.22ERR:Parachute.21.22" |
113 | "ERR:Parachute!" + Environment.NewLine + "http://wiki.mikrokopter.de/ErrorCodes#A43_.22ERR:Parachute.21.22" |
114 | }; |
114 | }; |
115 | 115 | ||
116 | [FlagsAttribute] |
116 | [FlagsAttribute] |
117 | enum NC_HWError0 : short |
117 | enum NC_HWError0 : short |
118 | { |
118 | { |
119 | None = 0, |
119 | None = 0, |
120 | SPI_RX = 1, |
120 | SPI_RX = 1, |
121 | COMPASS_RX = 2, |
121 | COMPASS_RX = 2, |
122 | FC_INCOMPATIBLE = 4, |
122 | FC_INCOMPATIBLE = 4, |
123 | COMPASS_INCOMPATIBLE = 8, |
123 | COMPASS_INCOMPATIBLE = 8, |
124 | GPS_RX = 16, |
124 | GPS_RX = 16, |
125 | COMPASS_VALUE = 32 |
125 | COMPASS_VALUE = 32 |
126 | }; |
126 | }; |
127 | [FlagsAttribute] |
127 | [FlagsAttribute] |
128 | enum FC_HWError0 : short |
128 | enum FC_HWError0 : short |
129 | { |
129 | { |
130 | None = 0, |
130 | None = 0, |
131 | GYRO_NICK = 1, |
131 | GYRO_NICK = 1, |
132 | GYRO_ROLL = 2, |
132 | GYRO_ROLL = 2, |
133 | GYRO_YAW = 4, |
133 | GYRO_YAW = 4, |
134 | ACC_NICK = 8, |
134 | ACC_NICK = 8, |
135 | ACC_ROLL = 16, |
135 | ACC_ROLL = 16, |
136 | ACC_TOP = 32, |
136 | ACC_TOP = 32, |
137 | PRESSURE = 64, |
137 | PRESSURE = 64, |
138 | CAREFREE = 128 |
138 | CAREFREE = 128 |
139 | }; |
139 | }; |
140 | [FlagsAttribute] |
140 | [FlagsAttribute] |
141 | enum FC_HWError1 : short |
141 | enum FC_HWError1 : short |
142 | { |
142 | { |
143 | None = 0, |
143 | None = 0, |
144 | I2C = 1, |
144 | I2C = 1, |
145 | BL_MISSING = 2, |
145 | BL_MISSING = 2, |
146 | SPI_RX = 4, |
146 | SPI_RX = 4, |
147 | PPM = 8, |
147 | PPM = 8, |
148 | MIXER = 16, |
148 | MIXER = 16, |
149 | RC_VOLTAGE = 32, |
149 | RC_VOLTAGE = 32, |
150 | ACC_NOT_CAL = 64, |
150 | ACC_NOT_CAL = 64, |
151 | RES3 = 128 |
151 | RES3 = 128 |
152 | }; |
152 | }; |
153 | public enum LogMsgType { Incoming, Outgoing, Normal, Warning, Error }; |
153 | public enum LogMsgType { Incoming, Outgoing, Normal, Warning, Error }; |
154 | // Various colors for logging info |
154 | // Various colors for logging info |
155 | private Color[] LogMsgTypeColor = { Color.FromArgb(43, 145, 175), Color.Green, Color.Black, Color.Orange, Color.Red }; |
155 | private Color[] LogMsgTypeColor = { Color.FromArgb(43, 145, 175), Color.Green, Color.Black, Color.Orange, Color.Red }; |
156 | 156 | ||
157 | string[] sAnalogLabel = new string[32]; |
157 | string[] sAnalogLabel = new string[32]; |
158 | string[] sAnalogData = new string[32]; |
158 | string[] sAnalogData = new string[32]; |
159 | bool bReadContinously = false; |
159 | bool bReadContinously = false; |
160 | bool check_HWError = false; |
160 | bool check_HWError = false; |
161 | bool _bCBInit = true; |
161 | bool _bCBInit = true; |
162 | bool _init = true; |
162 | bool _init = true; |
163 | bool _debugDataAutorefresh = true; |
163 | bool _debugDataAutorefresh = true; |
164 | bool _navCtrlDataAutorefresh = true; |
164 | bool _navCtrlDataAutorefresh = true; |
165 | bool _blctrlDataAutorefresh = true; |
165 | bool _blctrlDataAutorefresh = true; |
166 | bool _OSDAutorefresh = true; |
166 | bool _OSDAutorefresh = true; |
167 | bool _bErrorLog = false; |
167 | bool _bErrorLog = false; |
168 | int crcError = 0; |
168 | int crcError = 0; |
169 | int iLableIndex = 0; |
169 | int iLableIndex = 0; |
170 | string filePath = Directory.GetCurrentDirectory(); |
170 | string filePath = Directory.GetCurrentDirectory(); |
171 | string fileName = "NCLabelTexts.txt"; |
171 | string fileName = "NCLabelTexts.txt"; |
172 | int _iCtrlAct = 0; |
172 | int _iCtrlAct = 0; |
173 | int _iLifeCounter = 0; |
173 | int _iLifeCounter = 0; |
174 | int iOSDPage = 0; |
174 | int iOSDPage = 0; |
175 | int iOSDMax = 0; |
175 | int iOSDMax = 0; |
176 | int[] serChan = new int[12] { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 }; |
176 | int[] serChan = new int[12] { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 }; |
177 | string[] serChanTitle = new string[12]; |
177 | string[] serChanTitle = new string[12]; |
178 | /// <summary> |
178 | /// <summary> |
179 | /// interval for sending debugdata (multiplied by 10ms) |
179 | /// interval for sending debugdata (multiplied by 10ms) |
180 | /// </summary> |
180 | /// </summary> |
181 | byte debugInterval = 10; //(=> 100ms) |
181 | byte debugInterval = 10; //(=> 100ms) |
182 | /// <summary> |
182 | /// <summary> |
183 | /// interval for sending BL-CTRL status (multiplied by 10ms) |
183 | /// interval for sending BL-CTRL status (multiplied by 10ms) |
184 | /// </summary> |
184 | /// </summary> |
185 | byte blctrlInterval = 75; |
185 | byte blctrlInterval = 75; |
186 | /// <summary> |
186 | /// <summary> |
187 | /// interval for sending NAV-CTRL status (multiplied by 10ms) |
187 | /// interval for sending NAV-CTRL status (multiplied by 10ms) |
188 | /// </summary> |
188 | /// </summary> |
189 | byte navctrlInterval = 80; |
189 | byte navctrlInterval = 80; |
190 | /// <summary> |
190 | /// <summary> |
191 | /// interval for sending OSD page update (multiplied by 10ms) |
191 | /// interval for sending OSD page update (multiplied by 10ms) |
192 | /// </summary> |
192 | /// </summary> |
193 | byte OSDInterval = 85; |
193 | byte OSDInterval = 85; |
194 | /// <summary> |
194 | /// <summary> |
195 | /// datatable for the debug data array - displayed on settings tabpage in datagridview |
195 | /// datatable for the debug data array - displayed on settings tabpage in datagridview |
196 | /// </summary> |
196 | /// </summary> |
197 | DataTable dtAnalog = new DataTable(); |
197 | DataTable dtAnalog = new DataTable(); |
198 | /// <summary> |
198 | /// <summary> |
199 | /// datatable for motordata (current,temp) |
199 | /// datatable for motordata (current,temp) |
200 | /// </summary> |
200 | /// </summary> |
201 | DataTable dtMotors1 = new DataTable(); |
201 | DataTable dtMotors1 = new DataTable(); |
202 | DataTable dtMotors2 = new DataTable(); |
202 | DataTable dtMotors2 = new DataTable(); |
203 | 203 | ||
204 | DataTable dtWaypoints = new DataTable(); |
204 | DataTable dtWaypoints = new DataTable(); |
205 | 205 | ||
206 | public MainForm() |
206 | public MainForm() |
207 | { |
207 | { |
208 | InitializeComponent(); |
208 | InitializeComponent(); |
- | 209 | _initForm(); |
|
- | 210 | } |
|
- | 211 | void _initForm() |
|
- | 212 | { |
|
209 | serChanTitle.Initialize(); |
213 | serChanTitle.Initialize(); |
210 | 214 | ||
211 | _readIni(); |
215 | _readIni(); |
212 | 216 | ||
213 | _dataTablesInit(); |
217 | _dataTablesInit(); |
214 | 218 | ||
215 | simpleSerialPort.PortClosed += SimpleSerialPort_PortClosed; |
219 | simpleSerialPort.PortClosed += SimpleSerialPort_PortClosed; |
216 | simpleSerialPort.PortOpened += SimpleSerialPort_PortOpened; |
220 | simpleSerialPort.PortOpened += SimpleSerialPort_PortOpened; |
217 | simpleSerialPort.DataReceived += processMessage; |
221 | simpleSerialPort.DataReceived += processMessage; |
218 | 222 | ||
219 | chkbAutoBL.Checked = _blctrlDataAutorefresh; |
223 | chkbAutoBL.Checked = _blctrlDataAutorefresh; |
220 | chkbAutoDbg.Checked = _debugDataAutorefresh; |
224 | chkbAutoDbg.Checked = _debugDataAutorefresh; |
221 | chkbAutoNav.Checked = _navCtrlDataAutorefresh; |
225 | chkbAutoNav.Checked = _navCtrlDataAutorefresh; |
222 | chkbAutoOSD.Checked = _OSDAutorefresh; |
226 | chkbAutoOSD.Checked = _OSDAutorefresh; |
223 | 227 | ||
224 | labelTimingDebug.Text = (debugInterval * 10).ToString(); |
228 | labelTimingDebug.Text = (debugInterval * 10).ToString(); |
225 | labelTimingBLCTRL.Text = (blctrlInterval * 10).ToString(); |
229 | labelTimingBLCTRL.Text = (blctrlInterval * 10).ToString(); |
226 | labelTimingNAV.Text = (navctrlInterval * 10).ToString(); |
230 | labelTimingNAV.Text = (navctrlInterval * 10).ToString(); |
227 | labelTimingOSD.Text = (OSDInterval * 10).ToString(); |
231 | labelTimingOSD.Text = (OSDInterval * 10).ToString(); |
228 | 232 | ||
229 | TabControl1.TabPages.Remove(tabPageTesting); //a testing page |
233 | TabControl1.TabPages.Remove(tabPageTesting); //a testing page |
230 | } |
234 | } |
231 | - | ||
232 | #region events |
235 | #region events |
233 | private void MainForm_Shown(object sender, EventArgs e) |
236 | private void MainForm_Shown(object sender, EventArgs e) |
234 | { |
237 | { |
235 | _loadLabelNames(); |
238 | _loadLabelNames(); |
236 | _initSerialCtrl(); |
239 | _initSerialCtrl(); |
237 | _init = false; |
240 | _init = false; |
238 | splitContainer1.SplitterDistance = 510; |
241 | splitContainer1.SplitterDistance = 510; |
239 | } |
242 | } |
240 | private void MainForm_FormClosed(object sender, FormClosedEventArgs e) |
243 | private void MainForm_FormClosed(object sender, FormClosedEventArgs e) |
241 | { |
244 | { |
242 | _writeIni(); |
245 | _writeIni(); |
- | 246 | // after adding a second language the programm didn't close properly anymore |
|
- | 247 | // so this is kinda workaround... |
|
- | 248 | Dispose(true); |
|
- | 249 | Environment.Exit(0); |
|
243 | } |
250 | } |
244 | private void SimpleSerialPort_PortOpened() |
251 | private void SimpleSerialPort_PortOpened() |
245 | { |
252 | { |
246 | btnConn.Invoke((Action)(() => btnConn.BackColor = Color.FromArgb(192, 255, 192))); |
253 | btnConn.Invoke((Action)(() => btnConn.BackColor = Color.FromArgb(192, 255, 192))); |
- | 254 | if(Thread.CurrentThread.CurrentUICulture.Name== "") |
|
247 | btnConn.Invoke((Action)(() => btnConn.Text = "close" + Environment.NewLine + "serial port")); |
255 | btnConn.Invoke((Action)(() => btnConn.Text = "close" + Environment.NewLine + "serial port")); |
- | 256 | else |
|
- | 257 | btnConn.Invoke((Action)(() => btnConn.Text = "COM-Port" + Environment.NewLine + "schliessen")); |
|
248 | _getVersion(); |
258 | _getVersion(); |
249 | Thread.Sleep(100); |
259 | Thread.Sleep(100); |
250 | _OSDMenue(0); |
260 | _OSDMenue(0); |
251 | Thread.Sleep(200); |
261 | Thread.Sleep(200); |
252 | _sendSerialData(); |
262 | _sendSerialData(); |
253 | // _readCont(true); |
263 | // _readCont(true); |
254 | } |
264 | } |
255 | private void SimpleSerialPort_PortClosed() |
265 | private void SimpleSerialPort_PortClosed() |
256 | { |
266 | { |
257 | btnConn.Invoke((Action)(() => btnConn.BackColor = Color.FromArgb(224, 224, 224))); |
267 | btnConn.Invoke((Action)(() => btnConn.BackColor = Color.FromArgb(224, 224, 224))); |
- | 268 | if (Thread.CurrentThread.CurrentUICulture.Name == "") |
|
258 | btnConn.Invoke((Action)(() => btnConn.Text = "open" + Environment.NewLine + "serial port")); |
269 | btnConn.Invoke((Action)(() => btnConn.Text = "open" + Environment.NewLine + "serial port")); |
- | 270 | else |
|
- | 271 | btnConn.Invoke((Action)(() => btnConn.Text = "COM-Port" + Environment.NewLine + "öffnen")); |
|
259 | _readCont(false); |
272 | _readCont(false); |
260 | } |
273 | } |
261 | /// <summary> |
274 | /// <summary> |
262 | /// timer for refreshing subscription of subscribed data |
275 | /// timer for refreshing subscription of subscribed data |
263 | /// query lifecounter for connection failure |
276 | /// query lifecounter for connection failure |
264 | /// </summary> |
277 | /// </summary> |
265 | private void timer1_Tick(object sender, EventArgs e) |
278 | private void timer1_Tick(object sender, EventArgs e) |
266 | { |
279 | { |
267 | if(bReadContinously) |
280 | if(bReadContinously) |
268 | { |
281 | { |
269 | if (_debugDataAutorefresh) { _readDebugData(true); Thread.Sleep(10); } |
282 | if (_debugDataAutorefresh) { _readDebugData(true); Thread.Sleep(10); } |
270 | 283 | ||
271 | if (_blctrlDataAutorefresh) { _readBLCtrl(true); Thread.Sleep(10); } |
284 | if (_blctrlDataAutorefresh) { _readBLCtrl(true); Thread.Sleep(10); } |
272 | 285 | ||
273 | if (_navCtrlDataAutorefresh && _iCtrlAct == 2) { _readNavData(true); Thread.Sleep(10); } |
286 | if (_navCtrlDataAutorefresh && _iCtrlAct == 2) { _readNavData(true); Thread.Sleep(10); } |
274 | check_HWError = true; |
287 | check_HWError = true; |
275 | _getVersion(); |
288 | _getVersion(); |
276 | Thread.Sleep(10); |
289 | Thread.Sleep(10); |
277 | if (_OSDAutorefresh) { _OSDMenueAutoRefresh(); } |
290 | if (_OSDAutorefresh) { _OSDMenueAutoRefresh(); } |
278 | if (_iLifeCounter > 0) |
291 | if (_iLifeCounter > 0) |
279 | { |
292 | { |
280 | lblLifeCounter.BackColor = Color.FromArgb(0, 224, 0); |
293 | lblLifeCounter.BackColor = Color.FromArgb(0, 224, 0); |
281 | _iLifeCounter = 0; |
294 | _iLifeCounter = 0; |
282 | } |
295 | } |
283 | else |
296 | else |
284 | { |
297 | { |
285 | Log(LogMsgType.Error, "No communication to NC/FC!"); |
298 | Log(LogMsgType.Error, "No communication to NC/FC!"); |
286 | lblLifeCounter.BackColor = Color.FromArgb(224, 0, 0); |
299 | lblLifeCounter.BackColor = Color.FromArgb(224, 0, 0); |
287 | } |
300 | } |
288 | } |
301 | } |
289 | } |
302 | } |
290 | private void cbOSD_SelectedIndexChanged(object sender, EventArgs e) |
303 | private void cbOSD_SelectedIndexChanged(object sender, EventArgs e) |
291 | { |
304 | { |
292 | if (!_bCBInit && cbOSD.SelectedIndex > -1) |
305 | if (!_bCBInit && cbOSD.SelectedIndex > -1) |
293 | _OSDMenue(cbOSD.SelectedIndex); |
306 | _OSDMenue(cbOSD.SelectedIndex); |
294 | } |
307 | } |
295 | private void chkbAutoDbg_CheckedChanged(object sender, EventArgs e) |
308 | private void chkbAutoDbg_CheckedChanged(object sender, EventArgs e) |
296 | { |
309 | { |
297 | if(!_init) _debugDataAutorefresh = chkbAutoDbg.Checked; |
310 | if(!_init) _debugDataAutorefresh = chkbAutoDbg.Checked; |
298 | } |
311 | } |
299 | private void chkbAutoNav_CheckedChanged(object sender, EventArgs e) |
312 | private void chkbAutoNav_CheckedChanged(object sender, EventArgs e) |
300 | { |
313 | { |
301 | if (!_init) _navCtrlDataAutorefresh = chkbAutoNav.Checked; |
314 | if (!_init) _navCtrlDataAutorefresh = chkbAutoNav.Checked; |
302 | } |
315 | } |
303 | private void chkbAutoBL_CheckedChanged(object sender, EventArgs e) |
316 | private void chkbAutoBL_CheckedChanged(object sender, EventArgs e) |
304 | { |
317 | { |
305 | if (!_init) _blctrlDataAutorefresh = chkbAutoBL.Checked; |
318 | if (!_init) _blctrlDataAutorefresh = chkbAutoBL.Checked; |
306 | } |
319 | } |
307 | private void chkbAutoOSD_CheckedChanged(object sender, EventArgs e) |
320 | private void chkbAutoOSD_CheckedChanged(object sender, EventArgs e) |
308 | { |
321 | { |
309 | if (!_init) _OSDAutorefresh = chkbAutoOSD.Checked; |
322 | if (!_init) _OSDAutorefresh = chkbAutoOSD.Checked; |
310 | } |
323 | } |
311 | private void cbTimingDebug_SelectedIndexChanged(object sender, EventArgs e) |
324 | private void cbTimingDebug_SelectedIndexChanged(object sender, EventArgs e) |
312 | { |
325 | { |
313 | if (cbTimingDebug.SelectedIndex > -1) |
326 | if (cbTimingDebug.SelectedIndex > -1) |
314 | { |
327 | { |
315 | debugInterval = (byte)(Convert.ToInt16(cbTimingDebug.SelectedItem) / 10); |
328 | debugInterval = (byte)(Convert.ToInt16(cbTimingDebug.SelectedItem) / 10); |
316 | labelTimingDebug.Text = (debugInterval * 10).ToString(); |
329 | labelTimingDebug.Text = (debugInterval * 10).ToString(); |
317 | } |
330 | } |
318 | } |
331 | } |
319 | private void cbTimingNAV_SelectedIndexChanged(object sender, EventArgs e) |
332 | private void cbTimingNAV_SelectedIndexChanged(object sender, EventArgs e) |
320 | { |
333 | { |
321 | if (cbTimingNAV.SelectedIndex > -1) |
334 | if (cbTimingNAV.SelectedIndex > -1) |
322 | { |
335 | { |
323 | navctrlInterval = (byte)(Convert.ToInt16(cbTimingNAV.SelectedItem) / 10); |
336 | navctrlInterval = (byte)(Convert.ToInt16(cbTimingNAV.SelectedItem) / 10); |
324 | labelTimingNAV.Text = (navctrlInterval * 10).ToString(); |
337 | labelTimingNAV.Text = (navctrlInterval * 10).ToString(); |
325 | } |
338 | } |
326 | } |
339 | } |
327 | private void cbTimingBLCTRL_SelectedIndexChanged(object sender, EventArgs e) |
340 | private void cbTimingBLCTRL_SelectedIndexChanged(object sender, EventArgs e) |
328 | { |
341 | { |
329 | if (cbTimingBLCTRL.SelectedIndex > -1) |
342 | if (cbTimingBLCTRL.SelectedIndex > -1) |
330 | { |
343 | { |
331 | blctrlInterval = (byte)(Convert.ToInt16(cbTimingBLCTRL.SelectedItem) / 10); |
344 | blctrlInterval = (byte)(Convert.ToInt16(cbTimingBLCTRL.SelectedItem) / 10); |
332 | labelTimingBLCTRL.Text = (blctrlInterval * 10).ToString(); |
345 | labelTimingBLCTRL.Text = (blctrlInterval * 10).ToString(); |
333 | } |
346 | } |
334 | } |
347 | } |
335 | private void cbTimingOSD_SelectedIndexChanged(object sender, EventArgs e) |
348 | private void cbTimingOSD_SelectedIndexChanged(object sender, EventArgs e) |
336 | { |
349 | { |
337 | if (cbTimingOSD.SelectedIndex > -1) |
350 | if (cbTimingOSD.SelectedIndex > -1) |
338 | { |
351 | { |
339 | OSDInterval = (byte)(Convert.ToInt16(cbTimingOSD.SelectedItem) / 10); |
352 | OSDInterval = (byte)(Convert.ToInt16(cbTimingOSD.SelectedItem) / 10); |
340 | labelTimingOSD.Text = (OSDInterval * 10).ToString(); |
353 | labelTimingOSD.Text = (OSDInterval * 10).ToString(); |
341 | } |
354 | } |
342 | } |
355 | } |
343 | private void rtfError_LinkClicked(object sender, LinkClickedEventArgs e) |
356 | private void rtfError_LinkClicked(object sender, LinkClickedEventArgs e) |
344 | { |
357 | { |
345 | System.Diagnostics.Process.Start(e.LinkText); |
358 | System.Diagnostics.Process.Start(e.LinkText); |
346 | } |
359 | } |
- | 360 | /// <summary> |
|
- | 361 | /// Combobox for selecting UI language |
|
- | 362 | /// </summary> |
|
- | 363 | /// <param name="sender"></param> |
|
- | 364 | /// <param name="e"></param> |
|
- | 365 | private void cbLanguage_SelectedIndexChanged(object sender, EventArgs e) |
|
- | 366 | { |
|
- | 367 | if (cbLanguage.SelectedIndex == 1) |
|
- | 368 | Thread.CurrentThread.CurrentUICulture = new System.Globalization.CultureInfo("de-DE"); |
|
- | 369 | else |
|
- | 370 | Thread.CurrentThread.CurrentUICulture = new System.Globalization.CultureInfo(""); |
|
- | 371 | updateStringRessource(); |
|
- | 372 | } |
|
- | 373 | /// <summary> |
|
- | 374 | /// the form has to be recreated when changing the language of the UI |
|
- | 375 | /// </summary> |
|
- | 376 | private void updateStringRessource() |
|
- | 377 | { |
|
- | 378 | try |
|
- | 379 | { |
|
- | 380 | Point pt = this.Location;// memorize location of form |
|
- | 381 | Size sz = this.Size;// memorize size of form |
|
- | 382 | ||
- | 383 | if (simpleSerialPort.Port.IsOpen) |
|
- | 384 | { |
|
- | 385 | simpleSerialPort.Port.Close(); |
|
- | 386 | Thread.Sleep(200); |
|
- | 387 | _readCont(false); |
|
- | 388 | Thread.Sleep(100); |
|
- | 389 | while (simpleSerialPort.Port.IsOpen | bReadContinously) |
|
- | 390 | Thread.Sleep(100); |
|
- | 391 | } |
|
- | 392 | ||
- | 393 | this.Controls.Clear();// clear all controls of form |
|
- | 394 | components.Dispose();// dispose all components and release resources |
|
- | 395 | // delete all events to avoid double instances when calling InitializeComponent(); |
|
- | 396 | this.Events.Dispose(); |
|
- | 397 | if (timer1 != null) |
|
- | 398 | { |
|
- | 399 | timer1.Dispose(); |
|
- | 400 | timer1 = null; |
|
- | 401 | } |
|
- | 402 | _init = true; |
|
- | 403 | timer1 = new System.Windows.Forms.Timer(); |
|
- | 404 | ||
- | 405 | dtAnalog = new DataTable(); |
|
- | 406 | dtMotors1 = new DataTable(); |
|
- | 407 | dtMotors2 = new DataTable(); |
|
- | 408 | dtWaypoints = new DataTable(); |
|
- | 409 | ||
- | 410 | InitializeComponent(); // reload UI |
|
- | 411 | ||
- | 412 | _dataTablesInit(); |
|
- | 413 | ||
- | 414 | simpleSerialPort.PortClosed += SimpleSerialPort_PortClosed; |
|
- | 415 | simpleSerialPort.PortOpened += SimpleSerialPort_PortOpened; |
|
- | 416 | simpleSerialPort.DataReceived += processMessage; |
|
- | 417 | ||
- | 418 | chkbAutoBL.Checked = _blctrlDataAutorefresh; |
|
- | 419 | chkbAutoDbg.Checked = _debugDataAutorefresh; |
|
- | 420 | chkbAutoNav.Checked = _navCtrlDataAutorefresh; |
|
- | 421 | chkbAutoOSD.Checked = _OSDAutorefresh; |
|
- | 422 | ||
- | 423 | labelTimingDebug.Text = (debugInterval * 10).ToString(); |
|
- | 424 | labelTimingBLCTRL.Text = (blctrlInterval * 10).ToString(); |
|
- | 425 | labelTimingNAV.Text = (navctrlInterval * 10).ToString(); |
|
- | 426 | labelTimingOSD.Text = (OSDInterval * 10).ToString(); |
|
- | 427 | ||
- | 428 | TabControl1.TabPages.Remove(tabPageTesting); //a testing page |
|
- | 429 | ||
- | 430 | this.Size = sz;// set size |
|
- | 431 | this.Location = pt;// position form |
|
- | 432 | _loadLabelNames(); |
|
- | 433 | _initSerialCtrl(); |
|
- | 434 | _init = false; |
|
- | 435 | ||
- | 436 | } |
|
- | 437 | catch (Exception ex) |
|
- | 438 | { |
|
- | 439 | MessageBox.Show(ex.Message); |
|
- | 440 | } |
|
- | 441 | } |
|
347 | 442 | ||
348 | #endregion events |
443 | #endregion events |
349 | 444 | ||
350 | /// <summary> Log data to the terminal window. </summary> |
445 | /// <summary> Log data to the terminal window. </summary> |
351 | /// <param name="msgtype"> The type of message to be written. </param> |
446 | /// <param name="msgtype"> The type of message to be written. </param> |
352 | /// <param name="msg"> The string containing the message to be shown. </param> |
447 | /// <param name="msg"> The string containing the message to be shown. </param> |
353 | private void Log(LogMsgType msgtype, string msg) |
448 | private void Log(LogMsgType msgtype, string msg) |
354 | { |
449 | { |
355 | rtfTerminal.Invoke(new EventHandler(delegate |
450 | rtfTerminal.Invoke(new EventHandler(delegate |
356 | { |
451 | { |
357 | if (rtfTerminal.Lines.Length >= 1000) //Wenn Terminal mehr als 1000 Zeilen hat |
452 | if (rtfTerminal.Lines.Length >= 1000) //Wenn Terminal mehr als 1000 Zeilen hat |
358 | rtfTerminal.Select(42, (500 * 129)); //500 löschen |
453 | rtfTerminal.Select(42, (500 * 129)); //500 löschen |
359 | rtfTerminal.Select(rtfTerminal.Text.Length, 0); |
454 | rtfTerminal.Select(rtfTerminal.Text.Length, 0); |
360 | rtfTerminal.SelectedText = string.Empty; |
455 | rtfTerminal.SelectedText = string.Empty; |
361 | rtfTerminal.SelectionFont = new Font(rtfTerminal.SelectionFont, FontStyle.Regular); |
456 | rtfTerminal.SelectionFont = new Font(rtfTerminal.SelectionFont, FontStyle.Regular); |
362 | rtfTerminal.SelectionColor = LogMsgTypeColor[(int)msgtype]; |
457 | rtfTerminal.SelectionColor = LogMsgTypeColor[(int)msgtype]; |
363 | rtfTerminal.AppendText(msg + Environment.NewLine); |
458 | rtfTerminal.AppendText(msg + Environment.NewLine); |
364 | rtfTerminal.ScrollToCaret(); |
459 | rtfTerminal.ScrollToCaret(); |
365 | })); |
460 | })); |
366 | } |
461 | } |
367 | /// <summary> display the OSD text in 4 lines à 20 chars </summary> |
462 | /// <summary> display the OSD text in 4 lines à 20 chars </summary> |
368 | /// <param name="msgtype"> The type of message to be written. </param> |
463 | /// <param name="msgtype"> The type of message to be written. </param> |
369 | /// <param name="msg"> The string containing the message to be shown. </param> |
464 | /// <param name="msg"> The string containing the message to be shown. </param> |
370 | private void OSD(LogMsgType msgtype, string msg) |
465 | private void OSD(LogMsgType msgtype, string msg) |
371 | { |
466 | { |
372 | rtfOSD.Invoke(new EventHandler(delegate |
467 | rtfOSD.Invoke(new EventHandler(delegate |
373 | { |
468 | { |
374 | if (rtfOSD.Lines.Length > 4) |
469 | if (rtfOSD.Lines.Length > 4) |
375 | rtfOSD.Clear(); |
470 | rtfOSD.Clear(); |
376 | rtfOSD.Select(rtfOSD.Text.Length,0); |
471 | rtfOSD.Select(rtfOSD.Text.Length,0); |
377 | rtfOSD.SelectedText = string.Empty; |
472 | rtfOSD.SelectedText = string.Empty; |
378 | rtfOSD.SelectionFont = new Font(rtfOSD.SelectionFont, FontStyle.Regular); |
473 | rtfOSD.SelectionFont = new Font(rtfOSD.SelectionFont, FontStyle.Regular); |
379 | rtfOSD.SelectionColor = LogMsgTypeColor[(int)msgtype]; |
474 | rtfOSD.SelectionColor = LogMsgTypeColor[(int)msgtype]; |
380 | rtfOSD.AppendText(msg + Environment.NewLine); |
475 | rtfOSD.AppendText(msg + Environment.NewLine); |
381 | if (rtfOSD.Text.IndexOf("ERR") > 0) |
476 | if (rtfOSD.Text.IndexOf("ERR") > 0) |
382 | { |
477 | { |
383 | rtfOSD.Select(rtfOSD.Text.IndexOf("ERR"), 40); |
478 | rtfOSD.Select(rtfOSD.Text.IndexOf("ERR"), 40); |
384 | rtfOSD.SelectionColor = LogMsgTypeColor[(int)LogMsgType.Error]; |
479 | rtfOSD.SelectionColor = LogMsgTypeColor[(int)LogMsgType.Error]; |
385 | } |
480 | } |
386 | })); |
481 | })); |
387 | } |
482 | } |
388 | private void ErrorLog(LogMsgType msgtype, string msg) |
483 | private void ErrorLog(LogMsgType msgtype, string msg) |
389 | { |
484 | { |
390 | rtfError.Invoke(new EventHandler(delegate |
485 | rtfError.Invoke(new EventHandler(delegate |
391 | { |
486 | { |
392 | if (rtfError.Lines.Length > 4) |
487 | if (rtfError.Lines.Length > 4) |
393 | rtfError.Clear(); |
488 | rtfError.Clear(); |
394 | rtfError.Focus(); |
489 | rtfError.Focus(); |
395 | rtfError.Select(rtfError.Text.Length, 0); |
490 | rtfError.Select(rtfError.Text.Length, 0); |
396 | rtfError.SelectedText = string.Empty; |
491 | rtfError.SelectedText = string.Empty; |
397 | rtfError.SelectionFont = new Font(rtfError.SelectionFont, FontStyle.Regular); |
492 | rtfError.SelectionFont = new Font(rtfError.SelectionFont, FontStyle.Regular); |
398 | rtfError.SelectionColor = LogMsgTypeColor[(int)msgtype]; |
493 | rtfError.SelectionColor = LogMsgTypeColor[(int)msgtype]; |
399 | rtfError.AppendText(msg + Environment.NewLine); |
494 | rtfError.AppendText(msg + Environment.NewLine); |
400 | 495 | ||
401 | })); |
496 | })); |
402 | _bErrorLog = true; |
497 | _bErrorLog = true; |
403 | } |
498 | } |
404 | 499 | ||
405 | #region functions |
500 | #region functions |
406 | 501 | ||
407 | #region processing received data |
502 | #region processing received data |
408 | /// <summary> Processing the messages and displaying them in the according form controls |
503 | /// <summary> Processing the messages and displaying them in the according form controls |
409 | /// function called by simpleSerialPort.DataReceived event |
504 | /// function called by simpleSerialPort.DataReceived event |
410 | /// </summary> |
505 | /// </summary> |
411 | /// <param name="message"> message bytearray recieved by SimpleSerialPort class </param> |
506 | /// <param name="message"> message bytearray recieved by SimpleSerialPort class </param> |
412 | private void processMessage(byte[] message) |
507 | private void processMessage(byte[] message) |
413 | { |
508 | { |
414 | if (message.Length > 0) |
509 | if (message.Length > 0) |
415 | { |
510 | { |
416 | _iLifeCounter++; |
511 | _iLifeCounter++; |
417 | //Log(LogMsgType.Incoming, BitConverter.ToString(message)); |
512 | //Log(LogMsgType.Incoming, BitConverter.ToString(message)); |
418 | //Log(LogMsgType.Incoming, message.Length.ToString()); |
513 | //Log(LogMsgType.Incoming, message.Length.ToString()); |
419 | string s = new string(ASCIIEncoding.ASCII.GetChars(message, 0, message.Length)); |
514 | string s = new string(ASCIIEncoding.ASCII.GetChars(message, 0, message.Length)); |
420 | char cmdID; |
515 | char cmdID; |
421 | byte adr; |
516 | byte adr; |
422 | byte[] data; |
517 | byte[] data; |
423 | byte[] tmp = null; |
518 | byte[] tmp = null; |
424 | if (message[0] != '#') |
519 | if (message[0] != '#') |
425 | { |
520 | { |
426 | int iFound = -1; |
521 | int iFound = -1; |
427 | for(int i=0;i<message.Length;i++) //Sometimes the FC/NC sends strings without termination (like WP messages) |
522 | for(int i=0;i<message.Length;i++) //Sometimes the FC/NC sends strings without termination (like WP messages) |
428 | { //so this is a workaround to not spam the log box |
523 | { //so this is a workaround to not spam the log box |
429 | if (message[i] == 35) |
524 | if (message[i] == 35) |
430 | { |
525 | { |
431 | iFound = i; |
526 | iFound = i; |
432 | break; |
527 | break; |
433 | } |
528 | } |
434 | } |
529 | } |
435 | if(iFound>0) |
530 | if(iFound>0) |
436 | { |
531 | { |
437 | s = new string(ASCIIEncoding.ASCII.GetChars(message, 0,iFound)); |
532 | s = new string(ASCIIEncoding.ASCII.GetChars(message, 0,iFound)); |
438 | tmp = new byte[message.Length - iFound]; |
533 | tmp = new byte[message.Length - iFound]; |
439 | Buffer.BlockCopy(message, iFound, tmp, 0, message.Length - iFound); |
534 | Buffer.BlockCopy(message, iFound, tmp, 0, message.Length - iFound); |
440 | } |
535 | } |
441 | s = s.Trim('\0', '\n', '\r'); |
536 | s = s.Trim('\0', '\n', '\r'); |
442 | if(s.Length > 0) |
537 | if(s.Length > 0) |
443 | Log(LogMsgType.Normal, s); |
538 | Log(LogMsgType.Normal, s); |
444 | if (tmp != null) |
539 | if (tmp != null) |
445 | { |
540 | { |
446 | s = new string(ASCIIEncoding.ASCII.GetChars(tmp, 0, tmp.Length)); |
541 | s = new string(ASCIIEncoding.ASCII.GetChars(tmp, 0, tmp.Length)); |
447 | processMessage(tmp); |
542 | processMessage(tmp); |
448 | } |
543 | } |
449 | } |
544 | } |
450 | //Debug.Print(s); |
545 | //Debug.Print(s); |
451 | else |
546 | else |
452 | { |
547 | { |
453 | FlightControllerMessage.ParseMessage(message, out cmdID, out adr, out data); |
548 | FlightControllerMessage.ParseMessage(message, out cmdID, out adr, out data); |
454 | 549 | ||
455 | if (adr == 255) { crcError++; } |
550 | if (adr == 255) { crcError++; } |
456 | else crcError = 0; |
551 | else crcError = 0; |
457 | lblCRCErr.Invoke((Action)(() => lblCRCErr.Text = crcError.ToString())); |
552 | lblCRCErr.Invoke((Action)(() => lblCRCErr.Text = crcError.ToString())); |
458 | //display the active controller (FC / NC) |
553 | //display the active controller (FC / NC) |
459 | if (adr > 0 && adr < 3 && adr != _iCtrlAct) //adr < 3: temporary workaround cause when I've connected the FC alone it always switches between mk3mag & FC every second...??? |
554 | if (adr > 0 && adr < 3 && adr != _iCtrlAct) //adr < 3: temporary workaround cause when I've connected the FC alone it always switches between mk3mag & FC every second...??? |
460 | { |
555 | { |
461 | _iCtrlAct = adr; |
556 | _iCtrlAct = adr; |
462 | switch (adr) |
557 | switch (adr) |
463 | { |
558 | { |
464 | case 1: |
559 | case 1: |
465 | lblCtrl.Invoke((Action)(() => lblCtrl.Text = "FC")); |
560 | lblCtrl.Invoke((Action)(() => lblCtrl.Text = "FC")); |
466 | lblNCCtrl.Invoke((Action)(() => lblNCCtrl.Text = "FC")); |
561 | lblNCCtrl.Invoke((Action)(() => lblNCCtrl.Text = "FC")); |
467 | _setFieldsNA(); //display fields NA for FC |
562 | _setFieldsNA(); //display fields NA for FC |
468 | break; |
563 | break; |
469 | case 2: |
564 | case 2: |
470 | lblCtrl.Invoke((Action)(() => lblCtrl.Text = "NC")); |
565 | lblCtrl.Invoke((Action)(() => lblCtrl.Text = "NC")); |
471 | lblNCCtrl.Invoke((Action)(() => lblNCCtrl.Text = "NC")); |
566 | lblNCCtrl.Invoke((Action)(() => lblNCCtrl.Text = "NC")); |
472 | break; |
567 | break; |
473 | case 3: |
568 | case 3: |
474 | lblCtrl.Invoke((Action)(() => lblCtrl.Text = "MK3MAG")); |
569 | lblCtrl.Invoke((Action)(() => lblCtrl.Text = "MK3MAG")); |
475 | break; |
570 | break; |
476 | case 4: |
571 | case 4: |
477 | lblCtrl.Invoke((Action)(() => lblCtrl.Text = "BL-CTRL")); |
572 | lblCtrl.Invoke((Action)(() => lblCtrl.Text = "BL-CTRL")); |
478 | break; |
573 | break; |
479 | default: |
574 | default: |
480 | lblCtrl.Invoke((Action)(() => lblCtrl.Text = "....")); |
575 | lblCtrl.Invoke((Action)(() => lblCtrl.Text = "....")); |
481 | break; |
576 | break; |
482 | } |
577 | } |
483 | _loadLabelNames(); |
578 | _loadLabelNames(); |
484 | } |
579 | } |
485 | // else |
580 | // else |
486 | // Debug.Print("Address == 0?"); |
581 | // Debug.Print("Address == 0?"); |
487 | 582 | ||
488 | if (data != null && data.Length > 0) |
583 | if (data != null && data.Length > 0) |
489 | { |
584 | { |
490 | s = new string(ASCIIEncoding.ASCII.GetChars(data, 1, data.Length - 1)); |
585 | s = new string(ASCIIEncoding.ASCII.GetChars(data, 1, data.Length - 1)); |
491 | s = s.Trim('\0', '\n'); |
586 | s = s.Trim('\0', '\n'); |
492 | 587 | ||
493 | switch (cmdID) |
588 | switch (cmdID) |
494 | { |
589 | { |
495 | case 'A': //Label names |
590 | case 'A': //Label names |
496 | _processLabelNames(s); |
591 | _processLabelNames(s); |
497 | break; |
592 | break; |
498 | 593 | ||
499 | case 'D': //Debug data |
594 | case 'D': //Debug data |
500 | _processDebugVals(adr, data); |
595 | _processDebugVals(adr, data); |
501 | break; |
596 | break; |
502 | 597 | ||
503 | case 'V': //Version |
598 | case 'V': //Version |
504 | _processVersion(adr, data); |
599 | _processVersion(adr, data); |
505 | break; |
600 | break; |
506 | 601 | ||
507 | case 'K'://BL-CTRL data |
602 | case 'K'://BL-CTRL data |
508 | _processBLCtrl(data); |
603 | _processBLCtrl(data); |
509 | break; |
604 | break; |
510 | 605 | ||
511 | case 'O': //NC Data |
606 | case 'O': //NC Data |
512 | _processNCData(data); |
607 | _processNCData(data); |
513 | break; |
608 | break; |
514 | 609 | ||
515 | case 'E': //NC error-string |
610 | case 'E': //NC error-string |
516 | ErrorLog(LogMsgType.Error, "NC Error: " + s); |
611 | ErrorLog(LogMsgType.Error, "NC Error: " + s); |
517 | break; |
612 | break; |
518 | 613 | ||
519 | case 'L': //OSD Menue (called by pagenumber) |
614 | case 'L': //OSD Menue (called by pagenumber) |
520 | _processOSDSingle(data); |
615 | _processOSDSingle(data); |
521 | break; |
616 | break; |
522 | 617 | ||
523 | case 'H': //OSD Menue (with autoupdate - called by Key) |
618 | case 'H': //OSD Menue (with autoupdate - called by Key) |
524 | _processOSDAuto(data); |
619 | _processOSDAuto(data); |
525 | break; |
620 | break; |
526 | 621 | ||
527 | case 'X': //Waypoint data |
622 | case 'X': //Waypoint data |
528 | _processWPData(data); |
623 | _processWPData(data); |
529 | break; |
624 | break; |
530 | 625 | ||
531 | //default: |
626 | //default: |
532 | // Log(LogMsgType.Incoming, "cmd: " + cmdID.ToString()); |
627 | // Log(LogMsgType.Incoming, "cmd: " + cmdID.ToString()); |
533 | // Log(LogMsgType.Incoming, BitConverter.ToString(data)); |
628 | // Log(LogMsgType.Incoming, BitConverter.ToString(data)); |
534 | // break; |
629 | // break; |
535 | } |
630 | } |
536 | } |
631 | } |
537 | //else |
632 | //else |
538 | //{ |
633 | //{ |
539 | // Log(LogMsgType.Incoming, "cmd: " + cmdID.ToString()); |
634 | // Log(LogMsgType.Incoming, "cmd: " + cmdID.ToString()); |
540 | // Log(LogMsgType.Incoming, BitConverter.ToString(data)); |
635 | // Log(LogMsgType.Incoming, BitConverter.ToString(data)); |
541 | //} |
636 | //} |
542 | } |
637 | } |
543 | } |
638 | } |
544 | } |
639 | } |
545 | /// <summary> |
640 | /// <summary> |
546 | /// Analog label names 'A' |
641 | /// Analog label names 'A' |
547 | /// each label name is returned as a single string |
642 | /// each label name is returned as a single string |
548 | /// and added to string array sAnalogLabel[] |
643 | /// and added to string array sAnalogLabel[] |
549 | /// and the datatable dtAnalog |
644 | /// and the datatable dtAnalog |
550 | /// </summary> |
645 | /// </summary> |
551 | /// <param name="s">the label name</param> |
646 | /// <param name="s">the label name</param> |
552 | void _processLabelNames(string s) |
647 | void _processLabelNames(string s) |
553 | { |
648 | { |
554 | if (iLableIndex < 32) |
649 | if (iLableIndex < 32) |
555 | { |
650 | { |
556 | sAnalogLabel[iLableIndex] = s; |
651 | sAnalogLabel[iLableIndex] = s; |
557 | if (dtAnalog.Rows.Count < 32) |
652 | if (dtAnalog.Rows.Count < 32) |
558 | dtAnalog.Rows.Add(s, ""); |
653 | dtAnalog.Rows.Add(s, ""); |
559 | else |
654 | else |
560 | dtAnalog.Rows[iLableIndex].SetField(0, s); |
655 | dtAnalog.Rows[iLableIndex].SetField(0, s); |
561 | 656 | ||
562 | _getAnalogLabels(iLableIndex + 1); |
657 | _getAnalogLabels(iLableIndex + 1); |
563 | } |
658 | } |
564 | Debug.Print(s); |
659 | Debug.Print(s); |
565 | } |
660 | } |
566 | /// <summary> |
661 | /// <summary> |
567 | /// Debug values 'D' |
662 | /// Debug values 'D' |
568 | /// </summary> |
663 | /// </summary> |
569 | /// <param name="adr">adress of the active controller (1-FC, 2-NC)</param> |
664 | /// <param name="adr">adress of the active controller (1-FC, 2-NC)</param> |
570 | /// <param name="data">the received byte array to process</param> |
665 | /// <param name="data">the received byte array to process</param> |
571 | void _processDebugVals(byte adr,byte[] data) |
666 | void _processDebugVals(byte adr,byte[] data) |
572 | { |
667 | { |
573 | if (data.Length == 66) |
668 | if (data.Length == 66) |
574 | { |
669 | { |
575 | int[] iAnalogData = new int[32]; |
670 | int[] iAnalogData = new int[32]; |
576 | 671 | ||
577 | int index = 0; |
672 | int index = 0; |
578 | Int16 i16 = 0; |
673 | Int16 i16 = 0; |
579 | double dTemp = 0; |
674 | double dTemp = 0; |
580 | for (int i = 2; i < 66; i += 2) |
675 | for (int i = 2; i < 66; i += 2) |
581 | { |
676 | { |
582 | i16 = data[i + 1]; |
677 | i16 = data[i + 1]; |
583 | i16 = (Int16)(i16 << 8); |
678 | i16 = (Int16)(i16 << 8); |
584 | iAnalogData[index] = data[i] + i16; |
679 | iAnalogData[index] = data[i] + i16; |
585 | sAnalogData[index] = (data[i] + i16).ToString(); |
680 | sAnalogData[index] = (data[i] + i16).ToString(); |
586 | dtAnalog.Rows[index].SetField(1, sAnalogData[index]); |
681 | dtAnalog.Rows[index].SetField(1, sAnalogData[index]); |
587 | 682 | ||
588 | if (adr == 2) //NC |
683 | if (adr == 2) //NC |
589 | { |
684 | { |
590 | switch (index) |
685 | switch (index) |
591 | { |
686 | { |
592 | case 0: //pitch (German: nick) |
687 | case 0: //pitch (German: nick) |
593 | artificialHorizon1.Invoke((Action)(() => artificialHorizon1.pitch_angle = ((double)iAnalogData[index] / (double)10))); |
688 | artificialHorizon1.Invoke((Action)(() => artificialHorizon1.pitch_angle = ((double)iAnalogData[index] / (double)10))); |
594 | lblNCPitch.Invoke((Action)(() => lblNCPitch.Text = ((double)iAnalogData[index] / (double)10).ToString("0.0°"))); |
689 | lblNCPitch.Invoke((Action)(() => lblNCPitch.Text = ((double)iAnalogData[index] / (double)10).ToString("0.0°"))); |
595 | break; |
690 | break; |
596 | case 1: //roll |
691 | case 1: //roll |
597 | artificialHorizon1.Invoke((Action)(() => artificialHorizon1.roll_angle = ((double)iAnalogData[index] / (double)10))); |
692 | artificialHorizon1.Invoke((Action)(() => artificialHorizon1.roll_angle = ((double)iAnalogData[index] / (double)10))); |
598 | lblNCRoll.Invoke((Action)(() => lblNCRoll.Text = ((double)iAnalogData[index] / (double)10).ToString("0.0°"))); |
693 | lblNCRoll.Invoke((Action)(() => lblNCRoll.Text = ((double)iAnalogData[index] / (double)10).ToString("0.0°"))); |
599 | break; |
694 | break; |
600 | case 4: //altitude |
695 | case 4: //altitude |
601 | lblNCAlt.Invoke((Action)(() => lblNCAlt.Text = ((double)iAnalogData[index] / (double)10).ToString("0.0 m"))); |
696 | lblNCAlt.Invoke((Action)(() => lblNCAlt.Text = ((double)iAnalogData[index] / (double)10).ToString("0.0 m"))); |
602 | break; |
697 | break; |
603 | case 7: //Voltage |
698 | case 7: //Voltage |
604 | lblNCVolt.Invoke((Action)(() => lblNCVolt.Text = ((double)iAnalogData[index] / (double)10).ToString("0.0 V"))); |
699 | lblNCVolt.Invoke((Action)(() => lblNCVolt.Text = ((double)iAnalogData[index] / (double)10).ToString("0.0 V"))); |
605 | break; |
700 | break; |
606 | case 8: // Current |
701 | case 8: // Current |
607 | lblNCCur.Invoke((Action)(() => lblNCCur.Text = ((double)iAnalogData[index] / (double)10).ToString("0.0 A"))); |
702 | lblNCCur.Invoke((Action)(() => lblNCCur.Text = ((double)iAnalogData[index] / (double)10).ToString("0.0 A"))); |
608 | break; |
703 | break; |
609 | case 10: //heading |
704 | case 10: //heading |
610 | lblNCCompass.Invoke((Action)(() => lblNCCompass.Text = sAnalogData[index] + "°")); |
705 | lblNCCompass.Invoke((Action)(() => lblNCCompass.Text = sAnalogData[index] + "°")); |
611 | headingIndicator1.Invoke((Action)(() => headingIndicator1.SetHeadingIndicatorParameters(iAnalogData[index]))); |
706 | headingIndicator1.Invoke((Action)(() => headingIndicator1.SetHeadingIndicatorParameters(iAnalogData[index]))); |
612 | break; |
707 | break; |
613 | case 12: // SPI error |
708 | case 12: // SPI error |
614 | lblNCSPI.Invoke((Action)(() => lblNCSPI.Text = sAnalogData[index])); |
709 | lblNCSPI.Invoke((Action)(() => lblNCSPI.Text = sAnalogData[index])); |
615 | break; |
710 | break; |
616 | case 14: //i2c error |
711 | case 14: //i2c error |
617 | lblNCI2C.Invoke((Action)(() => lblNCI2C.Text = sAnalogData[index])); |
712 | lblNCI2C.Invoke((Action)(() => lblNCI2C.Text = sAnalogData[index])); |
618 | break; |
713 | break; |
619 | case 20: //Earthmagnet field |
714 | case 20: //Earthmagnet field |
620 | lblNCMF.Invoke((Action)(() => lblNCMF.Text = sAnalogData[index] + "%")); |
715 | lblNCMF.Invoke((Action)(() => lblNCMF.Text = sAnalogData[index] + "%")); |
621 | break; |
716 | break; |
622 | case 21: //GroundSpeed |
717 | case 21: //GroundSpeed |
623 | lblNCGSpeed.Invoke((Action)(() => lblNCGSpeed.Text = ((double)iAnalogData[index] / (double)100).ToString("0.00 m/s"))); |
718 | lblNCGSpeed.Invoke((Action)(() => lblNCGSpeed.Text = ((double)iAnalogData[index] / (double)100).ToString("0.00 m/s"))); |
624 | break; |
719 | break; |
625 | case 28: //Distance East from saved home position -> calculate distance with distance N + height |
720 | case 28: //Distance East from saved home position -> calculate distance with distance N + height |
626 | dTemp = Math.Pow((double)iAnalogData[index], 2) + Math.Pow((double)iAnalogData[index - 1], 2); |
721 | dTemp = Math.Pow((double)iAnalogData[index], 2) + Math.Pow((double)iAnalogData[index - 1], 2); |
627 | dTemp = Math.Sqrt(dTemp) / (double)10; //'flat' distance from HP with N/E |
722 | dTemp = Math.Sqrt(dTemp) / (double)10; //'flat' distance from HP with N/E |
628 | // lblNCDist.Invoke((Action)(() => lblNCDist.Text = dTemp.ToString("0.00"))); |
723 | // lblNCDist.Invoke((Action)(() => lblNCDist.Text = dTemp.ToString("0.00"))); |
629 | dTemp = Math.Pow(dTemp, 2) + Math.Pow(((double)iAnalogData[4] / (double)10), 2); //adding 'height' into calculation |
724 | dTemp = Math.Pow(dTemp, 2) + Math.Pow(((double)iAnalogData[4] / (double)10), 2); //adding 'height' into calculation |
630 | dTemp = Math.Sqrt(dTemp) / (double)10; |
725 | dTemp = Math.Sqrt(dTemp) / (double)10; |
631 | lblNCDistHP.Invoke((Action)(() => lblNCDistHP.Text = dTemp.ToString("0.0 m"))); |
726 | lblNCDistHP.Invoke((Action)(() => lblNCDistHP.Text = dTemp.ToString("0.0 m"))); |
632 | break; |
727 | break; |
633 | case 31: //Sats used |
728 | case 31: //Sats used |
634 | lblNCSat.Invoke((Action)(() => lblNCSat.Text = sAnalogData[index])); |
729 | lblNCSat.Invoke((Action)(() => lblNCSat.Text = sAnalogData[index])); |
635 | break; |
730 | break; |
636 | } |
731 | } |
637 | } |
732 | } |
638 | if (adr == 1) //FC |
733 | if (adr == 1) //FC |
639 | { |
734 | { |
640 | switch (index) |
735 | switch (index) |
641 | { |
736 | { |
642 | case 0: //pitch (German: nick) |
737 | case 0: //pitch (German: nick) |
643 | artificialHorizon1.Invoke((Action)(() => artificialHorizon1.pitch_angle = ((double)iAnalogData[index] / (double)10))); |
738 | artificialHorizon1.Invoke((Action)(() => artificialHorizon1.pitch_angle = ((double)iAnalogData[index] / (double)10))); |
644 | lblNCPitch.Invoke((Action)(() => lblNCPitch.Text = ((double)iAnalogData[index] / (double)10).ToString("0.0°"))); |
739 | lblNCPitch.Invoke((Action)(() => lblNCPitch.Text = ((double)iAnalogData[index] / (double)10).ToString("0.0°"))); |
645 | break; |
740 | break; |
646 | case 1: //roll |
741 | case 1: //roll |
647 | artificialHorizon1.Invoke((Action)(() => artificialHorizon1.roll_angle = ((double)iAnalogData[index] / (double)10))); |
742 | artificialHorizon1.Invoke((Action)(() => artificialHorizon1.roll_angle = ((double)iAnalogData[index] / (double)10))); |
648 | lblNCRoll.Invoke((Action)(() => lblNCRoll.Text = ((double)iAnalogData[index] / (double)10).ToString("0.0°"))); |
743 | lblNCRoll.Invoke((Action)(() => lblNCRoll.Text = ((double)iAnalogData[index] / (double)10).ToString("0.0°"))); |
649 | break; |
744 | break; |
650 | case 5: //altitude |
745 | case 5: //altitude |
651 | lblNCAlt.Invoke((Action)(() => lblNCAlt.Text = ((double)iAnalogData[index] / (double)10).ToString("0.0 m"))); |
746 | lblNCAlt.Invoke((Action)(() => lblNCAlt.Text = ((double)iAnalogData[index] / (double)10).ToString("0.0 m"))); |
652 | break; |
747 | break; |
653 | case 8: //heading |
748 | case 8: //heading |
654 | lblNCCompass.Invoke((Action)(() => lblNCCompass.Text = sAnalogData[index] + "°")); |
749 | lblNCCompass.Invoke((Action)(() => lblNCCompass.Text = sAnalogData[index] + "°")); |
655 | headingIndicator1.Invoke((Action)(() => headingIndicator1.SetHeadingIndicatorParameters(iAnalogData[index]))); |
750 | headingIndicator1.Invoke((Action)(() => headingIndicator1.SetHeadingIndicatorParameters(iAnalogData[index]))); |
656 | break; |
751 | break; |
657 | case 9: //Voltage |
752 | case 9: //Voltage |
658 | lblNCVolt.Invoke((Action)(() => lblNCVolt.Text = ((double)iAnalogData[index] / (double)10).ToString("0.0 V"))); |
753 | lblNCVolt.Invoke((Action)(() => lblNCVolt.Text = ((double)iAnalogData[index] / (double)10).ToString("0.0 V"))); |
659 | break; |
754 | break; |
660 | case 10: //Receiver quality |
755 | case 10: //Receiver quality |
661 | lblNCRC.Invoke((Action)(() => lblNCRC.Text = sAnalogData[index])); |
756 | lblNCRC.Invoke((Action)(() => lblNCRC.Text = sAnalogData[index])); |
662 | break; |
757 | break; |
663 | case 22: // Current |
758 | case 22: // Current |
664 | lblNCCur.Invoke((Action)(() => lblNCCur.Text = ((double)iAnalogData[index] / (double)10).ToString("0.0 A"))); |
759 | lblNCCur.Invoke((Action)(() => lblNCCur.Text = ((double)iAnalogData[index] / (double)10).ToString("0.0 A"))); |
665 | break; |
760 | break; |
666 | case 23: //capacity used |
761 | case 23: //capacity used |
667 | lblNCCap.Invoke((Action)(() => lblNCCap.Text = (iAnalogData[index]).ToString("0 mAh"))); |
762 | lblNCCap.Invoke((Action)(() => lblNCCap.Text = (iAnalogData[index]).ToString("0 mAh"))); |
668 | break; |
763 | break; |
669 | case 27: // SPI error |
764 | case 27: // SPI error |
670 | lblNCSPI.Invoke((Action)(() => lblNCSPI.Text = sAnalogData[index])); |
765 | lblNCSPI.Invoke((Action)(() => lblNCSPI.Text = sAnalogData[index])); |
671 | break; |
766 | break; |
672 | case 28: //i2c error |
767 | case 28: //i2c error |
673 | lblNCI2C.Invoke((Action)(() => lblNCI2C.Text = sAnalogData[index])); |
768 | lblNCI2C.Invoke((Action)(() => lblNCI2C.Text = sAnalogData[index])); |
674 | break; |
769 | break; |
675 | } |
770 | } |
676 | } |
771 | } |
677 | index++; |
772 | index++; |
678 | } |
773 | } |
679 | } |
774 | } |
680 | else |
775 | else |
681 | Debug.Print("wrong data-length (66): " + data.Length.ToString()); |
776 | Debug.Print("wrong data-length (66): " + data.Length.ToString()); |
682 | } |
777 | } |
683 | /// <summary> |
778 | /// <summary> |
684 | /// Version string 'V' |
779 | /// Version string 'V' |
685 | /// </summary> |
780 | /// </summary> |
686 | /// <param name="adr">adress of the active controller (1-FC, 2-NC)</param> |
781 | /// <param name="adr">adress of the active controller (1-FC, 2-NC)</param> |
687 | /// <param name="data">the received byte array to process</param> |
782 | /// <param name="data">the received byte array to process</param> |
688 | void _processVersion(byte adr,byte[] data) |
783 | void _processVersion(byte adr,byte[] data) |
689 | { |
784 | { |
690 | if (data.Length == 12) |
785 | if (data.Length == 12) |
691 | { |
786 | { |
692 | if (!check_HWError) |
787 | if (!check_HWError) |
693 | { |
788 | { |
694 | string[] sVersionStruct = new string[10] { "SWMajor: ", "SWMinor: ", "ProtoMajor: ", "LabelTextCRC: ", "SWPatch: ", "HardwareError 1: ", "HardwareError 2: ", "HWMajor: ", "BL_Firmware: ", "Flags: " }; |
789 | string[] sVersionStruct = new string[10] { "SWMajor: ", "SWMinor: ", "ProtoMajor: ", "LabelTextCRC: ", "SWPatch: ", "HardwareError 1: ", "HardwareError 2: ", "HWMajor: ", "BL_Firmware: ", "Flags: " }; |
695 | string sVersion = ""; |
790 | string sVersion = ""; |
696 | //sbyte[] signed = Array.ConvertAll(data, b => unchecked((sbyte)b)); |
791 | //sbyte[] signed = Array.ConvertAll(data, b => unchecked((sbyte)b)); |
697 | Log(LogMsgType.Warning, (adr == 1 ? "FC-" : "NC-") + "Version: "); |
792 | Log(LogMsgType.Warning, (adr == 1 ? "FC-" : "NC-") + "Version: "); |
698 | sVersion = "HW V" + (data[7] / 10).ToString() + "." + (data[7] % 10).ToString(); |
793 | sVersion = "HW V" + (data[7] / 10).ToString() + "." + (data[7] % 10).ToString(); |
699 | Log(LogMsgType.Incoming, sVersion); |
794 | Log(LogMsgType.Incoming, sVersion); |
700 | sVersion = "SW V" + (data[0]).ToString() + "." + (data[1]).ToString() + ((char)(data[4] + 'a')).ToString(); |
795 | sVersion = "SW V" + (data[0]).ToString() + "." + (data[1]).ToString() + ((char)(data[4] + 'a')).ToString(); |
701 | Log(LogMsgType.Incoming, sVersion); |
796 | Log(LogMsgType.Incoming, sVersion); |
702 | Log(LogMsgType.Incoming, "BL-Firmware: V" + (data[8] / 100).ToString() + "." + (data[8] % 100).ToString()); |
797 | Log(LogMsgType.Incoming, "BL-Firmware: V" + (data[8] / 100).ToString() + "." + (data[8] % 100).ToString()); |
703 | } |
798 | } |
704 | if (data[5] > 0) //error0 |
799 | if (data[5] > 0) //error0 |
705 | { |
800 | { |
706 | if (adr == 1) |
801 | if (adr == 1) |
707 | ErrorLog(LogMsgType.Error, "FC - HW-Error " + data[5].ToString() + ": " + ((FC_HWError0)data[5]).ToString()); |
802 | ErrorLog(LogMsgType.Error, "FC - HW-Error " + data[5].ToString() + ": " + ((FC_HWError0)data[5]).ToString()); |
708 | if (adr == 2) |
803 | if (adr == 2) |
709 | ErrorLog(LogMsgType.Error, "NC - HW-Error " + data[5].ToString() + ": " + ((NC_HWError0)data[5]).ToString()); |
804 | ErrorLog(LogMsgType.Error, "NC - HW-Error " + data[5].ToString() + ": " + ((NC_HWError0)data[5]).ToString()); |
710 | } |
805 | } |
711 | if (data[6] > 0) //error1 |
806 | if (data[6] > 0) //error1 |
712 | { |
807 | { |
713 | if (adr == 1) |
808 | if (adr == 1) |
714 | ErrorLog(LogMsgType.Error, "FC - HW-Error " + data[6].ToString() + ": " + ((FC_HWError1)data[6]).ToString()); |
809 | ErrorLog(LogMsgType.Error, "FC - HW-Error " + data[6].ToString() + ": " + ((FC_HWError1)data[6]).ToString()); |
715 | if (adr == 2) |
810 | if (adr == 2) |
716 | ErrorLog(LogMsgType.Error, "NC - Unknown HW-ERROR: " + data[6].ToString()); //@moment NC has only one error field |
811 | ErrorLog(LogMsgType.Error, "NC - Unknown HW-ERROR: " + data[6].ToString()); //@moment NC has only one error field |
717 | } |
812 | } |
718 | if((data[5] + data[6] == 0) && _bErrorLog) |
813 | if((data[5] + data[6] == 0) && _bErrorLog) |
719 | _clearErrorLog(adr==1 ? "FC - HW-Error" : "FC - HW-Error"); |
814 | _clearErrorLog(adr==1 ? "FC - HW-Error" : "FC - HW-Error"); |
720 | 815 | ||
721 | } |
816 | } |
722 | check_HWError = false; |
817 | check_HWError = false; |
723 | } |
818 | } |
724 | /// <summary> |
819 | /// <summary> |
725 | /// BL-Ctrl data 'K' |
820 | /// BL-Ctrl data 'K' |
726 | /// for FC you have to use a customized firmware |
821 | /// for FC you have to use a customized firmware |
727 | /// </summary> |
822 | /// </summary> |
728 | /// <param name="data">the received byte array to process</param> |
823 | /// <param name="data">the received byte array to process</param> |
729 | void _processBLCtrl(byte[] data) |
824 | void _processBLCtrl(byte[] data) |
730 | { |
825 | { |
731 | if (data.Length % 6 == 0) //data.Length up to 96 (16 motors x 6 byte data) --> new datastruct in FC -> not standard! |
826 | if (data.Length % 6 == 0) //data.Length up to 96 (16 motors x 6 byte data) --> new datastruct in FC -> not standard! |
732 | { |
827 | { |
733 | bool bAvailable = false; |
828 | bool bAvailable = false; |
734 | for (int i = 0; i < data.Length && data[i] < 8; i += 6) // data[i] < 8 --> at moment there are 8 display fields for motors |
829 | for (int i = 0; i < data.Length && data[i] < 8; i += 6) // data[i] < 8 --> at moment there are 8 display fields for motors |
735 | { |
830 | { |
736 | 831 | ||
737 | if ((data[i + 4] & 128) == 128) //Status bit at pos 7 = 128 dec -- if true, motor is available |
832 | if ((data[i + 4] & 128) == 128) //Status bit at pos 7 = 128 dec -- if true, motor is available |
738 | bAvailable = true; |
833 | bAvailable = true; |
739 | else |
834 | else |
740 | bAvailable = false; |
835 | bAvailable = false; |
741 | 836 | ||
742 | if (data[i] < 4) |
837 | if (data[i] < 4) |
743 | { |
838 | { |
744 | if (bAvailable) |
839 | if (bAvailable) |
745 | { |
840 | { |
746 | dtMotors1.Rows[data[i]].SetField(1, ((double)data[i + 1] / (double)10).ToString("0.0 A")); |
841 | dtMotors1.Rows[data[i]].SetField(1, ((double)data[i + 1] / (double)10).ToString("0.0 A")); |
747 | dtMotors1.Rows[data[i]].SetField(2, data[i + 2].ToString("0 °C")); |
842 | dtMotors1.Rows[data[i]].SetField(2, data[i + 2].ToString("0 °C")); |
748 | } |
843 | } |
749 | else |
844 | else |
750 | { |
845 | { |
751 | dtMotors1.Rows[data[i]].SetField(1, "NA"); |
846 | dtMotors1.Rows[data[i]].SetField(1, "NA"); |
752 | dtMotors1.Rows[data[i]].SetField(2, "NA"); |
847 | dtMotors1.Rows[data[i]].SetField(2, "NA"); |
753 | } |
848 | } |
754 | } |
849 | } |
755 | if (data[i] > 3 && data[i] < 8) |
850 | if (data[i] > 3 && data[i] < 8) |
756 | { |
851 | { |
757 | if (bAvailable) |
852 | if (bAvailable) |
758 | { |
853 | { |
759 | dtMotors2.Rows[data[i] - 4].SetField(1, ((double)data[i + 1] / (double)10).ToString("0.0 A")); |
854 | dtMotors2.Rows[data[i] - 4].SetField(1, ((double)data[i + 1] / (double)10).ToString("0.0 A")); |
760 | dtMotors2.Rows[data[i] - 4].SetField(2, data[i + 2].ToString("0 °C")); |
855 | dtMotors2.Rows[data[i] - 4].SetField(2, data[i + 2].ToString("0 °C")); |
761 | } |
856 | } |
762 | else |
857 | else |
763 | { |
858 | { |
764 | dtMotors2.Rows[data[i] - 4].SetField(1, "NA"); |
859 | dtMotors2.Rows[data[i] - 4].SetField(1, "NA"); |
765 | dtMotors2.Rows[data[i] - 4].SetField(2, "NA"); |
860 | dtMotors2.Rows[data[i] - 4].SetField(2, "NA"); |
766 | } |
861 | } |
767 | } |
862 | } |
768 | } |
863 | } |
769 | } |
864 | } |
770 | 865 | ||
771 | } |
866 | } |
772 | /// <summary> |
867 | /// <summary> |
773 | /// Navi-Ctrl data 'O' |
868 | /// Navi-Ctrl data 'O' |
774 | /// GPS-Position, capacatiy, flying time... |
869 | /// GPS-Position, capacatiy, flying time... |
775 | /// </summary> |
870 | /// </summary> |
776 | /// <param name="data">the received byte array to process</param> |
871 | /// <param name="data">the received byte array to process</param> |
777 | void _processNCData(byte[] data) |
872 | void _processNCData(byte[] data) |
778 | { |
873 | { |
779 | int i_32, i_16, iVal; |
874 | int i_32, i_16, iVal; |
780 | double d; |
875 | double d; |
781 | i_32 = data[4]; |
876 | i_32 = data[4]; |
782 | iVal = i_32 << 24; |
877 | iVal = i_32 << 24; |
783 | i_32 = data[3]; |
878 | i_32 = data[3]; |
784 | iVal += i_32 << 16; |
879 | iVal += i_32 << 16; |
785 | i_32 = data[2]; |
880 | i_32 = data[2]; |
786 | iVal += i_32 << 8; |
881 | iVal += i_32 << 8; |
787 | iVal += data[1]; |
882 | iVal += data[1]; |
788 | d = (double)iVal / Math.Pow(10, 7); |
883 | d = (double)iVal / Math.Pow(10, 7); |
789 | lblNCGPSLong.Invoke((Action)(() => lblNCGPSLong.Text = d.ToString("0.######°"))); //GPS-Position: Longitude in decimal degree |
884 | lblNCGPSLong.Invoke((Action)(() => lblNCGPSLong.Text = d.ToString("0.######°"))); //GPS-Position: Longitude in decimal degree |
790 | //lblNCGPSLong.Invoke((Action)(() => lblNCGPSLong.Text = _convertDegree(d))); //GPS-Position: Longitude in minutes, seconds |
885 | //lblNCGPSLong.Invoke((Action)(() => lblNCGPSLong.Text = _convertDegree(d))); //GPS-Position: Longitude in minutes, seconds |
791 | 886 | ||
792 | i_32 = data[8]; |
887 | i_32 = data[8]; |
793 | iVal = i_32 << 24; |
888 | iVal = i_32 << 24; |
794 | i_32 = data[7]; |
889 | i_32 = data[7]; |
795 | iVal += i_32 << 16; |
890 | iVal += i_32 << 16; |
796 | i_32 = data[6]; |
891 | i_32 = data[6]; |
797 | iVal += i_32 << 8; |
892 | iVal += i_32 << 8; |
798 | iVal += data[5]; |
893 | iVal += data[5]; |
799 | d = (double)iVal / Math.Pow(10, 7); |
894 | d = (double)iVal / Math.Pow(10, 7); |
800 | lblNCGPSLat.Invoke((Action)(() => lblNCGPSLat.Text = d.ToString("0.######°"))); //GPS-Position: Latitude in decimal degree |
895 | lblNCGPSLat.Invoke((Action)(() => lblNCGPSLat.Text = d.ToString("0.######°"))); //GPS-Position: Latitude in decimal degree |
801 | //lblNCGPSLat.Invoke((Action)(() => lblNCGPSLat.Text = _convertDegree(d))); //GPS-Position: Latitude in minutes, seconds |
896 | //lblNCGPSLat.Invoke((Action)(() => lblNCGPSLat.Text = _convertDegree(d))); //GPS-Position: Latitude in minutes, seconds |
802 | 897 | ||
803 | i_16 = data[28]; |
898 | i_16 = data[28]; |
804 | i_16 = (Int16)(i_16 << 8); |
899 | i_16 = (Int16)(i_16 << 8); |
805 | iVal = data[27] + i_16; |
900 | iVal = data[27] + i_16; |
806 | lblNCDistWP.Invoke((Action)(() => lblNCDistWP.Text = ((double)iVal/ (double)10).ToString("0.0 m"))); //Distance to next WP |
901 | lblNCDistWP.Invoke((Action)(() => lblNCDistWP.Text = ((double)iVal/ (double)10).ToString("0.0 m"))); //Distance to next WP |
807 | 902 | ||
808 | i_16 = data[45]; |
903 | i_16 = data[45]; |
809 | i_16 = (Int16)(i_16 << 8); |
904 | i_16 = (Int16)(i_16 << 8); |
810 | iVal = data[44] + i_16; |
905 | iVal = data[44] + i_16; |
811 | lblNCDistHP1.Invoke((Action)(() => lblNCDistHP1.Text = ((double)iVal/ (double)10).ToString("0.0 m"))); //Distance to next WP |
906 | lblNCDistHP1.Invoke((Action)(() => lblNCDistHP1.Text = ((double)iVal/ (double)10).ToString("0.0 m"))); //Distance to next WP |
812 | 907 | ||
813 | lblNCWPIndex.Invoke((Action)(() => lblNCWPIndex.Text = data[48].ToString())); //Waypoint index |
908 | lblNCWPIndex.Invoke((Action)(() => lblNCWPIndex.Text = data[48].ToString())); //Waypoint index |
814 | lblNCWPCount.Invoke((Action)(() => lblNCWPCount.Text = data[49].ToString())); //Waypoints count |
909 | lblNCWPCount.Invoke((Action)(() => lblNCWPCount.Text = data[49].ToString())); //Waypoints count |
815 | 910 | ||
816 | i_16 = data[81]; |
911 | i_16 = data[81]; |
817 | i_16 = (Int16)(i_16 << 8); |
912 | i_16 = (Int16)(i_16 << 8); |
818 | iVal = data[80] + i_16; |
913 | iVal = data[80] + i_16; |
819 | lblNCCap.Invoke((Action)(() => lblNCCap.Text = iVal.ToString() + " mAh")); //Capacity used |
914 | lblNCCap.Invoke((Action)(() => lblNCCap.Text = iVal.ToString() + " mAh")); //Capacity used |
820 | 915 | ||
821 | i_16 = data[56]; |
916 | i_16 = data[56]; |
822 | i_16 = (Int16)(i_16 << 8); |
917 | i_16 = (Int16)(i_16 << 8); |
823 | iVal = data[55] + i_16; |
918 | iVal = data[55] + i_16; |
824 | TimeSpan t = TimeSpan.FromSeconds(iVal); |
919 | TimeSpan t = TimeSpan.FromSeconds(iVal); |
825 | string Text = t.Hours.ToString("D2") + ":" + t.Minutes.ToString("D2") + ":" + t.Seconds.ToString("D2"); |
920 | string Text = t.Hours.ToString("D2") + ":" + t.Minutes.ToString("D2") + ":" + t.Seconds.ToString("D2"); |
826 | lblNCFlTime.Invoke((Action)(() => lblNCFlTime.Text = Text.ToString())); //Flying time |
921 | lblNCFlTime.Invoke((Action)(() => lblNCFlTime.Text = Text.ToString())); //Flying time |
827 | 922 | ||
828 | lblNCRC.Invoke((Action)(() => lblNCRC.Text = data[66].ToString())); //RC quality |
923 | lblNCRC.Invoke((Action)(() => lblNCRC.Text = data[66].ToString())); //RC quality |
829 | lblNCErrNmbr.Invoke((Action)(() => lblNCErrNmbr.Text = data[69].ToString())); //NC Errornumber |
924 | lblNCErrNmbr.Invoke((Action)(() => lblNCErrNmbr.Text = data[69].ToString())); //NC Errornumber |
830 | //if (data[69] > 0) |
925 | //if (data[69] > 0) |
831 | // _readNCError(); |
926 | // _readNCError(); |
832 | //break; |
927 | //break; |
833 | if (data[69] > 0 & data[69] < 44) |
928 | if (data[69] > 0 & data[69] < 44) |
834 | ErrorLog(LogMsgType.Error, "NC Error [" + data[69].ToString() + "]: " + NC_Error[data[69]]); |
929 | ErrorLog(LogMsgType.Error, "NC Error [" + data[69].ToString() + "]: " + NC_Error[data[69]]); |
835 | else |
930 | else |
836 | if(_bErrorLog) _clearErrorLog("NC Error"); |
931 | if(_bErrorLog) _clearErrorLog("NC Error"); |
837 | 932 | ||
838 | } |
933 | } |
839 | /// <summary> |
934 | /// <summary> |
840 | /// Navi-Ctrl WP data struct 'X' |
935 | /// Navi-Ctrl WP data struct 'X' |
841 | /// called by index |
936 | /// called by index |
842 | /// </summary> |
937 | /// </summary> |
843 | /// <param name="data">the received byte array to process</param> |
938 | /// <param name="data">the received byte array to process</param> |
844 | void _processWPData(byte[] data) |
939 | void _processWPData(byte[] data) |
845 | { |
940 | { |
846 | if (data.Length >= 28) |
941 | if (data.Length >= 28) |
847 | { |
942 | { |
848 | int count = data[0]; |
943 | int count = data[0]; |
849 | int index = data[1]; |
944 | int index = data[1]; |
850 | cbWPIndex.Invoke((Action)(() => cbWPIndex.Items.Clear())); |
945 | cbWPIndex.Invoke((Action)(() => cbWPIndex.Items.Clear())); |
851 | for (int i = 0; i < count; i++) |
946 | for (int i = 0; i < count; i++) |
852 | cbWPIndex.Invoke((Action)(() => cbWPIndex.Items.Add(i + 1))); |
947 | cbWPIndex.Invoke((Action)(() => cbWPIndex.Items.Add(i + 1))); |
853 | cbWPIndex.Invoke((Action)(() => cbWPIndex.SelectedItem = index)); |
948 | cbWPIndex.Invoke((Action)(() => cbWPIndex.SelectedItem = index)); |
854 | DataRow dr = dtWaypoints.NewRow(); |
949 | DataRow dr = dtWaypoints.NewRow(); |
855 | dr = Waypoints.toDataRow(data, dr); |
950 | dr = Waypoints.toDataRow(data, dr); |
856 | dtWaypoints.Rows.Add(dr); |
951 | dtWaypoints.Rows.Add(dr); |
857 | dgvWP.Invoke((Action)(() => dgvWP.Update())); |
952 | dgvWP.Invoke((Action)(() => dgvWP.Update())); |
858 | } |
953 | } |
859 | else |
954 | else |
860 | Debug.Print(new string(ASCIIEncoding.ASCII.GetChars(data, 0, data.Length))); |
955 | Debug.Print(new string(ASCIIEncoding.ASCII.GetChars(data, 0, data.Length))); |
861 | } |
956 | } |
862 | /// <summary> |
957 | /// <summary> |
863 | /// OSD Menue 'L' |
958 | /// OSD Menue 'L' |
864 | /// single page called by pagenumber |
959 | /// single page called by pagenumber |
865 | /// no autoupdate |
960 | /// no autoupdate |
866 | /// </summary> |
961 | /// </summary> |
867 | /// <param name="data">the received byte array to process</param> |
962 | /// <param name="data">the received byte array to process</param> |
868 | void _processOSDSingle(byte[] data) |
963 | void _processOSDSingle(byte[] data) |
869 | { |
964 | { |
870 | if (data.Length == 84) |
965 | if (data.Length == 84) |
871 | { |
966 | { |
872 | string sMessage = ""; |
967 | string sMessage = ""; |
873 | iOSDPage = data[0]; |
968 | iOSDPage = data[0]; |
874 | iOSDMax = data[1]; |
969 | iOSDMax = data[1]; |
875 | if (cbOSD.Items.Count != iOSDMax) _initOSDCB(); |
970 | if (cbOSD.Items.Count != iOSDMax) _initOSDCB(); |
876 | sMessage = new string(ASCIIEncoding.ASCII.GetChars(data, 2, data.Length - 4)); |
971 | sMessage = new string(ASCIIEncoding.ASCII.GetChars(data, 2, data.Length - 4)); |
877 | OSD(LogMsgType.Incoming, sMessage.Substring(0, 20)); |
972 | OSD(LogMsgType.Incoming, sMessage.Substring(0, 20)); |
878 | OSD(LogMsgType.Incoming, sMessage.Substring(20, 20)); |
973 | OSD(LogMsgType.Incoming, sMessage.Substring(20, 20)); |
879 | OSD(LogMsgType.Incoming, sMessage.Substring(40, 20)); |
974 | OSD(LogMsgType.Incoming, sMessage.Substring(40, 20)); |
880 | OSD(LogMsgType.Incoming, sMessage.Substring(60, 20)); |
975 | OSD(LogMsgType.Incoming, sMessage.Substring(60, 20)); |
881 | lblOSDPageNr.Invoke((Action)(() => lblOSDPageNr.Text = iOSDPage.ToString("[0]"))); |
976 | lblOSDPageNr.Invoke((Action)(() => lblOSDPageNr.Text = iOSDPage.ToString("[0]"))); |
882 | 977 | ||
883 | } |
978 | } |
884 | else |
979 | else |
885 | OSD(LogMsgType.Incoming, "Wrong length: " + data.Length + " (should be 84)"); |
980 | OSD(LogMsgType.Incoming, "Wrong length: " + data.Length + " (should be 84)"); |
886 | 981 | ||
887 | } |
982 | } |
888 | /// <summary> |
983 | /// <summary> |
889 | /// OSD Menue 'H' |
984 | /// OSD Menue 'H' |
890 | /// called by keys (0x01,0x02,0x03,0x04) |
985 | /// called by keys (0x01,0x02,0x03,0x04) |
891 | /// autoupdate |
986 | /// autoupdate |
892 | /// </summary> |
987 | /// </summary> |
893 | /// <param name="data">the received byte array to process</param> |
988 | /// <param name="data">the received byte array to process</param> |
894 | void _processOSDAuto(byte[] data) |
989 | void _processOSDAuto(byte[] data) |
895 | { |
990 | { |
896 | if (data.Length == 81) |
991 | if (data.Length == 81) |
897 | { |
992 | { |
898 | string sMessage = ""; |
993 | string sMessage = ""; |
899 | sMessage = new string(ASCIIEncoding.ASCII.GetChars(data, 0, data.Length - 1)); |
994 | sMessage = new string(ASCIIEncoding.ASCII.GetChars(data, 0, data.Length - 1)); |
900 | OSD(LogMsgType.Incoming, sMessage.Substring(0, 20)); |
995 | OSD(LogMsgType.Incoming, sMessage.Substring(0, 20)); |
901 | OSD(LogMsgType.Incoming, sMessage.Substring(20, 20)); |
996 | OSD(LogMsgType.Incoming, sMessage.Substring(20, 20)); |
902 | OSD(LogMsgType.Incoming, sMessage.Substring(40, 20)); |
997 | OSD(LogMsgType.Incoming, sMessage.Substring(40, 20)); |
903 | OSD(LogMsgType.Incoming, sMessage.Substring(60, 20)); |
998 | OSD(LogMsgType.Incoming, sMessage.Substring(60, 20)); |
904 | 999 | ||
905 | } |
1000 | } |
906 | else |
1001 | else |
907 | OSD(LogMsgType.Incoming, "Wrong length: " + data.Length + " (should be 81)"); |
1002 | OSD(LogMsgType.Incoming, "Wrong length: " + data.Length + " (should be 81)"); |
908 | } |
1003 | } |
909 | #endregion processing received data |
1004 | #endregion processing received data |
910 | 1005 | ||
911 | /// <summary> send message to controller to request data |
1006 | /// <summary> send message to controller to request data |
912 | /// for detailed info see http://wiki.mikrokopter.de/en/SerialProtocol/ |
1007 | /// for detailed info see http://wiki.mikrokopter.de/en/SerialProtocol/ |
913 | /// </summary> |
1008 | /// </summary> |
914 | /// <param name="CMDID"> the command ID </param> |
1009 | /// <param name="CMDID"> the command ID </param> |
915 | /// <param name="address"> the address of the controller: 0-any, 1-FC, 2-NC </param> |
1010 | /// <param name="address"> the address of the controller: 0-any, 1-FC, 2-NC </param> |
916 | private void _sendControllerMessage(char CMDID, byte address) |
1011 | private void _sendControllerMessage(char CMDID, byte address) |
917 | { |
1012 | { |
918 | if (simpleSerialPort.Port.IsOpen) |
1013 | if (simpleSerialPort.Port.IsOpen) |
919 | { |
1014 | { |
920 | Stream serialStream = simpleSerialPort.Port.BaseStream; |
1015 | Stream serialStream = simpleSerialPort.Port.BaseStream; |
921 | byte[] bytes = FlightControllerMessage.CreateMessage(CMDID, address); |
1016 | byte[] bytes = FlightControllerMessage.CreateMessage(CMDID, address); |
922 | serialStream.Write(bytes, 0, bytes.Length); |
1017 | serialStream.Write(bytes, 0, bytes.Length); |
923 | 1018 | ||
924 | } |
1019 | } |
925 | else |
1020 | else |
926 | Log(LogMsgType.Error, "NOT CONNECTED!"); |
1021 | Log(LogMsgType.Error, "NOT CONNECTED!"); |
927 | } |
1022 | } |
928 | /// <summary> send message to controller to request data |
1023 | /// <summary> send message to controller to request data |
929 | /// for detailed info see http://wiki.mikrokopter.de/en/SerialProtocol/ |
1024 | /// for detailed info see http://wiki.mikrokopter.de/en/SerialProtocol/ |
930 | /// </summary> |
1025 | /// </summary> |
931 | /// <param name="CMDID"> the command ID </param> |
1026 | /// <param name="CMDID"> the command ID </param> |
932 | /// <param name="address"> the address of the controller: 0-any, 1-FC, 2-NC </param> |
1027 | /// <param name="address"> the address of the controller: 0-any, 1-FC, 2-NC </param> |
933 | /// <param name="data"> additional data for the request</param> |
1028 | /// <param name="data"> additional data for the request</param> |
934 | private void _sendControllerMessage(char CMDID, byte address, byte[]data) |
1029 | private void _sendControllerMessage(char CMDID, byte address, byte[]data) |
935 | { |
1030 | { |
936 | if (simpleSerialPort.Port.IsOpen) |
1031 | if (simpleSerialPort.Port.IsOpen) |
937 | { |
1032 | { |
938 | Stream serialStream = simpleSerialPort.Port.BaseStream; |
1033 | Stream serialStream = simpleSerialPort.Port.BaseStream; |
939 | byte[] bytes = FlightControllerMessage.CreateMessage(CMDID, address,data); |
1034 | byte[] bytes = FlightControllerMessage.CreateMessage(CMDID, address,data); |
940 | serialStream.Write(bytes, 0, bytes.Length); |
1035 | serialStream.Write(bytes, 0, bytes.Length); |
941 | 1036 | ||
942 | } |
1037 | } |
943 | else |
1038 | else |
944 | Log(LogMsgType.Error, "NOT CONNECTED!"); |
1039 | Log(LogMsgType.Error, "NOT CONNECTED!"); |
945 | } |
1040 | } |
946 | 1041 | ||
947 | /// <summary> |
1042 | /// <summary> |
948 | /// read the analog-label names for the actual controller |
1043 | /// read the analog-label names for the actual controller |
949 | /// and load it into listbox |
1044 | /// and load it into listbox |
950 | /// </summary> |
1045 | /// </summary> |
951 | void _loadLabelNames() |
1046 | void _loadLabelNames() |
952 | { |
1047 | { |
953 | if (_iCtrlAct > 0 && _iCtrlAct < 3) |
1048 | if (_iCtrlAct > 0 && _iCtrlAct < 3) |
954 | { |
1049 | { |
955 | switch (_iCtrlAct) |
1050 | switch (_iCtrlAct) |
956 | { |
1051 | { |
957 | case 1: |
1052 | case 1: |
958 | sAnalogLabel = Properties.Resources.FCLabelTexts.Split(new[] { Environment.NewLine }, StringSplitOptions.None); |
1053 | sAnalogLabel = Properties.Resources.FCLabelTexts.Split(new[] { Environment.NewLine }, StringSplitOptions.None); |
959 | break; |
1054 | break; |
960 | case 2: |
1055 | case 2: |
961 | sAnalogLabel = Properties.Resources.NCLabelTexts.Split(new[] { Environment.NewLine }, StringSplitOptions.None); |
1056 | sAnalogLabel = Properties.Resources.NCLabelTexts.Split(new[] { Environment.NewLine }, StringSplitOptions.None); |
962 | break; |
1057 | break; |
963 | } |
1058 | } |
964 | for (int i = 0; i < 32; i++) |
1059 | for (int i = 0; i < 32; i++) |
965 | { |
1060 | { |
966 | if (dtAnalog.Rows.Count < 32) |
1061 | if (dtAnalog.Rows.Count < 32) |
967 | dtAnalog.Rows.Add(sAnalogLabel[i], ""); |
1062 | dtAnalog.Rows.Add(sAnalogLabel[i], ""); |
968 | else |
1063 | else |
969 | dtAnalog.Rows[i].SetField(0, sAnalogLabel[i]); |
1064 | dtAnalog.Rows[i].SetField(0, sAnalogLabel[i]); |
970 | } |
1065 | } |
971 | dataGridView1.Invoke((Action)(()=>dataGridView1.Refresh())); |
1066 | dataGridView1.Invoke((Action)(()=>dataGridView1.Refresh())); |
972 | } |
1067 | } |
973 | } |
1068 | } |
974 | /// <summary> |
1069 | /// <summary> |
975 | /// no longer used... |
1070 | /// no longer used... |
976 | /// read the analog-label textfile for the actual controller |
1071 | /// read the analog-label textfile for the actual controller |
977 | /// </summary> |
1072 | /// </summary> |
978 | private void _loadLabelFile() |
1073 | private void _loadLabelFile() |
979 | { |
1074 | { |
980 | switch (_iCtrlAct) |
1075 | switch (_iCtrlAct) |
981 | { |
1076 | { |
982 | case 1: |
1077 | case 1: |
983 | fileName = "FCLabelTexts.txt"; |
1078 | fileName = "FCLabelTexts.txt"; |
984 | break; |
1079 | break; |
985 | case 2: |
1080 | case 2: |
986 | fileName = "NCLabelTexts.txt"; |
1081 | fileName = "NCLabelTexts.txt"; |
987 | break; |
1082 | break; |
988 | //default: |
1083 | //default: |
989 | // fileName = "NCLabelTexts.txt"; |
1084 | // fileName = "NCLabelTexts.txt"; |
990 | // break; |
1085 | // break; |
991 | } |
1086 | } |
992 | 1087 | ||
993 | if (File.Exists(filePath + "\\" + fileName)) |
1088 | if (File.Exists(filePath + "\\" + fileName)) |
994 | { |
1089 | { |
995 | sAnalogLabel.Initialize(); |
1090 | sAnalogLabel.Initialize(); |
996 | sAnalogLabel = File.ReadAllLines(filePath + "\\" + fileName); |
1091 | sAnalogLabel = File.ReadAllLines(filePath + "\\" + fileName); |
997 | lbLabels.Invoke((Action)(() => lbLabels.Items.Clear())); |
1092 | lbLabels.Invoke((Action)(() => lbLabels.Items.Clear())); |
998 | lbLabels.Invoke((Action)(() => lbLabels.Update())); |
1093 | lbLabels.Invoke((Action)(() => lbLabels.Update())); |
999 | lbLabels.Invoke((Action)(() => lbLabels.Items.AddRange(sAnalogLabel))); |
1094 | lbLabels.Invoke((Action)(() => lbLabels.Items.AddRange(sAnalogLabel))); |
1000 | Console.WriteLine("Names loaded from file"); |
1095 | Console.WriteLine("Names loaded from file"); |
1001 | lblFileName.Invoke((Action)(() => lblFileName.Text = fileName)); |
1096 | lblFileName.Invoke((Action)(() => lblFileName.Text = fileName)); |
1002 | } |
1097 | } |
1003 | else |
1098 | else |
1004 | { |
1099 | { |
1005 | _readCont(false); |
1100 | _readCont(false); |
1006 | Log(LogMsgType.Error, "Label-file not found!"); |
1101 | Log(LogMsgType.Error, "Label-file not found!"); |
1007 | Log(LogMsgType.Error, "Please go to settings-tab and load the label texts from the copter control (FC & NC)"); |
1102 | Log(LogMsgType.Error, "Please go to settings-tab and load the label texts from the copter control (FC & NC)"); |
1008 | Log(LogMsgType.Error, "When done, you have to save the label texts with the 'save' button!"); |
1103 | Log(LogMsgType.Error, "When done, you have to save the label texts with the 'save' button!"); |
1009 | } |
1104 | } |
1010 | } |
1105 | } |
1011 | /// <summary> |
1106 | /// <summary> |
1012 | /// no longer used... |
1107 | /// no longer used... |
1013 | /// assign the analog-label names from the textfile to the datatable |
1108 | /// assign the analog-label names from the textfile to the datatable |
1014 | /// |
1109 | /// |
1015 | /// </summary> |
1110 | /// </summary> |
1016 | private void _assignLabelNames() |
1111 | private void _assignLabelNames() |
1017 | { |
1112 | { |
1018 | if (lbLabels.Items.Count == 32) |
1113 | if (lbLabels.Items.Count == 32) |
1019 | { |
1114 | { |
1020 | lbLabels.Items.CopyTo(sAnalogLabel, 0); |
1115 | lbLabels.Items.CopyTo(sAnalogLabel, 0); |
1021 | for (int i = 0; i < 32; i++) |
1116 | for (int i = 0; i < 32; i++) |
1022 | { |
1117 | { |
1023 | if (dtAnalog.Rows.Count < 32) |
1118 | if (dtAnalog.Rows.Count < 32) |
1024 | dtAnalog.Rows.Add(sAnalogLabel[i], ""); |
1119 | dtAnalog.Rows.Add(sAnalogLabel[i], ""); |
1025 | else |
1120 | else |
1026 | dtAnalog.Rows[i].SetField(0, sAnalogLabel[i]); |
1121 | dtAnalog.Rows[i].SetField(0, sAnalogLabel[i]); |
1027 | 1122 | ||
1028 | } |
1123 | } |
1029 | } |
1124 | } |
1030 | } |
1125 | } |
1031 | /// <summary> |
1126 | /// <summary> |
1032 | /// get the version struct of actual controller |
1127 | /// get the version struct of actual controller |
1033 | /// </summary> |
1128 | /// </summary> |
1034 | /// <summary> |
1129 | /// <summary> |
1035 | /// get the labeltexts for the analog values |
1130 | /// get the labeltexts for the analog values |
1036 | /// </summary> |
1131 | /// </summary> |
1037 | private void _getAnalogLabels() |
1132 | private void _getAnalogLabels() |
1038 | { |
1133 | { |
1039 | if (simpleSerialPort.Port.IsOpen) |
1134 | if (simpleSerialPort.Port.IsOpen) |
1040 | { |
1135 | { |
1041 | iLableIndex = 0; |
1136 | iLableIndex = 0; |
1042 | for (int i = 0; i < 32; i++) |
1137 | for (int i = 0; i < 32; i++) |
1043 | { |
1138 | { |
1044 | Stream serialStream = simpleSerialPort.Port.BaseStream; |
1139 | Stream serialStream = simpleSerialPort.Port.BaseStream; |
1045 | byte[] bytes = FlightControllerMessage.CreateMessage('a', 0, new byte[1] { (byte)i }); |
1140 | byte[] bytes = FlightControllerMessage.CreateMessage('a', 0, new byte[1] { (byte)i }); |
1046 | serialStream.Write(bytes, 0, bytes.Length); |
1141 | serialStream.Write(bytes, 0, bytes.Length); |
1047 | Thread.Sleep(10); |
1142 | Thread.Sleep(10); |
1048 | } |
1143 | } |
1049 | } |
1144 | } |
1050 | else |
1145 | else |
1051 | Log(LogMsgType.Error, "NOT CONNECTED!"); |
1146 | Log(LogMsgType.Error, "NOT CONNECTED!"); |
1052 | } |
1147 | } |
1053 | /// <summary> |
1148 | /// <summary> |
1054 | /// get the labeltext for a single label |
1149 | /// get the labeltext for a single label |
1055 | /// </summary> |
1150 | /// </summary> |
1056 | /// <param name="iIndex">index of the label</param> |
1151 | /// <param name="iIndex">index of the label</param> |
1057 | private void _getAnalogLabels(int iIndex) |
1152 | private void _getAnalogLabels(int iIndex) |
1058 | { |
1153 | { |
1059 | if (simpleSerialPort.Port.IsOpen) |
1154 | if (simpleSerialPort.Port.IsOpen) |
1060 | { |
1155 | { |
1061 | if (iIndex < 32) |
1156 | if (iIndex < 32) |
1062 | { |
1157 | { |
1063 | iLableIndex = iIndex; |
1158 | iLableIndex = iIndex; |
1064 | _sendControllerMessage('a', 0, new byte[1] { (byte)iLableIndex }); |
1159 | _sendControllerMessage('a', 0, new byte[1] { (byte)iLableIndex }); |
1065 | } |
1160 | } |
1066 | } |
1161 | } |
1067 | else |
1162 | else |
1068 | Log(LogMsgType.Error, "NOT CONNECTED!"); |
1163 | Log(LogMsgType.Error, "NOT CONNECTED!"); |
1069 | } |
1164 | } |
1070 | private void _getVersion() |
1165 | private void _getVersion() |
1071 | { |
1166 | { |
1072 | _sendControllerMessage('v', 0); |
1167 | _sendControllerMessage('v', 0); |
1073 | } |
1168 | } |
1074 | /// <summary> |
1169 | /// <summary> |
1075 | /// get FC version struct via NC |
1170 | /// get FC version struct via NC |
1076 | /// by sending '1' as data (not documented in wiki...) |
1171 | /// by sending '1' as data (not documented in wiki...) |
1077 | /// returns HW error 255 (comment in uart1.c : tells the KopterTool that it is the FC-version) |
1172 | /// returns HW error 255 (comment in uart1.c : tells the KopterTool that it is the FC-version) |
1078 | /// </summary> |
1173 | /// </summary> |
1079 | /// <param name="ctrl">controller number 1=FC</param> |
1174 | /// <param name="ctrl">controller number 1=FC</param> |
1080 | private void _getVersion(byte ctrl) |
1175 | private void _getVersion(byte ctrl) |
1081 | { |
1176 | { |
1082 | _sendControllerMessage('v', 0, new byte[1] {ctrl}); |
1177 | _sendControllerMessage('v', 0, new byte[1] {ctrl}); |
1083 | } |
1178 | } |
1084 | /// <summary> |
1179 | /// <summary> |
1085 | /// Switch back to NC by sending the 'Magic Packet' 0x1B,0x1B,0x55,0xAA,0x00 |
1180 | /// Switch back to NC by sending the 'Magic Packet' 0x1B,0x1B,0x55,0xAA,0x00 |
1086 | /// </summary> |
1181 | /// </summary> |
1087 | private void _switchToNC() |
1182 | private void _switchToNC() |
1088 | { |
1183 | { |
1089 | if (simpleSerialPort.Port.IsOpen) |
1184 | if (simpleSerialPort.Port.IsOpen) |
1090 | { |
1185 | { |
1091 | Stream serialStream = simpleSerialPort.Port.BaseStream; |
1186 | Stream serialStream = simpleSerialPort.Port.BaseStream; |
1092 | byte[] bytes = new byte[5] { 0x1B,0x1B,0x55,0xAA,0x00 }; |
1187 | byte[] bytes = new byte[5] { 0x1B,0x1B,0x55,0xAA,0x00 }; |
1093 | serialStream.Write(bytes, 0, bytes.Length); |
1188 | serialStream.Write(bytes, 0, bytes.Length); |
1094 | 1189 | ||
1095 | Thread.Sleep(100); |
1190 | Thread.Sleep(100); |
1096 | _getVersion(); |
1191 | _getVersion(); |
1097 | Thread.Sleep(100); |
1192 | Thread.Sleep(100); |
1098 | _OSDMenue(0); |
1193 | _OSDMenue(0); |
1099 | } |
1194 | } |
1100 | else |
1195 | else |
1101 | Log(LogMsgType.Error, "NOT CONNECTED!"); |
1196 | Log(LogMsgType.Error, "NOT CONNECTED!"); |
1102 | } |
1197 | } |
1103 | /// <summary> |
1198 | /// <summary> |
1104 | /// switch to FC |
1199 | /// switch to FC |
1105 | /// </summary> |
1200 | /// </summary> |
1106 | private void _switchToFC() |
1201 | private void _switchToFC() |
1107 | { |
1202 | { |
1108 | _sendControllerMessage('u', 2, new byte[1] { (byte)0 }); |
1203 | _sendControllerMessage('u', 2, new byte[1] { (byte)0 }); |
1109 | Thread.Sleep(100); |
1204 | Thread.Sleep(100); |
1110 | _getVersion(); |
1205 | _getVersion(); |
1111 | Thread.Sleep(100); |
1206 | Thread.Sleep(100); |
1112 | _OSDMenue(0); |
1207 | _OSDMenue(0); |
1113 | } |
1208 | } |
1114 | /// <summary> |
1209 | /// <summary> |
1115 | /// send RESET signal to FC |
1210 | /// send RESET signal to FC |
1116 | /// </summary> |
1211 | /// </summary> |
1117 | private void _resetCtrl() |
1212 | private void _resetCtrl() |
1118 | { |
1213 | { |
1119 | _sendControllerMessage('R', 1); |
1214 | _sendControllerMessage('R', 1); |
1120 | } |
1215 | } |
1121 | /// <summary> |
1216 | /// <summary> |
1122 | /// poll the debug data (4sec subscription) |
1217 | /// poll the debug data (4sec subscription) |
1123 | /// </summary> |
1218 | /// </summary> |
1124 | /// <param name="auto"> onetimequery(false) or autoupdate(true) with set timing interval </param> |
1219 | /// <param name="auto"> onetimequery(false) or autoupdate(true) with set timing interval </param> |
1125 | private void _readDebugData(bool auto) |
1220 | private void _readDebugData(bool auto) |
1126 | { |
1221 | { |
1127 | byte interval = auto ? debugInterval : (byte)0; |
1222 | byte interval = auto ? debugInterval : (byte)0; |
1128 | _sendControllerMessage('d', 0, new byte[1] { debugInterval }); |
1223 | _sendControllerMessage('d', 0, new byte[1] { debugInterval }); |
1129 | } |
1224 | } |
1130 | /// <summary> |
1225 | /// <summary> |
1131 | /// poll the BL-CTRL status via NC (4sec subscription) |
1226 | /// poll the BL-CTRL status via NC (4sec subscription) |
1132 | /// </summary> |
1227 | /// </summary> |
1133 | /// <param name="auto"> onetimequery(false) or autoupdate(true) with set timing interval </param> |
1228 | /// <param name="auto"> onetimequery(false) or autoupdate(true) with set timing interval </param> |
1134 | private void _readBLCtrl(bool auto) |
1229 | private void _readBLCtrl(bool auto) |
1135 | { |
1230 | { |
1136 | byte interval = auto ? blctrlInterval : (byte)0; |
1231 | byte interval = auto ? blctrlInterval : (byte)0; |
1137 | _sendControllerMessage('k', 0, new byte[1] { interval }); |
1232 | _sendControllerMessage('k', 0, new byte[1] { interval }); |
1138 | } |
1233 | } |
1139 | /// <summary> |
1234 | /// <summary> |
1140 | /// poll the NC data struct (4sec subscription) |
1235 | /// poll the NC data struct (4sec subscription) |
1141 | /// </summary> |
1236 | /// </summary> |
1142 | /// <param name="auto"> onetimequery(false) or autoupdate(true) with set timing interval </param> |
1237 | /// <param name="auto"> onetimequery(false) or autoupdate(true) with set timing interval </param> |
1143 | private void _readNavData(bool auto) |
1238 | private void _readNavData(bool auto) |
1144 | { |
1239 | { |
1145 | byte interval = auto ? navctrlInterval : (byte)0; |
1240 | byte interval = auto ? navctrlInterval : (byte)0; |
1146 | _sendControllerMessage('o', 2, new byte[1] { interval }); |
1241 | _sendControllerMessage('o', 2, new byte[1] { interval }); |
1147 | } |
1242 | } |
1148 | /// <summary> |
1243 | /// <summary> |
1149 | /// get the errortext for pending NC error |
1244 | /// get the errortext for pending NC error |
1150 | /// </summary> |
1245 | /// </summary> |
1151 | private void _readNCError() |
1246 | private void _readNCError() |
1152 | { |
1247 | { |
1153 | _sendControllerMessage('e', 2); |
1248 | _sendControllerMessage('e', 2); |
1154 | } |
1249 | } |
1155 | /// <summary> |
1250 | /// <summary> |
1156 | /// start/stop continous polling of controller values |
1251 | /// start/stop continous polling of controller values |
1157 | /// </summary> |
1252 | /// </summary> |
1158 | /// <param name="b">start/stop switch</param> |
1253 | /// <param name="b">start/stop switch</param> |
1159 | void _readCont(bool b) |
1254 | void _readCont(bool b) |
1160 | { |
1255 | { |
1161 | bReadContinously = b; |
1256 | bReadContinously = b; |
- | 1257 | ||
- | 1258 | if (Thread.CurrentThread.CurrentUICulture.Name == "") |
|
1162 | btnReadDebugCont.Invoke((Action)(() => btnReadDebugCont.Text = bReadContinously ? "stop automatic" + Environment.NewLine + "data refresh" : "start automatic" + Environment.NewLine + "data refresh")); |
1259 | btnReadDebugCont.Invoke((Action)(() => btnReadDebugCont.Text = bReadContinously ? "stop automatic" + Environment.NewLine + "data refresh" : "start automatic" + Environment.NewLine + "data refresh")); |
- | 1260 | else |
|
- | 1261 | btnReadDebugCont.Invoke((Action)(() => btnReadDebugCont.Text = bReadContinously ? "Aktualisierung" + Environment.NewLine + "beenden" : "Aktualisierung" + Environment.NewLine + "starten")); |
|
1163 | btnReadDebugCont.Invoke((Action)(() => btnReadDebugCont.BackColor = bReadContinously ? Color.FromArgb(192, 255, 192) : Color.FromArgb(224, 224, 224))); |
1262 | btnReadDebugCont.Invoke((Action)(() => btnReadDebugCont.BackColor = bReadContinously ? Color.FromArgb(192, 255, 192) : Color.FromArgb(224, 224, 224))); |
1164 | if (bReadContinously) |
1263 | if (bReadContinously) |
1165 | { |
1264 | { |
1166 | if (_debugDataAutorefresh) { _readDebugData(true); Thread.Sleep(10); } |
1265 | if (_debugDataAutorefresh) { _readDebugData(true); Thread.Sleep(10); } |
1167 | if (_blctrlDataAutorefresh) { _readBLCtrl(true); Thread.Sleep(10); } |
1266 | if (_blctrlDataAutorefresh) { _readBLCtrl(true); Thread.Sleep(10); } |
1168 | if (_navCtrlDataAutorefresh && _iCtrlAct == 2) { _readNavData(true); Thread.Sleep(10); } |
1267 | if (_navCtrlDataAutorefresh && _iCtrlAct == 2) { _readNavData(true); Thread.Sleep(10); } |
1169 | if (_OSDAutorefresh) { _OSDMenueAutoRefresh(); Thread.Sleep(10);} |
1268 | if (_OSDAutorefresh) { _OSDMenueAutoRefresh(); Thread.Sleep(10);} |
1170 | lblLifeCounter.Invoke((Action)(() => lblLifeCounter.BackColor = Color.FromArgb(0, 224, 0))); |
1269 | lblLifeCounter.Invoke((Action)(() => lblLifeCounter.BackColor = Color.FromArgb(0, 224, 0))); |
1171 | } |
1270 | } |
1172 | else |
1271 | else |
1173 | lblLifeCounter.Invoke((Action)(() => lblLifeCounter.BackColor = Color.FromArgb(224, 224, 224))); |
1272 | lblLifeCounter.Invoke((Action)(() => lblLifeCounter.BackColor = Color.FromArgb(224, 224, 224))); |
1174 | _iLifeCounter = 0; |
1273 | _iLifeCounter = 0; |
1175 | } |
1274 | } |
1176 | /// <summary> |
1275 | /// <summary> |
1177 | /// set values to "NA" when not available with FC |
1276 | /// set values to "NA" when not available with FC |
1178 | /// </summary> |
1277 | /// </summary> |
1179 | void _setFieldsNA() |
1278 | void _setFieldsNA() |
1180 | { |
1279 | { |
1181 | Thread.Sleep(100); |
1280 | Thread.Sleep(100); |
1182 | _initDTMotors(); |
1281 | _initDTMotors(); |
1183 | lblNCFlTime.Invoke((Action)(() => lblNCFlTime.Text = "NA")); //FlightTime |
1282 | lblNCFlTime.Invoke((Action)(() => lblNCFlTime.Text = "NA")); //FlightTime |
1184 | lblNCErrNmbr.Invoke((Action)(() => lblNCErrNmbr.Text = "NA")); //NC ErrorNr |
1283 | lblNCErrNmbr.Invoke((Action)(() => lblNCErrNmbr.Text = "NA")); //NC ErrorNr |
1185 | lblNCMF.Invoke((Action)(() => lblNCMF.Text = "NA")); //earth magnet field |
1284 | lblNCMF.Invoke((Action)(() => lblNCMF.Text = "NA")); //earth magnet field |
1186 | lblNCGSpeed.Invoke((Action)(() => lblNCGSpeed.Text = "NA")); //GroundSpeed |
1285 | lblNCGSpeed.Invoke((Action)(() => lblNCGSpeed.Text = "NA")); //GroundSpeed |
1187 | lblNCDistHP.Invoke((Action)(() => lblNCDistHP.Text = "NA")); //Distance to HP |
1286 | lblNCDistHP.Invoke((Action)(() => lblNCDistHP.Text = "NA")); //Distance to HP |
1188 | lblNCSat.Invoke((Action)(() => lblNCSat.Text = "NA")); //Sats used |
1287 | lblNCSat.Invoke((Action)(() => lblNCSat.Text = "NA")); //Sats used |
1189 | lblNCGPSLong.Invoke((Action)(() => lblNCGPSLong.Text = "NA")); //GPS position - longitude |
1288 | lblNCGPSLong.Invoke((Action)(() => lblNCGPSLong.Text = "NA")); //GPS position - longitude |
1190 | lblNCGPSLat.Invoke((Action)(() => lblNCGPSLat.Text = "NA")); //GPS position - latitude |
1289 | lblNCGPSLat.Invoke((Action)(() => lblNCGPSLat.Text = "NA")); //GPS position - latitude |
1191 | lblNCDistWP.Invoke((Action)(() => lblNCDistWP.Text = "NA")); //next WP distance |
1290 | lblNCDistWP.Invoke((Action)(() => lblNCDistWP.Text = "NA")); //next WP distance |
1192 | lblNCWPIndex.Invoke((Action)(() => lblNCWPIndex.Text = "NA")); //index of actual WP |
1291 | lblNCWPIndex.Invoke((Action)(() => lblNCWPIndex.Text = "NA")); //index of actual WP |
1193 | lblNCWPCount.Invoke((Action)(() => lblNCWPCount.Text = "NA")); //count of items in WP list |
1292 | lblNCWPCount.Invoke((Action)(() => lblNCWPCount.Text = "NA")); //count of items in WP list |
1194 | } |
1293 | } |
1195 | /// <summary> |
1294 | /// <summary> |
1196 | /// one time query of the OSD Menue with pagenumber |
1295 | /// one time query of the OSD Menue with pagenumber |
1197 | /// </summary> |
1296 | /// </summary> |
1198 | /// <param name="iMenue">Menue page</param> |
1297 | /// <param name="iMenue">Menue page</param> |
1199 | void _OSDMenue(int iMenue) |
1298 | void _OSDMenue(int iMenue) |
1200 | { |
1299 | { |
1201 | if (simpleSerialPort.Port.IsOpen) |
1300 | if (simpleSerialPort.Port.IsOpen) |
1202 | { |
1301 | { |
1203 | if (iMenue > iOSDMax) |
1302 | if (iMenue > iOSDMax) |
1204 | iMenue = 0; |
1303 | iMenue = 0; |
1205 | Stream serialStream = simpleSerialPort.Port.BaseStream; |
1304 | Stream serialStream = simpleSerialPort.Port.BaseStream; |
1206 | byte[] bytes = FlightControllerMessage.CreateMessage('l', 0, new byte[1] { (byte)iMenue }); |
1305 | byte[] bytes = FlightControllerMessage.CreateMessage('l', 0, new byte[1] { (byte)iMenue }); |
1207 | serialStream.Write(bytes, 0, bytes.Length); |
1306 | serialStream.Write(bytes, 0, bytes.Length); |
1208 | } |
1307 | } |
1209 | else |
1308 | else |
1210 | Log(LogMsgType.Error, "NOT CONNECTED!"); |
1309 | Log(LogMsgType.Error, "NOT CONNECTED!"); |
1211 | 1310 | ||
1212 | } |
1311 | } |
1213 | /// <summary> |
1312 | /// <summary> |
1214 | /// call the OSDMenue and start autorefresh |
1313 | /// call the OSDMenue and start autorefresh |
1215 | /// usually by sending a menuekey |
1314 | /// usually by sending a menuekey |
1216 | /// a bit tricky - but by sending inverted value of 32 (32 = 0010 0000) you can start the OSD menue with autoupdate (abo) without switching the page with the keyvalues (0x1, 0x2) |
1315 | /// a bit tricky - but by sending inverted value of 32 (32 = 0010 0000) you can start the OSD menue with autoupdate (abo) without switching the page with the keyvalues (0x1, 0x2) |
1217 | /// therefore the value has to be negative (inverted) in order to distinguish from old (2 line) menuestyle |
1316 | /// therefore the value has to be negative (inverted) in order to distinguish from old (2 line) menuestyle |
1218 | /// and must not have any bits of the menue keys 0x1 0x2 0x4 0x8 (0x10?) --> 0x20 = -33 |
1317 | /// and must not have any bits of the menue keys 0x1 0x2 0x4 0x8 (0x10?) --> 0x20 = -33 |
1219 | /// </summary> |
1318 | /// </summary> |
1220 | void _OSDMenueAutoRefresh() |
1319 | void _OSDMenueAutoRefresh() |
1221 | { |
1320 | { |
1222 | _sendControllerMessage('h', 0, new byte[2] { unchecked((byte)(-33)),OSDInterval }); |
1321 | _sendControllerMessage('h', 0, new byte[2] { unchecked((byte)(-33)),OSDInterval }); |
1223 | } |
1322 | } |
1224 | void _OSDMenueAutoRefresh(byte key) |
1323 | void _OSDMenueAutoRefresh(byte key) |
1225 | { |
1324 | { |
1226 | _sendControllerMessage('h', 0, new byte[2] { unchecked((byte)~key), OSDInterval }); |
1325 | _sendControllerMessage('h', 0, new byte[2] { unchecked((byte)~key), OSDInterval }); |
1227 | } |
1326 | } |
1228 | /// <summary> |
1327 | /// <summary> |
1229 | /// initialize the OSD menue combobox |
1328 | /// initialize the OSD menue combobox |
1230 | /// combox is filled by numbers from 0 to max pagenumber |
1329 | /// combox is filled by numbers from 0 to max pagenumber |
1231 | /// </summary> |
1330 | /// </summary> |
1232 | void _initOSDCB() |
1331 | void _initOSDCB() |
1233 | { |
1332 | { |
1234 | _bCBInit = true; |
1333 | _bCBInit = true; |
1235 | if(iOSDMax == 0) |
1334 | if(iOSDMax == 0) |
1236 | { |
1335 | { |
1237 | _OSDMenue(0); |
1336 | _OSDMenue(0); |
1238 | Thread.Sleep(10); |
1337 | Thread.Sleep(10); |
1239 | } |
1338 | } |
1240 | cbOSD.Invoke((Action)(()=>cbOSD.Items.Clear())); |
1339 | cbOSD.Invoke((Action)(()=>cbOSD.Items.Clear())); |
1241 | for(int i = 0; i <= iOSDMax;i++) |
1340 | for(int i = 0; i <= iOSDMax;i++) |
1242 | { |
1341 | { |
1243 | cbOSD.Invoke((Action)(() => cbOSD.Items.Add(i))); |
1342 | cbOSD.Invoke((Action)(() => cbOSD.Items.Add(i))); |
1244 | } |
1343 | } |
1245 | cbOSD.Invoke((Action)(() => cbOSD.SelectedItem = iOSDPage)); |
1344 | cbOSD.Invoke((Action)(() => cbOSD.SelectedItem = iOSDPage)); |
1246 | _bCBInit = false; |
1345 | _bCBInit = false; |
1247 | } |
1346 | } |
1248 | /// <summary> |
1347 | /// <summary> |
1249 | /// initialize the datatables |
1348 | /// initialize the datatables |
1250 | /// with columnnames etc |
1349 | /// with columnnames etc |
1251 | /// </summary> |
1350 | /// </summary> |
1252 | void _dataTablesInit() |
1351 | void _dataTablesInit() |
1253 | { |
1352 | { |
1254 | dtAnalog.Columns.Add("ID"); |
1353 | dtAnalog.Columns.Add("ID"); |
1255 | dtAnalog.Columns.Add("Value"); |
1354 | dtAnalog.Columns.Add("Value"); |
1256 | dataGridView1.DataSource = dtAnalog; |
1355 | dataGridView1.DataSource = dtAnalog; |
1257 | 1356 | ||
1258 | dtMotors1.Columns.Add("#"); |
1357 | dtMotors1.Columns.Add("#"); |
- | 1358 | if (Thread.CurrentThread.CurrentUICulture.Name == "") |
|
1259 | dtMotors1.Columns.Add("Current"); |
1359 | dtMotors1.Columns.Add("Current"); |
- | 1360 | else |
|
- | 1361 | dtMotors1.Columns.Add("Strom"); |
|
1260 | dtMotors1.Columns.Add("Temp"); |
1362 | dtMotors1.Columns.Add("Temp"); |
1261 | dtMotors2.Columns.Add("#"); |
1363 | dtMotors2.Columns.Add("#"); |
- | 1364 | if (Thread.CurrentThread.CurrentUICulture.Name == "") |
|
1262 | dtMotors2.Columns.Add("Current"); |
1365 | dtMotors2.Columns.Add("Current"); |
- | 1366 | else |
|
- | 1367 | dtMotors2.Columns.Add("Strom"); |
|
1263 | dtMotors2.Columns.Add("Temp"); |
1368 | dtMotors2.Columns.Add("Temp"); |
1264 | dgvMotors1.DataSource = dtMotors1; |
1369 | dgvMotors1.DataSource = dtMotors1; |
1265 | dgvMotors2.DataSource = dtMotors2; |
1370 | dgvMotors2.DataSource = dtMotors2; |
1266 | _initDTMotors(); |
1371 | _initDTMotors(); |
1267 | dgvMotors1.Columns[0].Width = 24; |
1372 | dgvMotors1.Columns[0].Width = 24; |
1268 | dgvMotors1.Columns[1].Width = 74; |
1373 | dgvMotors1.Columns[1].Width = 74; |
1269 | dgvMotors1.Columns[2].Width = 74; |
1374 | dgvMotors1.Columns[2].Width = 74; |
1270 | dgvMotors2.Columns[0].Width = 24; |
1375 | dgvMotors2.Columns[0].Width = 24; |
1271 | dgvMotors2.Columns[1].Width = 74; |
1376 | dgvMotors2.Columns[1].Width = 74; |
1272 | dgvMotors2.Columns[2].Width = 74; |
1377 | dgvMotors2.Columns[2].Width = 74; |
1273 | 1378 | ||
1274 | dtWaypoints.Columns.Add("Index"); |
1379 | dtWaypoints.Columns.Add("Index"); |
1275 | dtWaypoints.Columns.Add("Type"); |
1380 | dtWaypoints.Columns.Add("Type"); |
1276 | dtWaypoints.Columns.Add("Name"); |
1381 | dtWaypoints.Columns.Add("Name"); |
1277 | dtWaypoints.Columns.Add("Latitude"); |
1382 | dtWaypoints.Columns.Add("Latitude"); |
1278 | dtWaypoints.Columns.Add("Longitude"); |
1383 | dtWaypoints.Columns.Add("Longitude"); |
1279 | dtWaypoints.Columns.Add("Altitude"); |
1384 | dtWaypoints.Columns.Add("Altitude"); |
1280 | dtWaypoints.Columns.Add("Heading"); |
1385 | dtWaypoints.Columns.Add("Heading"); |
1281 | dtWaypoints.Columns.Add("Speed"); |
1386 | dtWaypoints.Columns.Add("Speed"); |
1282 | dtWaypoints.Columns.Add("Altitude rate"); |
1387 | dtWaypoints.Columns.Add("Altitude rate"); |
1283 | dtWaypoints.Columns.Add("Tol.radius"); |
1388 | dtWaypoints.Columns.Add("Tol.radius"); |
1284 | dtWaypoints.Columns.Add("Hold time"); |
1389 | dtWaypoints.Columns.Add("Hold time"); |
1285 | dtWaypoints.Columns.Add("AutoTrigger"); |
1390 | dtWaypoints.Columns.Add("AutoTrigger"); |
1286 | dtWaypoints.Columns.Add("Cam angle"); |
1391 | dtWaypoints.Columns.Add("Cam angle"); |
1287 | dtWaypoints.Columns.Add("Event"); |
1392 | dtWaypoints.Columns.Add("Event"); |
1288 | dtWaypoints.Columns.Add("Eventchan. Val."); |
1393 | dtWaypoints.Columns.Add("Eventchan. Val."); |
1289 | dtWaypoints.Columns.Add("Status"); |
1394 | dtWaypoints.Columns.Add("Status"); |
1290 | dgvWP.DataSource = dtWaypoints; |
1395 | dgvWP.DataSource = dtWaypoints; |
1291 | } |
1396 | } |
1292 | /// <summary> |
1397 | /// <summary> |
1293 | /// read settings from ini-file |
1398 | /// read settings from ini-file |
1294 | /// </summary> |
1399 | /// </summary> |
1295 | void _readIni() |
1400 | void _readIni() |
1296 | { |
1401 | { |
1297 | if (!File.Exists(filePath + "\\MKLiveViewSettings.ini")) |
1402 | if (!File.Exists(filePath + "\\MKLiveViewSettings.ini")) |
1298 | _writeIni(); |
1403 | _writeIni(); |
1299 | IniFile ini = new IniFile("MKLiveViewSettings.ini"); |
1404 | IniFile ini = new IniFile("MKLiveViewSettings.ini"); |
1300 | ini.path = filePath + "\\MKLiveViewSettings.ini"; |
1405 | ini.path = filePath + "\\MKLiveViewSettings.ini"; |
1301 | 1406 | ||
1302 | string sVal = ini.IniReadValue("default", "AutorefreshDebugData"); |
1407 | string sVal = ini.IniReadValue("default", "AutorefreshDebugData"); |
1303 | _debugDataAutorefresh = Convert.ToBoolean(sVal); |
1408 | _debugDataAutorefresh = Convert.ToBoolean(sVal); |
1304 | sVal = ini.IniReadValue("default", "AutorefreshNavCtrlData"); |
1409 | sVal = ini.IniReadValue("default", "AutorefreshNavCtrlData"); |
1305 | _navCtrlDataAutorefresh = Convert.ToBoolean(sVal); |
1410 | _navCtrlDataAutorefresh = Convert.ToBoolean(sVal); |
1306 | sVal = ini.IniReadValue("default", "AutorefreshBLCtrlData"); |
1411 | sVal = ini.IniReadValue("default", "AutorefreshBLCtrlData"); |
1307 | _blctrlDataAutorefresh = Convert.ToBoolean(sVal); |
1412 | _blctrlDataAutorefresh = Convert.ToBoolean(sVal); |
1308 | sVal = ini.IniReadValue("default", "AutorefreshOSDData"); |
1413 | sVal = ini.IniReadValue("default", "AutorefreshOSDData"); |
1309 | _OSDAutorefresh = Convert.ToBoolean(sVal); |
1414 | _OSDAutorefresh = Convert.ToBoolean(sVal); |
1310 | 1415 | ||
1311 | sVal = ini.IniReadValue("default", "IntervalDebugData"); |
1416 | sVal = ini.IniReadValue("default", "IntervalDebugData"); |
1312 | debugInterval = (byte)Convert.ToInt16(sVal); |
1417 | debugInterval = (byte)Convert.ToInt16(sVal); |
1313 | sVal = ini.IniReadValue("default", "IntervalNavCtrlData"); |
1418 | sVal = ini.IniReadValue("default", "IntervalNavCtrlData"); |
1314 | navctrlInterval = (byte)Convert.ToInt16(sVal); |
1419 | navctrlInterval = (byte)Convert.ToInt16(sVal); |
1315 | sVal = ini.IniReadValue("default", "IntervalBLCtrlData"); |
1420 | sVal = ini.IniReadValue("default", "IntervalBLCtrlData"); |
1316 | blctrlInterval = (byte)Convert.ToInt16(sVal); |
1421 | blctrlInterval = (byte)Convert.ToInt16(sVal); |
1317 | sVal = ini.IniReadValue("default", "IntervalOSDData"); |
1422 | sVal = ini.IniReadValue("default", "IntervalOSDData"); |
1318 | OSDInterval = (byte)Convert.ToInt16(sVal); |
1423 | OSDInterval = (byte)Convert.ToInt16(sVal); |
1319 | for(int i = 0; i < 12; i++) |
1424 | for(int i = 0; i < 12; i++) |
1320 | { |
1425 | { |
1321 | sVal = ini.IniReadValue("serial", "ch" + i.ToString() + "Val"); |
1426 | sVal = ini.IniReadValue("serial", "ch" + i.ToString() + "Val"); |
1322 | if(sVal != "") |
1427 | if(sVal != "") |
1323 | serChan[i] = Convert.ToInt16(sVal); |
1428 | serChan[i] = Convert.ToInt16(sVal); |
1324 | sVal = ini.IniReadValue("serial", "ch" + i.ToString() + "Title"); |
1429 | sVal = ini.IniReadValue("serial", "ch" + i.ToString() + "Title"); |
1325 | if(sVal != "") |
1430 | if(sVal != "") |
1326 | serChanTitle[i] = sVal; |
1431 | serChanTitle[i] = sVal; |
1327 | } |
1432 | } |
1328 | } |
1433 | } |
1329 | /// <summary> |
1434 | /// <summary> |
1330 | /// save settings to ini-file |
1435 | /// save settings to ini-file |
1331 | /// </summary> |
1436 | /// </summary> |
1332 | void _writeIni() |
1437 | void _writeIni() |
1333 | { |
1438 | { |
1334 | 1439 | ||
1335 | IniFile ini = new IniFile("MKLiveViewSettings.ini"); |
1440 | IniFile ini = new IniFile("MKLiveViewSettings.ini"); |
1336 | ini.path = filePath + "\\MKLiveViewSettings.ini"; |
1441 | ini.path = filePath + "\\MKLiveViewSettings.ini"; |
1337 | 1442 | ||
1338 | ini.IniWriteValue("default", "AutorefreshDebugData", _debugDataAutorefresh ? "true":"false"); |
1443 | ini.IniWriteValue("default", "AutorefreshDebugData", _debugDataAutorefresh ? "true":"false"); |
1339 | ini.IniWriteValue("default", "AutorefreshNavCtrlData", _navCtrlDataAutorefresh ? "true":"false"); |
1444 | ini.IniWriteValue("default", "AutorefreshNavCtrlData", _navCtrlDataAutorefresh ? "true":"false"); |
1340 | ini.IniWriteValue("default", "AutorefreshBLCtrlData", _blctrlDataAutorefresh ? "true":"false"); |
1445 | ini.IniWriteValue("default", "AutorefreshBLCtrlData", _blctrlDataAutorefresh ? "true":"false"); |
1341 | ini.IniWriteValue("default", "AutorefreshOSDData", _OSDAutorefresh ? "true":"false"); |
1446 | ini.IniWriteValue("default", "AutorefreshOSDData", _OSDAutorefresh ? "true":"false"); |
1342 | 1447 | ||
1343 | ini.IniWriteValue("default", "IntervalDebugData", debugInterval.ToString()); |
1448 | ini.IniWriteValue("default", "IntervalDebugData", debugInterval.ToString()); |
1344 | ini.IniWriteValue("default", "IntervalNavCtrlData", navctrlInterval.ToString()); |
1449 | ini.IniWriteValue("default", "IntervalNavCtrlData", navctrlInterval.ToString()); |
1345 | ini.IniWriteValue("default", "IntervalBLCtrlData", blctrlInterval.ToString()); |
1450 | ini.IniWriteValue("default", "IntervalBLCtrlData", blctrlInterval.ToString()); |
1346 | ini.IniWriteValue("default", "IntervalOSDData", OSDInterval.ToString()); |
1451 | ini.IniWriteValue("default", "IntervalOSDData", OSDInterval.ToString()); |
1347 | 1452 | ||
1348 | for (int i = 0; i < 12; i++) |
1453 | for (int i = 0; i < 12; i++) |
1349 | { |
1454 | { |
1350 | ini.IniWriteValue("serial", "ch" + i.ToString() + "Val", serChan[i].ToString()); |
1455 | ini.IniWriteValue("serial", "ch" + i.ToString() + "Val", serChan[i].ToString()); |
1351 | ini.IniWriteValue("serial", "ch" + i.ToString() + "Title", serChanTitle[i]); |
1456 | ini.IniWriteValue("serial", "ch" + i.ToString() + "Title", serChanTitle[i]); |
1352 | } |
1457 | } |
1353 | 1458 | ||
1354 | } |
1459 | } |
1355 | 1460 | ||
1356 | /// <summary> |
1461 | /// <summary> |
1357 | /// initialize the 2 datatables for motor values |
1462 | /// initialize the 2 datatables for motor values |
1358 | /// dtMotors1 - motor 1 - 4 |
1463 | /// dtMotors1 - motor 1 - 4 |
1359 | /// dtMotors2 - motor 5 - 8 |
1464 | /// dtMotors2 - motor 5 - 8 |
1360 | /// DataGridView dgvMotors1/2 are bound to dtMotors1/2 |
1465 | /// DataGridView dgvMotors1/2 are bound to dtMotors1/2 |
1361 | /// </summary> |
1466 | /// </summary> |
1362 | void _initDTMotors() |
1467 | void _initDTMotors() |
1363 | { |
1468 | { |
1364 | for(int i = 0; i < 4; i++) |
1469 | for(int i = 0; i < 4; i++) |
1365 | { |
1470 | { |
1366 | if (dtMotors1.Rows.Count < 4) |
1471 | if (dtMotors1.Rows.Count < 4) |
1367 | dtMotors1.Rows.Add((i + 1).ToString(), "NA", "NA"); |
1472 | dtMotors1.Rows.Add((i + 1).ToString(), "NA", "NA"); |
1368 | else |
1473 | else |
1369 | { |
1474 | { |
1370 | dtMotors1.Rows[i].SetField(1, "NA"); |
1475 | dtMotors1.Rows[i].SetField(1, "NA"); |
1371 | dtMotors1.Rows[i].SetField(2, "NA"); |
1476 | dtMotors1.Rows[i].SetField(2, "NA"); |
1372 | } |
1477 | } |
1373 | if (dtMotors2.Rows.Count < 4) |
1478 | if (dtMotors2.Rows.Count < 4) |
1374 | dtMotors2.Rows.Add((i + 5).ToString(), "NA", "NA"); |
1479 | dtMotors2.Rows.Add((i + 5).ToString(), "NA", "NA"); |
1375 | else |
1480 | else |
1376 | { |
1481 | { |
1377 | dtMotors2.Rows[i].SetField(1, "NA"); |
1482 | dtMotors2.Rows[i].SetField(1, "NA"); |
1378 | dtMotors2.Rows[i].SetField(2, "NA"); |
1483 | dtMotors2.Rows[i].SetField(2, "NA"); |
1379 | } |
1484 | } |
1380 | } |
1485 | } |
1381 | dgvMotors1.Invoke((Action)(() => dgvMotors1.Refresh())); |
1486 | dgvMotors1.Invoke((Action)(() => dgvMotors1.Refresh())); |
1382 | dgvMotors2.Invoke((Action)(() => dgvMotors2.Refresh())); |
1487 | dgvMotors2.Invoke((Action)(() => dgvMotors2.Refresh())); |
1383 | } |
1488 | } |
1384 | 1489 | ||
1385 | /// <summary> |
1490 | /// <summary> |
1386 | /// Convert decimal degrees to degrees, minutes, seconds, milliseconds |
1491 | /// Convert decimal degrees to degrees, minutes, seconds, milliseconds |
1387 | /// </summary> |
1492 | /// </summary> |
1388 | /// <param name="coord">the degree value as double</param> |
1493 | /// <param name="coord">the degree value as double</param> |
1389 | /// <returns>0° 0' 0,0"</returns> |
1494 | /// <returns>0° 0' 0,0"</returns> |
1390 | string _convertDegree(double coord) |
1495 | string _convertDegree(double coord) |
1391 | { |
1496 | { |
1392 | //double minutes = (degree - Math.Floor(degree)) * 60.0; |
1497 | //double minutes = (degree - Math.Floor(degree)) * 60.0; |
1393 | //double seconds = (minutes - Math.Floor(minutes)) * 60.0; |
1498 | //double seconds = (minutes - Math.Floor(minutes)) * 60.0; |
1394 | //double tenths = (seconds - Math.Floor(seconds)) * 10.0; |
1499 | //double tenths = (seconds - Math.Floor(seconds)) * 10.0; |
1395 | //// get rid of fractional part |
1500 | //// get rid of fractional part |
1396 | //minutes = Math.Floor(minutes); |
1501 | //minutes = Math.Floor(minutes); |
1397 | //seconds = Math.Floor(seconds); |
1502 | //seconds = Math.Floor(seconds); |
1398 | //tenths = Math.Floor(tenths); |
1503 | //tenths = Math.Floor(tenths); |
1399 | 1504 | ||
1400 | 1505 | ||
1401 | //int sec = (int)Math.Round(coord * 3600); |
1506 | //int sec = (int)Math.Round(coord * 3600); |
1402 | //int deg = sec / 3600; |
1507 | //int deg = sec / 3600; |
1403 | //sec = Math.Abs(sec % 3600); |
1508 | //sec = Math.Abs(sec % 3600); |
1404 | //int min = sec / 60; |
1509 | //int min = sec / 60; |
1405 | //sec %= 60; |
1510 | //sec %= 60; |
1406 | 1511 | ||
1407 | var ts = TimeSpan.FromHours(Math.Abs(coord)); |
1512 | var ts = TimeSpan.FromHours(Math.Abs(coord)); |
1408 | double deg = Math.Sign(coord) * Math.Floor(ts.TotalHours); |
1513 | double deg = Math.Sign(coord) * Math.Floor(ts.TotalHours); |
1409 | int min = ts.Minutes; |
1514 | int min = ts.Minutes; |
1410 | int sec = ts.Seconds; |
1515 | int sec = ts.Seconds; |
1411 | int milli = ts.Milliseconds; |
1516 | int milli = ts.Milliseconds; |
1412 | 1517 | ||
1413 | return deg.ToString("0° ") + min.ToString("0") + "' " + sec.ToString("0") + "," + milli.ToString() + "\""; |
1518 | return deg.ToString("0° ") + min.ToString("0") + "' " + sec.ToString("0") + "," + milli.ToString() + "\""; |
1414 | } |
1519 | } |
1415 | /// <summary> |
1520 | /// <summary> |
1416 | /// Clear the line in the errorlog window |
1521 | /// Clear the line in the errorlog window |
1417 | /// containing the error string when error has ceased |
1522 | /// containing the error string when error has ceased |
1418 | /// </summary> |
1523 | /// </summary> |
1419 | /// <param name="s">substring of errrormessage</param> |
1524 | /// <param name="s">substring of errrormessage</param> |
1420 | void _clearErrorLog(string s) |
1525 | void _clearErrorLog(string s) |
1421 | { |
1526 | { |
1422 | rtfError.Invoke((Action)(() => |
1527 | rtfError.Invoke((Action)(() => |
1423 | { |
1528 | { |
1424 | if (rtfError.Text.Contains(s)) |
1529 | if (rtfError.Text.Contains(s)) |
1425 | { |
1530 | { |
1426 | int iLength = 0; |
1531 | int iLength = 0; |
1427 | int iStart = rtfError.Text.IndexOf(s); |
1532 | int iStart = rtfError.Text.IndexOf(s); |
1428 | int iEnd = rtfError.Text.IndexOf('\n', iStart); |
1533 | int iEnd = rtfError.Text.IndexOf('\n', iStart); |
1429 | if (iEnd > 0) |
1534 | if (iEnd > 0) |
1430 | { |
1535 | { |
1431 | iLength = iEnd + 1; |
1536 | iLength = iEnd + 1; |
1432 | int iHttp = rtfError.Text.IndexOf("http", iEnd); |
1537 | int iHttp = rtfError.Text.IndexOf("http", iEnd); |
1433 | if (iHttp == iLength) |
1538 | if (iHttp == iLength) |
1434 | { |
1539 | { |
1435 | int iEnd2 = rtfError.Text.IndexOf('\n', iLength); |
1540 | int iEnd2 = rtfError.Text.IndexOf('\n', iLength); |
1436 | if (iEnd2 > iLength) |
1541 | if (iEnd2 > iLength) |
1437 | { |
1542 | { |
1438 | iLength = iEnd2 + 1; |
1543 | iLength = iEnd2 + 1; |
1439 | rtfError.Select(iStart, iLength); |
1544 | rtfError.Select(iStart, iLength); |
1440 | rtfError.SelectedText = string.Empty; |
1545 | rtfError.SelectedText = string.Empty; |
1441 | if(rtfError.Text.Length < 2) _bErrorLog = false; |
1546 | if(rtfError.Text.Length < 2) _bErrorLog = false; |
1442 | } |
1547 | } |
1443 | 1548 | ||
1444 | } |
1549 | } |
1445 | else |
1550 | else |
1446 | { |
1551 | { |
1447 | rtfError.Select(iStart, iLength); |
1552 | rtfError.Select(iStart, iLength); |
1448 | rtfError.SelectedText = string.Empty; |
1553 | rtfError.SelectedText = string.Empty; |
1449 | if(rtfError.Text.Length < 2) _bErrorLog = false; |
1554 | if(rtfError.Text.Length < 2) _bErrorLog = false; |
1450 | } |
1555 | } |
1451 | } |
1556 | } |
1452 | } |
1557 | } |
1453 | })); |
1558 | })); |
1454 | 1559 | ||
1455 | } |
1560 | } |
1456 | /// <summary> |
1561 | /// <summary> |
1457 | /// request the Waypoint at index |
1562 | /// request the Waypoint at index |
1458 | /// </summary> |
1563 | /// </summary> |
1459 | /// <param name="index"></param> |
1564 | /// <param name="index"></param> |
1460 | void _getpWP(int index) |
1565 | void _getpWP(int index) |
1461 | { |
1566 | { |
1462 | if (simpleSerialPort.Port.IsOpen) |
1567 | if (simpleSerialPort.Port.IsOpen) |
1463 | { |
1568 | { |
1464 | Stream serialStream = simpleSerialPort.Port.BaseStream; |
1569 | Stream serialStream = simpleSerialPort.Port.BaseStream; |
1465 | byte[] bytes = FlightControllerMessage.CreateMessage('x', 2, new byte[1] { (byte)index }); |
1570 | byte[] bytes = FlightControllerMessage.CreateMessage('x', 2, new byte[1] { (byte)index }); |
1466 | serialStream.Write(bytes, 0, bytes.Length); |
1571 | serialStream.Write(bytes, 0, bytes.Length); |
1467 | } |
1572 | } |
1468 | else |
1573 | else |
1469 | Log(LogMsgType.Error, "NOT CONNECTED!"); |
1574 | Log(LogMsgType.Error, "NOT CONNECTED!"); |
1470 | 1575 | ||
1471 | } |
1576 | } |
1472 | /// <summary> |
1577 | /// <summary> |
1473 | /// Sending the serial channel values |
1578 | /// Sending the serial channel values |
1474 | /// </summary> |
1579 | /// </summary> |
1475 | void _sendSerialData() |
1580 | void _sendSerialData() |
1476 | { |
1581 | { |
1477 | byte[] serData = new byte[12]; |
1582 | byte[] serData = new byte[12]; |
1478 | for(int i = 0; i < 12; i++) |
1583 | for(int i = 0; i < 12; i++) |
1479 | { |
1584 | { |
1480 | serData[i] = unchecked((byte)(serChan[i] - 127)); |
1585 | serData[i] = unchecked((byte)(serChan[i] - 127)); |
1481 | } |
1586 | } |
1482 | _sendControllerMessage('y', 1, serData); |
1587 | _sendControllerMessage('y', 1, serData); |
1483 | } |
1588 | } |
1484 | /// <summary> |
1589 | /// <summary> |
1485 | /// init the controls for displaying |
1590 | /// init the controls for displaying |
1486 | /// and setting serial control channels |
1591 | /// and setting serial control channels |
1487 | /// </summary> |
1592 | /// </summary> |
1488 | void _initSerialCtrl() |
1593 | void _initSerialCtrl() |
1489 | { |
1594 | { |
1490 | trckbarSerial1.Value = serChan[0]; |
1595 | trckbarSerial1.Value = serChan[0]; |
1491 | textBoxSerial1.Text = serChanTitle[0]; |
1596 | textBoxSerial1.Text = serChanTitle[0]; |
1492 | lblTbSerial1.Text = serChan[0].ToString(); |
1597 | lblTbSerial1.Text = serChan[0].ToString(); |
1493 | trckbarSerial2.Value = serChan[1]; |
1598 | trckbarSerial2.Value = serChan[1]; |
1494 | textBoxSerial2.Text = serChanTitle[1]; |
1599 | textBoxSerial2.Text = serChanTitle[1]; |
1495 | lblTbSerial2.Text = serChan[1].ToString(); |
1600 | lblTbSerial2.Text = serChan[1].ToString(); |
1496 | trckbarSerial3.Value = serChan[2]; |
1601 | trckbarSerial3.Value = serChan[2]; |
1497 | textBoxSerial3.Text = serChanTitle[2]; |
1602 | textBoxSerial3.Text = serChanTitle[2]; |
1498 | lblTbSerial3.Text = serChan[2].ToString(); |
1603 | lblTbSerial3.Text = serChan[2].ToString(); |
1499 | trckbarSerial4.Value = serChan[3]; |
1604 | trckbarSerial4.Value = serChan[3]; |
1500 | textBoxSerial4.Text = serChanTitle[3]; |
1605 | textBoxSerial4.Text = serChanTitle[3]; |
1501 | lblTbSerial4.Text = serChan[3].ToString(); |
1606 | lblTbSerial4.Text = serChan[3].ToString(); |
1502 | trckbarSerial5.Value = serChan[4]; |
1607 | trckbarSerial5.Value = serChan[4]; |
1503 | textBoxSerial5.Text = serChanTitle[4]; |
1608 | textBoxSerial5.Text = serChanTitle[4]; |
1504 | lblTbSerial5.Text = serChan[4].ToString(); |
1609 | lblTbSerial5.Text = serChan[4].ToString(); |
1505 | trckbarSerial6.Value = serChan[5]; |
1610 | trckbarSerial6.Value = serChan[5]; |
1506 | textBoxSerial6.Text = serChanTitle[5]; |
1611 | textBoxSerial6.Text = serChanTitle[5]; |
1507 | lblTbSerial6.Text = serChan[5].ToString(); |
1612 | lblTbSerial6.Text = serChan[5].ToString(); |
1508 | trckbarSerial7.Value = serChan[6]; |
1613 | trckbarSerial7.Value = serChan[6]; |
1509 | textBoxSerial7.Text = serChanTitle[6]; |
1614 | textBoxSerial7.Text = serChanTitle[6]; |
1510 | lblTbSerial7.Text = serChan[6].ToString(); |
1615 | lblTbSerial7.Text = serChan[6].ToString(); |
1511 | trckbarSerial8.Value = serChan[7]; |
1616 | trckbarSerial8.Value = serChan[7]; |
1512 | textBoxSerial8.Text = serChanTitle[7]; |
1617 | textBoxSerial8.Text = serChanTitle[7]; |
1513 | lblTbSerial8.Text = serChan[7].ToString(); |
1618 | lblTbSerial8.Text = serChan[7].ToString(); |
1514 | } |
1619 | } |
1515 | #endregion functions |
1620 | #endregion functions |
1516 | 1621 | ||
1517 | #region buttons |
1622 | #region buttons |
1518 | private void buttonReset_Click(object sender, EventArgs e) |
1623 | private void buttonReset_Click(object sender, EventArgs e) |
1519 | { |
1624 | { |
1520 | _resetCtrl(); |
1625 | _resetCtrl(); |
1521 | } |
1626 | } |
1522 | private void btnVersion_Click(object sender, EventArgs e) |
1627 | private void btnVersion_Click(object sender, EventArgs e) |
1523 | { |
1628 | { |
1524 | _getVersion(); |
1629 | _getVersion(); |
1525 | } |
1630 | } |
1526 | private void btnAnalogLabels_Click(object sender, EventArgs e) |
1631 | private void btnAnalogLabels_Click(object sender, EventArgs e) |
1527 | { |
1632 | { |
1528 | _getAnalogLabels(0); |
1633 | _getAnalogLabels(0); |
1529 | } |
1634 | } |
1530 | private void btnDbgData_Click(object sender, EventArgs e) |
1635 | private void btnDbgData_Click(object sender, EventArgs e) |
1531 | { |
1636 | { |
1532 | _readDebugData(false); //onetime reading of debug data --> subscription lasts 4sec - this means you will receive data for 4 seconds |
1637 | _readDebugData(false); //onetime reading of debug data --> subscription lasts 4sec - this means you will receive data for 4 seconds |
1533 | } |
1638 | } |
1534 | private void btnSaveLabels_Click(object sender, EventArgs e) |
1639 | private void btnSaveLabels_Click(object sender, EventArgs e) |
1535 | { |
1640 | { |
1536 | switch (_iCtrlAct) |
1641 | switch (_iCtrlAct) |
1537 | { |
1642 | { |
1538 | case 1: |
1643 | case 1: |
1539 | fileName = "FCLabelTexts.txt"; |
1644 | fileName = "FCLabelTexts.txt"; |
1540 | break; |
1645 | break; |
1541 | case 2: |
1646 | case 2: |
1542 | fileName = "NCLabelTexts.txt"; |
1647 | fileName = "NCLabelTexts.txt"; |
1543 | break; |
1648 | break; |
1544 | default: |
1649 | default: |
1545 | fileName = "NCLabelTexts.txt"; |
1650 | fileName = "NCLabelTexts.txt"; |
1546 | break; |
1651 | break; |
1547 | } |
1652 | } |
1548 | if (sAnalogLabel[0] != null) |
1653 | if (sAnalogLabel[0] != null) |
1549 | { |
1654 | { |
1550 | File.WriteAllLines(filePath + "\\" + fileName, sAnalogLabel); |
1655 | File.WriteAllLines(filePath + "\\" + fileName, sAnalogLabel); |
1551 | Console.WriteLine("Names saved to file"); |
1656 | Console.WriteLine("Names saved to file"); |
1552 | _loadLabelFile(); |
1657 | _loadLabelFile(); |
1553 | } |
1658 | } |
1554 | else |
1659 | else |
1555 | Log(LogMsgType.Warning, "there's no data -> read first from fc/nc!"); |
1660 | Log(LogMsgType.Warning, "there's no data -> read first from fc/nc!"); |
1556 | } |
1661 | } |
1557 | private void btnLoadLabels_Click(object sender, EventArgs e) |
1662 | private void btnLoadLabels_Click(object sender, EventArgs e) |
1558 | { |
1663 | { |
1559 | _assignLabelNames(); |
1664 | _assignLabelNames(); |
1560 | } |
1665 | } |
1561 | private void btnReadLabelFile_Click(object sender, EventArgs e) |
1666 | private void btnReadLabelFile_Click(object sender, EventArgs e) |
1562 | { |
1667 | { |
1563 | _loadLabelFile(); |
1668 | _loadLabelFile(); |
1564 | } |
1669 | } |
1565 | private void btnSwitchFC_Click(object sender, EventArgs e) |
1670 | private void btnSwitchFC_Click(object sender, EventArgs e) |
1566 | { |
1671 | { |
1567 | _switchToFC(); |
1672 | _switchToFC(); |
1568 | } |
1673 | } |
1569 | private void btnSwitchNC_Click(object sender, EventArgs e) |
1674 | private void btnSwitchNC_Click(object sender, EventArgs e) |
1570 | { |
1675 | { |
1571 | _switchToNC(); |
1676 | _switchToNC(); |
1572 | } |
1677 | } |
1573 | private void btnReadDbgCont_Click(object sender, EventArgs e) |
1678 | private void btnReadDbgCont_Click(object sender, EventArgs e) |
1574 | { |
1679 | { |
1575 | _readCont(!bReadContinously); |
1680 | _readCont(!bReadContinously); |
1576 | } |
1681 | } |
1577 | private void btnReadBLCtrl_Click(object sender, EventArgs e) |
1682 | private void btnReadBLCtrl_Click(object sender, EventArgs e) |
1578 | { |
1683 | { |
1579 | 1684 | ||
1580 | if (_iCtrlAct == 2) _readBLCtrl(false); |
1685 | if (_iCtrlAct == 2) _readBLCtrl(false); |
1581 | else Log(LogMsgType.Warning, "only available when connected to NC"); |
1686 | else Log(LogMsgType.Warning, "only available when connected to NC"); |
1582 | } |
1687 | } |
1583 | private void btnGetNaviData_Click(object sender, EventArgs e) |
1688 | private void btnGetNaviData_Click(object sender, EventArgs e) |
1584 | { |
1689 | { |
1585 | if (_iCtrlAct == 2) _readNavData(false); |
1690 | if (_iCtrlAct == 2) _readNavData(false); |
1586 | else Log(LogMsgType.Warning, "only available when connected to NC"); |
1691 | else Log(LogMsgType.Warning, "only available when connected to NC"); |
1587 | } |
1692 | } |
1588 | private void btnConn_Click(object sender, EventArgs e) |
1693 | private void btnConn_Click(object sender, EventArgs e) |
1589 | { |
1694 | { |
1590 | simpleSerialPort.Connect(!simpleSerialPort.Port.IsOpen); |
1695 | simpleSerialPort.Connect(!simpleSerialPort.Port.IsOpen); |
1591 | } |
1696 | } |
1592 | private void button3_Click(object sender, EventArgs e) |
1697 | private void button3_Click(object sender, EventArgs e) |
1593 | { |
1698 | { |
1594 | _getVersion(1); |
1699 | _getVersion(1); |
1595 | } |
1700 | } |
1596 | private void button4_Click(object sender, EventArgs e) |
1701 | private void button4_Click(object sender, EventArgs e) |
1597 | { |
1702 | { |
1598 | _getVersion(2); |
1703 | _getVersion(2); |
1599 | } |
1704 | } |
1600 | private void btnOSD_Click(object sender, EventArgs e) |
1705 | private void btnOSD_Click(object sender, EventArgs e) |
1601 | { |
1706 | { |
1602 | if (iOSDPage > iOSDMax) |
1707 | if (iOSDPage > iOSDMax) |
1603 | iOSDPage = 0; |
1708 | iOSDPage = 0; |
1604 | _OSDMenue(iOSDPage); |
1709 | _OSDMenue(iOSDPage); |
1605 | } |
1710 | } |
1606 | private void btnOSDForward_Click(object sender, EventArgs e) |
1711 | private void btnOSDForward_Click(object sender, EventArgs e) |
1607 | { |
1712 | { |
1608 | iOSDPage++; |
1713 | iOSDPage++; |
1609 | if (iOSDPage > iOSDMax) |
1714 | if (iOSDPage > iOSDMax) |
1610 | iOSDPage = 0; |
1715 | iOSDPage = 0; |
1611 | 1716 | ||
1612 | _OSDMenue(iOSDPage); |
1717 | _OSDMenue(iOSDPage); |
1613 | } |
1718 | } |
1614 | private void btnOSDBackward_Click(object sender, EventArgs e) |
1719 | private void btnOSDBackward_Click(object sender, EventArgs e) |
1615 | { |
1720 | { |
1616 | iOSDPage--; |
1721 | iOSDPage--; |
1617 | if (iOSDPage < 0) |
1722 | if (iOSDPage < 0) |
1618 | iOSDPage = iOSDMax; |
1723 | iOSDPage = iOSDMax; |
1619 | 1724 | ||
1620 | _OSDMenue(iOSDPage); |
1725 | _OSDMenue(iOSDPage); |
1621 | } |
1726 | } |
1622 | private void btnOSDAuto_Click(object sender, EventArgs e) |
1727 | private void btnOSDAuto_Click(object sender, EventArgs e) |
1623 | { |
1728 | { |
1624 | _OSDMenueAutoRefresh(); |
1729 | _OSDMenueAutoRefresh(); |
1625 | } |
1730 | } |
1626 | /// call the OSDMenue with Key 0x8 |
1731 | /// call the OSDMenue with Key 0x8 |
1627 | private void btnOSDLeave_Click(object sender, EventArgs e) |
1732 | private void btnOSDLeave_Click(object sender, EventArgs e) |
1628 | { |
1733 | { |
1629 | _OSDMenueAutoRefresh(8); |
1734 | _OSDMenueAutoRefresh(8); |
1630 | } |
1735 | } |
1631 | /// call the OSDMenue with Key 0x4 |
1736 | /// call the OSDMenue with Key 0x4 |
1632 | private void btnOSDEnter_Click(object sender, EventArgs e) |
1737 | private void btnOSDEnter_Click(object sender, EventArgs e) |
1633 | { |
1738 | { |
1634 | _OSDMenueAutoRefresh(4); |
1739 | _OSDMenueAutoRefresh(4); |
1635 | } |
1740 | } |
1636 | private void btnGetWP_Click(object sender, EventArgs e) |
1741 | private void btnGetWP_Click(object sender, EventArgs e) |
1637 | { |
1742 | { |
1638 | if(cbWPIndex.Items.Count >0) |
1743 | if(cbWPIndex.Items.Count >0) |
1639 | _getpWP((int)cbWPIndex.SelectedItem); |
1744 | _getpWP((int)cbWPIndex.SelectedItem); |
1640 | else |
1745 | else |
1641 | _getpWP(1); |
1746 | _getpWP(1); |
1642 | } |
1747 | } |
1643 | #endregion buttons |
1748 | #endregion buttons |
1644 | #region serial control channels - buttons & events |
1749 | #region serial control channels - buttons & events |
1645 | private void tbSerial1_Scroll(object sender, EventArgs e) |
1750 | private void tbSerial1_Scroll(object sender, EventArgs e) |
1646 | { |
1751 | { |
1647 | lblTbSerial1.Text = trckbarSerial1.Value.ToString(); |
1752 | lblTbSerial1.Text = trckbarSerial1.Value.ToString(); |
1648 | serChan[0] = trckbarSerial1.Value; |
1753 | serChan[0] = trckbarSerial1.Value; |
1649 | if (!_init) _sendSerialData(); |
1754 | if (!_init) _sendSerialData(); |
1650 | } |
1755 | } |
1651 | private void textBoxSerial1_TextChanged(object sender, EventArgs e) |
1756 | private void textBoxSerial1_TextChanged(object sender, EventArgs e) |
1652 | { |
1757 | { |
1653 | serChanTitle[0] = textBoxSerial1.Text; |
1758 | serChanTitle[0] = textBoxSerial1.Text; |
1654 | } |
1759 | } |
1655 | private void btnSer1_0_Click(object sender, EventArgs e) |
1760 | private void btnSer1_0_Click(object sender, EventArgs e) |
1656 | { |
1761 | { |
1657 | trckbarSerial1.Value = 0; |
1762 | trckbarSerial1.Value = 0; |
1658 | } |
1763 | } |
1659 | private void btnSer1_127_Click(object sender, EventArgs e) |
1764 | private void btnSer1_127_Click(object sender, EventArgs e) |
1660 | { |
1765 | { |
1661 | trckbarSerial1.Value = 127; |
1766 | trckbarSerial1.Value = 127; |
1662 | } |
1767 | } |
1663 | private void btnSer1_254_Click(object sender, EventArgs e) |
1768 | private void btnSer1_254_Click(object sender, EventArgs e) |
1664 | { |
1769 | { |
1665 | trckbarSerial1.Value = 254; |
1770 | trckbarSerial1.Value = 254; |
1666 | } |
1771 | } |
1667 | private void trckbarSerial1_ValueChanged(object sender, EventArgs e) |
1772 | private void trckbarSerial1_ValueChanged(object sender, EventArgs e) |
1668 | { |
1773 | { |
1669 | lblTbSerial1.Text = trckbarSerial1.Value.ToString(); |
1774 | lblTbSerial1.Text = trckbarSerial1.Value.ToString(); |
1670 | serChan[0] = trckbarSerial1.Value; |
1775 | serChan[0] = trckbarSerial1.Value; |
1671 | if (!_init) _sendSerialData(); |
1776 | if (!_init) _sendSerialData(); |
1672 | } |
1777 | } |
1673 | private void textBoxSerial2_TextChanged(object sender, EventArgs e) |
1778 | private void textBoxSerial2_TextChanged(object sender, EventArgs e) |
1674 | { |
1779 | { |
1675 | serChanTitle[1] = textBoxSerial2.Text; |
1780 | serChanTitle[1] = textBoxSerial2.Text; |
1676 | } |
1781 | } |
1677 | private void trckbarSerial2_ValueChanged(object sender, EventArgs e) |
1782 | private void trckbarSerial2_ValueChanged(object sender, EventArgs e) |
1678 | { |
1783 | { |
1679 | lblTbSerial2.Text = trckbarSerial2.Value.ToString(); |
1784 | lblTbSerial2.Text = trckbarSerial2.Value.ToString(); |
1680 | serChan[1] = trckbarSerial2.Value; |
1785 | serChan[1] = trckbarSerial2.Value; |
1681 | if (!_init) _sendSerialData(); |
1786 | if (!_init) _sendSerialData(); |
1682 | } |
1787 | } |
1683 | private void btnSer2_0_Click(object sender, EventArgs e) |
1788 | private void btnSer2_0_Click(object sender, EventArgs e) |
1684 | { |
1789 | { |
1685 | trckbarSerial2.Value = 0; |
1790 | trckbarSerial2.Value = 0; |
1686 | } |
1791 | } |
1687 | private void btnSer2_127_Click(object sender, EventArgs e) |
1792 | private void btnSer2_127_Click(object sender, EventArgs e) |
1688 | { |
1793 | { |
1689 | trckbarSerial2.Value = 127; |
1794 | trckbarSerial2.Value = 127; |
1690 | } |
1795 | } |
1691 | private void btnSer2_254_Click(object sender, EventArgs e) |
1796 | private void btnSer2_254_Click(object sender, EventArgs e) |
1692 | { |
1797 | { |
1693 | trckbarSerial2.Value = 254; |
1798 | trckbarSerial2.Value = 254; |
1694 | } |
1799 | } |
1695 | private void textBoxSerial3_TextChanged(object sender, EventArgs e) |
1800 | private void textBoxSerial3_TextChanged(object sender, EventArgs e) |
1696 | { |
1801 | { |
1697 | serChanTitle[2] = textBoxSerial3.Text; |
1802 | serChanTitle[2] = textBoxSerial3.Text; |
1698 | } |
1803 | } |
1699 | private void trckbarSerial3_ValueChanged(object sender, EventArgs e) |
1804 | private void trckbarSerial3_ValueChanged(object sender, EventArgs e) |
1700 | { |
1805 | { |
1701 | lblTbSerial3.Text = trckbarSerial3.Value.ToString(); |
1806 | lblTbSerial3.Text = trckbarSerial3.Value.ToString(); |
1702 | serChan[2] = trckbarSerial3.Value; |
1807 | serChan[2] = trckbarSerial3.Value; |
1703 | if (!_init) _sendSerialData(); |
1808 | if (!_init) _sendSerialData(); |
1704 | } |
1809 | } |
1705 | private void btnSer3_0_Click(object sender, EventArgs e) |
1810 | private void btnSer3_0_Click(object sender, EventArgs e) |
1706 | { |
1811 | { |
1707 | trckbarSerial3.Value = 0; |
1812 | trckbarSerial3.Value = 0; |
1708 | } |
1813 | } |
1709 | private void btnSer3_127_Click(object sender, EventArgs e) |
1814 | private void btnSer3_127_Click(object sender, EventArgs e) |
1710 | { |
1815 | { |
1711 | trckbarSerial3.Value = 127; |
1816 | trckbarSerial3.Value = 127; |
1712 | } |
1817 | } |
1713 | private void btnSer3_254_Click(object sender, EventArgs e) |
1818 | private void btnSer3_254_Click(object sender, EventArgs e) |
1714 | { |
1819 | { |
1715 | trckbarSerial3.Value = 254; |
1820 | trckbarSerial3.Value = 254; |
1716 | } |
1821 | } |
1717 | private void textBoxSerial4_TextChanged(object sender, EventArgs e) |
1822 | private void textBoxSerial4_TextChanged(object sender, EventArgs e) |
1718 | { |
1823 | { |
1719 | serChanTitle[3] = textBoxSerial4.Text; |
1824 | serChanTitle[3] = textBoxSerial4.Text; |
1720 | } |
1825 | } |
1721 | private void trckbarSerial4_ValueChanged(object sender, EventArgs e) |
1826 | private void trckbarSerial4_ValueChanged(object sender, EventArgs e) |
1722 | { |
1827 | { |
1723 | lblTbSerial4.Text = trckbarSerial4.Value.ToString(); |
1828 | lblTbSerial4.Text = trckbarSerial4.Value.ToString(); |
1724 | serChan[3] = trckbarSerial4.Value; |
1829 | serChan[3] = trckbarSerial4.Value; |
1725 | if (!_init) _sendSerialData(); |
1830 | if (!_init) _sendSerialData(); |
1726 | } |
1831 | } |
1727 | private void btnSer4_0_Click(object sender, EventArgs e) |
1832 | private void btnSer4_0_Click(object sender, EventArgs e) |
1728 | { |
1833 | { |
1729 | trckbarSerial4.Value = 0; |
1834 | trckbarSerial4.Value = 0; |
1730 | } |
1835 | } |
1731 | private void btnSer4_127_Click(object sender, EventArgs e) |
1836 | private void btnSer4_127_Click(object sender, EventArgs e) |
1732 | { |
1837 | { |
1733 | trckbarSerial4.Value = 127; |
1838 | trckbarSerial4.Value = 127; |
1734 | } |
1839 | } |
1735 | private void btnSer4_254_Click(object sender, EventArgs e) |
1840 | private void btnSer4_254_Click(object sender, EventArgs e) |
1736 | { |
1841 | { |
1737 | trckbarSerial4.Value = 254; |
1842 | trckbarSerial4.Value = 254; |
1738 | } |
1843 | } |
1739 | private void tbSerial5_Scroll(object sender, EventArgs e) |
1844 | private void tbSerial5_Scroll(object sender, EventArgs e) |
1740 | { |
1845 | { |
1741 | lblTbSerial5.Text = trckbarSerial5.Value.ToString(); |
1846 | lblTbSerial5.Text = trckbarSerial5.Value.ToString(); |
1742 | serChan[4] = trckbarSerial5.Value; |
1847 | serChan[4] = trckbarSerial5.Value; |
1743 | if (!_init) _sendSerialData(); |
1848 | if (!_init) _sendSerialData(); |
1744 | } |
1849 | } |
1745 | private void textBoxSerial5_TextChanged(object sender, EventArgs e) |
1850 | private void textBoxSerial5_TextChanged(object sender, EventArgs e) |
1746 | { |
1851 | { |
1747 | serChanTitle[4] = textBoxSerial5.Text; |
1852 | serChanTitle[4] = textBoxSerial5.Text; |
1748 | } |
1853 | } |
1749 | private void btnSer5_0_Click(object sender, EventArgs e) |
1854 | private void btnSer5_0_Click(object sender, EventArgs e) |
1750 | { |
1855 | { |
1751 | trckbarSerial5.Value = 0; |
1856 | trckbarSerial5.Value = 0; |
1752 | } |
1857 | } |
1753 | private void btnSer5_127_Click(object sender, EventArgs e) |
1858 | private void btnSer5_127_Click(object sender, EventArgs e) |
1754 | { |
1859 | { |
1755 | trckbarSerial5.Value = 127; |
1860 | trckbarSerial5.Value = 127; |
1756 | } |
1861 | } |
1757 | private void btnSer5_254_Click(object sender, EventArgs e) |
1862 | private void btnSer5_254_Click(object sender, EventArgs e) |
1758 | { |
1863 | { |
1759 | trckbarSerial5.Value = 254; |
1864 | trckbarSerial5.Value = 254; |
1760 | } |
1865 | } |
1761 | private void trckbarSerial5_ValueChanged(object sender, EventArgs e) |
1866 | private void trckbarSerial5_ValueChanged(object sender, EventArgs e) |
1762 | { |
1867 | { |
1763 | lblTbSerial5.Text = trckbarSerial5.Value.ToString(); |
1868 | lblTbSerial5.Text = trckbarSerial5.Value.ToString(); |
1764 | serChan[4] = trckbarSerial5.Value; |
1869 | serChan[4] = trckbarSerial5.Value; |
1765 | if (!_init) _sendSerialData(); |
1870 | if (!_init) _sendSerialData(); |
1766 | } |
1871 | } |
1767 | private void tbSerial6_Scroll(object sender, EventArgs e) |
1872 | private void tbSerial6_Scroll(object sender, EventArgs e) |
1768 | { |
1873 | { |
1769 | lblTbSerial6.Text = trckbarSerial6.Value.ToString(); |
1874 | lblTbSerial6.Text = trckbarSerial6.Value.ToString(); |
1770 | serChan[5] = trckbarSerial6.Value; |
1875 | serChan[5] = trckbarSerial6.Value; |
1771 | if (!_init) _sendSerialData(); |
1876 | if (!_init) _sendSerialData(); |
1772 | } |
1877 | } |
1773 | private void textBoxSerial6_TextChanged(object sender, EventArgs e) |
1878 | private void textBoxSerial6_TextChanged(object sender, EventArgs e) |
1774 | { |
1879 | { |
1775 | serChanTitle[5] = textBoxSerial6.Text; |
1880 | serChanTitle[5] = textBoxSerial6.Text; |
1776 | } |
1881 | } |
1777 | private void btnSer6_0_Click(object sender, EventArgs e) |
1882 | private void btnSer6_0_Click(object sender, EventArgs e) |
1778 | { |
1883 | { |
1779 | trckbarSerial6.Value = 0; |
1884 | trckbarSerial6.Value = 0; |
1780 | } |
1885 | } |
1781 | private void btnSer6_127_Click(object sender, EventArgs e) |
1886 | private void btnSer6_127_Click(object sender, EventArgs e) |
1782 | { |
1887 | { |
1783 | trckbarSerial6.Value = 127; |
1888 | trckbarSerial6.Value = 127; |
1784 | } |
1889 | } |
1785 | private void btnSer6_254_Click(object sender, EventArgs e) |
1890 | private void btnSer6_254_Click(object sender, EventArgs e) |
1786 | { |
1891 | { |
1787 | trckbarSerial6.Value = 254; |
1892 | trckbarSerial6.Value = 254; |
1788 | } |
1893 | } |
1789 | private void trckbarSerial6_ValueChanged(object sender, EventArgs e) |
1894 | private void trckbarSerial6_ValueChanged(object sender, EventArgs e) |
1790 | { |
1895 | { |
1791 | lblTbSerial6.Text = trckbarSerial6.Value.ToString(); |
1896 | lblTbSerial6.Text = trckbarSerial6.Value.ToString(); |
1792 | serChan[5] = trckbarSerial6.Value; |
1897 | serChan[5] = trckbarSerial6.Value; |
1793 | if (!_init) _sendSerialData(); |
1898 | if (!_init) _sendSerialData(); |
1794 | } |
1899 | } |
1795 | private void tbSerial7_Scroll(object sender, EventArgs e) |
1900 | private void tbSerial7_Scroll(object sender, EventArgs e) |
1796 | { |
1901 | { |
1797 | lblTbSerial7.Text = trckbarSerial7.Value.ToString(); |
1902 | lblTbSerial7.Text = trckbarSerial7.Value.ToString(); |
1798 | serChan[6] = trckbarSerial7.Value; |
1903 | serChan[6] = trckbarSerial7.Value; |
1799 | if (!_init) _sendSerialData(); |
1904 | if (!_init) _sendSerialData(); |
1800 | } |
1905 | } |
1801 | private void textBoxSerial7_TextChanged(object sender, EventArgs e) |
1906 | private void textBoxSerial7_TextChanged(object sender, EventArgs e) |
1802 | { |
1907 | { |
1803 | serChanTitle[6] = textBoxSerial7.Text; |
1908 | serChanTitle[6] = textBoxSerial7.Text; |
1804 | } |
1909 | } |
1805 | private void btnSer7_0_Click(object sender, EventArgs e) |
1910 | private void btnSer7_0_Click(object sender, EventArgs e) |
1806 | { |
1911 | { |
1807 | trckbarSerial7.Value = 0; |
1912 | trckbarSerial7.Value = 0; |
1808 | } |
1913 | } |
1809 | private void btnSer7_127_Click(object sender, EventArgs e) |
1914 | private void btnSer7_127_Click(object sender, EventArgs e) |
1810 | { |
1915 | { |
1811 | trckbarSerial7.Value = 127; |
1916 | trckbarSerial7.Value = 127; |
1812 | } |
1917 | } |
1813 | private void btnSer7_254_Click(object sender, EventArgs e) |
1918 | private void btnSer7_254_Click(object sender, EventArgs e) |
1814 | { |
1919 | { |
1815 | trckbarSerial7.Value = 254; |
1920 | trckbarSerial7.Value = 254; |
1816 | } |
1921 | } |
1817 | private void trckbarSerial7_ValueChanged(object sender, EventArgs e) |
1922 | private void trckbarSerial7_ValueChanged(object sender, EventArgs e) |
1818 | { |
1923 | { |
1819 | lblTbSerial7.Text = trckbarSerial7.Value.ToString(); |
1924 | lblTbSerial7.Text = trckbarSerial7.Value.ToString(); |
1820 | serChan[6] = trckbarSerial7.Value; |
1925 | serChan[6] = trckbarSerial7.Value; |
1821 | if (!_init) _sendSerialData(); |
1926 | if (!_init) _sendSerialData(); |
1822 | } |
1927 | } |
1823 | private void tbSerial8_Scroll(object sender, EventArgs e) |
1928 | private void tbSerial8_Scroll(object sender, EventArgs e) |
1824 | { |
1929 | { |
1825 | lblTbSerial8.Text = trckbarSerial8.Value.ToString(); |
1930 | lblTbSerial8.Text = trckbarSerial8.Value.ToString(); |
1826 | serChan[7] = trckbarSerial8.Value; |
1931 | serChan[7] = trckbarSerial8.Value; |
1827 | if (!_init) _sendSerialData(); |
1932 | if (!_init) _sendSerialData(); |
1828 | } |
1933 | } |
1829 | private void textBoxSerial8_TextChanged(object sender, EventArgs e) |
1934 | private void textBoxSerial8_TextChanged(object sender, EventArgs e) |
1830 | { |
1935 | { |
1831 | serChanTitle[7] = textBoxSerial8.Text; |
1936 | serChanTitle[7] = textBoxSerial8.Text; |
1832 | } |
1937 | } |
1833 | private void btnSer8_0_Click(object sender, EventArgs e) |
1938 | private void btnSer8_0_Click(object sender, EventArgs e) |
1834 | { |
1939 | { |
1835 | trckbarSerial8.Value = 0; |
1940 | trckbarSerial8.Value = 0; |
1836 | } |
1941 | } |
1837 | private void btnSer8_127_Click(object sender, EventArgs e) |
1942 | private void btnSer8_127_Click(object sender, EventArgs e) |
1838 | { |
1943 | { |
1839 | trckbarSerial8.Value = 127; |
1944 | trckbarSerial8.Value = 127; |
1840 | } |
1945 | } |
1841 | private void btnSer8_254_Click(object sender, EventArgs e) |
1946 | private void btnSer8_254_Click(object sender, EventArgs e) |
1842 | { |
1947 | { |
1843 | trckbarSerial8.Value = 254; |
1948 | trckbarSerial8.Value = 254; |
1844 | } |
1949 | } |
1845 | private void trckbarSerial8_ValueChanged(object sender, EventArgs e) |
1950 | private void trckbarSerial8_ValueChanged(object sender, EventArgs e) |
1846 | { |
1951 | { |
1847 | lblTbSerial8.Text = trckbarSerial8.Value.ToString(); |
1952 | lblTbSerial8.Text = trckbarSerial8.Value.ToString(); |
1848 | serChan[7] = trckbarSerial8.Value; |
1953 | serChan[7] = trckbarSerial8.Value; |
1849 | if (!_init) _sendSerialData(); |
1954 | if (!_init) _sendSerialData(); |
1850 | } |
1955 | } |
1851 | #endregion serial control channels |
1956 | #endregion serial control channels |
1852 | 1957 | ||
1853 | } |
1958 | } |
1854 | public class IniFile |
1959 | public class IniFile |
1855 | { |
1960 | { |
1856 | public string path; |
1961 | public string path; |
1857 | 1962 | ||
1858 | [DllImport("kernel32")] |
1963 | [DllImport("kernel32")] |
1859 | private static extern long WritePrivateProfileString(string section, |
1964 | private static extern long WritePrivateProfileString(string section, |
1860 | string key, string val, string filePath); |
1965 | string key, string val, string filePath); |
1861 | 1966 | ||
1862 | [DllImport("kernel32.dll", CharSet = CharSet.Auto)] |
1967 | [DllImport("kernel32.dll", CharSet = CharSet.Auto)] |
1863 | static extern uint GetPrivateProfileSectionNames(IntPtr lpszReturnBuffer, |
1968 | static extern uint GetPrivateProfileSectionNames(IntPtr lpszReturnBuffer, |
1864 | uint nSize, string lpFileName); |
1969 | uint nSize, string lpFileName); |
1865 | 1970 | ||
1866 | [DllImport("kernel32")] |
1971 | [DllImport("kernel32")] |
1867 | private static extern int GetPrivateProfileString(string section, |
1972 | private static extern int GetPrivateProfileString(string section, |
1868 | string key, string def, StringBuilder retVal, |
1973 | string key, string def, StringBuilder retVal, |
1869 | int size, string filePath); |
1974 | int size, string filePath); |
1870 | 1975 | ||
1871 | public IniFile(string INIPath) |
1976 | public IniFile(string INIPath) |
1872 | { |
1977 | { |
1873 | path = INIPath; |
1978 | path = INIPath; |
1874 | } |
1979 | } |
1875 | 1980 | ||
1876 | public void IniWriteValue(string Section, string Key, string Value) |
1981 | public void IniWriteValue(string Section, string Key, string Value) |
1877 | { |
1982 | { |
1878 | WritePrivateProfileString(Section, Key, Value, this.path); |
1983 | WritePrivateProfileString(Section, Key, Value, this.path); |
1879 | } |
1984 | } |
1880 | 1985 | ||
1881 | public string IniReadValue(string Section, string Key) |
1986 | public string IniReadValue(string Section, string Key) |
1882 | { |
1987 | { |
1883 | StringBuilder temp = new StringBuilder(255); |
1988 | StringBuilder temp = new StringBuilder(255); |
1884 | int i = GetPrivateProfileString(Section, Key, "", temp, 255, this.path); |
1989 | int i = GetPrivateProfileString(Section, Key, "", temp, 255, this.path); |
1885 | return temp.ToString(); |
1990 | return temp.ToString(); |
1886 | } |
1991 | } |
1887 | //Ini_sections auslesen in String-Array |
1992 | //Ini_sections auslesen in String-Array |
1888 | public string[] IniSectionNames() |
1993 | public string[] IniSectionNames() |
1889 | { |
1994 | { |
1890 | 1995 | ||
1891 | // uint MAX_BUFFER = 32767; |
1996 | // uint MAX_BUFFER = 32767; |
1892 | uint MAX_BUFFER = 8388608; |
1997 | uint MAX_BUFFER = 8388608; |
1893 | IntPtr pReturnedString = Marshal.AllocCoTaskMem((int)MAX_BUFFER); |
1998 | IntPtr pReturnedString = Marshal.AllocCoTaskMem((int)MAX_BUFFER); |
1894 | uint bytesReturned = GetPrivateProfileSectionNames(pReturnedString, MAX_BUFFER, this.path); |
1999 | uint bytesReturned = GetPrivateProfileSectionNames(pReturnedString, MAX_BUFFER, this.path); |
1895 | if (bytesReturned == 0) |
2000 | if (bytesReturned == 0) |
1896 | { |
2001 | { |
1897 | Marshal.FreeCoTaskMem(pReturnedString); |
2002 | Marshal.FreeCoTaskMem(pReturnedString); |
1898 | return null; |
2003 | return null; |
1899 | } |
2004 | } |
1900 | string local = Marshal.PtrToStringAuto(pReturnedString, (int)bytesReturned).ToString(); |
2005 | string local = Marshal.PtrToStringAuto(pReturnedString, (int)bytesReturned).ToString(); |
1901 | Marshal.FreeCoTaskMem(pReturnedString); |
2006 | Marshal.FreeCoTaskMem(pReturnedString); |
1902 | //use of Substring below removes terminating null for split |
2007 | //use of Substring below removes terminating null for split |
1903 | return local.Substring(0, local.Length - 1).Split('\0'); |
2008 | return local.Substring(0, local.Length - 1).Split('\0'); |
1904 | 2009 | ||
1905 | 2010 | ||
1906 | } |
2011 | } |
1907 | } |
2012 | } |
1908 | public static class ControlExtensions |
2013 | public static class ControlExtensions |
1909 | { |
2014 | { |
1910 | /// <summary> |
2015 | /// <summary> |
1911 | /// Execute a threadsafe operation, when accessing a control via another thread |
2016 | /// Execute a threadsafe operation, when accessing a control via another thread |
1912 | /// action is a lamdaexpression |
2017 | /// action is a lamdaexpression |
1913 | /// e.g. comboBox1.ExecuteThreadSafe(() => comboBox1.Enabled = true); |
2018 | /// e.g. comboBox1.ExecuteThreadSafe(() => comboBox1.Enabled = true); |
1914 | /// </summary> |
2019 | /// </summary> |
1915 | /// <param name="control"> The control </param> |
2020 | /// <param name="control"> The control </param> |
1916 | /// <param name="action"> The 'action' to perform </param> |
2021 | /// <param name="action"> The 'action' to perform </param> |
1917 | public static void ExecuteThreadSafe(this Control control, Action action) |
2022 | public static void ExecuteThreadSafe(this Control control, Action action) |
1918 | { |
2023 | { |
1919 | if (control.InvokeRequired) |
2024 | if (control.InvokeRequired) |
1920 | { |
2025 | { |
1921 | control.BeginInvoke(action); //"BeginInvoke" is an async call -> threadsafety error when called to many times successively -> then take "Invoke" |
2026 | control.BeginInvoke(action); //"BeginInvoke" is an async call -> threadsafety error when called to many times successively -> then take "Invoke" |
1922 | } |
2027 | } |
1923 | else |
2028 | else |
1924 | { |
2029 | { |
1925 | action.Invoke(); |
2030 | action.Invoke(); |
1926 | } |
2031 | } |
1927 | } |
2032 | } |
1928 | } |
2033 | } |
1929 | 2034 | ||
1930 | } |
2035 | } |
1931 | 2036 |