Subversion Repositories Projects

Rev

Details | Last modification | View Log | RSS feed

Rev Author Line No. Line
1702 - 1
/*
2
ArduCam OSD - The Arduino based Remote Camera Control and OSD.
3
 
4
File : ArduCamOSD_Beta.pde
5
Version : v0.95, 17 may 2011
6
 
7
Author(s): Sandro Benigno
8
           FastSerial and BetterStream from Michael Smith
9
           USB host and PTP library from Oleg Mazurov - circuitsathome.com
10
 
11
This program is free software: you can redistribute it and/or modify
12
it under the terms of the GNU General Public License as published by
13
the Free Software Foundation, either version 3 of the License, or
14
(at your option) any later version.
15
 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/>.
16
*/
17
 
18
#include <FastSerial.h>
19
 
20
#undef PROGMEM
21
#define PROGMEM __attribute__(( section(".progmem.data") ))
22
 
23
#undef PSTR
24
#define PSTR(s) (__extension__({static prog_char __c[] PROGMEM = (s); &__c[0];}))
25
 
26
#include <inttypes.h>
27
#include <avr/pgmspace.h>
28
#include <stdio.h>
29
 
30
#include "Spi.h"
31
#include "Wire.h" //Future i2c comunication. Uncommented to watch hex size
32
 
33
/****** USB INCLUDES ******/
34
#include <Max3421e.h>
35
#include <Max3421e_constants.h>
36
#include <Usb.h>
37
#include <ptp.h>
38
#include <ptpdebug.h>
39
#include <canonps.h>
40
#include <simpletimer.h>
41
#include "pseventparser.h"
42
#include "ptpobjinfoparser.h"
43
 
44
#define DEV_ADDR        1
45
//Example -> Canon PowerShot S3 IS
46
#define DATA_IN_EP      1
47
#define DATA_OUT_EP     2
48
#define INTERRUPT_EP    3
49
#define CONFIG_NUM      1
50
 
51
#define MAX_USB_STRING_LEN 64
52
 
53
/****** OSD INCLUDES ******/
54
#include "ArduCam_Max7456.h"
55
#include "OSD_Vars.h"
56
 
57
#define SerPri  Serial.print
58
#define SerPriln Serial.println
59
#define SerAva  Serial.available
60
#define SerRea  Serial.read
61
 
62
void setup();
63
void loop();
64
 
65
FastSerialPort0(Serial);
66
 
67
/****** CAMSTATES CLASS ******/
68
class CamStateHandlers : public PSStateHandlers
69
{
70
      bool stateConnected;
71
 
72
public:
73
      CamStateHandlers() : stateConnected(false) {};
74
 
75
      virtual void OnDeviceDisconnectedState(PTP *ptp);
76
      virtual void OnDeviceInitializedState(PTP *ptp);
77
} CamStates;
78
/****** END CAMSTATES ******/
79
 
80
/****** OBJECTS ******/
81
OSD osd; //OSD object instance
82
CanonPS  Ps(DEV_ADDR, DATA_IN_EP, DATA_OUT_EP, INTERRUPT_EP, CONFIG_NUM, &CamStates); //Canon PS object instance
83
SimpleTimer  displayTimer, cameraTimer; //Timers
84
 
85
/********** HANDLERS**********/
86
 
87
void CamStateHandlers::OnDeviceDisconnectedState(PTP *ptp)
88
{
89
    if (stateConnected)
90
    {
91
        cameraTimer.Disable();
92
        stateConnected = false;
93
        Notify(PSTR("Camera disconnected\r\n"));
94
    }
95
}
96
 
97
void CamStateHandlers::OnDeviceInitializedState(PTP *ptp)
98
{
99
    if (!stateConnected)
100
    {
101
        Notify(PSTR("Camera connected\r\n"));
102
        stateConnected = true;
103
        cameraTimer.Enable();
104
    }
105
}
106
 
107
/**********END TIMERS HANDLERS******/
108
 
109
//Demo vars control (!!! Remember to delete it after APM integration)
110
float lastGPSUpdate = 0;
111
float lastBatUpdate = 0;
112
float lastHeadUpdate = 0;
113
float headIncrementSignal = 1;
114
 
115
void setup()
116
{
117
  Serial.begin(57600);
118
  pinMode(10, OUTPUT); //usb host CS
119
  pinMode(6,  OUTPUT); //OSD CS
120
  unplugSlaves();
121
 
122
  osd.init();
123
  startPanels();
124
  delay( 200 );
125
 
126
  unplugSlaves();
127
  Ps.Setup();
128
  delay( 2000 );
129
  osd.clear();
130
 
131
  //Setting Timers
132
  displayTimer.Set(&OnDisplayTimer, 150);
133
  cameraTimer.Set(&OnCameraTimer, 500);
134
  delay( 200 );
135
 
136
  displayTimer.Enable(); //Starting OSD timer (camera timer depends on camera is attached or not)
137
}
138
 
139
void loop(){
140
  unplugSlaves();
141
  displayTimer.Run();
142
  unplugSlaves();
143
  Ps.Task();
144
  cameraTimer.Run();
145
}
146
 
147
void OnCameraTimer()
148
{
149
  readSerialCommand();
150
}
151
 
152
void OnDisplayTimer()
153
{
154
  osd_job();
155
}
156
 
157
void writeOSD() //Interrupt function (ISR)
158
{
159
  //Serial.println("Interrupt!");
160
  detachInterrupt(0); //It will respect the new aquisition
161
  unplugSlaves();
162
  writePanels();//Check OSD_Panels Tab!
163
}
164
 
165
void osd_job()
166
{
167
	/*Its the place for data aquisition*/
168
 
169
	/*JUST Simulated here as DEMO and test*/
170
 
171
  if(millis() > lastGPSUpdate + 100){
172
    lastGPSUpdate = millis();
173
    lat+=0.0001;
174
    lon+=0.002;
175
    hom_dis+=1;
176
  }
177
  if(millis() > lastHeadUpdate + 100){
178
    lastHeadUpdate = millis();
179
 
180
    //looping forever
181
 
182
    if(head >= 180){
183
      head -= 360;
184
    }else head+=5;
185
 
186
    //or ping-pong
187
 
188
    /*if(head >= 180) headIncrementSignal = -1;
189
    if(head <= -180) headIncrementSignal = 1;
190
    head += 1.8 * headIncrementSignal;*/
191
  }
192
  if(millis() > lastBatUpdate + 2000){
193
    lastBatUpdate = millis();
194
    alt++;
195
    vel+=5;
196
    bat_val -= 0.1;
197
  }
198
 
199
  //Next line will arm OSD function for the next VSync interruption
200
  attachInterrupt(0, writeOSD, FALLING);
201
}
202
 
203
void readSerialCommand() {
204
  char queryType;
205
  if (SerAva()) {
206
    queryType = SerRea();
207
    switch (queryType) {
208
    case 'A': //Activate Capture
209
      Ps.Initialize(true);
210
      //mapping capture target to SD card
211
      Ps.SetDevicePropValue(PS_DPC_CaptureTransferMode, (uint16_t)0x0F);
212
      break;
213
    case 'C': //Capture!!!
214
      Ps.Capture();
215
      break;
216
    case 'D': //Deactivate Capture
217
      Ps.Operation(PS_OC_ViewfinderOff);
218
      Ps.Initialize(false);
219
      break;
220
    case 'L': //Focus Lock
221
      Ps.Operation(PS_OC_FocusLock);
222
      delay(50);
223
      break;
224
    case 'O': //ViewFinder Output. 1 = LCD. 2 = AV.
225
      Ps.SetDevicePropValue(PS_DPC_CameraOutput, (uint16_t)readFloatSerial());
226
      break;
227
    case 'U': //Focus Unlock
228
      Ps.Operation(PS_OC_FocusUnlock);
229
      break;
230
    case 'V': //ViewFinder ON/OFF
231
      if((uint16_t)readFloatSerial() == 0){
232
        Ps.Operation(PS_OC_ViewfinderOff);
233
      }
234
      else Ps.Operation(PS_OC_ViewfinderOn);
235
      break;
236
    case 'X': //Close session forever
237
      Ps.Initialize(false);
238
      break;
239
    case 'Z': //Set Zoom
240
      Ps.SetDevicePropValue(PS_DPC_Zoom, (uint16_t)readFloatSerial());
241
      break;
242
    }
243
  }
244
}
245
 
246
float readFloatSerial() {
247
  byte index = 0;
248
  byte timeout = 0;
249
  char data[128] = "";
250
 
251
  do {
252
    if (SerAva() == 0) {
253
      delay(10);
254
      timeout++;
255
    }
256
    else {
257
      data[index] = SerRea();
258
      timeout = 0;
259
      index++;
260
    }
261
  }
262
  while ((data[constrain(index-1, 0, 128)] != ';') && (timeout < 5) && (index < 128));
263
  return atof(data);
264
}
265
 
266
void unplugSlaves(){
267
  digitalWrite(10, HIGH); //unplug USB Host
268
  digitalWrite(6,  HIGH); //unplug OSD
269
}