Skip to content

Command and Programming Manual

Rev 1.7.1

Applicable to CH0x0/HI02/04/05/06/14/50/90/70 series (shared programming interface)

This manual is based on firmware version: 1.7.1

Actual feature availability depends on the specific product model, firmware version, and delivered configuration.

Applicable Firmware Version

📌 Check your firmware version first — commands differ slightly between firmware versions. To check: send LOG VERSION over the serial port, or look it up in the CHCenter host software, then pick the matching manual below.

Your firmware versionMatching manualGet it
≥ 1.7.1 (latest)v1.7.1This manual (this page / "Download PDF" above)
1.5.5 – 1.7.0v1.3.0imu_cum_cn_150_170.pdf

Module Configuration Overview

Before using the product, please read this chapter carefully and determine whether user configuration is required based on your actual use case.

Operating Mode Configuration - AHRS / 9-Axis Mode

⚠️ Warning In robotic applications and indoor environments, the AHRS (9-axis) mode is easily disturbed by ambient magnetic fields or magnetic fields generated by motors, which can introduce errors into the heading angle.

In open environments without magnetic interference (e.g., outdoor UAV operations), magnetometer-aided mode may be used. Before use, you need to:

  1. Configure the module to magnetometer-aided mode;
  2. Perform magnetic calibration (see the "Magnetic Calibration" chapter).

Synchronous Input - SYNC_IN / PPS

The module's synchronization-related features rely on the SYNC_IN/PPS pin, mainly including the following two categories:

  • SYNC_IN data trigger
  • PPS (pulse-per-second) input for UTC time synchronization

SYNC_IN Data Trigger

Some products provide a synchronization input pin (SYNC_IN/PPS) that can be used to trigger data output by external pulses. Leave the pin floating or grounded when not in use. Working principle: when the output protocol is configured to the ONMARK trigger mode (see the LOG command), the module outputs one frame of data each time a rising edge is detected on the SYNC_IN pin.

Application scenario: mainly used to receive high-precision pulses generated by the host controller or an external clock source to trigger synchronous IMU data output.

PPS Standard Pulse Input

This function uses the (SYNC_IN/PPS) pin to receive the GPS PPS pulse signal, combined with time messages received from the UART, to provide precise UTC time synchronization for the IMU. When the module detects a valid PPS rising edge and receives a matching time message via the UART, its internal clock automatically aligns to UTC integer seconds.

1. Timing and Signal Requirements

To ensure reliable time synchronization, the PPS pulse and the UART time message must satisfy the following timing relationship:

Parameter description:

ParameterDescriptionValid rangeRecommended value
t0Interval between two adjacent PPS rising edges990 ms ~ 1010 ms1000 ms
t1PPS high-level duration (pulse width)1 ms ~ 100 ms10 ms ~ 50 ms
t2Transmission time of the time messageDepends on baud rate-
t3Delay between start of the time message and the PPS rising edge-200 ms ~ +200 ms0 ms ~ 100 ms

⚠️ Core requirement: The time message used for synchronization must be sent within 200 ms before or after the PPS rising edge (i.e., |t3|200ms); otherwise the IMU will not be able to match UTC time correctly.

2. Hardware and Interface Requirements
  • Hardware pin (SYNC_IN/PPS):
    • Trigger edge: rising edge;
    • Logic level: high level ≤ 5 V (TTL/CMOS compatible);
  • UART data (RX):
    • Message rate: 1~10 Hz (recommended: 1 Hz);
    • Baud rate: must exactly match the IMU UART setting;
    • Supported protocols: only standard NMEA RMC or GGA sentences.
3. Time Message Example (GPRMC)
text
$GPRMC,235952.00,A,3112.5000,N,12127.5000,E,0.0,0.0,141125,0.0,E,A*3B

After time synchronization, the timestamp (uint32_t) in each data frame indicates the milliseconds elapsed since UTC 00:00:00 of the current day.

ParameterValue
Range0~86,399,999 ms
Range of time00:00:00.000 to 23:59:59.999
Resolution1 ms

Timestamp conversion examples and C code:

Timestamp (ms)UTC time
000:00:00.000
366100001:01:01.000
4320000012:00:00.000
8639999923:59:59.999
c
// Time conversion formula:
// Hours = timestamp / 3600000
// Minutes = (timestamp % 3600000) / 60000
// Seconds = (timestamp % 60000) / 1000
// Milliseconds = timestamp % 1000

void ms_to_utc_time(uint32_t total_ms, char *utc_time, int buf_size)
{
    // Calculate hours, minutes, seconds and milliseconds
    uint32_t total_seconds = total_ms / 1000;
    uint32_t ms_part = total_ms % 1000;

    uint8_t hours = (total_seconds / 3600) % 24;
    uint8_t minutes = (total_seconds % 3600) / 60;
    uint8_t seconds = total_seconds % 60;

    // Format as hh:mm:ss.sss
    snprintf(utc_time, buf_size, "%02d:%02d:%02d.%03d",
             hours, minutes, seconds, ms_part);
}

📝 Notes

  • The timestamp does not contain date information; it only represents UTC time of the current day (milliseconds since 00:00:00).
  • It does not include time-zone information and is interpreted as UTC+0; for local time, the host should add the time-zone offset.

Synchronous Output - SOUT

SOUT is the module's synchronous output pin. It stays low (idle) when no data is being transmitted; before a frame starts to transmit, a high pulse is emitted, and data transmission begins immediately after the falling edge of the pulse.

The SOUT pin also supports frequency division, allowing the synchronization pulse to be output at a configurable divisor. This can be used to trigger lower-rate devices such as cameras for tight time synchronization. See CONFIG PMUX2 DIV in the "Module Configuration" chapter for divider configuration.

Vessel Wave-Compensated Displacement Output - Heave, Surge, Sway

This product can measure the periodic vessel motion induced by sea waves (heave, surge, sway) and provide high-precision real-time three-axis wave motion information:

Motion axisDescriptionOutput data
HeaveVertical heaveVertical displacement, vertical velocity, vertical displacement period
SurgeLongitudinal surgeLongitudinal displacement, longitudinal velocity, longitudinal displacement period
SwayLateral swayLateral displacement, lateral velocity, lateral displacement period

Application scenarios:

  • Vessel dynamic monitoring and attitude control
  • Offshore engineering motion compensation (lifting, docking)
  • Wave characterization and statistical analysis
  • Offshore platform stability analysis
  • Dynamic positioning (DP) system assistance

Usage Limitations

⚠️ Important limitations

  • Only applicable to periodic reciprocating motion.

  • The following situations generally cannot be measured accurately:

    • Motions with very long periods (>30 s)
    • One-directional linear motion
    • Step-type displacement
  • Zero-mean assumption: the algorithm assumes the long-term average of displacement is 0.

  • Initialization time: a steady 5~20 wave cycles are required for initialization to obtain correct results.

  • Frequency response range: typical wave periods are 3~20 s; accuracy degrades outside this range.

📝 Product compatibility Only HI7x/HI9x series products support this feature. See "Product Feature Support Matrix".

Product Feature Support Matrix

The following table provides an overview of common feature support across product families. Actual feature availability depends on the specific product model, firmware version, and delivered configuration.

Features not listed in the table do not imply they are necessarily supported or enabled by default; for a specific model, please refer to the delivery notes.

Model / CommandHI02HI05/06CH0x0, HI04/12/13/14HI50HI7x/9x
Magnetometer aiding / mag calibration
User attitude calibration
IO pin multiplexing (PMUX)
CAN communication interface
Vessel heave output
Inclinometer output

Module Configuration Commands (ASCII)

Module configuration uses ASCII string commands sent over the UART. Each command must end with carriage-return + line-feed \r\n (similar to AT commands).

For any operation that modifies parameters, the recommended procedure is: "Send the configuration command -> execute SAVECONFIG -> reset or power cycle -> verify again". Query-type commands and some communication-control commands may take effect immediately in the current session, but the recommended configuration flow above still applies.

📝 Configuration semantics

  • Whether a command takes effect immediately is specified in each command description;
  • For configurations that must persist, execute SAVECONFIG and then reset or power cycle to confirm;
  • Communication-parameter commands may switch immediately on the current interface;
  • Restore-type commands may automatically save and trigger a reset.

The following table lists common externally-facing configuration commands. Additional commands for compatibility, debugging, or customization purposes depend on the actual delivered configuration.

Command Overview

CommandFunctionRemarks
REBOOTReset the moduleEquivalent to a power cycle
SAVECONFIGSave all configuration parametersTakes effect immediately
SERIALCONFIGConfigure UART baud rateTakes effect immediately
CONFIGConfigure module parameters and modesSave and reset for effect
LOGQuery module info or configure outputTakes effect immediately
FRESETRestore factory defaultsTakes effect immediately

Command Details

REBOOT

Reset the module. Execute REBOOT BL to reset into Bootloader mode. Examples: REBOOT, REBOOT BL

SAVECONFIG

Save all user configurations to flash. Example: SAVECONFIG

SERIALCONFIG

Set the current UART baud rate.

Format: SERIALCONFIG <BAUD>

Parameters:

  • BAUD: target baud rate. Supported values: 4800, 9600, 19200, 38400, 57600, 115200, 230400, 256000, 460800, 921600

Example:

  • SERIALCONFIG 115200 - set the current UART to 115200 baud

⚠️ Important This command takes effect immediately. After execution, switch to the new baud rate to continue communicating with the module.

CONFIG

Used to configure module parameters and operating modes. For any CONFIG setting that needs to persist, run SAVECONFIG after the change and confirm the result after a reset or power cycle.

Operating Mode Configuration

Operating mode configuration: 6-axis or 9-axis (magnetometer-aided) mode. Format: CONFIG ATT MODE <VAL>. The most common modes are listed below; other industry-specific or customized modes depend on the actual delivered configuration.

Examples:

  • CONFIG ATT MODE 0 - configure the module to VRU (6-axis) mode
  • CONFIG ATT MODE 1 - configure the module to AHRS (9-axis) mode
  • CONFIG ATT MODE 4 - humanoid robot dedicated mode
User Attitude Calibration

Used to perform attitude zero-point related operations. Format: CONFIG ATT RST <VAL>. The device must remain stationary while executing this command; otherwise large calibration errors may be introduced.

Examples:

  • CONFIG ATT RST 1 - Heading reset: zero the current heading angle
  • CONFIG ATT RST 2 - Set relative zero: zero the current Pitch and Roll angles
  • CONFIG ATT RST 3 - Auto-level: only valid when the device is close to horizontal. Defined as:
    • If the current Pitch/Roll is close to 0° (placed horizontally right-side up), auto-calibrate to Pitch=0°, Roll=0°;
    • If the current Pitch is close to 0° and Roll is close to 180° (placed horizontally upside-down), auto-calibrate to Pitch=0°, Roll=180°;
    • The "close to" threshold is Pitch and Roll both less than 5°.
  • CONFIG ATT RST 5 - Cancel auto-level: clear relative Pitch and Roll angles and restore absolute angles
Mounting Orientation Setting

Used to modify the module's mounting orientation, such as horizontal mounting, vertical mounting, upside-down, or forward-facing installation for integrated navigation. Save and reset to confirm such settings; no need to resend at every power-up.

Format: CONFIG IMU URFR <CODE>

Parameters:

  • CODE: 2- to 3-digit orientation code, representing the mounting direction of the user coordinate system relative to the sensor coordinate system.
  • The code is written as ABC, where:
    • A indicates which direction in the sensor frame the user-frame X axis points to
    • B indicates which direction in the sensor frame the user-frame Y axis points to
    • C indicates which direction in the sensor frame the user-frame Z axis points to
  • Each digit has the following meaning:
DigitDirection
0+X
1-X
2+Y
3-Y
4+Z
5-Z

Notes:

  • 24 is equivalent to 024, meaning user frame X=+X, Y=+Y, Z=+Z. For the product's default mounting, this can be understood as X points right, Y points forward, Z points up.
  • This command uses spaces to separate parameters. The correct form is CONFIG IMU URFR 24, not CONFIG IMU URFR=24.
  • The current configuration query result is displayed in the form URFR=<CODE>.
  • If the user coordinate system is defined as right/forward/up of the body, you can directly choose the corresponding code from the table below based on the installation orientation.

Complete configuration examples (24 valid right-handed combinations):

  • The table is presented in "Equivalent installation description" form (consistent with the host UI dropdown): direction of IMU X/Y/Z in Body(B).
  • The URFR encoding itself is still three digits ABC (with the right-handed constraint X × Y = Z); the 2-digit display value is equivalent to the 3-digit value with a leading zero (e.g., 24 = 024).
Equivalent installation description (IMU axes in Body(B))Configuration commandNotes
IMU X points right, IMU Y points forward, IMU Z points upCONFIG IMU URFR 24Default horizontal mounting; full code is 024.
IMU X points right, IMU Y points backward, IMU Z points downCONFIG IMU URFR 35Common upside-down mounting (rotated about X relative to default); full code is 035.
IMU X points right, IMU Y points down, IMU Z points forwardCONFIG IMU URFR 43Common side mounting; matches "Right + Down" in the host UI.
IMU X points right, IMU Y points up, IMU Z points backwardCONFIG IMU URFR 52Common side mounting; matches "Right + Up" in the host UI.
IMU X points left, IMU Y points forward, IMU Z points downCONFIG IMU URFR 125Inverted combo with X reversed and Z pointing down.
IMU X points left, IMU Y points backward, IMU Z points upCONFIG IMU URFR 134Both X/Y reversed with Z up; common when orientation is reversed.
IMU X points left, IMU Y points up, IMU Z points forwardCONFIG IMU URFR 142Left-facing vertical mounting with Y pointing up.
IMU X points left, IMU Y points down, IMU Z points backwardCONFIG IMU URFR 153Left-facing vertical mounting with Y pointing down.
IMU X points forward, IMU Y points right, IMU Z points downCONFIG IMU URFR 205Forward-facing mounting, suitable when X is aligned with the vehicle heading.
IMU X points backward, IMU Y points right, IMU Z points upCONFIG IMU URFR 214Backward-facing mounting; Y still points right.
IMU X points up, IMU Y points right, IMU Z points forwardCONFIG IMU URFR 240Vertical mounting with X up and Y right.
IMU X points down, IMU Y points right, IMU Z points backwardCONFIG IMU URFR 251Vertical mounting with X down and Y right.
IMU X points forward, IMU Y points left, IMU Z points upCONFIG IMU URFR 304Forward-facing mounting with Y changed to left.
IMU X points backward, IMU Y points left, IMU Z points downCONFIG IMU URFR 315Backward-facing upside-down mounting; both X/Y reversed.
IMU X points down, IMU Y points left, IMU Z points forwardCONFIG IMU URFR 341Left-facing vertical mounting with X down.
IMU X points up, IMU Y points left, IMU Z points backwardCONFIG IMU URFR 350Left-facing vertical mounting with X up.
IMU X points forward, IMU Y points up, IMU Z points rightCONFIG IMU URFR 402Forward-facing vertical mounting with Y up and Z right.
IMU X points backward, IMU Y points down, IMU Z points rightCONFIG IMU URFR 413Backward-facing vertical mounting with Y down and Z right.
IMU X points down, IMU Y points forward, IMU Z points rightCONFIG IMU URFR 421Vertical mounting with X down and Z right.
IMU X points up, IMU Y points backward, IMU Z points rightCONFIG IMU URFR 430Vertical mounting with X up and Z right.
IMU X points forward, IMU Y points down, IMU Z points leftCONFIG IMU URFR 503Forward-facing vertical mounting with Y down and Z left.
IMU X points backward, IMU Y points up, IMU Z points leftCONFIG IMU URFR 512Backward-facing vertical mounting with Y up and Z left.
IMU X points up, IMU Y points forward, IMU Z points leftCONFIG IMU URFR 520Common vertical mounting with X up and Z left.
IMU X points down, IMU Y points backward, IMU Z points leftCONFIG IMU URFR 531Common vertical mounting with X down and Z left.
Multi-Function IO Multiplexing Configuration

The module provides multiple multi-function pins (IOx). Each IO pin has a default multiplexing function and can also be remapped to other functions via software. Format: CONFIG <PMUX> <IO>.

Parameters:

  • PMUX: multiplexing function ID (PMUX1 ~ PMUX3)
  • IO: target pin ID (IO1 ~ IO5)
FunctionNameDirDescriptionDefault IO
PMUX1SIN/PPSISync pulse input (SIN/PPS): input pin, see "Synchronous Input/Output"IO1
PMUX2SOUTOLow when no data is being transmitted (idle); before a frame starts to be sent, a high pulse is emitted, and data transmission begins immediately after the falling edge of the pulseIO2
PMUX3LEDOOperating-status indicator outputIO5

Examples:

  • CONFIG PMUX3 IO2 - assign IO2 to the LED (PMUX3) function
  • CONFIG PMUX2 IO1 - assign IO1 to the sync output (PMUX2) function

📝 Note Not all IO pins are physically exposed on every product. See the corresponding product user manual for detailed hardware resources.

SOUT (PMUX2) Sync-Output Divider

The SOUT sync output supports frequency division, which can be used to trigger lower-rate fusion sensors such as cameras. Format: CONFIG PMUX2 DIV <N>.

Parameters:

  • N: divider, range 1~1000, default 1 (no division)

Example:

  • CONFIG PMUX2 DIV 5 - set the SOUT divider to 5. If the data output rate is 100 Hz, the SOUT pulse output frequency is 20 Hz.
Magnetic Calibration

Start a manual magnetic calibration: CONFIG MCAL START. After issuing this command, the module starts the calibration procedure and completes it automatically based on the spatial magnetic-field distribution; no explicit stop command is needed. During calibration, slowly rotate the module in place and ensure that any objects rigidly attached to it (PCB, housing, robot, etc.) maintain their relative positions. See the "Magnetic Calibration" chapter for details.

After issuing the start command, you can query calibration status with LOG MCAL STAT. Example response:

STAT=1
PROGRESS=8
OK
  • STAT: current magnetic calibration state. 0 = idle, 1 = calibrating, 3 = calibration complete, 4 = calibration failed
  • PROGRESS: current calibration progress, range 0~100

📝 Important The magnetic calibration command requires firmware version ≥ 1.7.0.

Coordinate System Definition

The module uses the East-North-Up (ENU) coordinate system by default. You can switch the world coordinate system using the following commands:

  • CONFIG IMU COORD 0 - set the world frame to East-North-Up (ENU)
  • CONFIG IMU COORD 4 - set the world frame to North-West-Up (NWU)
User-Level Gyroscope Calibration

This command is used to manually calibrate the gyroscope Z-axis scale factor. When properly executed, it can improve heading accuracy (after calibration, the scale-factor error is within 0.1%). Suitable for AGVs, large horizontally-moving robots, and other applications with high long-term heading-accuracy requirements. Format: CONFIG USRCAL START <ANGLE>.

Parameters:

  • ANGLE: calibration angle, range 720~1800° (2~5 turns). More turns reduce statistical error, but uniform rotation speed must be maintained.

Examples:

  1. Preparation: place the module (together with the rigidly attached platform such as a robot) on a flat horizontal surface, ensure stable ambient temperature, and avoid strong vibration.
  2. Send the start command: e.g., CONFIG USRCAL START 720 - start 720° (2 turns) calibration.
  3. Perform the calibration motion: rotate horizontally by the angle set in <ANGLE> at 20~100 deg/s (about 5~20 s per turn). The rotation direction can be either clockwise or counterclockwise. Maintain uniform speed throughout the rotation; avoid pauses, sudden acceleration, or deceleration.
  4. Send the stop command: when the rotation is complete and the actual rotation angle is within ±5° of the <ANGLE> setpoint, send CONFIG USRCAL STOP to finish the calibration. The module returns OK on success or ERR on failure.

Common causes of calibration failure:

Failure causeDescription
Non-standard rotationEnsure the module is placed horizontally and stably
Improper operationRotation too fast or too slow, mid-way pauses
Environmental disturbanceAvoid operating near vibrating equipment, e.g., excessive motor vibration
Errors persist or worsen after calibrationMost likely due to non-standard rotation. Calibration is a precise process: if the specified rotation is 720° but the actual rotation is 725°, the scale factor will be erroneously calibrated as 5/720 = 0.6%, far exceeding the factory accuracy

LOG

Enable/Disable Data Output
  • LOG ENABLE - globally enable data frame output
  • LOG DISABLE - globally disable data frame output
Module Version Information

LOG VERSION - query and print firmware version information

Display UART Configuration

LOG COMCONFIG - print UART and output protocol configuration

Set Output Frame Type and Rate

Format: LOG <MSG> <TYPE> <VALUE>

Parameters:

  • MSG: data frame type. Common types include HI91, HI81, HI83, GGA, RMC, SXT, etc. Available types depend on the specific product and current UART configuration.
  • TYPE: output trigger mode, supports ONTIME (periodic output) and ONMARK (sync-pulse trigger or software trigger).
  • VALUE: when TYPE=ONTIME, the output period in seconds. Range: 0.001 (1 kHz) ~ 1 (1 Hz); 0 disables periodic output. When TYPE=ONMARK, 1 means trigger on SYNC_IN/PPS pulse, and ONCE triggers one output manually.

Examples:

  • LOG HI91 ONTIME 0.01 - set the HI91 output period on the current UART to 0.01 s (100 Hz)
  • LOG HI91 ONTIME 0.05 - set the HI91 output period on the current UART to 0.05 s (20 Hz)
  • LOG HI91 ONTIME 0 - disable HI91 output
  • LOG HI91 ONMARK 1 - configure the HI91 frame on the current UART to be triggered by the SYNC_IN/PPS pin
  • LOG HI91 ONMARK ONCE - trigger one HI91 output manually (same effect as one SYNC_IN/PPS pulse)
HI83 Variable-Length Frame Configuration

HI83 is a variable-length binary output frame, suitable for applications that need to simultaneously output IMU, attitude, time, GNSS, or integrated navigation data while controlling frame length on demand. The HI83 payload is determined by data_bitmap: each bit of data_bitmap corresponds to one data segment; setting the bit to 1 enables that segment, and 0 disables it. The data segments are arranged in the frame from low bit to high bit.

Bitmap configuration format: LOG HI83 MAP <BITMAP>

  • <BITMAP> can be expressed in hex or decimal, e.g., 0x000000FF;
  • For the meaning of each bit, see the "Variable-Length Protocol (HI83)" section below;
  • The default HI83 bitmap is 0x000000FF.

Common configuration examples:

CommandDescription
LOG HI83 MAP 0x000000FFDefault HI83 fields: acceleration, angular velocity, magnetic field, Euler angles, quaternion, system time, UTC, barometric pressure
LOG HI83 MAP 0x0000001FIMU + basic attitude: acceleration, angular velocity, magnetic field, Euler angles, quaternion
LOG HI83 ONTIME 0.01Set the HI83 output period on the current UART to 0.01 s (100 Hz)
LOG HI83 ONTIME 0Disable periodic HI83 output on the current UART

⚠️ Baud rate notes When the output rate is high (e.g., 500 Hz), the default 115200 baud rate may not provide sufficient bandwidth. In that case, increase the module baud rate to a higher value (e.g., 921600) to ensure stable data output.

FRESET

Restore the module's default user configuration. After execution, the module automatically saves and resets — use with caution. Some calibration-related parameters may be retained, depending on current firmware behavior. Example: FRESET

RS-232/TTL/USB Data Protocol (Binary)

RS-232, UART-TTL, and USB (virtual COM) are stream-style serial interfaces that support Hipnuc's proprietary binary protocol.

Data Frame Format

FieldValueLength (bytes)Description
SOF5A A52Start-of-frame sync word
LEN1-40962Payload length, LSB first (does not include header, type, length, or CRC fields)
CRC-216-bit CRC over the header, length, and payload (excludes the CRC field itself)
Payload-1-4096Frame payload, composed of one or more sub-packets. Each sub-packet has a tag and data part, where the tag determines the data type and length.

Factory Default Output

Default output: floating-point IMU data frame (HI91).

Payload Content

Floating-Point IMU Data Frame (HI91)

The payload is 76 bytes and includes module ID, temperature, raw IMU data, magnetic field, barometric pressure, and fused attitude data.

OffsetNameTypeSize (bytes)UnitScaleDescription
0taguint8_t1--Data tag: 0x91
1main_statusuint16_t2--Status word, see MAIN_STATUS description
3temperatureint8_t1°C1Module average temperature
4air_pressurefloat4Pa1Barometric pressure
8system_timeuint32_t4ms1When GPS time is not synchronized, this field is a local timestamp (milliseconds since power-up); when GPS time is synchronized, this field is aligned to UTC milliseconds of the current day
12acc_bfloat4×3G1Factory-calibrated acceleration, XYZ order. 1 G = 1× standard gravity (~9.8 m/s²)
24gyr_bfloat4×3deg/s1Factory-calibrated angular velocity, XYZ order
36mag_bfloat4×3μT1Magnetic field strength, XYZ order
48rollfloat4deg1Roll angle
52pitchfloat4deg1Pitch angle
56yawfloat4deg1Heading angle
60quatfloat4×4--Node quaternion set, WXYZ order

Variable-Length Protocol (HI83)

The data carried in this protocol is configurable; different combinations can be output by data_bitmap, and the frame size changes accordingly.

OffsetNameTypeSize (bytes)UnitScaleDescription
0taguint8_t1--Data tag: 0x83
1main_statusuint16_t2--Status word, see MAIN_STATUS description
3ins_statusuint8_t1--Integrated navigation solution status (only for integrated-navigation products):
0: Solution invalid - no GNSS info, cannot initialize position
1: Aligning - position initialized, but speed is required to complete the integrated-navigation filter initialization to enter the integrated-navigation state
3: Integrated navigation - currently in integrated-navigation state
6: Inertial dead-reckoning - currently in integrated-navigation state but GNSS is lost; pure-inertial mode (tunnel, parking garage, etc.)
4data_bitmapuint32_t4--Bitmap of carried data segments, configurable. Each bit corresponds to one data type; segments are arranged from the lowest bit to the highest
8--1-512--Subsequent payload defined by data_bitmap.

data_bitmap Bits and Data Segments

data_bitmap
bit
NameTypeSizeUnitScaleDescription
0acc_bfloat4x3m/s^(2)1IMU body-frame, factory-calibrated acceleration, order: XYZ
1gyr_bfloat4x3rad/s1IMU body-frame, factory-calibrated angular velocity, order: XYZ
2mag_bfloat4x3μT1IMU body-frame, calibrated magnetic field, order: XYZ
3rpyfloat4x3deg1Attitude angles (Euler angles), order:
roll, range: -180 - 180
pitch, range: -90 - 90
yaw, range: -180 - 180, counterclockwise positive
4quatfloat4x4-1Node quaternion set, WXYZ order
5system_time_usuint64_t8us1Local high-resolution timestamp, microseconds elapsed since power-up, incrementing by 1 every 1 us
6utc-8--UTC time, 8 bytes total:
year: 1 byte, e.g., 24 represents 2024
month: 1 byte
day: 1 byte
hour: 1 byte
minute: 1 byte
seconds: 2 bytes, unit 1 ms, e.g., 12 s is encoded as 12000
reserved: 1 byte
7air_pressurefloat4Pa1Barometric pressure
8temperaturefloat41Module average temperature
9inclinationfloat4x3deg1Inclinometer output, order: about X axis, about Y axis, about Z axis
10heave_surge_swayfloat4x3m1Vessel heave-surge-sway displacement, order: heave, surge, sway
11heave_surge_sway_frqfloat4x3Hz1Vessel heave-surge-sway frequency, order: heave, surge, sway
12vel_enufloat4x3m/s1East-North-Up velocity in the navigation frame, integrated-navigation output
13acc_enufloat4x3m/s^(2)1East-North-Up acceleration in the navigation frame, integrated-navigation output
14ins_lon_lat_msldouble8x3-1Fused longitude/latitude from integrated navigation, order: longitude (deg), latitude (deg), MSL altitude (m)
15gnss_quality_nv-4--GNSS solution status group, 4 bytes:
solq_pos: 1 byte, position solution status
nv_pos: 1 byte, number of satellites used for position
solq_heading: 1 byte, heading solution status
nv_heading: 1 byte, number of satellites used for heading
16od_speedfloat4m/s-External odometer sensor speed
17undulationfloat4mGeoid undulation
18diff_agefloat4sRTK differential age
19node_info-4-Device version and ID:
node_id: 1 byte, node ID identical to CAN ID, range 1~127
reserved: 3 bytes
20-24Reserved
25event_counteruint32_t4x16-1Internal measurement event counters. Common order: gravity, mag, gnss_pos, gnss_vel, dual_heading, nhc, zupt, zaru, zihr, od; the rest are reserved
26kf_acc_biasfloat4x3m/s^(2)1Accelerometer bias estimated by the integrated-navigation KF, order: XYZ
27kf_gyr_biasfloat4x3rad/s1Gyroscope bias estimated by the integrated-navigation KF, order: XYZ
28gnss_stdfloat4x3-1GNSS accuracy, order: position standard-deviation norm, velocity standard-deviation norm, reserved
29gnss_heading_infofloat4x3-1Dual-antenna GNSS heading info, order: baseline length (m), pitch (deg), heading (deg)
30gnss_lon_lat_msldouble8x3-1Raw GNSS longitude/latitude/altitude, order: longitude (deg), latitude (deg), MSL altitude (m)
31gnss_velfloat4x3m/s1GNSS East-North-Up velocity, order: E, N, U

MAIN_STATUS Status Word Description

BitNameDescription
0-2Reserved-
3WB_CONVBias convergence alarm. 1: current bias estimation accuracy is poor; recommended to keep the module still for 3~5 s to improve heading accuracy. 0: bias estimate has converged well.
4MAG_DISTMagnetic anomaly alarm. 1: magnetic interference detected, or the magnetometer is not calibrated, or the hard-magnetic environment has changed; heading error may be large in 9-axis mode. 0: magnetic environment is good and the heading has converged, or the system is in 6-axis mode.
5ACC_SATAccelerometer range saturation alarm. 1: accelerometer range saturation detected currently or within the last 2 s. 0: no saturation detected at present, and no saturation event for the last continuous 2 s.
6GYR_SATGyroscope range saturation alarm. 1: gyroscope range saturation detected currently or within the last 2 s. 0: no saturation detected at present, and no saturation event for the last continuous 2 s.
7ATT_CONVAttitude accuracy indicator. 1: current attitude accuracy is poor (the AHRS attitude KF covariance is large); keep the module still for a moment to allow attitude accuracy to recover. 0: attitude accuracy is normal.
8-9Reserved-
10MAG_AIDINGMagnetometer aiding flag. 1: magnetometer is involved in heading computation (9-axis mode). 0: magnetometer is not involved in heading computation (6-axis mode).
11UTC_SYNCEDTime-sync flag. 1: time sync is not complete and system_time is local time; 0: UTC time sync is complete and system_time in HI91 is aligned to UTC milliseconds of the current day.
12SOUT_PULSESOUT pulse output flag, used to time-synchronize with low-rate sensors (camera, LiDAR, etc.). 1: this data frame corresponds to an SOUT pulse output; 0: this data frame does not correspond to an SOUT pulse output.
13-15Reserved-

📝 Compatibility The MAIN_STATUS status word is only available on firmware versions ≥ 1.7.0.

CRC Verification

CRC uses the CRC-16/CCITT polynomial. Example C implementation:

/*
	currectCrc: previous crc value, set 0 if it's first section
	src: source stream data
	lengthInBytes: length
*/
static void crc16_update(uint16_t *currectCrc, const uint8_t *src, uint32_t lengthInBytes)
{
    uint32_t crc = *currectCrc;
    uint32_t j;
    for (j=0; j < lengthInBytes; ++j)
    {
        uint32_t i;
        uint32_t byte = src[j];
        crc ^= byte << 8;
        for (i = 0; i < 8; ++i)
        {
            uint32_t temp = crc << 1;
            if (crc & 0x8000)
            {
                temp ^= 0x1021;
            }
            crc = temp;
        }
    }
    *currectCrc = crc;
}

Data Frame Example (HI91)

A sample HI91 frame captured by a serial terminal contains 82 bytes in total: the first 6 bytes are the header, length, and CRC; the remaining 76 bytes are the payload. Assume the data is received into a C array buf as shown below:

5A A5 4C 00 14 BB 91 08 15 23 09 A2 C4 47 08 15 1C 00 CC E8 61 BE 9A 35 56 3E 65 EA 72 3F 31 D0 7C BD 75 DD C5 BB 6B D7 24 BC 89 88 FC 40 01 00 6A 41 AB 2A 70 C2 96 D4 50 41 ED 03 43 41 41 F4 F4 C2 CC CA F8 BE 73 6A 19 BE F0 00 1C 3D 8D 37 5C 3F

Parsing table:

Field nameTypeRaw valueParsed valueDescription
Header-5A A5-Frame header
Payload length-4C 000x004C = 76Payload length = 76 bytes
CRC-14 BB0xBB14CRC
tag-910x910x91 sub-packet tag (payload starts here)
main_statusuint16_t08 150x1508Status word
temperatureint8_t230x23 = 35Temperature, °C
air_pressurefloat09 A2 C4 47100676Barometric pressure, Pa
system_timeuint32_t08 15 1C 000x001C1508 = 1840392Timestamp, ms
acc_b_xfloatCC E8 61 BE-0.220615X-axis acceleration, G
acc_b_yfloat9A 35 56 3E0.209189Y-axis acceleration, G
acc_b_zfloat65 EA 72 3F0.948889Z-axis acceleration, G
gyr_b_xfloat31 D0 7C BD-0.061722X-axis angular velocity, deg/s
gyr_b_yfloat75 DD C5 BB-0.00603836Y-axis angular velocity, deg/s
gyr_b_zfloat6B D7 24 BC-0.0100611Z-axis angular velocity, deg/s
mag_b_xfloat89 88 FC 407.89167X-axis magnetic field, μT
mag_b_yfloat01 00 6A 4114.625Y-axis magnetic field, μT
mag_b_zfloatAB 2A 70 C2-60.0417Z-axis magnetic field, μT
rollfloat96 D4 50 4113.0519Roll, deg
pitchfloatED 03 43 4112.1885Pitch, deg
yawfloat41 F4 F4 C2-122.477Heading, deg
q_wfloatCC CA F8 BE-0.485922Quaternion W
q_xfloat73 6A 19 BE-0.14982Quaternion X
q_yfloatF0 00 1C 3D0.0380868Quaternion Y
q_zfloat8D 37 5C 3F0.860223Quaternion Z

C Parsing Code Example (HI91)

The following snippets show common C parsing fragments:

CRC Check

c
int16_t payload_len;
uint16_t crc;
crc = 0;
payload_len = buf[2] + (buf[3] << 8);

/* Calculate 5A A5 and LEN field crc */
crc16_update(&crc, buf, 4);

/* Calculate payload crc */
crc16_update(&crc, buf + 6, payload_len);

The computed CRC value is 0xBB14, identical to the CRC field in the frame, so the CRC check passes.

Define Receive Data Structure

Starting from 0x91 is the sub-packet payload. The following gives an example data structure and common conversion macros:

c
#include "stdio.h"
#include "string.h"

/* Common type conversion */
#define U1(p) (*((uint8_t *)(p)))
#define I1(p) (*((int8_t  *)(p)))
#define I2(p) (*((int16_t  *)(p)))

static uint16_t U2(uint8_t *p) {uint16_t u; memcpy(&u,p,2); return u;}
static uint32_t U4(uint8_t *p) {uint32_t u; memcpy(&u,p,4); return u;}
static int32_t  I4(uint8_t *p) {int32_t  u; memcpy(&u,p,4); return u;}
static float    R4(uint8_t *p) {float    r; memcpy(&r,p,4); return r;}

typedef struct
{
    uint8_t     tag;              /* Item tag: 0x91        */
    float       acc[3];           /* Acceleration          */
    float       gyr[3];           /* Angular velocity      */
    float       mag[3];           /* Magnetic field        */
    float       eul[3];           /* Attitude: Euler angle */
    float       quat[4];          /* Attitude: quaternion  */
    float       pressure;         /* Air pressure          */
    uint32_t    timestamp;        /* Timestamp             */
}imu_data_t;

Receive Data

Starting at buf[6]=0x91 is the payload:

c
imu_data_t i0x91 = {0};
int offset = 6; /* Payload start at buf[6] */

i0x91.tag =             U1(buf+offset+0);
i0x91.pressure =        R4(buf+offset+4);
i0x91.timestamp =       U4(buf+offset+8);
i0x91.acc[0] =          R4(buf+offset+12);
i0x91.acc[1] =          R4(buf+offset+16);
i0x91.acc[2] =          R4(buf+offset+20);
i0x91.gyr[0] =          R4(buf+offset+24);
i0x91.gyr[1] =          R4(buf+offset+28);
i0x91.gyr[2] =          R4(buf+offset+32);
i0x91.mag[0] =          R4(buf+offset+36);
i0x91.mag[1] =          R4(buf+offset+40);
i0x91.mag[2] =          R4(buf+offset+44);
i0x91.eul[0] =          R4(buf+offset+48);
i0x91.eul[1] =          R4(buf+offset+52);
i0x91.eul[2] =          R4(buf+offset+56);
i0x91.quat[0] =         R4(buf+offset+60);
i0x91.quat[1] =         R4(buf+offset+64);
i0x91.quat[2] =         R4(buf+offset+68);
i0x91.quat[3] =         R4(buf+offset+72);
c
printf("%-16s0x%X\r\n",                 "tag:",           i0x91.tag);
printf("%-16s%8.4f %8.4f %8.4f\r\n",    "acc(G):",        i0x91.acc[0], i0x91.acc[1],  i0x91.acc[2]);
printf("%-16s%8.3f %8.3f %8.3f\r\n",    "gyr(deg/s):",    i0x91.gyr[0], i0x91.gyr[1],  i0x91.gyr[2]);
printf("%-16s%8.3f %8.3f %8.3f\r\n",    "mag(uT):",       i0x91.mag[0], i0x91.mag[1],  i0x91.mag[2]);
printf("%-16s%8.3f %8.3f %8.3f\r\n",    "eul(deg):",      i0x91.eul[0], i0x91.eul[1],  i0x91.eul[2]);
printf("%-16s%8.3f %8.3f %8.3f %8.3f\r\n",  "quat:",      i0x91.quat[0], i0x91.quat[1], i0x91.quat[2], i0x91.quat[3]);
printf("%-16s%8.3f\r\n",                    "pressure(pa):", i0x91.pressure);
printf("%-16s%d\r\n",                       "timestamp(ms):", i0x91.timestamp);

Maximum Transmission Rate

ProtocolBytes9600 bps115200 bps230400 bps256000 bps460800 bps921600 bps
HI917610 Hz100 Hz250 Hz250 Hz500 Hz1000 Hz

RS-485 Output Protocol (Modbus)

Modbus is a widely used general-purpose protocol in industrial automation, and can run over RS-485 or Ethernet. Products with an RS-485 or Ethernet interface usually support Modbus; actual availability depends on the specific product model and delivered configuration.

In the current firmware, the Modbus slave is mounted on the RS-485 channel of COM1 by default. For products with multiple interfaces or customized communication mappings, refer to the actual delivered configuration.

Modbus Command Description

The RS-485 communication follows the Modbus RTU specification. Data is sent and received in registers; each register is 2 bytes, big-endian (high byte first). Standard Modbus CRC is used.

Supported function codes:

  • 0x06 (Write Single Register): write a single register (each Modbus register is 2 bytes)
  • 0x03 (Read Holding Registers): read one or more registers
  • 0x50 (Custom function code): used for Modbus ID auto-assignment and similar use cases, for mass production deployment and firmware upgrades

Factory default node ID: 80 (0x50)

Data Frame Format

Read Registers (0x03)

Master sends:

FieldValueDescription
ID1-0xFFModbus node ID
FUN_CODE0x03Function code
ADDR_H-Register address high 8 bits
ADDR_L-Register address low 8 bits
LEN_H-Number of registers to read, high 8 bits
LEN_L-Number of registers to read, low 8 bits
CRC_L-CRC low 8 bits
CRC_H-CRC high 8 bits

Slave (module) responds:

FieldValueDescription
ID1-0xFFModbus node ID
FUN_CODE0x03Function code
LEN-Length of returned register data in bytes (excluding ID, FUN_CODE, LEN, CRC)
DATAH-Returned data high 8 bits
DATAL-Returned data low 8 bits
...-More returned data
CRC_L-CRC low 8 bits
CRC_H-CRC high 8 bits

Write Register (0x06)

Master sends:

FieldValueDescription
ID1-0xFFModbus node ID
FUN_CODE0x06Function code
ADDR_H-Register address high 8 bits
ADDR_L-Register address low 8 bits
DATA_H-Data to write high 8 bits
DATA_L-Data to write low 8 bits
CRC_L-CRC low 8 bits
CRC_H-CRC high 8 bits

Slave responds:

FieldValueDescription
ID1-0xFFModbus node ID
FUN_CODE0x06Function code
ADDR_H-Register address high 8 bits
ADDR_L-Register address low 8 bits
DATA_H-Data written high 8 bits
DATA_L-Data written low 8 bits
CRC_L-CRC low 8 bits
CRC_H-CRC high 8 bits

Register List

Address (Hex)Address (Dec)NameTypeFunctionR/WDescription
0x000CTRLu16ControlWSee control register description
0x044UART1_BAUDu16Baud rateR/WUART baud rate
0x055MD_IDu16Modbus IDR/WModbus ID, valid range: 1-128
0x066HEADING_MODEu16Heading modeR/W0: 6-axis mode (relative heading, 0 at power-up). 1: 9-axis mode (mag-fused, absolute heading)
0x3452ACCXi16Acceleration XRUnit: G (1 G = 1× gravity), scale: 0.00048828
0x3553ACCYi16Acceleration YRUnit: G (1 G = 1× gravity), scale: 0.00048828
0x3654ACCZi16Acceleration ZRUnit: G (1 G = 1× gravity), scale: 0.00048828
0x3755GYRXi16Angular velocity XRUnit: deg/s, scale: 0.061035
0x3856GYRYi16Angular velocity YRUnit: deg/s, scale: 0.061035
0x3957GYRZi16Angular velocity ZRUnit: deg/s, scale: 0.061035
0x3A58MAGXi16Magnetic field XRUnit: μT, scale: 0.030517
0x3B59MAGYi16Magnetic field YRUnit: μT, scale: 0.030517
0x3C60MAGZi16Magnetic field ZRUnit: μT, scale: 0.030517
0x3D61R_Hi32Roll high 16 bitsRUnit: deg, scale: 0.001
0x3E62R_L-Roll low 16 bitsRUnit: deg, scale: 0.001
0x3F63P_Hi32Pitch high 16 bitsRUnit: deg, scale: 0.001
0x4064P_L-Pitch low 16 bitsRUnit: deg, scale: 0.001
0x4165Y_Hi32Heading high 16 bitsRUnit: deg, scale: 0.001
0x4266Y_L-Heading low 16 bitsRUnit: deg, scale: 0.001
0x4367TEMPi16TemperatureRUnit: ℃, scale: 0.01
0x4468PRS_Hi32Pressure high 16 bitsRUnit: Pa, scale: 0.01
0x4569PRS_L-Pressure low 16 bitsRUnit: Pa, scale: 0.01
0x4670Q0u16Quaternion QWRQuaternion, scale: 0.0001
0x4771Q1u16Quaternion QXRQuaternion, scale: 0.0001
0x4872Q2u16Quaternion QYRQuaternion, scale: 0.0001
0x4973Q3u16Quaternion QZRQuaternion, scale: 0.0001
0x4A74INCLI_Xi16Inclinometer X angleRDual-axis inclinometer products: X angle, ±180, unit: deg, scale: 0.011
Single-axis inclinometer products: X angle, 0-360, unit: deg, scale: 0.011
0x4B75INCLI_Yi16Inclinometer Y angleRDual-axis inclinometer: Y angle, ±90, unit: deg, scale: 0.011
Single-axis inclinometer: reserved
0x4E78HEVAEi16Vessel heaveRVessel heave displacement output, unit: m, scale: 0.01
0x5181HEAVE_PERIODi16Vessel heave periodRVessel heave displacement period, unit: s, scale: 0.001
0x70-0x77112-119PNAMEu16Device nameRDevice name string in ASCII, 8 registers total
0x78120SW_VERSIONu16Software versionRSoftware version
0x79121BL_VERSIONu16BL versionRBootloader version
0x7F-0x82127-130SNu16Unique serial numberRUnique serial number, 4 registers
0xA5165ATT_RSTu16Auto-levelW3: perform one auto-level: if current pitch/roll is close to 0°,0° (placed horizontally right-side up), auto-calibrate to 0°,0°. If current pitch/roll is close to 0° or 180° (placed horizontally upside-down), auto-calibrate to 0°,180°. Suitable for robotic installations. "Close to" means both Pitch and Roll are less than 15°.
5: cancel auto-level and restore absolute angle output
Other values: invalid

Control register description (register address: 0x00)

CommandValue to write
Save all configuration to Flash0x0000
Restore factory defaults0x0001
Reset0x00FF

Common Configurations

📝 Note All configuration examples below use Modbus address 0x50 (factory default) as an example. If you have modified the Modbus ID, update the ID field and CRC in the message accordingly.

Save Configuration to Flash

50 06 00 00 00 00 84 4B

Restore Factory Defaults

50 06 00 00 00 01 45 8B

⚠️ Executing this command restores the module's default user configuration, then automatically saves and resets. Some calibration-related parameters may be retained.

Reset

50 06 00 00 00 FF C4 0B

Configure Baud Rate (0x04)

Target baud rateCommand (Hex) ID=0x50 (factory default)
480050 06 00 04 00 00 C5 8A
960050 06 00 04 00 01 04 4A
1920050 06 00 04 00 02 44 4B
3840050 06 00 04 00 03 85 8B
5760050 06 00 04 00 04 C4 49
11520050 06 00 04 00 05 05 89
23040050 06 00 04 00 06 45 88
46080050 06 00 04 00 07 84 48
92160050 06 00 04 00 08 C4 4C

Configure Node ID (0x05)

Format: [CURRENT_ID] 06 00 05 00 [NEW_ID] CRC(2 bytes)

Parameters:

  • CURRENT_ID: current Modbus node ID
  • NEW_ID: new target Modbus node ID

Examples (current node ID = 0x50):

  • Set NEW_ID=0x50: 50 06 00 05 00 50 94 76
  • Set NEW_ID=0x51: 50 06 00 05 00 51 55 B6
  • Set NEW_ID=0x52: 50 06 00 05 00 52 15 B7
  • Set NEW_ID=0x53: 50 06 00 05 00 53 D4 77

⚠️ Important Once changed, the new Modbus address takes effect immediately. The host must switch CURRENT_ID to the new node ID for subsequent communication. If you are not familiar with Modbus message construction, use a host tool to perform the configuration.

Set Mounting Orientation (0xA6)

Target mounting orientationCommand (Hex) ID=0x50 (factory default)
Horizontal, Z-axis up (default)50 06 00 A6 00 18 64 62
Rotated -90° about X (vertical mount, Y+ pointing down)50 06 00 A6 00 2B 24 77
Rotated +90° about X (vertical mount, Y+ pointing up)50 06 00 A6 00 34 65 BF
Rotated +90° about Y (vertical mount, X+ pointing up)50 06 00 A6 02 08 64 CE
Rotated -90° about Y (vertical mount, X+ pointing down)50 06 00 A6 01 A5 A5 83

Set Auto-Level (0xA5)

  • Start auto-level: 50 06 00 A5 00 02 15 A9
  • Cancel auto-level: 50 06 00 A5 00 05 54 6B

Set 6-Axis or 9-Axis Mode (0x06)

  • Set to 6-axis mode: 50 06 00 06 00 00 64 4A
  • Set to 9-axis mode: 50 06 00 06 00 01 A5 8A

Read Module Version Information (0x70-0x82)

Read product name, software version, and serial number. Request frame: 50 03 00 70 00 14 49 9F

FieldValueDescription
Modbus node ID0x50Modbus node ID
Function code0x03Read holding registers
Start address0x0070Product info start address
Read length0x0014Read 20 registers
CRC0x9F49-

Response frame: 50 03 28 48 49 31 34 52 32 4E 2D 34 38 35 2D 30 30 30 00 00 98 00 6B 00 00 00 00 00 00 00 00 00 00 04 7D 95 5F 8D 2A 17 08 00 00 4D 0C

FieldDataDescription
Modbus node ID0x50Modbus node ID
Function code0x03Function code
Data length0x28Returns 40 bytes of data; 20 registers requested, 2 bytes each
Product name48 49...30 30CH10x(M)
Software version0x98V1.52
Bootloader version0x6BV1.07
Serial number047D955F8D2A1708SN code

Read Sensor Data (0x34-0x4B)

Request frame: 50 03 00 34 00 18 09 8F

FieldValueDescription
Modbus node ID0x50Modbus node ID
Function code0x03Read holding registers
Start address0x0034Sensor data start address
Read length0x0018Read 24 registers
CRC0x8F09-

Response frame: 50 03 30 FF 01 03 B0 06 50 FC C9 FF 7C 00 91 01 D5 FD DB FD 27 00 00 21 FF 00 00 7F F6 FF FD 73 E7 00 00 00 00 00 00 10 A6 0D 59 DD 4E 86 A8 06 30 17 82 1E CE

Data parsing examples:

Acceleration (unit: G, where 1 G = 9.8 m/s²):

AxisRegister value (HEX)Raw value (DEC)ScalePhysical value
XFF 01-2550.00048828-0.1245
Y03 B09440.000488280.4609
Z06 5016160.000488280.7891

Angular velocity (unit: deg/s):

AxisRegister value (HEX)Raw value (DEC)ScalePhysical value
XFC C9-8230.061035-50.2318
YFF 7C-1320.061035-8.0566
Z00 911450.0610358.8501

Magnetic field (unit: μT):

AxisRegister value (HEX)Raw value (DEC)ScalePhysical value
X01 D54690.03051714.3125
YFD DB-5490.030517-16.7538
ZFD 27-7290.030517-22.2469

Euler angles (unit: deg):

AxisRegister value (HEX)Raw value (DEC)ScalePhysical value
Roll00 00 21 FF87030.0018.703
Pitch00 00 7F F6327580.00132.758
Yaw (heading)FF FD 73 E7-1669370.001-166.937

CAN Data Protocol (J1939)

Products with CAN output usually use the J1939 protocol by default, strictly following the SAE J1939 international standard. J1939 is a higher-layer protocol based on the CAN 2.0B extended frame format, widely used in commercial vehicles and industrial equipment. For more details, see here.

CAN Extended Frame Format

J1939 uses the CAN 2.0B extended frame format. The 29-bit identifier is structured as follows:

Bit field layout (MSB → LSB):
[28:26] Priority (P)     - priority (3 bits)
[25]    Reserved (R)     - reserved (1 bit)
[24]    Data Page (DP)   - data page (1 bit)
[23:16] PDU Format (PF)  - PDU format (8 bits)
[15:8]  PDU Specific (PS)- PDU specific (8 bits)
[7:0]   Source Address   - source address (8 bits)

Identifier formula:

CAN_ID = (Priority << 26) | (Reserved << 25) | (DataPage << 24) | (PF << 16) | (PS << 8) | SourceAddress

Byte Order (Endianness)

Important note: The J1939 protocol uses little-endian data format:

  • Multi-byte data: low byte first, high byte last.

  • Bit order: LSB (Least Significant Bit) at the low position.

  • Example: the 32-bit integer 0x12345678 appears in a CAN frame as: 78 56 34 12.

CANFD Support

This section describes the protocol for CANFD output. Whether a specific product supports CANFD and whether the current firmware enables it depends on the actual product model and firmware configuration.

When the product supports and enables CANFD output, the control-field baud rate of the CANFD frame is the same as classic CAN 2.0B, the FD frame data-field baud rate is typically 4 Mbps, and the data length is 64 bytes.

Protocol Parameters

ParameterValueDescription
CAN baud rate500 Kbps (default)Supports 125K/250K/500K/800K/1000K
Frame formatCAN 2.0B extended frame (29-bit identifier)Conforms to J1939 standard
Data length8 bytes (classic J1939)Classic PGN payload length; see the corresponding section for CANFD
Frame priority3 (default)Range: 0-7, 0 is the highest priority
Default node address8Configurable range: 1-127; broadcast address: 255
PF (PDU Format)0xFF (proprietary PGN)Vendor-defined PGN range
PS (PDU Specific)Data type identifierDistinguishes different sensor data types
Data formatLittle-endian (LSB first)Low byte of multi-byte data comes first
Data typeSigned / unsigned integersDepends on specific PGN definition

PGN Message List

This product supports multiple J1939 PGN messages for sensor data. All PGNs use the vendor-defined format (PF=0xFF). Most classic J1939 PGNs contain 8-byte payloads encoded in little-endian; see the dedicated section for CANFD frames.

PGN 65327 (0xFF2F) - Time Information

Function: outputs UTC time information for status viewing or host parsing.

CAN identifier format: 0x0CFF2F[SA]

  • Priority: 3 (0x0C)
  • PF: 0xFF, PS: 0x2F
  • SA: source address (default 0x08)

Data format:

ByteFieldTypeRangeUnitScaleDescription
0UTC yearuint80-99year120 represents 2020
1UTC monthuint80-12month11-12
2UTC dayuint80-31day11-31
3UTC houruint80-23hour124-hour format
4UTC minuteuint80-59min1Minutes
5UTC seconduint80-59s1Seconds
6-7UTC msuint160-999ms1Milliseconds, little-endian

Output example:

CAN ID: 0x0CFF2F08
Data:   18 06 12 0E 1E 2D 58 02
Parsed: 2024-06-18 14:30:45.600 UTC

PGN 65332 (0xFF34) - Three-Axis Acceleration

Function: outputs three-axis acceleration measurements.

CAN identifier format: 0x0CFF34[SA]

Data format:

ByteFieldTypeRangeUnitScaleDescription
0-1Acceleration Xint16±32767G0.00048828X-axis acceleration, little-endian
2-3Acceleration Yint16±32767G0.00048828Y-axis acceleration, little-endian
4-5Acceleration Zint16±32767G0.00048828Z-axis acceleration, little-endian
6-7Reserveduint160--Reserved, fixed at 0

PGN 65335 (0xFF37) - Three-Axis Angular Velocity

Function: outputs three-axis angular velocity (gyroscope) measurements.

CAN identifier format: 0x0CFF37[SA]

Data format:

ByteFieldTypeRangeUnitScaleDescription
0-1Angular velocity Xint16±32767deg/s0.061035X-axis angular velocity, little-endian
2-3Angular velocity Yint16±32767deg/s0.061035Y-axis angular velocity, little-endian
4-5Angular velocity Zint16±32767deg/s0.061035Z-axis angular velocity, little-endian
6-7Reserveduint160--Reserved, fixed at 0

PGN 65341 (0xFF3D) - Pitch and Roll

Function: outputs pitch and roll attitude information.

CAN identifier format: 0x0CFF3D[SA]

Data format:

ByteFieldTypeRangeUnitScaleDescription
0-3Rollint32±180,000,000deg0.001Roll, little-endian
4-7Pitchint32±90,000,000deg0.001Pitch, little-endian

PGN 65345 (0xFF41) - Heading

Function: outputs heading (yaw) information in two representations.

CAN identifier format: 0x0CFF41[SA]

Data format:

ByteFieldTypeRangeUnitScaleDescription
0-3Heading (0-360°)uint320-360,000,000deg0.0010-360°, clockwise positive, little-endian
4-7Heading (±180°)int32±180,000,000deg0.001±180°, counterclockwise positive, little-endian

PGN 65338 (0xFF3A) - Three-Axis Magnetic Field

Function: outputs three-axis magnetic field measurements.

CAN identifier format: 0x0CFF3A[SA]

Data format:

ByteFieldTypeRangeUnitScaleDescription
0-1Magnetic field Xint16±32767μT0.030517X-axis magnetic field, little-endian
2-3Magnetic field Yint16±32767μT0.030517Y-axis magnetic field, little-endian
4-5Magnetic field Zint16±32767μT0.030517Z-axis magnetic field, little-endian
6-7Reserveduint160--Reserved, fixed at 0

PGN 65350 (0xFF46) - Quaternion

Function: outputs attitude quaternion.

CAN identifier format: 0x0CFF46[SA]

Data format:

ByteFieldTypeRangeUnitScaleDescription
0-1Quaternion qwint16±32767-0.0001Quaternion real part, little-endian
2-3Quaternion qxint16±32767-0.0001Quaternion i component, little-endian
4-5Quaternion qyint16±32767-0.0001Quaternion j component, little-endian
6-7Quaternion qzint16±32767-0.0001Quaternion k component, little-endian

PGN 65354 (0xFF4A) - Inclinometer Output

Function: dedicated angle output for inclinometer products.

Applicable scope: only for inclinometer products and firmware configurations with J1939 output enabled.

CAN identifier format: 0x0CFF4A[SA]

Data format:

ByteFieldTypeRangeUnitScaleDescription
0-3X-axis tiltint320-360,000,000deg0.001X-axis tilt, configurable 0-360° or ±180°
4-7Y-axis tiltint320-360,000,000deg0.001Y-axis tilt, configurable 0-360° or ±90°

PGN 65370 (0xFF5A) - CANFD Data Frame 0 - IMU Data

Function: when the product supports and enables CANFD output, it can output CANFD data frame 0, containing packed IMU data with a frame length of 64 bytes.

Applicable scope: only for products and firmware configurations that support and enable CANFD output.

CAN identifier format: 0x0CFF5A[SA]

Data format:

The payload is 64 bytes and contains the main status, timestamp, raw IMU data, attitude angles, quaternion, temperature, and other information.

OffsetNameTypeSize (bytes)UnitScaleDescription
0main_statusuint162--Status word, see MAIN_STATUS description
2reserveduint81--Reserved
3reserveduint81--Reserved
4system_timeuint324ms1Local timestamp (ms since power-up)
8acc_xint162g0.00048828Acceleration X
10acc_yint162g0.00048828Acceleration Y
12acc_zint162g0.00048828Acceleration Z
14gyr_xint162deg/s0.061035Angular velocity X
16gyr_yint162deg/s0.061035Angular velocity Y
18gyr_zint162deg/s0.061035Angular velocity Z
20mag_xint162uT0.030517Magnetic field X
22mag_yint162uT0.030517Magnetic field Y
24mag_zint162uT0.030517Magnetic field Z
26rollint324deg0.001Roll
30pitchint324deg0.001Pitch
34yawint324deg0.001Yaw
38qwint162-0.0001Quaternion w
40qxint162-0.0001Quaternion x
42qyint162-0.0001Quaternion y
44qzint162-0.0001Quaternion z
46tempint1620.01Module average temperature
48reserveduint816--Reserved

Configuration Protocol

Protocol Format

This product uses a J1939-based configuration protocol that allows the host to read and write some device parameters. Configuration messages use a dedicated PGN and are transmitted via the standard J1939 extended frame format.

Configuration frame format:

  • CAN identifier: 0x0CEF[DA][SA]
  • SA: source address; the address of the host initiating the configuration request; can be assigned on the host side.
  • DA: destination address; usually the product node ID; the broadcast address 255 may also be used.

Data payload format:

ByteFieldTypeDescription
0-1ADDRuint16Register address, little-endian
2CMDuint8Command type (0x06 = write, 0x03 = read)
3STATUSuint8Status field (0 for write commands, status for read responses)
4-7VALuint32Data value, little-endian

Register Address Map

See the register list in the Modbus protocol chapter.

Configuration Examples

The following examples assume the factory default node ID 8.

29-bit extended IDDataDescriptionNotes
0x0CEF08xx2F 01 06 00 [VAL]VAL: 4 bytesPGN:FF2F (UTC time) period, unit: ms, range: 5-1000
0x0CEF08xx34 01 06 00 [VAL]VAL: 4 bytesPGN:FF34 (acceleration) period, unit: ms, range: 5-1000
0x0CEF08xx37 01 06 00 [VAL]VAL: 4 bytesPGN:FF37 (angular velocity) period, unit: ms, range: 5-1000
0x0CEF08xx3D 01 06 00 [VAL]VAL: 4 bytesPGN:FF3D (pitch/roll) period, unit: ms, range: 5-1000
0x0CEF08xx41 01 06 00 [VAL]VAL: 4 bytesPGN:FF41 (heading) period, unit: ms, range: 5-1000
0x0CEF08xx3A 01 06 00 [VAL]VAL: 4 bytesPGN:FF3A (magnetic field) period, unit: ms, range: 5-1000
0x0CEF08xx46 01 06 00 [VAL]VAL: 4 bytesPGN:FF46 (quaternion) period, unit: ms, range: 5-1000
0x0CEF08xx4A 01 06 00 [VAL]VAL: 4 bytesPGN:FF4A (inclinometer) period, unit: ms, range: 5-1000
0x0CEF08xx5A 01 06 00 [VAL]VAL: 4 bytesPGN:FF5A (CANFD frame 0) period, unit: ms, range: 5-1000; valid only when CANFD output is supported and enabled
0x0CEF08xx96 00 06 00 [PGN]PGN: 4 bytesSync-trigger output. For example, with PGN=0xFF34 (acceleration), sending 96 00 06 00 34 FF 00 00 triggers one acceleration frame. There is no response frame; the module sends the corresponding data frame on success
0x0CEF08xxA5 00 06 00 [VAL]VAL: 4 bytesVAL=1 Heading reset: zero the current heading
VAL=2 Set relative zero: zero current Pitch/Roll
VAL=3 Auto-level: auto-calibrate to horizontal
VAL=5 Cancel auto-level: clear relative Pitch/Roll
0x0CEF08xx9D 00 06 00 01 00 00 00-Globally enable node data output (default)
0x0CEF08xx9D 00 06 00 00 00 00 00-Globally disable node data output
0x0CEF08xx00 00 06 00 00 00 00 00-Save all configuration to Flash
0x0CEF08xx00 00 06 00 01 00 00 00-Restore default user configuration; auto-save and reset
0x0CEF08xx00 00 06 00 FF 00 00 00-Reset
0x0CEF08xx9A 00 06 00 [VAL]VAL: 4 bytesConfigure baud rate (save, reset to take effect): 0:1000K, 1:800K, 2:500K, 3:250K, 4:125K
0x0CEF08xx9C 00 06 00 [VAL]VAL: 4 bytesSet J1939 node ID: 1-127
0x0CEF08xx9E 00 06 00 [VAL]VAL: 4 bytesSet inclinometer X axis polarity, 0: default, 1: reversed
0x0CEF08xx9F 00 06 00 [VAL]VAL: 4 bytesSet inclinometer Y axis polarity, 0: default, 1: reversed

📋 Address note

  • The xx in the address field: source address (SA) in the J1939 identifier; can be any byte.
  • The xx in the data field: any byte.

Example: ID=0x0CEF0855, DATA = 37 01 06 00 64 00 00 00 sets PGN:FF37 (angular velocity) to a 100 ms period (10 Hz).

Time Synchronization

In the current firmware, J1939 PGN 65327 (time information) is used to output UTC time information; it is not used as an input channel for synchronizing the module's internal clock.

If UTC synchronization of the module time is required, use the PPS + UART time-message approach described in the earlier "Synchronous Input - SYNC_IN / PPS" chapter.

Notes
  • PGN 65327 can be used to read the UTC time currently output by the module;
  • The current firmware does not support clock synchronization via J1939 time frames;
  • For high-precision time synchronization, see the earlier PPS input and UART time-sync configuration requirements.
Output Example

The following example shows the module outputting one frame of time information over J1939, which the host can parse for the current UTC time:

CAN ID: 0x0CFF2F08
Data:   18 06 12 0E 1E 2D 58 02
Parsed:
- UTC year:   0x18 = 24 (2024)
- UTC month:  0x06 = 6  (June)
- UTC day:    0x12 = 18 (18th)
- UTC hour:   0x0E = 14
- UTC minute: 0x1E = 30
- UTC second: 0x2D = 45
- UTC ms:     0x0258 = 600

CAN Data Protocol (CANopen)

Products with a CAN interface usually use the J1939 stack by default. Some products or delivered configurations support CANopen slave communication; availability depends on the actual product model and delivered configuration. CANopen communication uses standard data frames; common data is transmitted via TPDO1/2/3/4/6/7 — remote frames and extended data frames are not used. By default, TPDO uses asynchronous periodic triggering; for synchronous mode, see the "Sync Protocol" section below.

CANopen Defaults

The following defaults apply to the standard delivered configuration; the actual values depend on the specific product model and delivered configuration.

DefaultValue
CAN baud rate500 kbit/s
Node ID8
Initialization stateOperational
TPDO output rate1 Hz - 200 Hz (per TPDO)

CANopen TPDO

ChannelFrame IDDLCTransmission modeFrequency (Hz)DataDescription
TPDO10x180+ID6Async timed (0xFE)100Accelerationint16, low byte first, 2 bytes per axis, 6 bytes total; X, Y, Z acceleration in mG (0.001 G)
TPDO20x280+ID6Async timed (0xFE)100Angular velocityint16, low byte first, 2 bytes per axis, 6 bytes total; X, Y, Z angular velocity in 0.1 deg/s
TPDO30x380+ID6Async timed (0xFE)100Euler anglesint16, low byte first, 2 bytes per axis, 6 bytes total; Roll, Pitch, Yaw in 0.01°
TPDO40x480+ID8Async timed (0xFE)100Quaternionint16, low byte first, 2 bytes per element, 8 bytes total; w, x, y, z multiplied by 10000. For example, when the quaternion is 1,0,0,0 the output is 10000,0,0,0
TPDO60x680+ID4Async timed (0xFE)20Pressureint32, 4 bytes, unit: Pa
TPDO70x780+ID8Async timed (0xFE)100Inclinometer anglesint32, low byte first, 4 bytes per axis, 8 bytes total; X axis, Y axis in 0.01°

Data Parsing Example

Acceleration and angular velocity parsing:

Acceleration CAN frame: ID=0x188, DATA = 4A 00 1F 00 C8 03

  • ID=0x188: acceleration frame sent by the device with node ID 8
  • Acceleration X = 0x004A = 74 = 74 mG
  • Acceleration Y = 0x001F = 31 = 31 mG
  • Acceleration Z = 0x03C8 = 968 = 968 mG

Angular velocity CAN frame: ID=0x288, DATA = 15 00 14 01 34 00

  • ID=0x288: angular velocity frame sent by the device with node ID 8
  • Angular velocity X = 0x0015 = 21 = 2.1 deg/s
  • Angular velocity Y = 0x0114 = 276 = 27.6 deg/s
  • Angular velocity Z = 0x0034 = 52 = 5.2 deg/s

Connecting to the CAN Device

Using PCAN-View with a PCAN adapter, the received CAN messages and their frame rates can be viewed in the Receive (Rx Message) window as shown below:

Configuration Commands (SDO Protocol)

The configuration commands in this section all use expedited SDO. For power-cycle retention, save the configuration to Flash after configuring.

SDO (Service Data Object) Protocol

Expedited SDO format:

Master sends SDO command to slave:

CAN_IDCS (1B)Object index (2B)Sub-index (1B)Data (4B)
0x600+ID0x23 (write 4 B)LSB firstSub-indexData, LSB first

Slave responds to master:

CAN_IDCS (1B)Object index (2B)Sub-index (1B)Data (4B)
0x580+ID0x60 (write OK ACK)LSB firstSub-indexReserved

Common Configuration Commands

Change Node ID (0x209C)

Command: ID=0x608, DATA=23,9C,20,00,[ID],00,00,00

  • ID range: 1-127
  • To retain across power cycles, save the configuration to Flash and reset (or power-cycle).
Save Configuration to Flash (0x2000)

Command: ID=0x608, DATA=23,00,20,00,00,00,00,00

Reset (0x2000)

Command: ID=0x608, DATA=23,00,20,00,FF,00,00,00

Restore Factory Defaults (0x2000)

Command: ID=0x608, DATA=23,00,20,00,01,00,00,00

⚠️ Warning Restoring factory defaults reverts the module to its default user configuration. After execution, the module automatically saves and resets. Some calibration-related parameters may be retained; use with caution.

Change CAN Baud Rate (0x209A)

Command: ID=0x608, DATA=23,9A,20,00,[BAUD_CODE]

To retain across power cycles, save the configuration to Flash and reset (or power-cycle).

  • Change CAN baud rate to 1000 kbit/s: ID=0x608, DATA=23,9A,20,00,00,00,00,00
  • Change CAN baud rate to 500 kbit/s: ID=0x608, DATA=23,9A,20,00,02,00,00,00
  • Change CAN baud rate to 250 kbit/s: ID=0x608, DATA=23,9A,20,00,03,00,00,00
  • Change CAN baud rate to 125 kbit/s: ID=0x608, DATA=23,9A,20,00,04,00,00,00

TPDO Configuration

The following operations write the corresponding object dictionary entries via expedited SDO. The mapping between TPDO channels and parameter indexes is:

ChannelFrame IDParameter indexDescription
TPDO10x180+ID0x1800Acceleration
TPDO20x280+ID0x1801Angular velocity
TPDO30x380+ID0x1802Euler angles
TPDO40x480+ID0x1803Quaternion
TPDO60x680+ID0x1804Pressure
TPDO70x780+ID0x1805Inclinometer
Set / Disable / Enable Output Rate (0x1800-0x1805)

📋 Note These settings take effect immediately after writing; save the configuration separately if power-cycle retention is needed.

Common configuration examples:

  • ID=0x608, DATA=2B,00,18,05,00,00,00,00 — disable acceleration output (1800.5=0)
  • ID=0x608, DATA=2B,00,18,05,05,00,00,00 — acceleration 200 Hz output (1800.5=5)
  • ID=0x608, DATA=2B,00,18,05,0A,00,00,00 — acceleration 100 Hz output (1800.5=10)
  • ID=0x608, DATA=2B,00,18,05,14,00,00,00 — acceleration 50 Hz output (1800.5=20)
  • ID=0x608, DATA=2B,00,18,05,32,00,00,00 — acceleration 20 Hz output (1800.5=50)
  • ID=0x608, DATA=2B,00,18,05,64,00,00,00 — acceleration 10 Hz output (1800.5=100)

Angular velocity configuration:

  • ID=0x608, DATA=2B,01,18,05,00,00,00,00 — disable angular velocity output (1801.5=0)
  • ID=0x608, DATA=2B,01,18,05,05,00,00,00 — angular velocity 200 Hz output (1801.5=5)
  • ID=0x608, DATA=2B,01,18,05,0A,00,00,00 — angular velocity 100 Hz output (1801.5=10)
  • ID=0x608, DATA=2B,01,18,05,14,00,00,00 — angular velocity 50 Hz output (1801.5=20)
  • ID=0x608, DATA=2B,01,18,05,32,00,00,00 — angular velocity 20 Hz output (1801.5=50)
  • ID=0x608, DATA=2B,01,18,05,64,00,00,00 — angular velocity 10 Hz output (1801.5=100)

Euler angle configuration:

  • ID=0x608, DATA=2B,02,18,05,00,00,00,00 — disable Euler angle output (1802.5=0)
  • ID=0x608, DATA=2B,02,18,05,05,00,00,00 — Euler angles 200 Hz output (1802.5=5)
  • ID=0x608, DATA=2B,02,18,05,0A,00,00,00 — Euler angles 100 Hz output (1802.5=10)
  • ID=0x608, DATA=2B,02,18,05,14,00,00,00 — Euler angles 50 Hz output (1802.5=20)
  • ID=0x608, DATA=2B,02,18,05,32,00,00,00 — Euler angles 20 Hz output (1802.5=50)
  • ID=0x608, DATA=2B,02,18,05,64,00,00,00 — Euler angles 10 Hz output (1802.5=100)

Quaternion configuration:

  • ID=0x608, DATA=2B,03,18,05,00,00,00,00 — disable quaternion output (1803.5=0)
  • ID=0x608, DATA=2B,03,18,05,05,00,00,00 — quaternion 200 Hz output (1803.5=5)
  • ID=0x608, DATA=2B,03,18,05,0A,00,00,00 — quaternion 100 Hz output (1803.5=10)
  • ID=0x608, DATA=2B,03,18,05,14,00,00,00 — quaternion 50 Hz output (1803.5=20)
  • ID=0x608, DATA=2B,03,18,05,32,00,00,00 — quaternion 20 Hz output (1803.5=50)
  • ID=0x608, DATA=2B,03,18,05,64,00,00,00 — quaternion 10 Hz output (1803.5=100)

Pressure configuration:

  • ID=0x608, DATA=2B,04,18,05,00,00,00,00 — disable pressure output (1804.5=0)
  • ID=0x608, DATA=2B,04,18,05,05,00,00,00 — pressure 200 Hz output (1804.5=5)
  • ID=0x608, DATA=2B,04,18,05,0A,00,00,00 — pressure 100 Hz output (1804.5=10)
  • ID=0x608, DATA=2B,04,18,05,14,00,00,00 — pressure 50 Hz output (1804.5=20)
  • ID=0x608, DATA=2B,04,18,05,32,00,00,00 — pressure 20 Hz output (1804.5=50)
  • ID=0x608, DATA=2B,04,18,05,64,00,00,00 — pressure 10 Hz output (1804.5=100)

📋 Configuration example Taking TPDO1 (acceleration) at 100 Hz (one frame every 10 ms) as an example: 0x23 indicates an SDO write of 4 bytes; 0x00 0x18 is the index 0x1800; 0x05 is the sub-index; 0x0A 0x00 is the period value 10 (unit: ms); the remaining bytes are zero-padded.

Set Inclinometer Zero (0x20A5)
  • ID=0x608, DATA=23,A5,20,00,02,00,00,00 — set the current position as the output zero point (X=0, Y=0)
  • ID=0x608, DATA=23,A5,20,00,05,00,00,00 — cancel zero configuration and output real X/Y angles (equivalent to X/Y offset = 0)

Sync Protocol

The module supports configuring each TPDO into synchronous mode. When enabled, the module stops asynchronous periodic transmission and waits for the CANopen sync frame; when the sync frame arrives, it sends one corresponding TPDO frame.

Configure a TPDO into Sync Mode

To configure a TPDO into sync mode, set the corresponding TPDO communication parameter [0x180x.2] (Transmission type) to 0x01. See the standard CANopen specification for field definitions.

Taking TPDO1 (acceleration) as an example:

  • ID=0x608, DATA=2F,00,18,02,01,00,00,00 — write [0x1800.2] = 1, set TPDO1 to sync mode
  • ID=0x608, DATA=2F,00,18,02,FF,00,00,00 — write [0x1800.2] = 0xFF, set TPDO1 to async mode (factory default)
Send CANopen Sync Frame

Send a CANopen sync frame: ID=0x80, no data

When the module receives the sync frame, all TPDOs configured in sync mode send one frame of data to achieve synchronization.

Set Heartbeat

The heartbeat period is set by writing [0x1017.0], valid range 0~65535, unit: ms. 0 disables the heartbeat.

Example: ID=0x608, DATA=2B,17,10,00,64,00,00,00 — set the heartbeat period to 100 ms

Magnetic Calibration

When to Use Magnetic Calibration

9-axis mode (magnetometer-aided absolute-heading mode) is recommended when the following conditions are met:

  1. Perform at least one user magnetic calibration before using 9-axis mode for the first time.
  2. There is no obvious spatial magnetic interference in the operating environment; calibration is recommended in open outdoor areas. Indoor environments with complex magnetic conditions are unlikely to produce good calibration results.
  3. The relative position between the module and the mounting platform (PCB, housing, robot, etc.) remains fixed during use.

Calibration Procedure

When using the module for the first time and AHRS (9-axis) mode is required, follow the steps below:

1. Switch Mode

First, switch the module to 9-axis mode. See "Operating Mode Configuration".

2. Environment Check

Common magnetic interference sources: iron furniture, computer monitors, motors and transformers, mobile phone chargers, rebar in building structures.

Recommended calibration environments:

  • Best: outdoor open area, away from buildings and vehicles (distance > 5 m)
  • Acceptable: indoor area away from interference sources (distance > 30 cm)

⚠️ Important

If the module has been installed on a product PCB, or the product has a magnetic housing, or it has been installed on a robot/machine, the assembly must be treated as a whole during calibration. Calibrating the module alone and then installing it does not achieve the required effect.

3. Calibration Operation

Send the calibration command: CONFIG MCAL START (firmware version ≥ 1.7.0 required)

Perform the calibration motion:

  1. Within a small physical region, keep the position essentially fixed and only slowly rotate the module.
  2. Rotate each axis at least 360° (recommended 2~3 turns), at a uniform speed, around 20~100 deg/s (about 5~20 s per turn). Avoid pauses.
  3. Calibration usually takes 30~60 s.

Recommended rotation plan: rotate 2 turns about X, then 2 turns about Y, then 2 turns about Z, or rotate randomly while making sure each axis sees sufficient angular change.

4. Query Calibration Status

Send: LOG MCAL STAT

Example response:

STAT=1
PROGRESS=8
OK

STAT field

STAT valueState descriptionSuggested action
0IdleA new calibration can be started
1CalibratingKeep rotating until calibration completes
2Verifying resultKeep stationary, wait for verification
3Calibration completeSuccess; ready for normal use
4Calibration failedSee the troubleshooting flow; recalibrate

PROGRESS: range 0~100, indicates the current calibration progress percentage. When PROGRESS=100 and STAT=3, calibration is successful.

5. Verify Calibration Result

  1. After calibration, place the module horizontally and slowly rotate one full turn (360°).
  2. Observe the heading output: it should change continuously from to 360° without jumps; acceptable error is within ±5°.
  3. If you see large jumps (>10°) or the heading does not change with rotation, see the troubleshooting flow below.

Calibration Troubleshooting Flow

If calibration fails (STAT=4) or the verification result is abnormal, troubleshoot as follows:

Step 1: Check ambient magnetic field strength

Place the module stationary at the calibration position, read the magnetic field strength (mag_b), and compute the total magnetic field magnitude: B_total = √(Bx² + By² + Bz²).

Magnetic field strengthEnvironmental assessmentRecommended action
20-60 μTNormalContinue calibration
< 20 μT or > 60 μTAbnormalCheck for nearby strong magnetic objects; move away from interference sources; change location if necessary

Step 2: Check the rotation motion — make sure each axis is rotated at least 360° at a uniform speed of 20~100 deg/s, with no pauses.

Step 3: Check for spatial magnetic interference — measure the magnetic field strength at the same location with different orientations. If the variation is > 10 μT, there is spatial magnetic interference; change location or switch to 6-axis mode.

Common Issues and Solutions

Failure causeTypical symptomSolution
Strong ambient magnetic interferenceSTAT=4 or heading jumpsMove to an outdoor open area
Non-standard rotationPROGRESS grows slowly or stagnatesEnsure each axis rotates sufficiently, at uniform speed
Position drift during rotationCalibration completes but accuracy is poorKeep the position fixed during calibration, only rotate orientation
Module-platform relative position changesHeading error increases after reinstallationTreat the module and platform as a unit and recalibrate

Important Reminders

⚠️ Warning 1: Indoor magnetic environment limitations — indoor spatial magnetic interference is severe and cannot be removed by calibration. Heading accuracy of the mag-aided (9-axis) mode strongly depends on the level of indoor magnetic distortion.

⚠️ Warning 2: Indoor usage suggestion — if the indoor magnetic environment is poor (server rooms, labs, workshops, underground parking lots, etc.), even a successful calibration may yield heading accuracy worse than 6-axis mode and large angular errors (>10°). In indoor environments, 6-axis mode is recommended.

⚠️ Warning 3: Fixed-installation requirement — if the installation environment contains magnetic interference, the interference source must maintain a fixed relative position to the module. When the module is mounted on a ferromagnetic rigid body (robot / machine / vehicle / vessel / tripod / PCB, etc.), the whole system must be rotated together during calibration. The module must not be displaced relative to the mounting platform during use; if separated, recalibrate.

⚠️ Warning 4: Motor vibration effects — vibration and magnetic interference from running robot motors can affect calibration. Calibrate with motors stopped, or calibrate while the motor is running in its working state (treating the motor field as a fixed interference source).

Calibration Frequency and Mode Selection

Calibration frequency suggestions:

  • For fixed installation in a stable environment, one initial calibration is sufficient;
  • For mobile applications, recalibrate after each environment change;
  • Recalibrate whenever the relative position between module and platform changes;
  • For long-term use (>1 year), recalibrate once per year;
  • Recalibrate immediately if abnormal heading errors appear.

Mode selection suggestions:

Application scenarioRecommended modeReason
Outdoor open environment (UAV)9-axis modeLow magnetic interference; absolute heading available
Indoor environment (AGV, robot)6-axis modeHigh indoor interference; 6-axis is more stable
Near motors / electromagnetic devices6-axis modeElectromagnetic interference cannot be removed by calibration
Absolute heading required9-axis modeRequires stable magnetic environment and proper calibration
Only relative heading required6-axis mode6-axis heading starts at 0 on power-up; suitable for relative measurement

Appendix 1: Quaternion / Euler Angle / Rotation Matrix Conversion

Quaternion to Rotation Matrix

Given a quaternion [Qb2n=[q0,q1,q2,q3]T], the direction cosine matrix is:

Cb2n=[q02+q12q22q322(q1q2q0q3)2(q1q3+q0q2)2(q1q2+q0q3)q02q12+q22q322(q2q3q0q1)2(q1q3q0q2)2(q2q3+q0q1)q02q12q22+q32]

Quaternion to Euler Angles - East-North-Up (ENU)-312 rotation order (Z, then X, then Y)

Given a quaternion Qb2n=[q0,q1,q2,q3]T, where q0 is the scalar part and [q1,q2,q3] is the vector part. Qb2n represents the rotation from the body frame (b) to the navigation frame (n), where:

  • pitch (θ): rotation about the X axis, range [π2,π2]
  • roll (φ): rotation about the Y axis, range [π,π]
  • yaw (ψ): rotation about the Z axis, range [π,π]

Quaternion to Euler:

pitch=arcsin(2(q0q1+q2q3))roll=arctan2(2(q1q3q0q2),q02q12q22+q32)yaw=arctan2(2(q1q2q0q3),q02q12+q22q32)

Euler to quaternion:

[q0q1q2q3]=[cos(pitch2)cos(roll2)cos(yaw2)sin(pitch2)sin(roll2)sin(yaw2)cos(roll2)cos(yaw2)sin(pitch2)cos(pitch2)sin(roll2)sin(yaw2)cos(pitch2)cos(yaw2)sin(roll2)+cos(roll2)sin(pitch2)sin(yaw2)cos(pitch2)cos(roll2)sin(yaw2)+sin(pitch2)sin(roll2)cos(yaw2)]

Quaternion to Euler Angles - North-East-Down (NED)-321 rotation order (Z, then Y, then X)

Given a quaternion Qb2n=[q0,q1,q2,q3]T, where q0 is the scalar part and [q1,q2,q3] is the vector part. Qb2n represents the rotation from the body frame (b) to the navigation frame (n), where:

  • pitch (θ): rotation about the Y axis, range [π2,π2]
  • roll (φ): rotation about the X axis, range [π,π]
  • yaw (ψ): rotation about the Z axis, range [π,π]

Quaternion to Euler:

roll=arctan2(2(q0q1+q2q3),12(q12+q22))pitch=arcsin(2(q0q2q1q3))yaw=arctan2(2(q0q3+q1q2),12(q22+q32))

Euler to quaternion:

[q0q1q2q3]=[cos(roll2)cos(pitch2)cos(yaw2)+sin(roll2)sin(pitch2)sin(yaw2)sin(roll2)cos(pitch2)cos(yaw2)cos(roll2)sin(pitch2)sin(yaw2)cos(roll2)sin(pitch2)cos(yaw2)+sin(roll2)cos(pitch2)sin(yaw2)cos(roll2)cos(pitch2)sin(yaw2)sin(roll2)sin(pitch2)cos(yaw2)]

Appendix 2: Firmware Upgrade

This product supports firmware upgrade. Use the CHCenter host software and follow the steps shown below; contact technical support to obtain the firmware upgrade file (.hex).

Appendix 3: More on Magnetic Interference

Magnetic interference can be divided into spatial magnetic interference and sensor-frame magnetic interference, as shown below:

Type of magnetic interferenceSensor-frame magnetic interference
(hard-iron / soft-iron)
Spatial magnetic interference
CharacteristicsThe interference source moves with the sensorThe interference source does not move with the sensor
Typical sourcesPCB, metal housing, UAV, etc., fixed to the moduleFurniture, household appliances, cables, rebar in buildings
Calibration feasibilityYesNo
MitigationCan be removed by the user magnetic calibration procedureCannot be removed by any calibration; severely degrades heading accuracy

Notes on spatial magnetic interference Spatial magnetic interference is the main reason why indoor magnetometer fusion is hard to use reliably. This type of interference cannot be removed by calibration and significantly increases heading error. In indoor environments, especially near desks, chairs, and appliances, this interference is usually more pronounced.

📋 Legend The figure above shows a typical distribution of indoor spatial magnetic interference: blue represents weak-interference regions, red represents strong-interference regions.

Appendix 5: Technical Support

The latest product and documentation information is available on our official website and WeChat account. WeChat:

Telegram:

Last updated: