Skip to content

Instantly share code, notes, and snippets.

@nlac
Last active April 30, 2018 19:37
Show Gist options
  • Save nlac/29616ea55fdcb5f2e5f04fbd2afac071 to your computer and use it in GitHub Desktop.
Save nlac/29616ea55fdcb5f2e5f04fbd2afac071 to your computer and use it in GitHub Desktop.
Simplified mod of kr0k0f4nt's Bayangtoys X21 Gimbal Control script for Arduino Nano
/*
* Simplified version of kr0k0f4nt's script by nlac
* - no STD ange, just MIN and MAX
* - no pin mode selection, only one, new mode: pressing DOWN (video) button slowly rotates the camera downwards until MAX, pressing it again stops the movement. Pressing UP does the same just upwards until MIN angle.
*
* Original header comment:
*
* Bayangtoys X21 BGC Gimbal Control for Ardunio
* by kr0k0f4nt (2017) - Version 1.1
*
* Version 1.1 (2017-09-20)
* - Added SPEED to SETTINGS to Control MODE 1
* - Pressing the Video Button will now always set next Movement on Photo Button to upwards
*
* Version 1.0 (2017-09-19)
* - Initial Release
*
* PPM Processing based on Code by Sijjim (https://forum.arduino.cc/index.php?topic=182681.0)
* Inspired by Muhammad Imam Zulkarnaen (https://www.youtube.com/watch?v=pYitT60Frjc)
*/
// *********************** SETTINGS ****************************
/*
* Angle can be 0-2000, but only Values between 1500-2000 make sense
* 1000 = Camera looks straight up to the drone body, lower values make it look backwards
* 1500 = Neutal Setting looking straight forward
* 2000 = Cameras looks straight down
*/
#define MAX 1990 // Max Angle (default 2000, looking down)
#define MIN 1590 // Min Angle (default 1500, looking straight forward)
#define SPEED 1 // Speed of movement, 1 is slowest to 10 fastest
/*
* Interrputs are not available on all Pins, for the Nano only on 2 & 3
*/
#define PPM_PIN 2 // PIN with X21 Signal
/*
* This only needs to be a Pin that is capable of PWM, for the Nano this is 3,5-6,9-11
*/
#define GIMBAL_PIN 6 // PIN with Gimbal Signal
/*
* Setting Up Pin Pair for MODE Control
*/
#define MODE_PIN_OUT 7 // MODE Pin Output
#define MODE_PIN_IN 8 // MODE Pin Input
/*
* This will set the number of channels in the PPM signal
*/
#define CHANNELS 3 // X21 works with 3 Channels
#define CHANNEL_SIGNAL 3 // X21 Signal is on Channel 3
/*
* These are the Signal average Values for the Channel 3, which varies on the Video/Photo Buttons being pressed
*/
#define SIGNAL_BASE 500
#define SIGNAL_PHOTO 1100
#define SIGNAL_VIDEO 1600
// ****************** GLOBAL VARIABLES ******************
#include <Servo.h>
Servo Gimbal;
// State Variables for handling Signal toggles
int LastSignal = SIGNAL_BASE;
int GimbalState = MIN;
// Variables for MODE 1 Control by Photo Button
int GimbalSteps = 0;
// Variables for PPM Processing
volatile int Values[CHANNELS + 1] = {0};
// *****************************************************
void setup() {
// Serial Communcication Output
Serial.begin(115200);
// Settings up MODE pins
pinMode(PPM_PIN, INPUT);
pinMode(MODE_PIN_OUT, OUTPUT);
pinMode(MODE_PIN_IN, INPUT_PULLUP);
digitalWrite(MODE_PIN_OUT, LOW);
// Setting up Gimbal
Gimbal.attach(GIMBAL_PIN);
Gimbal.writeMicroseconds(GimbalState);
}
void loop(){
// Wait for Sync on Signal
while(pulseIn(PPM_PIN, HIGH) < 2500){}
// Processing PPM Signal
for (int Channel = 1; Channel <= CHANNELS; Channel++) {
Values[Channel] = pulseIn(PPM_PIN, HIGH);
}
// Determinig the Signal for easier handling
int Signal = Values[CHANNEL_SIGNAL];
if (Signal <= 1800 && Signal >= 1500) {
Signal = SIGNAL_VIDEO;
} else if (Signal <= 1200 && Signal >= 900) {
Signal = SIGNAL_PHOTO;
} else {
Signal = SIGNAL_BASE;
}
// Only do something whenever Signal changes
if (LastSignal != Signal) {
/*
* Figuring out which Key was actually pressed ...
* This is a bit tricky as there are only 3 Signal States and the SIGNAL_BASE is shared by both Buttons
* To solve this we need to maintain the State of the VideoMode as well as the LastSignal.
*/
int KeyPressed;
switch(Signal) {
case SIGNAL_VIDEO:
KeyPressed = SIGNAL_VIDEO;
break;
case SIGNAL_PHOTO:
KeyPressed = SIGNAL_PHOTO;
break;
case SIGNAL_BASE: break;
}
// "MODE 3":
if (KeyPressed == SIGNAL_VIDEO) {
GimbalSteps = SPEED;
} else if (KeyPressed == SIGNAL_PHOTO) {
GimbalSteps = -SPEED;
} else {
GimbalSteps = 0;
}
// Overwrite Last Signal
LastSignal = Signal;
} //if
// Write GimbalState but maintain MIN/MAX Angles and stop movment if exceeded
if (GimbalState + GimbalSteps > MAX) {
GimbalState = MAX;
GimbalSteps = 0;
} else if (GimbalState + GimbalSteps < MIN) {
GimbalState = MIN;
GimbalSteps = 0;
} else {
Gimbal.writeMicroseconds(GimbalState += GimbalSteps);
}
}
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment