preparing for camera mounts
git-svn-id: https://arducopter.googlecode.com/svn/trunk@744 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
e7b26da27d
commit
b853247c08
@ -85,6 +85,8 @@ TODO:
|
|||||||
#define CHANN_CENTER 1500 // Channel center, legacy
|
#define CHANN_CENTER 1500 // Channel center, legacy
|
||||||
#define MIN_THROTTLE 1040 // Throttle pulse width at minimun...
|
#define MIN_THROTTLE 1040 // Throttle pulse width at minimun...
|
||||||
|
|
||||||
|
#define CAM_CENT 1500 // Camera center
|
||||||
|
|
||||||
/*************************************************************/
|
/*************************************************************/
|
||||||
// General definitions
|
// General definitions
|
||||||
//Modes
|
//Modes
|
||||||
|
@ -306,6 +306,7 @@ int Sonar_Counter=0;
|
|||||||
|
|
||||||
// AP_mode : 1=> Position hold 2=>Stabilization assist mode (normal mode)
|
// AP_mode : 1=> Position hold 2=>Stabilization assist mode (normal mode)
|
||||||
byte AP_mode = 2;
|
byte AP_mode = 2;
|
||||||
|
byte cam_mode = 0;
|
||||||
|
|
||||||
// Mode LED timers and variables, used to blink LED_Green
|
// Mode LED timers and variables, used to blink LED_Green
|
||||||
byte gled_status = HIGH;
|
byte gled_status = HIGH;
|
||||||
|
@ -251,6 +251,8 @@ void loop()
|
|||||||
// Send output commands to motor ESCs...
|
// Send output commands to motor ESCs...
|
||||||
motor_output();
|
motor_output();
|
||||||
|
|
||||||
|
// camera_output();
|
||||||
|
|
||||||
// Autopilot mode functions
|
// Autopilot mode functions
|
||||||
if (AP_mode == AP_AUTOMATIC_MODE)
|
if (AP_mode == AP_AUTOMATIC_MODE)
|
||||||
{
|
{
|
||||||
|
@ -119,7 +119,8 @@ void APMPinMode(volatile unsigned char &Port, byte Pin, boolean Set)
|
|||||||
{
|
{
|
||||||
if (Set) {
|
if (Set) {
|
||||||
Port |= (1 << Pin);
|
Port |= (1 << Pin);
|
||||||
} else {
|
}
|
||||||
|
else {
|
||||||
Port &= ~(1 << Pin);
|
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() {
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
@ -79,6 +79,10 @@ void motor_output()
|
|||||||
APM_RC.OutputCh(2, frontMotor);
|
APM_RC.OutputCh(2, frontMotor);
|
||||||
APM_RC.OutputCh(3, backMotor);
|
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
|
// InstantPWM => Force inmediate output on PWM signals
|
||||||
APM_RC.Force_Out0_Out1();
|
APM_RC.Force_Out0_Out1();
|
||||||
APM_RC.Force_Out2_Out3();
|
APM_RC.Force_Out2_Out3();
|
||||||
|
Loading…
Reference in New Issue
Block a user