DEV Community

Cover image for Integrating the DMR858M: A Practical Guide to Custom ESP32 Digital Walkie-Talkies
Ann Jiang
Ann Jiang

Posted on • Originally published at nicerf.hashnode.dev

Integrating the DMR858M: A Practical Guide to Custom ESP32 Digital Walkie-Talkies

Integrating the DMR858M: A Practical Guide to Custom ESP32 Digital Walkie-Talkies

1. Introduction: The DMR858M as an Integrated DMR Subsystem

In the field of embedded systems development, integrating radio frequency (RF) functionality into a product often involves complex hardware design and tedious protocol stack implementation. The DMR858M module significantly simplifies this process by providing a highly integrated Digital Mobile Radio (DMR) subsystem with up to 5W of transmit power. It is not just an RF transceiver but a complete solution, internally integrating a microcontroller (MCU), a digital walkie-talkie chip, an RF power amplifier, and an audio amplifier. This design allows developers to control a full-featured walkie-talkie core—supporting the DMR Tier II standard, compatible with traditional analog modes, and equipped with SMS and voice encryption—through a simple serial interface.

Internal functional block diagram of the DMR858M

Compared to solutions built from scratch in some open-source projects, this integrated approach offers distinct advantages. Many open-source walkie-talkie projects require developers to handle the SDR (Software-Defined Radio) front-end, power amplifier, audio codecs, and complex signal processing tasks themselves. The DMR858M encapsulates these complexities within the module, greatly accelerating the development cycle and reducing project risks.

Key Advantage: 5W Transmit Power and Long-Range Communication

For many walkie-talkie applications, communication range is the core metric of performance. The most significant advantage of the DMR858M module is its ability to deliver up to 5W of transmit power, making it stand out among similar products. Under ideal conditions, 5W of power is sufficient to support a communication distance of up to 7-8 kilometers, meeting the needs of various professional scenarios such as ports, forests, large warehouses, or outdoor activities.

High power output directly translates to stronger signal penetration and wider coverage, ensuring a reliable communication link even in complex environments. For developers, this means that products designed based on the DMR858M can meet or exceed the performance standards of many commercial handheld walkie-talkies without investing significant resources in complex RF power amplifier design and debugging.

Another Core Advantage: Onboard AMBE++ Vocoder

In addition to its powerful transmit capabilities, another core value of the DMR858M module is its integrated Motorola AMBE++ vocoder. For digital voice communication, the vocoder is a key technology for compressing and decompressing voice signals, but it has also been a major obstacle for the open-source community.

Digital voice communication standards like DMR rely on specific vocoders. The AMBE series of vocoders, developed by Digital Voice Systems, Inc. (DVSI), is protected by patents. This presents both technical and legal challenges for the open-source community. On one hand, for an open-source project to be interoperable with commercial DMR devices, it must use an AMBE-compatible codec algorithm. However, using these patented algorithms without authorization carries legal risks. Some projects attempt to reverse-engineer partial functionality (like mbelib), but this remains in a legal gray area.

On the other hand, the community has also developed fully open-source alternatives like Codec2. Although Codec2 is technically viable and has been adopted in some amateur radio projects (such as the M17 project), it is not compatible with the AMBE vocoder defined in the DMR standard. This means that devices using Codec2 cannot make voice calls with the vast majority of commercial DMR walkie-talkies on the market, which severely limits their practicality.

The DMR858M module perfectly circumvents this problem by providing a licensed, hardware-based AMBE++ vocoder. Developers do not need to worry about the complex implementation of the vocoder algorithm or potential patent licensing issues; they can simply invoke its functions through simple serial commands. This is not just a technical convenience but also an effective management of project risk. By abstracting the complex and sensitive vocoder part, the DMR858M allows developers to focus on application-level innovation, thereby significantly lowering the barrier to building DMR-compatible devices.

Key Specifications and Their Engineering Significance

To quickly assess whether the DMR858M meets project requirements, the following table summarizes its key technical specifications and explains the significance of these parameters in practical engineering applications.

Table 1: DMR858M Key Specifications Summary

Parameter Value Engineering Significance
Operating Frequency UHF: 400-470 MHz; VHF: 134-174 MHz; 350 MHz: 320-400 MHz (Optional) Covers major commercial and amateur bands, providing flexible frequency selection to comply with regulations in different countries and regions.
Transmit Power High Power: 5W, Low Power: 2W 5W high power enables long-range communication (up to 7-8 km) but requires a power system capable of handling high peak currents. Low power mode helps save energy for short-range communication.
Operating Mode DMR Tier II / Analog Dual-mode support ensures the device can leverage the advantages of DMR digital mode (e.g., dual time slots, encryption) while remaining backward compatible with existing analog systems.
Receive Sensitivity -120dBm (Analog), BER 5% @ -117dBm (Digital) High sensitivity means the module can reliably receive signals in weak signal environments, a key indicator for ensuring communication range and quality.
Operating Voltage 3.7V - 8.5V (Typical 8.0V) Wide voltage range design, but a stable supply of around 8.0V is required to achieve the maximum output power of 5W.
Peak Transmit Current Approx. 900mA - 1700mA @ 8V, 5W This is a core consideration for power supply design. The power supply must be able to provide a stable instantaneous current of nearly 2A, otherwise it could lead to system voltage drops and MCU resets.
Core Functions Integrated AMBE++ Vocoder, Supports SMS, Voice Encryption Provides the core functions of the DMR standard, allowing developers to easily implement secure communication and data transmission applications without dealing with the complexity of the underlying protocol.
Control Interface UART (57600 bps) A standard serial interface that is easy to integrate with various MCUs (like ESP32), with a control protocol based on a binary frame structure.

2. Hardware Integration and ESP32 Reference Design

Integrating the DMR858M module with a microcontroller (such as the ESP32 used here) requires focusing on three main aspects: power supply, control logic, and audio interface. This section provides a proven reference design to ensure stable system operation.

Hardware integration schematic of the DMR858M with an MCU

Key Design Consideration: Power Supply

Power supply design is the most easily overlooked and most common point of failure when integrating high-power RF modules. When the DMR858M transmits at 5W high power with an 8V supply, the peak current can reach 910mA or even higher. Any attempt to directly power the module using the 5V USB input or the 3.3V LDO on an ESP32 development board will fail.

A robust power system must meet the following requirements:

  1. Independent Power Unit: Use an external power source capable of providing at least 8V and over 2A of current, such as a lithium battery pack (2S Li-Po/Li-ion) with a buck-boost converter, or a stable DC power adapter.
  2. Excellent Transient Response: The key issue is not just the average current the power supply can provide, but its response speed to load transients. When the module switches instantly from receive mode (current < 165mA) to transmit mode (current > 900mA), it creates a huge instantaneous current spike (dI/dt). If the power supply's transient response is inadequate, or if the power traces on the PCB are too long and thin (introducing significant parasitic inductance and resistance), the system voltage will drop momentarily.
  3. Chain Effect of Voltage Sag: This voltage drop is the root cause of many hard-to-debug "ghost" issues. The ESP32 has a built-in Brown-out Detection circuit, which triggers a system reset to protect itself when its supply voltage falls below a certain threshold. Therefore, what appears to be a "power" issue may manifest as the program randomly restarting when the PTT button is pressed. Additionally, an unstable supply voltage can interfere with UART communication, leading to data transmission errors.
  4. Solution: To avoid these problems, large decoupling capacitors must be placed near the VCC pin of the DMR858M module. It is recommended to use a 100µF to 470µF electrolytic capacitor in parallel with a 0.1µF ceramic capacitor (the former for handling low-frequency high-current demands, the latter for filtering high-frequency noise). Also, ensure that the VCC and GND traces from the power source to the module are as short and wide as possible to minimize line voltage drop.

Interface Logic: UART, PTT, and Audio

The module's control and data exchange are primarily handled through GPIO and UART.

  • UART Communication: Connect one of the ESP32's hardware serial ports (e.g., UART2, corresponding to GPIO16 and GPIO17) to the DMR858M's RXD (pin 19) and TXD (pin 18). Note the crossover connection: ESP32's TX connects to the module's RX, and ESP32's RX connects to the module's TX.
  • PTT (Push-to-Talk): PTT control is very straightforward. Connect a GPIO pin from the ESP32 to the module's PTT (pin 5). This pin is active low, meaning the module enters transmit mode when the GPIO outputs a low level.
  • Audio Input: The module's MIC+ (pin 14) and MIC- (pin 13) are used to connect an external microphone. The datasheet specifies that a bias voltage is provided internally, so an electret microphone can be connected directly without an additional bias circuit.
  • Audio Output: The module's OUTP (pin 11) and OUTN (pin 12) are differential audio outputs that can directly drive an 8-ohm speaker.

Pin layout diagram of the DMR858M module (front and back views)

Table 2: ESP32 to DMR858M Pin Mapping Reference

ESP32 Pin (e.g., DevKitC) Function DMR858M Pin Notes
GPIO17 (U2TXD) UART TX 19 (RXD) Connects to the module's serial data receive pin.
GPIO16 (U2RXD) UART RX 18 (TXD) Connects to the module's serial data transmit pin.
GPIO25 PTT Control 5 (PTT) Active low, controls module entry into transmit mode.
GPIO26 CS (Sleep Control) 3 (CS) Low level puts the module into sleep mode, high level activates it.
GPIO27 RX Indicator 16 (SPKEN) This pin outputs a high level when the module receives a signal.
- Microphone Positive 14 (MIC+) Connect to the positive terminal of the electret microphone.
- Microphone Negative 13 (MIC-) Connect to the negative terminal of the electret microphone.
- Speaker Output + 11 (OUTP) Connect to one terminal of an 8-ohm speaker.
- Speaker Output - 12 (OUTN) Connect to the other terminal of the 8-ohm speaker.
VCC Module Power 1 (VCC) Connect to the positive terminal of the external 8V power supply.
GND System Ground 2, 4 (GND) Connect to the external power supply ground and share a common ground with the ESP32.

Mechanical dimensions drawing of the DMR858M module

3. Deconstructing the Serial Control Protocol

The key to effective communication with the module is to correctly implement its serial control protocol. This protocol uses a binary frame format, and all parameter configuration and status queries are accomplished by sending and receiving specific data frames.

Frame Structure Analysis

Frame structure diagram of the serial communication protocol

Example of a serial communication data frame

Each data frame follows a fixed structure, consisting of a header, command, data, and tail, among other parts.

Table 3: Serial Protocol Frame Structure

Offset (Bytes) Field Length (Bytes) Description
0 Head 1 Frame header, fixed at 0x68.
1 CMD 1 Command word, defines the function of the frame, such as setting frequency, sending SMS, etc.
2 R/W 1 Read/Write flag. 0x00=Read, 0x01=Write, 0x02=Module-initiated report.
3 S/R 1 Set/Response flag. When sent by the host, it is a set request; when replied by the module, it is a response status.
4-5 CKSUM 2 16-bit checksum. Covers all bytes from CMD to the end of DATA.
6-7 LEN 2 Data length of the DATA field (in bytes).
8... DATA n (determined by LEN) Data payload. The specific content is defined by the CMD.
8+n TAIL 1 Frame tail, fixed at 0x10.

Checksum Calculation Method

According to the protocol document, the checksum is calculated as follows: each pair of bytes in the data to be checked is formed into a 16-bit number and then added sequentially. If the data frame has an odd length, 0x00 is appended to the last byte. The carry-over part (exceeding 16 bits) from the accumulation process is added back to the lower 16 bits of the result until the sum is less than or equal to 0xFFFF. Finally, the resulting 16-bit number is XORed with 0xFFFF to get the final checksum.

The reference C code provided in the protocol document is as follows:

uint16 PcCheckSum(uint8 * buf, int16 len)
{
    uint32 sum = 0;
    while(len > 1)
    {
        sum += 0xFFFF & ((*buf<<8)|*(buf+1));
        buf += 2;
        len -= 2;
    }
    if (len)
    {
        sum += (0xFF & *buf)<<8;
    }
    while (sum>>16)
    {
        sum = (sum & 0xFFFF) + (sum>>16);
    }
    return((uint16) sum ^ 0xFFFF);
}
Enter fullscreen mode Exit fullscreen mode

Flowchart of the checksum (CKSUM) calculation process

A noteworthy engineering detail is that the protocol document mentions that if the user does not want to calculate the checksum, the CKSUM field can be sent as 0x0000, and the module will ignore the checksum process. This can be very useful during the initial debugging phase, but for the sake of communication reliability, the correct checksum should be implemented and used in the final product.

Complete Command Set Reference

The following table categorizes and organizes all the commands supported by the module, providing a more structured reference than the original documentation.

Table 4: DMR858M Command Code (CMD) Complete Reference

CMD (Hex) Function Description R/W Support Scope Persistent Notes
Configuration Commands (Saved on Power-off)
0x01 Change Channel Write Current Yes Switch to the specified channel.
0x02 Set Receive Volume Write All Yes Set the audio output volume level.
0x0B Set Microphone Gain Write All Yes Adjust microphone sensitivity.
0x0C Set Power Save Mode Write All Yes Enable or disable low-power mode.
0x0D Set TX/RX Frequency Read/Write Current Yes Set the receive and transmit frequencies for the current channel.
0x12 Set Squelch (SQ) Level Read/Write Current Yes Set the squelch threshold for analog mode.
0x13 Set CTCSS/CDCSS Mode Read/Write Current Yes Set the sub-audio mode (e.g., receive only, transmit only, both).
0x14 Set CTCSS/CDCSS Value Read/Write Current Yes Set the specific sub-audio code.
0x17 Set High/Low Power Read/Write Current Yes Switch the transmit power for the current channel.
Operational Commands (Effective Immediately)
0x03 Scan Write Current No Start or stop channel scanning.
0x06 Initiate Call Write Current No Initiate a group or private call.
0x07 Send SMS Write Current No Send a DMR text message.
0x09 Emergency Alarm Write Current No Trigger the emergency alarm function.
0x15 Monitor Switch Write Current No Force open the squelch to monitor channel activity.
Status Query Commands
0x04 Check TX/RX Status Read Current No Query if the module is in receive, transmit, or idle state.
0x05 Read Signal Strength Read Current No Get the RSSI value of the current received signal.
0x24 Read ID Read All No Read the module's DMR ID.
0x25 Read Firmware Version Read All No Read the module's firmware version number.
0x28 Check Encryption Status Read Current No Query if encryption is enabled on the current channel.

4. Firmware Development: A Structured ESP32 Driver

To control the DMR858M efficiently and reliably, an object-oriented approach is recommended, creating a driver class to encapsulate all interactions with the module. This architecture is similar to libraries designed for other AT command modules (such as GSM or Wi-Fi modules) and offers good modularity and reusability.

Architecture Method: DMR858M_Controller Class

We will design a C++ class named DMR858M_Controller. This class will be responsible for managing UART communication, building and parsing data frames, handling commands and responses, and managing the module's state.

C++

// DMR858M_Controller.h
#include <Arduino.h>

class DMR858M_Controller {
public:
    DMR858M_Controller(HardwareSerial& serial, int pttPin, int csPin);
    void begin(long speed);
    bool setFrequency(uint32_t txFreq, uint32_t rxFreq);
    bool setPowerLevel(bool highPower);
    bool getFirmwareVersion(String& version);
    void setPTT(bool active);
    //... other function prototypes

private:
    HardwareSerial& _serial;
    int _pttPin;
    int _csPin;

    void sendCommand(uint8_t cmd, uint8_t rw, const uint8_t* data, uint16_t len);
    bool waitForResponse(uint8_t* buffer, uint16_t& len, uint32_t timeout = 1000);
    uint16_t calculateChecksum(const uint8_t* data, size_t len);
};
Enter fullscreen mode Exit fullscreen mode

Core Implementation Details (Code Example)

Packet Construction and Transmission

sendCommand is the core of all write operations. It is responsible for assembling the complete binary packet, calculating the checksum, and sending it via UART.

// DMR858M_Controller.cpp

void DMR858M_Controller::sendCommand(uint8_t cmd, uint8_t rw, const uint8_t* data, uint16_t len) {

    // Calculate total frame length
    const uint16_t totalFrameLen = 9 + len; // Head(1) + CMD(1) + R/W(1) + S/R(1) + CKSUM(2) + LEN(2) + DATA(n) + Tail(1)

    // Allocate buffer
    uint8_t frame[totalFrameLen];

    // Build frame (checksum temporarily zeroed)
    frame[0] = 0x68;    // Head
    frame[1] = cmd;     // CMD
    frame[2] = rw;      // R/W
    frame[3] = 0x01;    // S/R (Request)

    // Reserve CKSUM position (set to 0 temporarily)
    frame[4] = 0x00;    // CKSUM_HI (temporary)
    frame[5] = 0x00;    // CKSUM_LO (temporary)

    // LEN (big-endian)
    frame[6] = (len >> 8) & 0xFF; // LEN_HI
    frame[7] = len & 0xFF;        // LEN_LO

    // DATA
    if (data && len > 0) {
        memcpy(&frame[8], data, len);
    }

    // Tail
    frame[8 + len] = 0x10;

    // Calculate checksum (from CMD to end of DATA, i.e., offset 1 to 8+len-1)
    // Note: CKSUM field (offset 4-5) is treated as 0 during calculation
    uint16_t checksum = calculateChecksum(&frame[1], 3 + 2 + len); // CMD + R/W + S/R + LEN + DATA

    // Insert checksum into frame (big-endian)
    frame[4] = (checksum >> 8) & 0xFF; // CKSUM_HI
    frame[5] = checksum & 0xFF;        // CKSUM_LO

    // Send frame
    _serial.write(frame, totalFrameLen);
}

uint16_t DMR858M_Controller::calculateChecksum(const uint8_t* buf, size_t len) {
    uint32_t sum = 0;
    const uint8_t* current_buf = buf;
    size_t current_len = len;

    while (current_len > 1) {
        sum += (uint16_t)((*current_buf << 8) | *(current_buf + 1));
        current_buf += 2;
        current_len -= 2;
    }

    if (current_len > 0) {
        sum += (uint16_t)(*current_buf << 8);
    }

    while (sum >> 16) {
        sum = (sum & 0xFFFF) + (sum >> 16);
    }

    return (uint16_t)(sum ^ 0xFFFF);
}
Enter fullscreen mode Exit fullscreen mode

Importance of Response Handling and Asynchronous Operations

In embedded systems, blocking waits are a programming pattern to be avoided. A simple waitForResponse function using a loop like while(!_serial.available()){} will freeze the entire main loop, preventing the MCU from performing other tasks such as updating a display or responding to button presses, leading to an unresponsive system.

A more robust design should be non-blocking. In the main loop, the program should continuously check the serial port for data and use a state machine to process the incoming data frame. This approach ensures that the system can still handle other real-time events while waiting for a response from the module. For a platform like the ESP32 that supports FreeRTOS, a better solution is to create a dedicated RTOS task to handle communication with the DMR module. This task can block when there is no data without affecting the execution of other tasks.

Here is a simplified example of non-blocking read logic suitable for an Arduino loop() function:

// Simplified non-blocking response handling logic
void loop() {
    //... other tasks...

    if (_serial.available()) {
        // Read byte and place it into a buffer
        // Use a state machine to parse the data frame (look for header 0x68, read specified length, verify checksum and tail 0x10)
        // Once successfully parsed, process the response data
    }
}
Enter fullscreen mode Exit fullscreen mode

Comprehensive Example: A Proof-of-Concept Program

The following is a complete Arduino/PlatformIO example that demonstrates how to initialize the module, control PTT with a button, and send an SMS via the serial monitor.

#include <Arduino.h>
#include "DMR858M_Controller.h"

#define PTT_BUTTON_PIN 25
#define PTT_MODULE_PIN 26
#define LED_PIN 2

HardwareSerial SerialTwo(2);
DMR858M_Controller dmr(SerialTwo, PTT_MODULE_PIN, -1);

void setup() {
    Serial.begin(115200);
    pinMode(PTT_BUTTON_PIN, INPUT_PULLUP);
    pinMode(LED_PIN, OUTPUT);

    dmr.begin(57600);
    delay(500);

    String fwVersion;
    if (dmr.getFirmwareVersion(fwVersion)) {
        Serial.println("DMR858M Firmware: " + fwVersion);
    } else {
        Serial.println("Failed to communicate with DMR858M module.");
    }

    // Example: Set frequency for channel 1 to 433.500 MHz
    dmr.setFrequency(433500000, 433500000);
}

void loop() {
    // PTT control logic
    if (digitalRead(PTT_BUTTON_PIN) == LOW) {
        dmr.setPTT(true);
        digitalWrite(LED_PIN, HIGH); // Transmit indicator
    } else {
        dmr.setPTT(false);
        digitalWrite(LED_PIN, LOW);
    }

    //... non-blocking serial response handling logic can be added here...

    // Example: Send SMS via serial monitor
    if (Serial.available()) {
        String cmd = Serial.readStringUntil('\n');
        if (cmd.startsWith("sms")) {
            // Parse SMS content and target ID
            // Call dm.sendSMS(...)
            Serial.println("SMS command received.");
        }
    }
}
Enter fullscreen mode Exit fullscreen mode

5. Conclusion and Advanced Topics

Successful integration of the DMR858M module hinges on following several key engineering practices: designing a robust power supply system capable of handling high transient currents; implementing the correct serial communication checksum algorithm according to the official documentation; and adopting a structured, non-blocking firmware architecture to ensure the system's real-time responsiveness.

As a highly integrated DMR subsystem, the DMR858M, with its 5W high transmit power and onboard AMBE++ vocoder, provides developers with a shortcut to building professional-grade digital communication products. It addresses the core pain points of communication range and open-source compatibility, allowing developers to focus their efforts on creating unique user experiences and application features.

Exploring Advanced Features

After mastering basic communication and control, developers can further leverage the module's advanced features to build more complex applications:

  • Low-Power Operation: For battery-powered devices, power consumption is critical. By controlling the CS pin (pin 3), the module can be put into a deep sleep mode, where current consumption is less than 0.1mA. Waking it up only when communication is needed can significantly extend the device's battery life. Additionally, the module supports a duty cycle working mode, entered via the CMD=0x0C command, which automatically switches between sleep and active states to maintain reception capability while further optimizing power consumption.

Timing diagram of the CS pin controlling sleep mode

Logic flowchart for the Duty Cycle Working Mode

  • DMR Advanced Calling: In addition to the default group call, the DMR protocol supports Private Call and All Call. By using commands like CMD=0x18 (Set Contact) and CMD=0x22 (Send Contact Info), more flexible call control can be achieved.

Signaling flowchart for DMR call setup and termination

Signaling flowchart for DMR call setup and termination

Flowchart for sending and receiving DMR SMS

  • DMR SMS Functionality: The module supports sending DMR text messages via the CMD=0x07 command, enabling text data exchange between devices.

Signaling flowchart for DMR call setup and termination

  • Emergency Alarm Function: Using the CMD=0x09 command, an emergency alarm signal can be sent to a specified group ID, useful for scenarios requiring a rapid response.

Flowchart for the DMR emergency alarm function

  • Voice Encryption: For applications requiring secure communication, the CMD=0x19 command can be used to enable or disable the built-in voice encryption feature, providing basic privacy protection for calls.
  • Repeater Mode: The module supports entering repeater mode via the CMD=0x0E command, allowing it to communicate through a repeater to extend its communication range. This mode requires different transmit and receive frequencies.

Setup flowchart for entering Repeater Mode

6. Information Resources

  1. G-NiceRF®. DMR858M Product Information Page. Retrieved from https://www.nicerf.com/walkie-talkie-module/dmr858m.html
  2. G-NiceRF®. DMR858M Resource Download Center. Retrieved from(https://www.nicerf.com/download/?keywords=DMR858M)
  3. G-NiceRF®. Official Website. Retrieved from https://www.nicerf.com/
  4. G-NiceRF® Official Store. AliExpress Product Page. Retrieved from https://www.aliexpress.com/item/1005009654348093.html
  5. DMR Association. Official Website. Retrieved from https://www.dmrassociation.org/
  6. Digital Voice Systems, Inc. (DVSI). AMBE™ Vocoder Developer. Retrieved from https://www.dvsinc.com/
  7. Codec2 Project. Open Source Vocoder Project. Retrieved from https://www.rowetel.com/wordpress/?page_id=452
  8. M17 Project. Open Source Digital Radio Project. Retrieved from https://m17project.org/
  9. Espressif Systems. ESP32 Official Page. Retrieved from https://www.espressif.com/en/products/socs/esp32
  10. Arduino. Official Website. Retrieved from https://www.arduino.cc/
  11. Arduino Core for ESP32. GitHub Repository. Retrieved from https://github.com/espressif/arduino-esp32

Top comments (0)