Details | Last modification | View Log | RSS feed
Rev | Author | Line No. | Line |
---|---|---|---|
1702 | - | 1 | /* |
2 | |||
3 | Copyright (c) 2011. All rights reserved. |
||
4 | An Open Source Arduino based OSD and Camera Control project. |
||
5 | |||
6 | Program : ArduCAM-OSD (Supports the variant: minimOSD) |
||
7 | Version : V1.9, 14 February 2012 |
||
8 | Author(s): Sandro Benigno |
||
9 | Coauthor(s): |
||
10 | Jani Hirvinen (All the EEPROM routines) |
||
11 | Michael Oborne (OSD Configutator) |
||
12 | Mike Smith (BetterStream and Fast Serial libraries) |
||
13 | Special Contribuitor: |
||
14 | Andrew Tridgell by all the support on MAVLink |
||
15 | Doug Weibel by his great orientation since the start of this project |
||
16 | Contributors: James Goppert, Max Levine |
||
17 | and all other members of DIY Drones Dev team |
||
18 | Thanks to: Chris Anderson, Jordi Munoz |
||
19 | |||
20 | |||
21 | This program is free software: you can redistribute it and/or modify |
||
22 | it under the terms of the GNU General Public License as published by |
||
23 | the Free Software Foundation, either version 3 of the License, or |
||
24 | (at your option) any later version. |
||
25 | |||
26 | This program is distributed in the hope that it will be useful, |
||
27 | but WITHOUT ANY WARRANTY; without even the implied warranty of |
||
28 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the |
||
29 | GNU General Public License for more details. |
||
30 | |||
31 | You should have received a copy of the GNU General Public License |
||
32 | along with this program. If not, see <http://www.gnu.org/licenses/> |
||
33 | |||
34 | */ |
||
35 | |||
36 | /* ************************************************************ */ |
||
37 | /* **************** MAIN PROGRAM - MODULES ******************** */ |
||
38 | /* ************************************************************ */ |
||
39 | |||
40 | #undef PROGMEM |
||
41 | #define PROGMEM __attribute__(( section(".progmem.data") )) |
||
42 | |||
43 | #undef PSTR |
||
44 | #define PSTR(s) (__extension__({static prog_char __c[] PROGMEM = (s); &__c[0];})) |
||
45 | |||
46 | #define MAVLINK10 |
||
47 | |||
48 | /* **********************************************/ |
||
49 | /* ***************** INCLUDES *******************/ |
||
50 | |||
51 | //#define membug |
||
52 | //#define FORCEINIT // You should never use this unless you know what you are doing |
||
53 | |||
54 | |||
55 | // AVR Includes |
||
56 | #include <FastSerial.h> |
||
57 | #include <AP_Common.h> |
||
58 | #include <AP_Math.h> |
||
59 | #include <math.h> |
||
60 | #include <inttypes.h> |
||
61 | #include <avr/pgmspace.h> |
||
62 | // Get the common arduino functions |
||
63 | #if defined(ARDUINO) && ARDUINO >= 100 |
||
64 | #include "Arduino.h" |
||
65 | #else |
||
66 | #include "wiring.h" |
||
67 | #endif |
||
68 | #include <EEPROM.h> |
||
69 | #include <SimpleTimer.h> |
||
70 | #include <GCS_MAVLink.h> |
||
71 | |||
72 | #ifdef membug |
||
73 | #include <MemoryFree.h> |
||
74 | #endif |
||
75 | |||
76 | // Configurations |
||
77 | #include "OSD_Config.h" |
||
78 | #include "ArduCam_Max7456.h" |
||
79 | #include "OSD_Vars.h" |
||
80 | #include "OSD_Func.h" |
||
81 | |||
82 | /* *************************************************/ |
||
83 | /* ***************** DEFINITIONS *******************/ |
||
84 | |||
85 | //OSD Hardware |
||
86 | //#define ArduCAM328 |
||
87 | #define MinimOSD |
||
88 | |||
89 | #define TELEMETRY_SPEED 57600 // How fast our MAVLink telemetry is coming to Serial port |
||
90 | #define BOOTTIME 2000 // Time in milliseconds that we show boot loading bar and wait user input |
||
91 | |||
92 | // Objects and Serial definitions |
||
93 | FastSerialPort0(Serial); |
||
94 | OSD osd; //OSD object |
||
95 | |||
96 | SimpleTimer mavlinkTimer; |
||
97 | |||
98 | |||
99 | /* **********************************************/ |
||
100 | /* ***************** SETUP() *******************/ |
||
101 | |||
102 | void setup() |
||
103 | { |
||
104 | #ifdef ArduCAM328 |
||
105 | pinMode(10, OUTPUT); // USB ArduCam Only |
||
106 | #endif |
||
107 | pinMode(MAX7456_SELECT, OUTPUT); // OSD CS |
||
108 | |||
109 | Serial.begin(TELEMETRY_SPEED); |
||
110 | // setup mavlink port |
||
111 | mavlink_comm_0_port = &Serial; |
||
112 | |||
113 | #ifdef membug |
||
114 | Serial.println(freeMem()); |
||
115 | #endif |
||
116 | |||
117 | // Prepare OSD for displaying |
||
118 | unplugSlaves(); |
||
119 | osd.init(); |
||
120 | |||
121 | // Start |
||
122 | startPanels(); |
||
123 | delay(500); |
||
124 | |||
125 | // OSD debug for development (Shown at start) |
||
126 | #ifdef membug |
||
127 | osd.setPanel(1,1); |
||
128 | osd.openPanel(); |
||
129 | osd.printf("%i",freeMem()); |
||
130 | osd.closePanel(); |
||
131 | #endif |
||
132 | |||
133 | // Just to easy up development things |
||
134 | #ifdef FORCEINIT |
||
135 | InitializeOSD(); |
||
136 | #endif |
||
137 | |||
138 | |||
139 | // Check EEPROM to see if we have initialized it already or not |
||
140 | // also checks if we have new version that needs EEPROM reset |
||
141 | if(readEEPROM(CHK1) + readEEPROM(CHK2) != VER) { |
||
142 | osd.setPanel(6,9); |
||
143 | osd.openPanel(); |
||
144 | osd.printf_P(PSTR("Missing/Old Config")); |
||
145 | osd.closePanel(); |
||
146 | InitializeOSD(); |
||
147 | } |
||
148 | |||
149 | // Get correct panel settings from EEPROM |
||
150 | readSettings(); |
||
151 | |||
152 | // Show bootloader bar |
||
153 | loadBar(); |
||
154 | |||
155 | // Startup MAVLink timers |
||
156 | mavlinkTimer.Set(&OnMavlinkTimer, 120); |
||
157 | |||
158 | // House cleaning, clear display and enable timers |
||
159 | osd.clear(); |
||
160 | mavlinkTimer.Enable(); |
||
161 | |||
162 | } // END of setup(); |
||
163 | |||
164 | |||
165 | |||
166 | /* ***********************************************/ |
||
167 | /* ***************** MAIN LOOP *******************/ |
||
168 | |||
169 | // Mother of all happenings, The loop() |
||
170 | // As simple as possible. |
||
171 | void loop() |
||
172 | { |
||
173 | |||
174 | if(enable_mav_request == 1){//Request rate control |
||
175 | osd.clear(); |
||
176 | osd.setPanel(3,10); |
||
177 | osd.openPanel(); |
||
178 | osd.printf_P(PSTR("Requesting DataStreams...")); |
||
179 | osd.closePanel(); |
||
180 | for(int n = 0; n < 3; n++){ |
||
181 | request_mavlink_rates();//Three times to certify it will be readed |
||
182 | delay(50); |
||
183 | } |
||
184 | enable_mav_request = 0; |
||
185 | delay(2000); |
||
186 | osd.clear(); |
||
187 | waitingMAVBeats = 0; |
||
188 | lastMAVBeat = millis();//Preventing error from delay sensing |
||
189 | } |
||
190 | |||
191 | read_mavlink(); |
||
192 | mavlinkTimer.Run(); |
||
193 | } |
||
194 | |||
195 | /* *********************************************** */ |
||
196 | /* ******** functions used in main loop() ******** */ |
||
197 | void OnMavlinkTimer() |
||
198 | { |
||
199 | setHeadingPatern(); // generate the heading patern |
||
200 | |||
201 | osd_battery_pic_A = setBatteryPic(osd_battery_remaining_A); // battery A remmaning picture |
||
202 | //osd_battery_pic_B = setBatteryPic(osd_battery_remaining_B); // battery B remmaning picture |
||
203 | |||
204 | setHomeVars(osd); // calculate and set Distance from home and Direction to home |
||
205 | |||
206 | writePanels(); // writing enabled panels (check OSD_Panels Tab) |
||
207 | } |
||
208 | |||
209 | |||
210 | void unplugSlaves(){ |
||
211 | //Unplug list of SPI |
||
212 | #ifdef ArduCAM328 |
||
213 | digitalWrite(10, HIGH); // unplug USB HOST: ArduCam Only |
||
214 | #endif |
||
215 | digitalWrite(MAX7456_SELECT, HIGH); // unplug OSD |
||
216 | } |