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