Hello all, as of writing I’m still hard at work on the Gen 2 electronics. As part of this, I’ve recently struggled getting a new ESC protocol to work. The internet desperately needs all of the info about it in one place, so here we go!
ESC Protocols - Quick Overview
Most ESC’s support communicating over several protocols. Start talking in one of them and the ESC will automatically figure it out and start accepting commands.
A quick list of the most common protocols:
Standard PWM, also known as servo control. A 1ms pulse is low, 2ms pulse is high.
OneShot125: A faster PWM protocol, 125us pulse is low, 250us pulse is high
MultiShot: the fastest PWM protocol used. 5us pulse is low, 25us pulse is high
DShot: a digital protocol. baud rates from 150Kb/s to 1200Kb/s
As quadcopters keep getting better, they are demanding faster update rates out of their ESC’s. The ESC hardware and software has been desperately keeping pace.
I mentioned in previous posts that the ESC’s we were using weren’t responsive enough for the meltybrain algorithm, and it limited our translation speed. It turns out that part of that is the protocol we used.
We were using standard PWM protocol, which limited our update rate to only 500Hz. The analog nature of the protocol also caused us trouble, with the ESC’s being more susceptible to noise.
We can now take advantage of faster protocols, with better noise tolerance. I’m going to focus on the one we ended up using.
DShot
We picked DShot for two reasons: speed and noise. Being a digital protocol, you wont have small inaccuracies or noise issues. If you command 50% throttle, the ESC will see 50% throttle. And you can find ESC’s that support up to 1200Kb baud, which is pretty fast!
A lot has been written about the basic details of DShot, like this excellent overview at blck.mn, so I wont get too in-depth here. I’ll instead focus on the practicalities of implementing a DShot controller.
The Basic Idea
DShot is a digital protocol with several rate options, ranging from 150,000 bits per second to 1,200,000 bits per second. It’s a packet based protocol, where each packet consists of 16 bits. The first 11 bits are the command code, ranging from 0 to 2047. The 12th bit marks whether telemetry is requested, which would be transmitted over a separate wire (we don’t use this in Halo, sorry if you’re looking for details here!). The final four bits are a checksum, which is used by the ESC to validate the packet.
The 16 bits are transmitted in 16 high pulses on the signal line, where the length of the pulse indicates whether it’s a one (75% duty cycle) or a zero (37% duty cycle).
The Details
A quick forward, this information I determined through testing an ESC I bought off amazon. I don’t have an official standard, and can’t guarantee accuracy in all cases. But, it’s information I wish I had starting out, so I hope it helps.
In standard mode, code 48 is the lowest throttle setting and code 2047 is the highest throttle setting, for a full range of 2000 throttle settings.
I was able to dig up the function of codes 0-47 in the source code for the betaflight controller. The full list:
//this typedef taken from src\main\drivers\pwm_output.h in the betaflight github page typedef enum { DSHOT_CMD_MOTOR_STOP = 0, DSHOT_CMD_BEACON1, DSHOT_CMD_BEACON2, DSHOT_CMD_BEACON3, DSHOT_CMD_BEACON4, DSHOT_CMD_BEACON5, DSHOT_CMD_ESC_INFO, // V2 includes settings DSHOT_CMD_SPIN_DIRECTION_1, DSHOT_CMD_SPIN_DIRECTION_2, DSHOT_CMD_3D_MODE_OFF, DSHOT_CMD_3D_MODE_ON, DSHOT_CMD_SETTINGS_REQUEST, // Currently not implemented DSHOT_CMD_SAVE_SETTINGS, DSHOT_CMD_SPIN_DIRECTION_NORMAL = 20, DSHOT_CMD_SPIN_DIRECTION_REVERSED = 21, DSHOT_CMD_LED0_ON, // BLHeli32 only DSHOT_CMD_LED1_ON, // BLHeli32 only DSHOT_CMD_LED2_ON, // BLHeli32 only DSHOT_CMD_LED3_ON, // BLHeli32 only DSHOT_CMD_LED0_OFF, // BLHeli32 only DSHOT_CMD_LED1_OFF, // BLHeli32 only DSHOT_CMD_LED2_OFF, // BLHeli32 only DSHOT_CMD_LED3_OFF, // BLHeli32 only DSHOT_CMD_AUDIO_STREAM_MODE_ON_OFF = 30, // KISS audio Stream mode on/Off DSHOT_CMD_SILENT_MODE_ON_OFF = 31, // KISS silent Mode on/Off DSHOT_CMD_SIGNAL_LINE_TELEMETRY_DISABLE = 32, DSHOT_CMD_SIGNAL_LINE_CONTINUOUS_ERPM_TELEMETRY = 33, DSHOT_CMD_MAX = 47 } dshotCommands_e;
Note that not all codes are shown in the list. It’s possible that different vendors use different code mappings, or it’s possible for extra features to be present. But it’s likely most vendors want to be natively supported by Betaflight, so that code list will be fine for the average user.
I haven’t tested all of these codes yet, but what I know so far:
If you change any settings with DShot commands, you have to issue the save settings command for them to take effect
To change the spin direction, set 3D mode, or save settings you must enable the telemetry bit in the associated command packet, and you must issue the command 10 times in a row for the command to take effect.
If you issue command 0 and the ESC is not armed, it arms the ESCs with the throttle ranges set to <Either max range or the pre-programmed ranges, I haven’t worked out which>. If the ESC is armed it stops the motors. This command should be used if you want the motor to be stopped. If you try to use a throttle setting to stop the motor, it still spins slowly.
If you stop sending commands, the ESC disarms. I haven’t timed the required update rate, but it’s pretty fast (10ms or less). This is a good thing, I was worried for a time that my bot would keep spinning if the code crashed!
DShot Bidirectional Motion (3D Mode)
If you enable 3D mode, the throttle ranges split in two.
Direction 1) 48 is the slowest, 1047 is the fastest
Direction 2) 1049 is the slowest, 2047 is the fastest
1048 does NOT stop the motor! Use command 0 for that.
Transmission Code
The goal with the code is to support the maximum data rate (1.2Mb) while using minimum CPU time. There are two general schemes used to talk DShot:
Use an SPI peripheral, and send three bits for every “bit”. sending a “100” is a “zero” and “110” is a “one”
We didn’t have an SPI port hooked up to our motor control pins, since we were originally expecting to use PWM to control them. So we chose option two:
Use a timer peripheral to send a PWM signal, and modify the duty cycle after every pulse
We needed to change the duty cycle 16 times over the period of the transmission. We could have programmed a loop that waits for the timer to send a pulse, and then load in the next duty cycle. But that would mean the code was stuck serving the transmission for the full duration, which would take too long.
Instead we used something called DMA, or Direct Memory Access. This is a fairly advanced microcontroller technique, but when used correctly it can make your code extremely efficient.
Our microcontroller (STM32F446) has a DMA peripheral that can be programmed to move a byte or a list of bytes from one location to another. Importantly, it can make this transfer at the behest of a different peripheral (such as our PWM timer), without involving the CPU at all.
We set up the DMA to target the beginning of a list of 17 values and the duty cycle register in the timer. The 17th value of the list is just zero, which keeps the output low after the final byte is transferred. Every time the timer is about to reset and transfer the next pulse, it issues a command to the DMA to transfer a single value. This updates the duty cycle for the next pulse. The DMA peripheral knows to only send 17 values, after which it will disable itself.
When we want to send another message, we just update the first 16 values with the new message, and re-enable the DMA peripheral. Below is my setup code for the timer and DMA. Again, this is for an STM32F446. I’m using ST’s HAL library for definitions.
//make sure the end is set to 0 //the last packet is 0 to make sure the line stays low when we aren't transmitting a code motorPulseTrain[16] = 0; //setup the timer timInst->CR1 &= 0xFFFE; //disable timer //disable the dma stream dmaStrInst->CR &= 0xFFFFFFFE; //wait until the stream is disabled while(dmaStrInst->CR & 0x00000001); timInst->CNT = 0; //clear counter timInst->DIER |= 0x0200; //enable DMA requests on CH1 (no interrupts enabled) //timInst->DIER = 0x0100;//send dma request on update timInst->CCMR1 |= 0x0010;//channel 1 active when the timer matches timInst->CCMR2 |= 0x6060;//channel 3 & 4 are active when timer < count timInst->CCER |= 0x1101;//output compare 1, 3 & 4 outputs are enabled timInst->ARR = DSHOT_PERIOD; //sets the frequency to the DSHOT baud rate //set the DMA trigger channels to fire right before the time rolls over timInst->CCR1 = DSHOT_PERIOD - 7; //setup the DMA on the peripheral side timInst->DCR |= 0x000F;//one transfer, starting from CCR3 //setup the DMA peripheral dmaStrInst->CR = 0x0C032C40;//channel 6, very high priority, size 4 peripheral offset, //half word data sizes, memory increment, memory-to-peripheral dmaStrInst->M0AR = (uint32_t) motorPulseTrain;//set the peripheral address //enable the timer timInst->CR1 |= 0x0085; //enable timer, prescaler=1, auto-reload enabled
You also need to configure the appropriate GPIO pins for alternate function to make sure the capture-compare channels drive outputs.
When setting up a transmission, we first need to work out what bits we’re sending. Below is how we calculate the checksum and build the packet:
void issueDshotCommand(uint8_t motor, uint16_t command) { //compute the checksum. xor the three nibbles of the speed + the telemetry bit (not used here) uint16_t checksum = 0; uint16_t checksum_data = command << 1; for(uint8_t i=0; i < 3; i++) { checksum ^= checksum_data; checksum_data >>= 4; } checksum &= 0x000F;//we only use the least-significant four bits as checksum uint16_t dshot_frame = (command << 5) | checksum; //add in the checksum bits to the least-four-significant bits
Now that we have the command in binary form, we just need to turn it into an array of duty cycles. The exact timing depends on the baud rate you’ve chosen, but DSHOT_1_TIME should be 75% of a full period and DSHOT_0_TIME should be 37% of a full period.
//wait until the stream is disabled while(dmaStrInst->CR & 0x00000001); //Convert the bits to pulse lengths, then write the pulse lengths into the buffer for(int i=0; i<16; i++) { motorPulseTrain[i] = dshot_frame & 0x8000 ? DSHOT_1_TIME : DSHOT_0_TIME; dshot_frame <<= 1; }
And finally we point the DMA at the channel for the motor we want to command, and enable the peripheral.
//set the peripheral address to the correct channel if(motor == MOTOR1) { dmaStrInst->PAR = (uint32_t) &(timInst->CCR3); } else if(motor == MOTOR2) { dmaStrInst->PAR = (uint32_t) &(timInst->CCR4); } else { return;//if the motor selection is invalid, just give up } //start the dma transfer dmaInst->HIFCR = 0x0F7D0F7D;//clear all of the flags because I'm lazy dmaInst->LIFCR = 0x0F7D0F7D; dmaStrInst->NDTR = 17;//set transfer size to 17 bytes dmaStrInst->CR |= 0x00000001;//enable the dma stream }
And that’s it! the DMA will happily chug along, push out our bits, and disable itself. It needs no further code interaction.