preparing for camera mounts

git-svn-id: https://arducopter.googlecode.com/svn/trunk@744 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
jphelirc 2010-10-29 05:47:54 +00:00
parent e7b26da27d
commit b853247c08
5 changed files with 60 additions and 34 deletions

View File

@ -85,6 +85,8 @@ TODO:
#define CHANN_CENTER 1500 // Channel center, legacy
#define MIN_THROTTLE 1040 // Throttle pulse width at minimun...
#define CAM_CENT 1500 // Camera center
/*************************************************************/
// General definitions
//Modes

View File

@ -306,6 +306,7 @@ int Sonar_Counter=0;
// AP_mode : 1=> Position hold 2=>Stabilization assist mode (normal mode)
byte AP_mode = 2;
byte cam_mode = 0;
// Mode LED timers and variables, used to blink LED_Green
byte gled_status = HIGH;

View File

@ -251,6 +251,8 @@ void loop()
// Send output commands to motor ESCs...
motor_output();
// camera_output();
// Autopilot mode functions
if (AP_mode == AP_AUTOMATIC_MODE)
{

View File

@ -6,9 +6,9 @@
File : Functions.pde
Version : v1.0, Aug 28, 2010
Author(s): ArduCopter Team
Ted Carancho (aeroquad), Jose Julio, Jordi Muñoz,
Jani Hirvinen, Ken McEwans, Roberto Navoni,
Sandro Benigno, Chris Anderson
Ted Carancho (aeroquad), Jose Julio, Jordi Muñoz,
Jani Hirvinen, Ken McEwans, Roberto Navoni,
Sandro Benigno, Chris Anderson
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
@ -22,16 +22,16 @@
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
* ************************************************************** *
ChangeLog:
* ************************************************************** *
TODO:
* ************************************************************** */
* ************************************************************** *
ChangeLog:
* ************************************************************** *
TODO:
* ************************************************************** */
// Flash those A,B,C LEDs on IMU Board
@ -39,7 +39,7 @@ TODO:
// Function: FullBlink(int, int);
// int 1 =
void FullBlink(int count, int blinkdelay) {
for(int i = 0; i <= count; i++) {
for(int i = 0; i <= count; i++) {
digitalWrite(LED_Green, HIGH);
digitalWrite(LED_Yellow, HIGH);
digitalWrite(LED_Red, HIGH);
@ -53,31 +53,31 @@ void FullBlink(int count, int blinkdelay) {
void RunningLights(int LightStep) {
if(LightStep == 0) {
digitalWrite(LED_Green, HIGH);
digitalWrite(LED_Yellow, LOW);
digitalWrite(LED_Red, LOW);
}
else if (LightStep == 1) {
digitalWrite(LED_Green, LOW);
digitalWrite(LED_Yellow, HIGH);
digitalWrite(LED_Red, LOW);
}
else {
digitalWrite(LED_Green, LOW);
digitalWrite(LED_Yellow, LOW);
digitalWrite(LED_Red, HIGH);
}
if(LightStep == 0) {
digitalWrite(LED_Green, HIGH);
digitalWrite(LED_Yellow, LOW);
digitalWrite(LED_Red, LOW);
}
else if (LightStep == 1) {
digitalWrite(LED_Green, LOW);
digitalWrite(LED_Yellow, HIGH);
digitalWrite(LED_Red, LOW);
}
else {
digitalWrite(LED_Green, LOW);
digitalWrite(LED_Yellow, LOW);
digitalWrite(LED_Red, HIGH);
}
}
void LightsOff() {
digitalWrite(LED_Green, LOW);
digitalWrite(LED_Yellow, LOW);
digitalWrite(LED_Red, LOW);
}
// Funtion to normalize an angle in degrees to -180,180 degrees
@ -119,7 +119,8 @@ void APMPinMode(volatile unsigned char &Port, byte Pin, boolean Set)
{
if (Set) {
Port |= (1 << Pin);
} else {
}
else {
Port &= ~(1 << Pin);
}
}
@ -133,3 +134,19 @@ boolean APMPinRead(volatile unsigned char &Port, byte Pin)
}
/* **************************************************** */
// Camera stabilization
//
// Stabilization for three different camera styles
// 1) Camera mounts that have tilt / pan
// 2) Camera mounts that have tilt / roll
// 3) Camera mounts that have tilt / roll / pan
void camera_output() {
}

View File

@ -78,7 +78,11 @@ void motor_output()
APM_RC.OutputCh(1, leftMotor);
APM_RC.OutputCh(2, frontMotor);
APM_RC.OutputCh(3, backMotor);
// Do we have cameras stabilization connected and in use?
if(SW_DIP2) camera_output();
// InstantPWM => Force inmediate output on PWM signals
APM_RC.Force_Out0_Out1();
APM_RC.Force_Out2_Out3();