Радиоуправляемый дирижабль для GoPro

Кто из нас в детстве не мечтал о домашнем Дирижабле Киров из культовой Red Alert. В этой статье мы расскажем как собрать настоящий дирижабль, пульт дистанционного управления, электронный стабилизатор для бортовой камеры и аппарат для сварки плёнки.

Видеоинструкции

Часть первая. Рассчитываем параметры дирижабля и выбираем материал оболочки. Собираем машинку для пайки баллона, бортовую электронику, электронный стабилизатор и пульт дистанционного управления.

Часть вторая. Собираем каркас, накачиваем баллон гелием и учимся летать.

Что потребуется

  1. Iskra Neo x2 шт.
  2. Troyka Shield x2 шт.
  3. Приёмо-передатчик на 433Мгц HC-11 x2 шт
  4. Iskra Nano Pro x1 шт.
  5. Двигатели с винтами x2 шт.
  6. Breadboard Half x1 шт.
  7. Блоки Hotend'а от 3D принтера x2 шт.
  8. Нагреватель от 3D принтера 40 Вт на 12 В x2 шт.
  9. Термистор в корпусе от 3D принтера x2 шт.
  10. Провод с вилкой сети 220 В x1 шт.
  11. карбоновый пруток 2 мм x1000 мм x16 шт.
  12. шпилька М3 x1 м x1 шт.
  13. Двухсторонний скотч 3M x1 шт.
  14. Плёнка полипропиленова 1 м x20 м x1 шт.
  15. Баллон гелия 10 л, 150 атм x1 шт.

Бортовая электроника

Электроника

  1. Для начала возьмём Iskra Nano Pro и впаяем её в макетную плату.
  2. Теперь с другой стороны макетки впаяем пару модулей Н-мост (Troyka-модуль).
  3. Ломаем на части длинную гребёнку штырьковых соединителей и распаиваем в соответствии со схемой.
  4. Последним компонентом впаянным в макетку станет модуль приёмо-передатчика HC-11.
  5. Соединяем линии питания. Красные провода соединяют линию +, а чёрные -. При этом снизу и сверху отдельные линии питания для электроники с передатчиком и для сервоприводов с двигателями.
  6. Соединяем линии передачи данных модуля HC-11 и Iskra Nano Pro.
  7. Паяем провода соединяющие шину I2C от контроллера к датчику положения IMU.
  8. Паяем провода управления сервоприводами стабилизатора камеры.
  9. Паяем провода управления сервоприводами тангажа.
  10. Паяем провода управления двигателями. Контакты с маркировкой E модулей Н-мост (Troyka-модуль) соединяются с Iskra Nano Pro, а контакты D соединим с линией питания. Изменять направление вращения двигателей нет необходимости. Винты установленные на вал движка умеют грести только в одном направлении.
  11. Подсоединим все внешние компоненты к макетной плате.
  12. Последний этап подключение модулей Power Bank (Li-Ion, 2000 мА·ч). Модуль расположенный вверху схемы питает электронику. Модуль расположенный внизу схемы питает двигатели и сервоприводы.

Бортовая электроника код

Для прошивки бортовой электроники необходимо в Arduino IDE добавить поддержку платформ Iskra. И установить библиотеки:

blimp.ino
#include <EasyTransfer.h>
#include <Servo.h>
#include <Wire.h>
#include <TroykaIMU.h>
 
#define BETA 0.22
#define LEFT_MOTOR_DIR A1
#define LEFT_MOTOR_PWM 11
#define RIGHT_MOTOR_DIR A2
#define RIGHT_MOTOR_PWM 2
#define ROLL_SERVO_R 6
#define ROLL_SERVO_L 8
#define CAM_PITCH_SERVO 7
#define CAM_ROLL_SERVO 9
 
EasyTransfer ET;
Servo rollServoR;
Servo rollServoL;
Servo camPitchServo;
Servo camRollServo;
Madgwick filter;
Accelerometer accel;
Gyroscope gyro;
Compass compass;
 
struct RECEIVE_DATA_STRUCTURE {
  int throttle = 0;
  int pitch = 0;
  int yaw = 0;
  int camPitch = 0;
  int camRoll = 0;
};
RECEIVE_DATA_STRUCTURE mydata;
 
float gx, gy, gz, ax, ay, az, mx, my, mz;
float yaw, pitch, roll;
float fps = 100;
const double compassCalibrationBias[3] = {
  524.21,
  3352.214,
  -1402.236
};
const double compassCalibrationMatrix[3][3] = {
  {1.757, 0.04, -0.028},
  {0.008, 1.767, -0.016},
  { -0.018, 0.077, 1.782}
};
 
int Px = 90;
int Py = 90;
long AsixTime = 0;
long lastTimeConnect = 0;
 
void setup() {
  Serial.begin(115200);
  ET.begin(details(mydata), &Serial);
  pinMode(13, OUTPUT);
  rollServoR.attach(ROLL_SERVO_R);
  rollServoL.attach(ROLL_SERVO_L);
  accel.begin();
  gyro.begin();
  compass.begin();
  compass.calibrateMatrix(compassCalibrationMatrix, compassCalibrationBias);
  camPitchServo.attach(CAM_PITCH_SERVO);
  camRollServo.attach(CAM_ROLL_SERVO);
  AsixTime = millis();
  pinMode(LEFT_MOTOR_DIR, OUTPUT);
  pinMode(RIGHT_MOTOR_DIR, OUTPUT);
}
 
void loop() {
  if (ET.receiveData()) {
    if (millis() - lastTimeConnect > 1000) {
      Serial.write('G');
      lastTimeConnect = millis();
    }
    rollServoR.write(mydata.pitch);
    rollServoL.write(180 - mydata.pitch);
    digitalWrite(LEFT_MOTOR_DIR, HIGH);
    digitalWrite(RIGHT_MOTOR_DIR, HIGH);
    analogWrite(LEFT_MOTOR_PWM, constrain(mydata.throttle - mydata.yaw, 0, 255));
    analogWrite(RIGHT_MOTOR_PWM, constrain(mydata.throttle + mydata.yaw, 0, 255));
  }
  unsigned long startMillis = millis();
  accel.readGXYZ(&ax, &ay, &az);
  gyro.readRadPerSecXYZ(&gx, &gy, &gz);
  compass.readCalibrateGaussXYZ(&mx, &my, &mz);
  filter.setKoeff(fps, BETA);
  filter.update(gx, gy, gz, ax, ay, az, mx, my, mz);
  camPitchServo.write(constrain(mydata.camPitch + filter.getRollDeg(), 0, 180));
  camRollServo.write(constrain(mydata.camRoll - filter.getPitchDeg(), 0, 180));
  unsigned long deltaMillis = millis() - startMillis;
  fps = 1000 / deltaMillis;
}

Стабилизатор камеры

STL модели для печати можно скачать тут.

Машинка для сварки плёнки

Сварка полипропиленовой плёнки оказалась достаточно сложна. Проблема в то, что полипропилен плавится при ​~170 °C​ и если оба куска свариваемой плёнки не прогреть до температуры плавления то качественного шва, нам не видать. Для качественной сварки была собрана небольшая машинка. Напечатанный корпус состоит из двух деталей. Первая деталь основания удерживает сервопривод и фанерное крепление нагревателя с термистором. Вторая деталь крепится в на качалку сервопривода и удерживает фанерное крепление второго нагревателя. Отдельно вынесена кнопка для активации машинки. При включении нагреватели набирают и удерживают температуру около ​200 °C,​ а по нажатию кнопки сервопривод смыкает нагреватели и удерживает в таком положении 7 секунд. Для сварки необходимо поместить плёнки между нагревателями и нажать на кнопку.

Данная машинка потенциально пожароопасна,​ потому как в ней есть нагревающиеся части. Не оставляйте работающее устройство без присмотра.

Электроника

Код сварочной машинки

welding.ino
#include <PID_v1.h>
#include <TroykaButton.h>
#include <Servo.h>
#define PIN_INPUT A0
#define PIN_INPUT1 A1
#define PIN_OUTPUT 11
#define PIN_OUTPUT1 9
#define B 3950 // B-коэффициент
#define SERIAL_R 100000 // сопротивление последовательного резистора, 100 кОм
#define THERMISTOR_R 100000 // номинальное сопротивления термистора, 100 кОм
#define NOMINAL_T 25 // номинальная температура (при которой TR = 100 кОм)
double Setpoint, Setpoint1, Input, Input1, Output, Output1;
double aggKp = 1.3, aggKi = 0.13, aggKd = 0.3;
double consKp = 1.1, consKi = 0.13, consKd = 0.25;
long lastTimeClick = 0;
PID myPID(&Input, &Output, &Setpoint, consKp, consKi, consKd, DIRECT);
PID myPID1(&Input1, &Output1, &Setpoint1, aggKp, aggKi, aggKd, DIRECT);
Servo myServo;
TroykaButton button(2);
void setup()
{
 
  pinMode( PIN_INPUT, INPUT );
  pinMode( PIN_INPUT1, INPUT );
  Setpoint = 205;
  Setpoint1 = 205;
  myPID.SetMode(AUTOMATIC);
  myPID1.SetMode(AUTOMATIC);
  myServo.attach(5);
  myServo.write(0);
  button.begin();
 
}
 
void loop()
{
  button.read();
  if (button.isClick()) {
    myServo.write(179);
    lastTimeClick = millis();
  }
  if (millis() - lastTimeClick > 7000) {
    myServo.write(0);
  }
  long g = 0;
  for (int i = 0; i <= 10; i++) {
    g += analogRead( PIN_INPUT );
  }
  g /= 10;
  Input = temperatureCalc(g);
  myPID.Compute();
  analogWrite(PIN_OUTPUT, Output);
  g = 0;
  for (int i = 0; i <= 10; i++) {
    g += analogRead( PIN_INPUT1 );
  }
  g /= 10;
  Input1 = temperatureCalc(g);
  myPID1.Compute();
  analogWrite(PIN_OUTPUT1, Output1);
  Serial.println("INPUT = " + String(Input) + '\t' + "OUTPUT = " + String(Output) + '\t' + "INPUT1 = " + String(Input1) + '\t' + "OUTPUT1 = " + String(Output1));
}
float temperatureCalc(int t) {
  float tr = 1023.0 / t - 1;
  tr = SERIAL_R / tr;
  float steinhart;
  steinhart = tr / THERMISTOR_R; // (R/Ro)
  steinhart = log(steinhart); // ln(R/Ro)
  steinhart /= B; // 1/B * ln(R/Ro)
  steinhart += 1.0 / (NOMINAL_T + 273.15); // + (1/To)
  steinhart = 1.0 / steinhart; 
  steinhart -= 273.15;
  return steinhart;
}

Сборка каркаса баллона

Пульт

Электроника

  1. На Iskra Nano Pro установим Power Shield и Troyka Shield.
  2. Соединим все модули с Troyka Shield с помощью проводов идущих в комплекте с модулями.

Пульт код

Что бы успешно загрузить код в пульт потребуется библиотека TroykaButton

blimp_rc.ino
#include <EasyTransfer.h>
#include <TroykaButton.h>
EasyTransfer ET;
 
#define THROTTLE_AXIS A0
#define PITCH_AXIS A3
#define YAW_AXIS A1
#define CAM_PITCH_AXIS A2
#define CAM_ROLL_AXIS A4
#define CAM_RESET_POSITION A5
#define RED_LED 13
#define GREEN_LED 8
#define RF_MODULE_SET_PIN 2
#define RF_MODULE_UART_SPEED 115200
 
struct SEND_DATA_STRUCTURE {
  int throttle = 0;
  int pitch = 0;
  int yaw = 0;
  int camPitch = 0;
  int camRoll = 0;
};
int Px = 90;
int Py = 90;
long lastTimeConnect = 0;
bool connectFlag = false;
long AsixTime = 0;
long lastTimeSendData = 0;
SEND_DATA_STRUCTURE mydata;
TroykaButton resetCamPosition(CAM_RESET_POSITION);
void setup() {
  Serial.begin(115200);
  Serial1.begin(RF_MODULE_UART_SPEED);
  ET.begin(details(mydata), &Serial1);
  pinMode(RF_MODULE_SET_PIN, OUTPUT);
  digitalWrite(RF_MODULE_SET_PIN, HIGH);
  pinMode(RED_LED, OUTPUT);
  pinMode(GREEN_LED, OUTPUT);
}
 
void loop() {
  resetCamPosition.read();
  while (Serial1.available() > 0) {
    char b = Serial1.read();
    if (b == 'G') {
      connectFlag = true;
      lastTimeConnect = millis();
    }
  }
  if (millis() - lastTimeConnect > 3000) {
    connectFlag = false;
  }
  if (connectFlag) {
    digitalWrite(GREEN_LED, HIGH);
    digitalWrite(RED_LED, LOW);
  } else {
    digitalWrite(RED_LED, HIGH);
    digitalWrite(GREEN_LED, LOW);
  }
  if (resetCamPosition.isClick()) {
    Px = 90;
    Py = 90;
  } else {
    int Vx = map(analogRead(CAM_PITCH_AXIS), 0, 1023, -4, 4);
    int Vy = map(analogRead(CAM_ROLL_AXIS), 0, 1023, -4, 4);
    if (millis() - AsixTime > 50) {
      if (Vx < -1 || Vx > 1) {
        Px += Vx;
      }
      if (Vy < -1 || Vy > 1) {
        Py += Vy;
      }
      AsixTime = millis();
    }
  }
  mydata.camPitch = Px;
  mydata.camRoll = Py;
  int temp = constrain(map(analogRead(THROTTLE_AXIS), 600, 1023, 0, 255), 0, 255);
  if (temp < 20) {
    mydata.throttle =  0;
  } else {
    mydata.throttle =  temp;
  }
  mydata.pitch = constrain(map(analogRead(PITCH_AXIS), 0, 1023, 0, 180), 0, 180);
  temp = constrain(map(analogRead(YAW_AXIS), 0, 1023, -255, 255), -255, 255);
  if ((temp > -20) && (temp < 20)) {
    mydata.yaw = 0;
  } else {
    mydata.yaw = temp;
  }
  if (millis() - lastTimeSendData > 100) {
    ET.sendData();
    lastTimeSendData = millis();
    Serial.println("Throttle = " + String(constrain(map(analogRead(THROTTLE_AXIS), 600, 1023, 0, 255), 0, 255)) + " Yaw = " + String(constrain(map(analogRead(YAW_AXIS), 0, 1023, -255, 255), -255, 255)));
  }
}

Схема структора