Arduino RC servo ramp generator

Тестирование моторов+ESC на предрасположенность к потере синхронизации

Массовое строительство многороторных систем, неизбежно порождает проблемы, обусловленные недостаточной квалоификацией собирающего и неточной, а иной раз и не достоверной технической информацией на моторы изготавлеваемые в поднебесной для нужд моделистов.

Наверняка это уже где-то обсуждалось, но как то не нашлось.

Никогда ранее с данной проблемой не встречался, но на днях пришлось познакомиться. Собран коптер на базе MT3506-25 и регулей Rctimer SimonK 30A (пробовал так же ESC32). Батарея 4S, пропы 10×4.5. Происходит срыв синхронизации, и останов одного из моторов при выполнении резких маневров.

Провел испытания на стенде – да, действительно, при резком увеличении газа из некоторых положений, проблема имеет место быть. Попробовал другую случайную комбинацию – 3S, пропы 12×4.5, на первый взгляд показалось что всё в порядке, но потом, экспериментируя с газом из разных положений, всё равно добился остановки мотора.
Интересует следующее:

  • Какова группа риска (т.е. какие условия наиболее не нравятся моторам+регулям, и чреваты аварийным остановом). Например, как показывает моя практика – Мощный мотор + высоковольтная батарея + маленький пропеллер?
  • Каков алгоритм проверки Моторно+Регуляторной группы на склонность к потере синхронизации? Написал простенькую прогу для Arduino, которая раз в секунду меняет случайный сигнал на регуль. Можно оставить на полчасика поработать, но видится мне это не очень оптимально. Быть может, как это сделано в алгоритме самодиагностики ESC32 (постепенное повышение частоты вращения, с периодическим резким газованием на 20, 40, 60, и 80 %) Кто-нибудь пробовал что-то подобное?

Сергей, давайте я намекну на Вашу ошибку(на этом форуме, кстати, эта ошибка очень распространена…), а Вы на досугепогуглитеподумаете, не в этом ли дело…)
Ваш тайгер, это высокомоментный мотор рассчитаный на работу в определенном диапазоне оборотов и нагрузок, а Вы заставляете его работать с пониженной нагрузкой и повышенными оборотами… Смотрите что происходит, проп маленький, легкий, инерция никакая, мотор скачком переходит на большие обороты, регуль(особенно такое дерьмо, как рцтаймер на 30 ампер) не успевает обработать обратную связь по неактивной фазе, и некоторое время продолжает синхрить мотор, как будто тот еще разгоняется. В результате, наступает момент, когда магнит уже пролетел отталкивающий полюс и нарывается на притягивающий… Понимаете? Чтобы этого не происходило, нужно использовать подходящий проп и адекватное пропу напряжение питания, про регуль от нормального производителя я уже не напоминаю…)
Конкретно для Вашего 3506 имеющего 650 оборотов в минуту на вольт, подойдут пропеллеры 12″ на напряжение 14.8 вольта или 13-14″ на напряжение 11.1 вольта…
Кстати, при описаном процессе, когда мотор крутится быстрее чем надо, еще и мощность падает(вместе с КПД), а нагрев увеличивается…

В тестировании RC системах электропривода (ESC + BLDC motor), повторяемый сценарий был необходим, чтобы оценить изменения, такие как изменения коммутации заранее.

Часто эти изменения имеют различные воздействия в рамках быстрое ускорение или замедление медленнее изменения.

В этой статье описывается простой сигнал серво рампы генератор на основе Arduino оборудования, в этом случае с помощью Arduino Nano, но большинство Arduinos или клоны могут быть использованы или адаптированы.

Метод, используемый здесь, не делает постоянными изменения в аппаратную конфигурацию Nano. Это прошивки собранные в Arduino workbench и загрузить на Nano с помощью USB-FTDI интерфейс. Сигнал ESC берется из-контактный разъем ISP, используя адаптер кабель изготовленный из серво-удлинитель с женской конце (т.е. с женским пен) заменен 2×3 IDC заголовка плагина.


Выше показан стандартный Nano board с 9 pin ISP заголовка установлен и адаптер кабель. Примечание IDC Заголовок plug поднимает белый, красный и черный провода на контакты 1, 2 и 6.

Нано питается от servo-кабель, и прошивка начинается таймера при подаче питания в систему, и после программируемой задержки запускает вверх пандус вниз пандус.

В eLogger4 был использован для захвата напряжения, тока, сервопривод, и rpm.

Другой цикл инициируется техническое перевооружение системы, которая также запускает новую запись на сеанс в eLogger4.

Полученные данные могут быть загружены и проанализированы.


Выше показан захват диска системы, где ESC теряет синхронизацию с мотором.

Исходный код: asrg.ino . Изменения должны быть внесены по мере необходимости, чтобы создать тестовый сигнал желаемого.

/*

Servo ramp generator

Copyright: Owen Duffy 2013. All rights reserved.

*/

#include <math.h> //known bug in delay()

#define SERVOUT 12

#define LED 13

#define RATE 100

volatile int pw=1000;

volatile int pwn=0;

volatile int pwi=0;

int i;

//=================================================================================================

//this routine sets up loop variable for the int handler to send incn increnents of inc value

//then waits until there are no more increments to be applied.

void ramp(int inc,int incn){

cli();

pwi=inc;

pwn=incn;

sei();

while(pwn); //wait until request done

}

//=================================================================================================

void setup() {

pinMode(SERVOUT, OUTPUT);

digitalWrite(SERVOUT,0);

cli();//disable interrupts while we set things up

//set timer1 interrupt

TCCR1A=0;

TCCR1B=(1<<WGM12)|(1<<CS12);// Set CTC mode, CS12 bit for 256 prescaler

// set compare match register for 50Hz, 20ms update rate

OCR1A=F_CPU/(256*RATE)-1 ;

// enable timer compare interrupt

TIMSK1|=(1<<OCIE1A);

GTCCR|=(1<<PSRSYNC);// reset the prescaler

TCNT1=0;

sei();//enable interrupts, start servo signal

//signal starting up

digitalWrite(LED,1);

delay(1000);

for(i=3;i–;){

digitalWrite(LED,0);

delay(500);

digitalWrite(LED,1);

delay(500);

}

//now run the tests

ramp(100/(RATE*0.02),RATE*0.02); //quick start to idle

delay(1000);

//Simon’s jump test 100ms @ 1900, instant jump

ramp(800,1); //instant up to 1900

delay(100);

ramp(-800,1); //instant down to 1100

delay(1000);

//restart test

ramp(200/(RATE*0.1),RATE*0.1); //quick up to 1300

for(i=3;i–;){

ramp(-300/(RATE*0.05),RATE*0.05); //quick down to 1000

delay(40);

ramp(300/(RATE*0.05),RATE*0.05); //quick up to 1300

delay(2000);

}

ramp(-200/(RATE*0.1),RATE*0.1); //quick down to 1100

//rapid mid range test

ramp(300/(RATE*0.05),RATE*0.05); //quick up to 1400

for(i=5;i–;){

ramp(200/(RATE*0.05),RATE*0.05); //quick up to 1600

delay(50);

ramp(-200/(RATE*0.05),RATE*0.05); //quick down to 1400

delay(50);

}

ramp(-300/(RATE*0.1),RATE*0.1); //quick down to 1100

delay(2000);

//other tests

ramp(900/(RATE*2),RATE*2); //slow up ramp to max

delay(500);

ramp(-150/(RATE*0.5),RATE*0.5); //quick down to 1850

delay(500);

for(i=3;i–;){

ramp(-650/(RATE*0.5),RATE*0.5); //quick down to 1200

ramp(650/(RATE*0.5),RATE*0.5); //quick up to 1850

ramp(-250/(RATE*0.2),RATE*0.2); //quick down to 1200

ramp(250/(RATE*0.2),RATE*0.2); //quick up to 1850

ramp(-850/(RATE*0.5),RATE*0.5); //quick down to 1000

ramp(400/(RATE*0.2),RATE*0.2); //quick up to 400

delay(500);

ramp(450/(RATE*0.2),RATE*0.2); //quick up to 1850

delay(1000);

}

ramp(-750/(RATE*2),RATE*2); //slow down to 1100 (idle)

delay(2000);

ramp(-100/(RATE*0.5),RATE*0.5); //quick down to 1000 (stop)

digitalWrite(LED,0); //all over

}

//=================================================================================================

ISR(TIMER1_COMPA_vect){

//send servo signal

digitalWrite(SERVOUT,1);

delayMicroseconds(pw-3);

digitalWrite(SERVOUT,0);

//update loop

if(pwn){

pw+=pwi;

pwn–;

}

}

//=================================================================================================

void loop() {

}

//=================================================================================================

Вариант от пользователя dROb (для ее работы потребуется ARDUINO UNO + LCD KEYBOARD шилд.

/*************************************************************************************

Sergey dROb, Oct 2014, http://forum.rcdesign.ru/member.php?u=29285

This program will test ESC+motor (or servo), sending range of valid PPM signals to the output pin at “servoPin”

Primarily, this is used to detect sync issues, happening when Motor is quickly accelerating from low to high speed.

If LCD display is connected – it displays number of test and Start-End microseconds of PPM signal (you can then record, which scenario is problem for your motor)

Connection: Plug the LCD Keypad to the Arduino. Output PPM will be on servoPin. Conect GND and servoPin to ESC.

Discussion: http://forum.rcdesign.ru/f123/thread380040.html

**************************************************************************************/

#include <LiquidCrystal.h>

#include <Servo.h>

Servo myservo; // create servo object to control a servo

LiquidCrystal lcd(8, 9, 4, 5, 6, 7); // select the pins used on the LCD panel

int servoPin = 22;

int lcd_key = 0;

int adc_key_in = 0;

#define btnRIGHT 0

#define btnUP 1

#define btnDOWN 2

#define btnLEFT 3

#define btnSELECT 4

#define btnNONE 5

void setup(){

lcd.begin(16, 2);

lcd.setCursor(0,0);

lcd.print(“Starting motor”);

lcd.setCursor(0,1);

lcd.print(“In 3 seconds..”);

myservo.attach(servoPin);

myservo.writeMicroseconds(950); // Init ESC

delay(3000); // Waiting 3 seconds to avoid chopping of user hands

myservo.writeMicroseconds(1250); // Start motor on low speed

}

void loop(){

int test_no=1;

int start_uS;

int end_uS;

int tact_delay=1000;

lcd.clear();

lcd.print(“No: Start: End:”);

// Main cycle – start series of cycles, when motor jumps from set of speeds to higher set of speeds.

for (start_uS=1100; start_uS<=1900; start_uS+=100){ // Start PPM from which motor will jump to End PPM

servoOutput(start_uS);

delay(tact_delay);

for (end_uS=start_uS+100; end_uS<=1900; end_uS+=100){ // End PPM of the current cycle

displayData(test_no, start_uS, end_uS);

servoOutput(end_uS);

tact_delay=end_uS – start_uS; if (tact_delay<400) tact_delay=400;// Intellectual delay. Pause will be bigger if motor have to change the speed a lot. But not less 0.4 sec

delay(tact_delay);

servoOutput(start_uS);

delay(tact_delay);

test_no++;

}

}

lcd.setCursor(0,1);

lcd_key = read_LCD_buttons();

dispatch_keys(lcd_key);

}

void servoOutput(int uS){

myservo.writeMicroseconds(uS);

}

void displayData(int test_no, int s_uS, int e_uS){

lcd.setCursor(1,1);

lcd.print(test_no);

lcd.setCursor(5,1);

lcd.print(s_uS);

lcd.setCursor(11,1);

lcd.print(e_uS);

lcd.print(” “);

}

//////////////////////////////////////////////////////////////////////////////

// This is actually not really used. Added to be able to get Keypad presses //

//////////////////////////////////////////////////////////////////////////////

int read_LCD_buttons(){ // read the buttons

adc_key_in = analogRead(0); // read the value from the sensor

if (adc_key_in > 1000) return btnNONE;

if (adc_key_in < 50) return btnRIGHT;

if (adc_key_in < 250) return btnUP;

if (adc_key_in < 450) return btnDOWN;

if (adc_key_in < 650) return btnLEFT;

if (adc_key_in < 850) return btnSELECT;

return btnNONE; // when all others fail, return this.

}

void dispatch_keys(int key){

switch (key){

case btnRIGHT:{

break;

}

case btnLEFT:{

break;

}

case btnUP:{

lcd.print(“UP “);

break;

}

case btnDOWN:{

lcd.print(“DOWN “);

break;

}

case btnSELECT:{

lcd.print(“SELECT”);

break;

setup();

}

case btnNONE:{

//lcd.print(“NONE “);

break;

}

}

}