Serielle Ansteurung der ESC

Status
Nicht offen für weitere Antworten.

cesco1

Erfahrener Benutzer
#1
Anstatt die ESC eines copters mit dem üblichen PWM anzusteuern kann man das auch seriell machen. Die simonk / konze ESC firmware beinhaltet schon ein recht geniales serielles protokoll. Ich nenne es das konze-protokoll. Genial deshalb weil alle ESC zusammen auf ein serielles signal hören und sich die eigenen daten anhand ihrer ID heraussuchen. Man braucht also auch für einen octacopter nur eine uart auf der FC.

Das funktioniert nur bei ESC die pwm-in auch zum rxd pin durchgeschleift haben. Das sind z.b. die "HK blue series 12A und 20A", und die "hk 20A ubec", aber auch modernere wie z.b. die "Tarot TL300G5 6A" (z.z. keine firmware für die tarot).

An der firmware muss man "uart" einschalten und "int0" und "icp" im typenfile ausschalten. Dazu noch eine kleine änderung wegen dem bootloader.

Firmware für "bs_nfet.hex" ESC habe ich getestet und auf rcgroups zum download bereit.
simonk esc kompatibilitäts liste
Download, ohne garantie, auf eigenes risiko

Der FC code muss natürlich auch geändert werden. Einen entsprechenden driver für multiwii habe ich getestet und geflogen. Ein driver für baseflight habe ich getestet aber nicht geflogen. Driver für cleanflight oder betaflight habe ich nicht. Die multiwii / baseflight teile werde ich hier unten reinstellen.

F450 copter mit seriellen esc, flugbereit:


ToDo liste:

Das Konze protokoll hat eine auflösung von 200 schritten und eine maximale refresh rate von etwas unter 2ms. Für mich reicht das volkommen aus, das fliegt sich wunderbar, sehr reaktionsschnell, sehr präzise, aber da geht noch viel mehr. Bei 1ms looptime wäre wohl 128kbaud das richtige, das geht problemlos. Etwas schwieriger ist die auflösung hochzuschrauben. Ich denke 12 bit / 4096 steps reichen. Das sind dann 7 bytes per message bei 4 motoren. Durchaus machbare firmwareänderung.

Die motor ID ist fix in der firmware eingestellt. Das heisst jeder motor braucht einen eigene firmware. Das ist schrott. Die ID gehört ins eeprom und muss sich leicht umprogrammieren lassen.

Das serielle Konze protokoll ist nur in simonk firmware enthalten, bei blheli nicht. Das müsste zuerst in avr-blheli, und dann in silabs-blheli reingepackt werden ...

Die seriellen driver sollten für cleanflight / betaflight implementiert werden. Das ist relativ einfach.

Dank des kürzeren protokolls hat 128kbaud bessere auflösung und ist schneller als dshot150. 256kbaud (getestet und läuft) ist schneller asl dsot300. 512kbaud hab ich nicht getestet, da seriell aber weniger pegelwechsel als dshot hat dürfte es auch schneller sein. Ich sage SESC ist das bessere / einfachere / schnellere protokoll.

Und ... man kann damit 10 eur F4 boards verwenden. :)
 
Zuletzt bearbeitet:

cesco1

Erfahrener Benutzer
#2
SESC driver für baseflight (basic) :

Code:
#include "board.h"
#include "mw.h"

// Driver for serial esc (konze protocol) on UART2

#define SESC_SYNCBYTE 0xF5
#define SESC_MAX_CHANNEL 4

void sEscInit(void)
{
	core.sescport = uartOpen(USART2, NULL, 38400, MODE_RXTX);
}

void sEscSend(void)
{
	int i;
	uint8_t sEscData;
                
	serialWrite(core.sescport,SESC_SYNCBYTE);
	for (i = 0; i < SESC_MAX_CHANNEL; i++) 
	{
		sEscData = constrain(((motor[i] - 1000) >> 2),0,200);
	  serialWrite(core.sescport,sEscData);
	}
}
 

cesco1

Erfahrener Benutzer
#3
SESC driver für multiwii (geflogen):

Output:
Code:
void writeMotors()
{
   uint8_t mot,i;
   
   serializeESC(0xF5);
   if (f.ARMED)
     for (i=0;i<4;i++)
     {  // 1100..1900 to 0..200
       mot = constrain((motor[i]-1100)>>2,1,200); 
       serializeESC(mot);
     }
   else 
     for (i=0;i<4;i++) serializeESC(0);
     
   serialWriteESC();
}

void initOutput() 
{
    SerialOpen(SERIALESCPORT,38400);  //5 byte at 3.8 byte per ms
    
    for (uint8_t i =0;i<NUMBER_MOTOR;i++) motor[i] = MINCOMMAND;
    writeMotors();
}
Serial:
Code:
void serializeESC(uint8_t a) 
{
  uint8_t t = serialHeadTX[SERIALESCPORT];
  if (++t >= TX_BUFFER_SIZE) t = 0;
  serialBufferTX[t][SERIALESCPORT] = a;
  serialHeadTX[SERIALESCPORT] = t;
}

void serialWriteESC()
{
  #if (SERIALESCPORT == 0)
    UCSR0B |= (1<<UDRIE0);
  #endif
  #if (SERIALESCPORT == 1)
    UCSR1B |= (1<<UDRIE1);
  #endif
  #if (SERIALESCPORT == 2)
    UCSR2B |= (1<<UDRIE2);
  #endif
  #if (SERIALESCPORT == 3)
    UCSR3B |= (1<<UDRIE3);
  #endif
}
 
Zuletzt bearbeitet:

nichtgedacht

Erfahrener Benutzer
#4
Die motor ID ist fix in der firmware eingestellt. Das heisst jeder motor braucht einen eigene firmware. Das ist schrott. Die ID gehört ins eeprom und muss sich leicht umprogrammieren lassen.

Dank des kürzeren protokolls hat 128kbaud bessere auflösung und ist schneller als dshot150. 256kbaud (getestet und läuft) ist schneller asl dsot300. 512kbaud hab ich nicht getestet, da seriell aber weniger pegelwechsel als dshot hat dürfte es auch schneller sein. Ich sage SESC ist das bessere / einfachere / schnellere protokoll.

[/URL]
In dem Übertragungsbeispiel, das Du auf rcgroups geposted hast sehe ich keine ID. Ist die ID im Protokoll nur die Position des Bytes im Datenstrom nach dem Sync Byte?

Wie wird dann eine höhere Auflösung realisiert? Mit 2 Bytes pro Kanal(ID) in der Übertragung?

Gruß
Dieter
 

cesco1

Erfahrener Benutzer
#5
Ist die ID im Protokoll nur die Position des Bytes im Datenstrom nach dem Sync Byte?
Genau. Nicht mal die anzahl motoren muss bekannt sein. Und es gibt dank wertebeschränkung auf 0..200 keine sync fehltrigger. Mir gefällt das.

Wie wird dann eine höhere Auflösung realisiert?
Da bin ich noch am überlegen.
8 bit sync
8 bit motor1,
8 bit motor2,
4 bit motor1 und 4 bit motor2
und die motordaten dann wiederholen. Bedingt dass eine gerade anzahl motoren definiert wird.
Vielleicht auch nur 11 bit motor, und ein bit "sende mal telemetrie". Sync ist nicht mehr so knallsicher eindeutig, aber erfahrungsgemäss ist das kein probelm.

Beim fliegen mit 200 steps / 62500 baud hab ich nix vermisst ... im gegenteil. Ich bin aber nicht der profi pilot.

btw MPU9250 ist bestellt :)
 
Zuletzt bearbeitet:

nichtgedacht

Erfahrener Benutzer
#6
Da bin ich noch am überlegen.
8 bit sync
8 bit motor1,
8 bit motor2,
4 bit motor1 und 4 bit motor2
und die motordaten dann wiederholen. Bedingt dass eine gerade anzahl motoren definiert wird.
Warum nicht ein Start Byte und dann für jeden Motor 2 Bytes. Lässt sich doch in 1ms schon ab ab 90k Baud übertragen für 4 ESCs.

Deine Gedanken zum Sync Problem habe ich nicht verstanden. Das ESC muss doch so oder so zusehen, dass das Sync Byte an der Spitze steht. Also nach dem Lesen und detektieren vom Sync Byte noch eine bestimmte Anzahl Bytes weiter lesen oder alle Bytes auf einmal lesen und das weitere Lesen soviel verzögern bis das Sync Byte an der Spitze zu liegen kommt.
Dazu braucht es aber eine deutliche Lücke zwischen den Frames oder Null Bytes die ignoriert werden dürfen. Wahrscheinlich geht es ohne eine Lücke gar nicht.

Eine STM32F103 MCU reicht zum Steuern bis 2.25 MBits/s. Also mit dem standard 10 Bit/Byte Protokoll könnten dann 25 Frames (ohne Lücke) für 4 ESCs in 1 ms übertragen werden mit 16 Bit Auflösung pro Kanal wenn man will. Oder anders gesagt das würde dann bis 25 kHz Framerate gehen. Für Oktokopter dann nur noch bis 6 kHz Framerate. Wenn mal Lücken von 1 Frame Länge lässt ist eben alles nur die Hälfte aber immer noch rasend schnell.

Das steht und fällt alles mit den MCUs in den ESCs, oder? Was können die den so?

Arbeitest Du selbst an dem Assembler Code?









Das
 

cesco1

Erfahrener Benutzer
#7
Warum nicht ein Start Byte und dann für jeden Motor 2 Bytes.
Simonk skaliert den input auf 800 schritte. Da sind 16 bit verschwendung. Aber einfacher ist es, hast du recht.

Dazu braucht es aber eine deutliche Lücke zwischen den Frames
Das konze protokoll braucht keine lücke. Die daten können nicht als sync interpretiert werden.

Das feststellen einer lücke ist recht aufwendig. Da muss man einen timer lesen und die differenz bilden. Ein protokoll mit eindeutigem sync ist einfacher.

Das steht und fällt alles mit den MCUs in den ESCs, oder? Was können die den so?
Ich glaube ein atmega8 schafft 2mbit/s.
 
Zuletzt bearbeitet:

nichtgedacht

Erfahrener Benutzer
#8
Simonk skaliert den input auf 800 schritte. Da sind 16 bit verschwendung. Aber einfacher ist es, hast du recht.

Das konze protokoll braucht keine lücke. Die daten können nicht als sync interpretiert werden.

Die volle Auflösung muss man ja nicht nutzen.

Die Daten müssen ja auch noch verarbeitet werden zwischendurch. Wie soll denn da der Ablauf ohne Lücke zwischen den Frames sein? Ich habe mich noch nicht in den Assembler Code vertieft, aber letztlich braucht man da doch wohl ein Array mit dem Sync Byte an der Spitze und einen Index der auf die eigenen 2 Bytes zielt. Also muss man das Array mit dem ersten eintreffenden Byte eines Frames beginnen zu füllen. Schau Dir mal den Code an mit dem ich die RC Daten in meiner Flightcontrol lese, dann siehst Du was ich meine.
 

OlliW

Erfahrener Benutzer
#9
einen ähnlichen Ansatz benutze ich zur Ansteuerung der MotorModule "meines" Gimbal-Controllers (STorM32 NT)

das Sync Problem löst man IMHO am Besten indem man sicherstellt dass das Syncbyte nie in den regulären Daten vorkommt, wie bei konze. Ich mache das allerdings so, dass ein gesetztes 7tes Bit ein Syncbyte kennzeichnet. Die nachfolgenden Daten müssen also in 7-bit Päckchen aufgeteilt werden, geht aber Dank shift-Befehlen effizient. Zur Absicherung kommt als letztes Byte ein xor crc. xor lässt sich auch effizient berechnen. Das sind bei 4 Motoren 1+2x4+1 = 10 Byte.
Das Synbyte hat dann noch Platz für weitere Funktionen, wie z.B. ein Bit zum Anzeigen eines "Befehls" um z.B. Daten ins EEPROM zu speichern, oder in Eurem Fall könnte man die Anzahl der Motoren angeben um die Datenlänge zu optimieren wenn man wollte, usw. .

Damit UART, in der heutigen Zeit der ultra-schnellen Protokolle, konkurenzfähig ist muss man allerdings zwingend zu hohen Baudraten gehen. Ich z.B. benutze 2Mbps. 8-Bitter werden damit Mühe haben.

btw, 2Mbps weil die meisten USB-TTL Adpater das noch können, bei 2.25Mbps hatte ich Probleme, d.h. ich kann mit jedem Terminal direkt den Bus überprüfen. Bei 2Mbps sind 10 Byte 50 us, oder max. 20 kHz. D.h. die "gebräuchlichen" 8kHz Looprates würden auch für Octos noch gut gehen.

Nachteilig beim Eindraht-UART ist, dass es mühevoller ist eine Telemetrie zu koordinieren. Dazu könnte der Platz im Syncbyte evtl. auch nützlich sein.

UART ist gut, ich bin auch ein UART-Fan ... allerdings muss man sich - IMHO - das Protokol vorher gut überlegen, damit man nachher nicht schnell von den Realitäten eingeholt wird

:)
 

cesco1

Erfahrener Benutzer
#10
Die Daten müssen ja auch noch verarbeitet werden zwischendurch. Wie soll denn da der Ablauf ohne Lücke zwischen den Frames sein?
Das ist interruptgesteuert. Die cpu wartet ja nicht und pollt den eingang. Das ist eine uart, hardware.

Ein array gibts auch nicht. Die daten werden im "byte empfangen" interrupt handler verarbeitet. Bei sync fängt er an bytes zu zählen. Die bytes werden weggeworfen, ausser empfangene_bytes_seit_sync = motor_id. Die einfachheit hat was geniales.

das Sync Problem löst man IMHO am Besten indem man sicherstellt dass das Syncbyte nie in den regulären Daten vorkommt, wie bei konze.
Dank dir. Gute ideen. Das mit 7 bit mit dem "Das Synbyte hat dann noch Platz für weitere Funktionen, wie z.B. ein Bit zum Anzeigen eines Befehls" ist sehr überzeugend.

Ist 2mbps in einer quadcopter umgebung nicht sehr störanfällig?

Meine idee war das konze protokoll unverändert zu lassen, 0xA5 sync, daten von 0 bis 200, und einfach noch ein byte anzuhängen das sagt wieviele male man noch 200 dauzaddieren muss.

Code:
sync, 122, 02 = 122 + 2 * 200 = 522
sync, 002, 33 = 2 + 33 * 200 = 6602
 
Zuletzt bearbeitet:

nichtgedacht

Erfahrener Benutzer
#11
OK jetzt hab ich es geschnallt. Die Payload Bytes können nicht F5 werden, weil der Wert bis max C8 gehen kann/darf so wie es jetzt ist. Beim Empfang von RC Daten z.B. SRXL ist das ja anders, weil die Nutzdaten Bytes jeden Wert annehmen können.

Also wird hier bei Konze jedes Byte on the fly getestet bis das Sync Byte auftaucht. Dann kann man man ja mit 2 Nutz Bytes in einer 16 Bit Variablen das untere Byte mit dem um 1 Bit nach rechts verschoben oberen Byte verodern und hat dann nach ausmaskieren noch 14 Bit Auflösung, wenn man will.

Wer macht jetzt den Assembler Code?
 

cesco1

Erfahrener Benutzer
#12
Die Payload Bytes können nicht F5 werden, weil der Wert bis max C8 gehen kann
Genau

Wer macht jetzt den Assembler Code?
Ich hab eine version die 2 bytes liest. Da darf man kein 0xF5 als daten senden, aber andere werte bis 800 gehen. Weitere normierungen hab ich bisher nicht geschafft. Die integration eines uart drivers in die blheli firmware scheint wichtiger.

Ein protokoll bei dem alle nicht sync 0xF5 in 0xF6 gewandelt werden ist einfach zu realisieren und verschiebt die arbeit von der ESC zur FC.
 

nichtgedacht

Erfahrener Benutzer
#13
Das github.com/sim-/tgy geraffel kann ich jetzt ohne Fehler assemblieren. Ich hab mir dazu auf meiner Linuxbox AVRA compiliert. Das war ja noch einfach. Kannst Du Deine Änderungen an tgy als Patch hier zeigen?
Hast Du Pointer auf BLHeli Software und die Tools zum bauen?
 

cesco1

Erfahrener Benutzer
#14
Ich hab die gewohnheit ziemlich viel zu löschen um den rest dann zu verstehen. Also die ganze skalierung ist raus ...

Das ist die 2 byte variante ohne bitshift.

inc file der esc
Code:
.equ	F_CPU		= 16000000
.equ	USE_INT0	= 0
.equ	USE_I2C		= 0
.equ	USE_UART	= 1
.equ	USE_ICP		= 0
tgy file
Code:
// id einstellen
.equ	MOTOR_ID	= 1	; MK-style I2C motor ID, or UART motor number

//interrupt handler
;-----bko-----------------------------------------------------------------
urxc_int:
; This is Bernhard's serial protocol implementation in the UART
; version here: http://home.versanet.de/~b-konze/blc_6a/blc_6a.htm
; This seems to be implemented for a project described here:
; http://www.control.aau.dk/uav/reports/10gr833/10gr833_student_report.pdf
; The UART runs at 38400 baud, N81. Input is ignored until >= 0xf5
; is received, where we start counting to MOTOR_ID, at which
; the received byte is used as throttle input. 0 is neutral,
; >= 200 is FULL_POWER.
	.if USE_UART
		in	i_sreg, SREG
		in	i_temp1, UDR
		cpi	i_temp1, 0xf5		; Start throttle byte sequence
		breq	urxc_x3d_sync
		sbrs	flags0, UART_SYNC
		rjmp	urxc_exit		; Throw away if not UART_SYNC
		lds	i_temp2, motor_count
		dec	i_temp2
		brne	urxc_set_exit		; Skip when motor_count != 0
		mov	rx_h, i_temp1		; Save 8-bit input
		sbr	flags1, (1<<EVAL_RC)+(1<<UART_MODE)
urxc_unknown:	
		cbr	flags0, (1<<UART_SYNC)
		rjmp	urxc_exit
urxc_x3d_sync:	
		sbr	flags0, (1<<UART_SYNC)
		ldi	i_temp2, 2*MOTOR_ID	; Start counting down from MOTOR_ID
urxc_set_exit:	
		sts	motor_count, i_temp2
		mov	rx_l, i_temp1		; Save 8-bit input
urxc_exit:	
		out	SREG, i_sreg
		reti
	.endif

// auswertung
evaluate_rc_init:
	; Fall through from evaluate_rc_init
;-----bko-----------------------------------------------------------------
; These routines may clobber temp* and Y, but not X.
evaluate_rc:
		cbr	flags1, (1<<EVAL_RC)
		mov	YL, rx_h		; Copy 8-bit input to YL
		mov	YH, rx_l
		cpi	YL, 0
		brne    notzero
		cpi YH, 0
		breq	rc_duty_set		; Power off if zero
notzero:
		adiw YL,MIN_DUTY   // add MIN_DUTY, 56
		cpi2	YL, YH, MAX_POWER, temp1
		brcs	rc_duty_set
		ldi2	YL, YH, MAX_POWER
rc_duty_set:
		sts	rc_duty_l, YL
		sts	rc_duty_h, YH
		sbrs	flags0, SET_DUTY
		rjmp	rc_no_set_duty
		ldi	temp1, RCP_TOT
		mov	rc_timeout, temp1	; Short rc_timeout when driving
		rjmp	set_new_duty_l		; Skip reload into YL:YH
rc_no_set_duty:	ldi	temp1, 12		; More than 10 needed to arm
		cp	rc_timeout, temp1
		adc	rc_timeout, ZH
		ret

// bootloader patch
.if BOOT_JUMP
boot_loader_test:
		.if USE_ICP
		sbis	PINB, rcp_in		; Skip clear if ICP pin high
		.elif USE_INT0 == 1
		sbis	PIND, rcp_in		; Skip clear if INT0 pin high
		.elif USE_UART
		sbis	PIND, rcp_in		; Skip clear if INT0 pin high
		.else
		sbic	PIND, rcp_in		; Skip clear if INT0 pin low (inverted)
		.endif
Das lesen des ersten byte ist super-würg...

rcsim2
Code:
import processing.serial.*;

// The serial port:
Serial myPort;   


int msgrate = 20;

void setup () 
{ 
  frameRate(msgrate);  
  
  // Sketch einstellen
  size (850, 850);
  stroke (255);

  // List all the available serial ports:
  println(Serial.list());

  // Open the port you are using at the rate you want:
  myPort = new Serial(this, Serial.list()[0], 38400);
  
  rect(25, 25, 800, 800);
}
 
void getinput() 
{
  int inBuf;
  while (myPort.available() > 0) 
  {
    inBuf = myPort.read(); 
    println(inBuf);
  }    
}
 
int arg1 = 0;
int arg2 = 0;
int arg1l = 0;
int arg2l = 0;
int arg1h = 0;
int arg2h = 0;

boolean mp;

void mousePressed()
{
  arg1 = constrain(mouseX - 25,0,799);
  arg2 = constrain(mouseY - 25,0,799);
  mp = true;
}



void draw () 
{
  getinput();
  
  arg1l = arg1 & 0xff;
  if (arg1l == 0xF5) arg1l = 0xF6;
  arg1h = arg1 >> 8;
  arg2l = arg2 & 0xff;
  arg2h = arg2 >> 8;
  
  myPort.write(0xf5);
  myPort.write(arg1h);
  myPort.write(arg1l);  
  //myPort.write(arg2h);
  //myPort.write(arg2l);  
  
  if (mp)
  {
    mp=false;
    print(arg1h);
    print("  ");
    print(arg1l);
    println();
  }
}
Blheli hab ich die atmel source geladen und dann ein avrstudio4 projekt gemacht.
https://github.com/bitdump/BLHeli/tree/master/Atmel

Soll ich das ganze projekt als zip hochladen?
 
Zuletzt bearbeitet:

nichtgedacht

Erfahrener Benutzer
#15
Ich kämpfe noch mit avrstudio4 unter Linux/Wine. Der sagt mir "No AVR Toolchain installation found. The AVR GCC-plug-in can still be used if you set up your own buld tools" Das obwohl ich alle AVR GCC Sachen installiert habe. Ich muss dem noch beibringen wo die liegen.

Aber lade mal das Projekt hoch.
 

nichtgedacht

Erfahrener Benutzer
#17
Es kostet mich unendlich viel Überwindung nach Windows zu booten. Das ist eine völlig fremde unlogische Umgebung für mich.

Welche Fehlermeldung hast Du bei systemWorkbench? Welche Version? Das openocd ist doch sehr gesprächig auf der Konsole auch ohne debug Meldungen einzuschalten.
 

cesco1

Erfahrener Benutzer
#19
Ich bin mit BLHeli_atmel etwas weiter.
Ich hab einfach die daten von der pwm routine ausgeschaltet und die seriellen daten drübergelegt. Läuft, lässt sich seriell steuern. Btw "damped mode" ist zum testen schrott, da fliegt beim ausschalten der ganze motor übern tisch.

BLHeli atmel hat .... 250 schritte auflösung. Ein byte. Noch weinger als simonk :( :( :(

BLHeli Projekt mit konze protokoll, afro esc, 62500 baud. Läuft. https://www.rcgroups.com/forums/showatt.php?attachmentid=10064884&d=1495631421

Mein "serialcopter"
 
Zuletzt bearbeitet:
Status
Nicht offen für weitere Antworten.
FPV1

Banggood

Oben Unten