LPMS-IG1 User Manual
- 1 Introduction
- 2 Reference Systems
- 2.1 Coordinates
- 2.2 Raw Data
- 2.3 Euler Angles
- 2.4 Orientation Alignment Modes
- 2.4.1 Heading Reset
- 2.4.2 Alignment Reset
- 2.4.3 Object Reset
- 2.5 GPS Data
- 3 Communication
- 3.1 Communication Modes
- 3.2 LPBUS Protocol
- 3.2.1 GET Commands
- 3.2.2 SET Commands
- 3.3 LPBUS Packet Format
- 3.3.1 Example
- 3.3.2 Data Format in a Packet Data Field
- 3.3.3 Sensor Measurement Data
- 3.4 LPBUS Example Communication
- 3.4.1 Goto Command Mode
- 3.4.2 Goto Steaming Mode
- 3.4.3 Request Gyroscope Range
- 3.4.4 Set Accelerometer Range
- 3.4.5 Save Sensor Parameters
- 3.4.6 Read Sensor Status
- 3.4.7 Set UART / RS232 Baudrate
- 3.5 CANOpen and Sequential CAN Protocols
- 3.6 CAN Data Output Format
- 3.7 Example
- 3.8 ASCII Output
- 4 Appendix
- 4.1 Firmware Function / Command List
- 4.1.1 Summary
- 4.1.2 Acknowledged and Not-acknowledged Identifiers
- 4.1.3 Register Value Save and Reset Command
- 4.1.4 Mode Switching Commands
- 4.1.5 Sensor Status Command
- 4.1.6 Get Data Commands
- 4.1.7 Device Info Commands
- 4.1.8 Data Transmission Commands
- 4.1.9 IMU ID Setting Command
- 4.1.10 Stream Frequency Commands
- 4.1.11 Deg/Rad Output Commands
- 4.1.12 Reference Setting and Offset Reset Command
- 4.1.13 Accelerometer Settings Command
- 4.1.14 Gyroscope Settings Command
- 4.1.15 Magnetometer Settings Command
- 4.1.16 Filter Settings Command
- 4.1.17 CAN Settings Command
- 4.1.18 UART / RS232 Settings Command
- 4.1.19 Sensor Data Timestamp Manipulation
- 4.1.20 GPS Data Transmission Commands
- 4.1 Firmware Function / Command List
Introduction
This manual applies to the following sensor types:
LPMS-IG1-CAN | LPMS-IG1-RS232 | LPMS-IG1P-RS232 |
LPMS-IG1-RS485 | LPMS-IG1P-RS485 |
|
LPMS-IG1 series sensors are high precision multi-purpose inertial measurement units specially developed for industrial applications. LPMS-IG1 sensors embed a powerful processor, 3 high precision single axis gyroscopes, a general purpose 3 axis gyroscope, accelerometer and magnetometer. The unique dual-gyroscope (Gyro I & II) setup enables accurate dynamics measurement in both low and high-speed applications. Gyro I is suitable for applications where the accuracy requirements are high and the detection range is not critical (<400dps). Gyro II is suitable for general applications where the expected measurement range exceeds 400dps.
LPMS-IG1 series include two models, LPMS-IG1 (without GPS) and LPMS-IG1P (with GPS). Both models offer the following communication methods: USB+RS232 or, USB+CAN or USB+RS485. For details on how to use the communication interface, please refer to the relevant sections below. LPMS-IG1 series come in a waterproof metal housing with a flat bottom profile and mounting holes for easy installation.
Main features:
High precision and stability
Dual 3-axis general purpose gyroscope, 3-axis accelerometer, 3-axis magnetometer
Gyro I: High precision 3-axis gyroscope
Gyro II: 3-axis general purpose gyroscope
Realtime output: Raw and calibrated sensor data, quaternion, Euler angles, temperature, GPS (LPMS-IG1P)
Communication method:USB+RS232 or USB+CAN or USB+RS485
Applications:
Robot navigation
Automotive navigation
Remote control and monitoring for industrial robots
Automated guided vehicle navigation
Reference Systems
Coordinates
The LPMS sensor calculates the orientation difference between a fixed sensor coordinate system (S), a object coordinate (O) and a global reference coordinate system (G). All coordinate systems are defined as right-handed Cartesian coordinate systems. The sensor coordinate system (S) can be referred to the sticker information on the sensor enclosure as showed in Fig. 2.1. The object coordinate (O) is the frame to which the sensor is attached. (S) and (O) can be aligned through the methods introduced in the following sections.
The global reference coordinate system (G) can be divided into two different cases. While the orientation calculation is using all acceleration, gyroscope and magnetic data (sensor filter mode set at acc+gyr+mag), (G) system is defined as following:
X positive when pointing to the magnetic north
Y positive when pointing to the magnetic west
Z positive when pointing up (gravity points vertically down with -1g)
While the orientation calculation is using only acceleration and gyroscope data (sensor filter mode set at acc+gyr), (G) system is defined as following:
X positive aligned to ground plane horizontal projection of x axis of (S) when sensor powered on
Y positive based on right-handed Cartesian coordinate definition
Z positive when pointing up (gravity points vertically down with -1g)
Raw Data
The raw data normally contains 3-axis accelerometer data, 3-axis gyroscope data and 3-axis magnetometer data. All these data are referred to coordinate (S) or (O).
Euler Angles
A positive rotation is always right-handed, i.e. defined according to the right-hand rule (corkscrew rule). This means a positive rotation is defined as clockwise in the direction of the axis of rotation.
The definition used for Euler angles in this document is equivalent to roll, pitch, yaw/heading. The Euler angles are of ZYX global type (subsequent rotation around global Z, Y and X axis, also known as aerospace sequence):
Roll: Rotation around global X, defined from -180°~180°
Pitch: Rotation around Y, defined from -90°~90°
Yaw: Rotation around Z, defined from -180°~180°
NOTE: Due to the definition of Euler angles there is a mathematical singularity when the sensor-fixed X-axis is pointing up or down in the global reference frame (i.e. pitch approaches+/-90). This singularity is not present in quaternion output.
Orientation Alignment Modes
Heading Reset
Often it is important that the global Z-axis remains along the vertical (defined by local gravity vector), but the global X-axis has to be pointed in a particular direction on horizontal plane. In this case a heading reset may be used. When performing a heading reset, the new global reference frame is chosen such that the global X-axis points in the direction of the sensor's x direction while keeping the global Z-axis vertical (along gravity, pointing upwards). In other words: The global Z-axis point upwards along gravity, where the X and Y axis orthogonally form a perpendicular plane.
The operation of heading reset comes out a result on Euler angles data is that yaw angle becomes zero, roll and pitch angles keep same.
NOTE: After a heading reset, the yaw may not be exactly zero, this occurs especially when the X-axis is close to the vertical. This is caused by the definition of the yaw when using Euler angles, which becomes unstable when the pitch approaches +/-90 deg.
Alignment Reset
The alignment reset function aims to facilitate in aligning the sensor coordinate system (S) with the ground plane. After an alignment reset, the (S) coordinate system is changed to (S') as follows:
The (S') Z-axis is the vertical (up) at time of reset
The (S') X-axis equals the (S) X-axis but projected on the new horizontal plane.
The (S') Y-axis is chosen as to obtain a right-handed coordinate frame.
The operation of alignment reset comes out a result on Euler angles data is that yaw angle keeps same, roll and pitch angles become zero.
NOTE: Once this alignment reset is done, orientation will be output in the new coordinate frame (S').
Object Reset
The object reset aligns the sensor coordinate frame to that of the object to which it is attached (see Fig. 2.2). The sensor must be attached in such a way that the X-axis is in the XZ-plane of the object coordinate frame, i.e. the sensor can be used to identify the X-axis of the object. To preserve the global vertical, the object must be oriented such that the object Z-axis is vertical. The object reset causes the new (S') coordinate frame and the object coordinate frame (O) to be aligned.
The object reset simply combines alignment reset and the heading reset at a single instant in time. This has the advantage that all coordinate systems can be aligned with a single action. Keep in mind that the new global reference X-axis (heading) is defined by the object X-axis (to which XZ-plane you have aligned the sensor).
NOTE: Since the sensor X-axis is used to describe the direction of the object X-axis, the reset will not work if the sensor X-axis is aligned along the Z-axis of the object.
GPS Data
LPMS-IG1P series also provide the GPS data output, which is contained by four parts as showed in the following table. See the LPMS-IG1P GPS data structure below.
Name | Description |
Timestamps | 1Hz update rate |
NAV-PVT | Navigation Position, Velocity, Time, etc |
NAV-ATT | Navigation Attitude, Orientation, etc |
ESF-STATUS | External Sensor Fusion Messages. |
Communication
LPMS-IG1 series offer two types of communication methods:
USB + RS232
USB + CAN
USB + RS485
Sensor data is streamed to both USB and RS232/CAN/RS485 terminals simultaneously. Communication protocol for different terminals are summarized as below:
Terminal | Protocol |
USB | LPBUS Protocol |
RS232 | LPBUS Protocol/ASCII |
RS232 | LPBUS Protocol/ASCII |
CAN | CANOpen / CAN sequential |
Communication Modes
There are two communication modes, Streaming Mode and Command mode in LPMS-IG1 sensors. By default, the sensor will start in Streaming Mode on power up (Except for RS485 communication, it starts at Command mode). In Streaming Mode, the sensor will continuously stream out sensor data via USB and RS232/CAN terminals simultaneously. Streaming frequency for both USB and RS232/CAN terminals is determined by the data streaming rate settings (default at 100Hz). The sensor will stop data streaming in Command Mode. User can change the sensor internal parameters in both Streaming and Command mode, but it is highly recommended to put the sensor in Command Mode before making any parameter changes. The state diagram of the sensor modes is summarized in Fig. 3.1.
NOTE: User must issue a Save Parameters command to retain any parameter changes to the sensor before next power cycle.
LPBUS Protocol
LPBUS is a communication protocol based on the industry standard MODBUS protocol. It is the default communication format used by LPMS sensors. .An LPBUS communication packet has two basic command types, GET and SET, that are sent from a host (PC, mobile data logging unit etc.) to a client (LPMS sensor). Later in this manual we will show a description of all supported commands to the sensor, their types and transported data.
GET Commands
Data from the client is read using GET requests. A GET request usually contains no data. The answer from the client to a GET request contains the requested data.
SET Commands
Data registers of the client are written using SET requests. A SET command from the host contains the data to be set. The answer from the client is either ACK (acknowledged) for a successful write, or NACK (not acknowledged) for a failure to set the register occurred.
LPBUS Packet Format
Each packet sent during the communication is based on the following structure:
Flag Name | Start | Sensor ID | Command No. | Data length | Data field | LRC | End |
Bytes | 1 | 2 | 2 | 2 | n | 2 | 2 |
Start: 1 byte. data packet start flag, which is fixed to 3Ah.
Sensor ID: 2 bytes transmitted at LSB. It contains ID of the sensor to be communicated with. The default value of this ID is 01h. The host sends out a GET / SET request to a specific LPMS sensor by using this ID, and the client answers to request also with the same ID. This ID can be adjusted by sending a SET command to the sensor firmware.
Command No.: 2 bytes transmitted at LSB. It contains command number information to be performed by the data transmission.
Data length: 2 bytes transmitted at LSB, It contains the length information of packet data field.
Data field: n bytes transmitted at LSB, where n is not a fixed number which depends on the command types. It contains all the data needed to be transmitted under a specific command.
LRC: 2 bytes transmitted at LSB. It contains the packet checksum information. To ensure the integrity of the transmitted data the LRC checksum is used. It is calculated in the following way:
LRC = sum(Sensor ID, Command no., Data length, and Data field).
The calculated LRC is usually compared with the LRC transmitted from the remote device. If the two LRCs are not equal, and error is reported.
End: 2 bytes transmitted at LSB, which is fixed to 0D0Ah.
Example
LPBus packet from sensor (hex):
3A 01 00 09 00 10 00 37 92 00 00 00 70 93 3E 00 40 7B BE 00 38 70 3F 84 04 0D 0A
Flag Name | Start | Sensor ID | Command No. | Data length | Data field | LRC | End |
Bytes | 1 | 2 | 2 | 2 | n | 2 | 2 |
Hex | 3A | 01 00 | 09 00 | 10 00 | 37 92 00 00 00 70 93 3E 00 40 7B BE 00 38 70 3F | 84 04 | 0D 0A |
Checksum LRC calculation
Calculated Checksum LRC (hex) | = 01 + 00 + 09 + 00 + 10 + 00 + 37 + 92 + 00 + 00 + 00 + 70 + 93 + 3E + 00 + 40 + 7B + BE + 00 + 38 + 70 + 3F |
| = 0x0484 |
LRC from sensor is transmitted at LSB, hence 84 04
Data Format in a Packet Data Field
Generally, data is sent in little-endian format, low order byte first, high order byte last. Data in the data fields of a packet can be encoded in several ways, depending on the type of information to be transmitted. In the following we list the most common data types. Other command-specific data types are explained in the command reference.
Identifier | Description |
Int32 | 32-bit signed integer value |
UInt32 | 32-bit unsigned integer value |
Int16 | 16-bit signed integer value |
UInt16 | 16-bit unsigned integer value |
Int8 | 8-bit signed integer value |
UInt8 | 8-bit unsigned integer value |
Float32 | 32-bit float value |
Vector3f | 3 element 32-bit float vector |
Vector3i16 | 3 element 16-bit signed integer vector |
Vector4f | 4 element 32-bit float vector |
Vector4i16 | 4 element 16-bit signed integer vector |
Matrix3x3f | 3x3 element 32-bit float value matrix |
Sensor Measurement Data
IMU data
There are two precision modes for sensor data: 32-bit float or 16-bit integer. Users can switch between these modes based on the requested data sampling rate and volume. While sensor is in streaming operational mode, LPBUS transports measurement data in the data field of a packet in the following orders shown in the charts below for the cases of 32-bit float and 16-bit integer precision modes. The order of the sensor data chunks depends on which sensor data is enabled.
NOTE: Timestamp data is always 32-bit unsigned integer in both data precision modes.
Order | Identifier | Description | Unit |
1 | UInt32 | Timestamp | multiply by factor 0.002 to convert to seconds |
2 | Vector3f | Raw accelerometer | g |
3 | Vector3f | Calibrated accelerometer | g |
4 | Vector3f | Raw Gyro I | dps (default) or rad/s |
5 | Vector3f | Raw GyroII | dps (default) or rad/s |
6 | Vector3f | Static bias calibrated Gyro I | dps (default) or rad/s |
7 | Vector3f | Static bias calibrated Gyro II | dps (default) or rad/s |
8 | Vector3f | Alignment calibrated Gyro I | dps (default) or rad/s |
9 | Vector3f | Alignment calibrated Gyro II | dps (default) or rad/s |
10 | Vector3f | Raw magnetometer | uT |
11 | Vector3f | Calibrated magnetometer | uT |
12 | Vector3f | Angular Vel. | dps (default) or rad/s |
13 | Vector4f | Quaternion |
|
14 | Vector3f | Euler | deg (default) or rad |
15 | Vector3f | Linear acceleration (g) | g |
16 | Float32 | Reserved |
|
17 | Float32 | Reserved |
|
18 | Float32 | Temperature | °C |
In 16-bit data precision mode values are transmitted to the host with a multiplication factor applied to increase precision:
Order | Format | Sensor data | Scale factor |
1 | UInt32 | Timestamp counter incremented in 500Hz. multiply by 0.002 to convert to seconds. | 500 |
2 | Vector3i16 | Raw accelerometer (g) | 1000 |
3 | Vector3i16 | Calibrated accelerometer (g) | 1000 |
4 | Vector3i16 | Raw GyroI (dps or rad/s) | dps: 10 rad/s: 1000 |
5 | Vector3i16 | Raw GyroII (dps or rad/s) | dps: 10 rad/s: 100 |
6 | Vector3i16 | Static bias calibrated GyroI (dps or rad/s) | dps: 10 rad/s: 1000 |
7 | Vector3i16 | Static bias calibrated GyroII (dps or rad/s) | dps: 10 rad/s: 100 |
8 | Vector3i16 | Alignment calibrated GyroI (dps or rad/s) | dps: 10 rad/s: 1000 |
9 | Vector3i16 | Alignment calibrated GyroII (dps or rad/s) | dps: 10 rad/s: 100 |
10 | Vector3i16 | Raw magnetometer (uT) | 100 |
11 | Vector3i16 | Calibrated magnetometer (uT) | 100 |
12 | Vector3i16 | Angular Vel. (dps or rad/s) | dps: 10 rad/s: 1000 (gyro range: 400dps) rad/s: 100 (gyro range >= 1000dps) |
13 | Vector4i16 | Quaternion | 10000 |
14 | Vector3i16 | Euler(degree or rad) | deg: 100 rad:10000 |
15 | Vector3i16 | Linear acceleration (g) | 1000 |
16 | Int16 | Reserved |
|
17 | Int16 | Reserved |
|
18 | Int16 | Temperature (°C) | 100 |
GPS Data
In addition to IMU data, LPMS-IG1P (with GPS) will output additional 1Hz GPS data packet with the following format:
Order | Format | Sensor data | Scale factor |
1 | UInt32 | Timestamp |
|
2 | UInt32 | PVT iTOW (ms) - GPS time of week of the navigation epoch. |
|
3 | UInt16 | PVT year (UTC) |
|
4 | UInt8 | PVT month (UTC) |
|
5 | UInt8 | PVT day (UTC) |
|
6 | UInt8 | PVT hour (UTC) |
|
7 | UInt8 | PVT min (UTC) |
|
8 | UInt8 | PVT sec (UTC) |
|
9 | UInt8 | PVT valid - Validity flags |
|
10 | UInt32 | PVT tAcc - Time accuracy estimate (UTC) |
|
11 | Int32 | PVT nano (ns) - Fraction of second (UTC) |
|
12 | UInt8 | PVT fixType |
|
13 | UInt8 | PVT flags - Fix status flags |
|
14 | UInt8 | PVT flags2 - Additional flags |
|
15 | UInt8 | PVT numSV - Number of satellites used in Nav Solution |
|
16 | Int32 | PVT longitude (deg) | 10000000 |
17 | Int32 | PVT latitude (deg) | 10000000 |
18 | Int32 | PVT height (mm) - Height above ellipsoid |
|
19 | Int32 | PVT hMSL (mm) - Height above mean sea level |
|
20 | UInt32 | PVT hAcc (mm)- Horizontal accuracy estimate |
|
21 | UInt32 | PVT vAcc (mm) - Vertical accuracy estimate |
|
22 | Int32 | PVT velN (mm/s) - NED north velocity |
|
23 | Int32 | PVT velE (mm/s) - NED east velocity |
|
24 | Int32 | PVT velD (mm/s) - NED down velocity |
|
25 | Int32 | PVT gSpeed (mm/s) - Ground Speed (2-D) |
|
26 | Int32 | PVT headMot (deg) - Heading of motion (2-D) | 100000 |
27 | UInt32 | PVT sAcc (mm/s) - Speed accuracy estimate |
|
28 | UInt32 | PVT headAcc (deg) - Heading accuracy estimate | 100000 |
29 | UInt16 | PVT pDOP - Position DOP | 100 |
30 | Int32 | PVT headVeh (deg) - Heading of vehicle (2-D) | 100000 |
31 | UInt32 | ATT iTOW (ms) - GPS time of week of the navigation epoch |
|
32 | UInt8 | ATT version - Message version (0 for this version) |
|
33 | Int32 | ATT roll (deg) - Vehicle roll | 100000 |
34 | Int32 | ATT pitch (deg) - Vehicle pitch | 100000 |
35 | Int32 | ATT heading (deg) - Vehicle heading | 100000 |
36 | UInt32 | ATT accRoll (deg) - Vehicle roll accuracy | 100000 |
37 | UInt32 | ATT accPitch (deg) - Vehicle pitch accuracy | 100000 |
38 | UInt32 | ATT accHeading (deg) - Vehicle heading accuracy | 100000 |
39 | UInt32 | ESF iTOW (ms) - GPS time of week of the navigation epoch |
|
40 | UInt8 | ESF version - Message version (2 for this version) |
|
41 | UInt8 | ESF initStatus1 |
|
42 | UInt8 | ESF initStatus2 |
|
43 | UInt8 | ESF fusionMode |
|
44 | UInt8 | ESF numSens - Number of sensors |
|
45 | UInt32[n] | ESF sensStatus |
|
LPBUS Example Communication
In this section we will show a few practical examples of communication using the LPBUS protocol.
Goto Command Mode
GET request (HOST -> SENSOR)
Packet byte no. | Content | Description |
0 | 3Ah | Packet start |
1 | 01h | Sensor ID LSB (ID = 1) |
2 | 00h | Sensor ID MSB |
3 | 06h | Command no. LSB |
4 | 00h | Command no. MSB |
5 | 00h | Data length LSB (GET command = no data) |
6 | 00h | Data length MSB |
7 | 07h | Check sum LSB |
8 | 00h | Check sum MSB |
9 | 0Dh | Packet end 1 |
10 | 0Ah | Packet end 2 |
Reply data (SENSOR -> HOST)
Packet byte no. | Content | Description |
0 | 3Ah | Packet start |
1 | 01h | Sensor ID LSB (ID = 1) |
2 | 00h | Sensor ID MSB |
3 | 00h | Command no. LSB (00h = REPLY_ACK) |
4 | 00h | Command no. MSB |
5 | 00h | Data length LSB (Zero length data for ACK reply) |
6 | 00h | Data length MSB |
7 | 01h | Check sum LSB |
8 | 00h | Check sum MSB |
9 | 0Dh | Packet end 1 |
10 | 0Ah | Packet end 2 |
Goto Steaming Mode
GET request (HOST -> SENSOR)
Packet byte no. | Content | Description |
0 | 3Ah | Packet start |
1 | 01h | Sensor ID LSB (ID = 1) |
2 | 00h | Sensor ID MSB |
3 | 07h | Command no. LSB(07h = GOTO_STREAMING_MODE) |
4 | 00h | Command no. MSB |
5 | 00h | Data length LSB (GET command = no data) |
6 | 00h | Data length MSB |
7 | 08h | Check sum LSB |
8 | 00h | Check sum MSB |
9 | 0Dh | Packet end 1 |
10 | 0Ah | Packet end 2 |
Reply data (SENSOR -> HOST)
Packet byte no. | Content | Description |
0 | 3Ah | Packet start |
1 | 01h | Sensor ID LSB (ID = 1) |
2 | 00h | Sensor ID MSB |
3 | 00h | Command no. LSB (00h = REPLY_ACK) |
4 | 00h | Command no. MSB |
5 | 00h | Data length LSB (Zero length data for ACK reply) |
6 | 00h | Data length MSB |
7 | 01h | Check sum LSB |
8 | 00h | Check sum MSB |
9 | 0Dh | Packet end 1 |
10 | 0Ah | Packet end 2 |
Request Gyroscope Range
GET request (HOST -> SENSOR)
Packet byte no. | Content | Description |
0 | 3Ah | Packet start |
1 | 01h | Sensor ID LSB (ID = 1) |
2 | 00h | Sensor ID MSB |
3 | 3Dh | Command no. LSB(3Dh = GET_GYRO_RANGE) |
4 | 00h | Command no. MSB |
5 | 00h | Data length LSB (GET command = no data) |
6 | 00h | Data length MSB |
7 | 3Eh | Check sum LSB |
8 | 00h | Check sum MSB |
9 | 0Dh | Packet end 1 |
10 | 0Ah | Packet end 2 |
Reply data (SENSOR -> HOST)
Packet byte no. | Content | Description |
0 | 3Ah | Packet start |
1 | 01h | Sensor ID LSB (ID = 1) |
2 | 00h | Sensor ID MSB |
3 | 3Dh | Command no. LSB(3Dh = GET_GYRO_RANGE) |
4 | 00h | Command no. MSB |
5 | 04h | Data length LSB (32-bit integer = 4 bytes) |
6 | 00h | Data length MSB |
7 | xxh | Range data byte 1 (LSB) |
8 | xxh | Range data byte 2 |
9 | xxh | Range data byte 3 |
10 | xxh | Range data byte 4 (MSB) |
11 | xxh | Check sum LSB |
12 | xxh | Check sum MSB |
13 | 0Dh | Packet end 1 |
14 | 0Ah | Packet end 2 |
xx = Value depends on the current sensor configuration.
Set Accelerometer Range
SET request (HOST -> SENSOR)
Packet byte no. | Content | Description |
0 | 3Ah | Packet start |
1 | 01h | Sensor ID LSB (ID = 1) |
2 | 00h | Sensor ID MSB |
3 | 32h | Command no. LSB (32h = SET_ACC_RANGE) |
4 | 00h | Command no. MSB |
5 | 04h | Data length LSB (32-bit integer = 4 bytes) |
6 | 00h | Data length MSB |
7 | 08h | Range data byte 1 (Range indicator 8g = 8d) |
8 | 00h | Range data byte 2 |
9 | 00h | Range data byte 3 |
10 | 00h | Range data byte 4 |
11 | 3Fh | Check sum LSB |
12 | 00h | Check sum MSB |
13 | 0Dh | Packet end 1 |
14 | 0Ah | Packet end 2 |
Reply data (SENSOR -> HOST)
Packet byte no. | Content | Description |
0 | 3Ah | Packet start |
1 | 01h | Sensor ID LSB (ID = 1) |
2 | 00h | Sensor ID MSB |
3 | 00h | Command no. LSB (00h = REPLY_ACK) |
4 | 00h | Command no. MSB |
5 | 00h | Data length LSB (Zero length data for ACK reply) |
6 | 00h | Data length MSB |
7 | 01h | Check sum LSB |
8 | 00h | Check sum MSB |
9 | 0Dh | Packet end 1 |
10 | 0Ah | Packet end 2 |
Save Sensor Parameters
WRITE_REGISTER request (HOST -> SENSOR)
Packet byte no. | Content | Description |
0 | 3Ah | Packet start |
1 | 01h | Sensor ID LSB (ID = 1) |
2 | 00h | Sensor ID MSB |
3 | 04h | Command no. LSB(04h = WRITE_REGISTER) |
4 | 00h | Command no. MSB |
5 | 00h | Data length LSB (WRITE_REGISTER command = no data) |
6 | 00h | Data length MSB |
7 | 05h | Check sum LSB |
8 | 00h | Check sum MSB |
9 | 0Dh | Packet end 1 |
10 | 0Ah | Packet end 2 |
Reply data (SENSOR -> HOST)
Packet byte no. | Content | Description |
0 | 3Ah | Packet start |
1 | 01h | Sensor ID LSB (ID = 1) |
2 | 00h | Sensor ID MSB |
3 | 00h | Command no. LSB (00h = REPLY_ACK) |
4 | 00h | Command no. MSB |
5 | 00h | Data length LSB (Zero length data for ACK reply) |
6 | 00h | Data length MSB |
7 | 01h | Check sum LSB |
8 | 00h | Check sum MSB |
9 | 0Dh | Packet end 1 |
10 | 0Ah | Packet end 2 |
NOTE: WRITE_REGISTER command involves flash operation, which might result in delay ACK response
Read Sensor Status
GET request (HOST -> SENSOR)
Packet byte no. | Content | Description |
0 | 3Ah | Packet start |
1 | 01h | Sensor ID LSB (ID = 1) |
2 | 00h | Sensor ID MSB |
3 | 08h | Command no. LSB(08h = GET_SENSOR_STATUS) |
4 | 00h | Command no. MSB |
5 | 00h | Data length LSB (GET command = no data) |
6 | 00h | Data length MSB |
7 | 09h | Check sum LSB |
8 | 00h | Check sum MSB |
9 | 0Dh | Packet end 1 |
10 | 0Ah | Packet end 2 |
Reply data (SENSOR -> HOST)
Packet byte no. | Content | Description |
0 | 3Ah | Packet start |
1 | 01h | Sensor ID LSB (ID = 1) |
2 | 00h | Sensor ID MSB |
3 | 08h | Command no. LSB (08h = GET_SENSOR_STATUS) |
4 | 00h | Command no. MSB |
5 | 04h | Data length LSB (32-bit integer = 4 bytes) |
6 | 00h | Data length MSB |
7-10 | xxxxxxxxh | Sensor status data |
11 | xxh | Check sum LSB |
12 | xxh | Check sum MSB |
13 | 0Dh | Packet end 1 |
14 | 0Ah | Packet end 2 |
NOTE: Please refer to Appendix for details of reply data mapping
Set UART / RS232 Baudrate
SET request (HOST -> SENSOR)
Packet byte no. | Content | Description |
0 | 3Ah | Packet start |
1 | 01h | Sensor ID LSB (ID = 1) |
2 | 00h | Sensor ID MSB |
3 | 82h | Command no. LSB (82h = SET_UART_BAUDRATE) |
4 | 00h | Command no. MSB |
5 | 04h | Data length LSB (32-bit integer = 4 bytes) |
6 | 00h | Data length MSB |
7 | 00h | 921600 = 0x000E1000 |
8 | 10h |
|
9 | 0Eh |
|
10 | 00h |
|
11 | A5h | Check sum LSB |
12 | 00h | Check sum MSB |
13 | 0Dh | Packet end 1 |
14 | 0Ah | Packet end 2 |
Reply data (SENSOR -> HOST)
Packet byte no. | Content | Description |
0 | 3Ah | Packet start |
1 | 01h | Sensor ID LSB (ID = 1) |
2 | 00h | Sensor ID MSB |
3 | 00h | Command no. LSB (00h = REPLY_ACK) |
4 | 00h | Command no. MSB |
5 | 00h | Data length LSB (Zero length data for ACK reply) |
6 | 00h | Data length MSB |
7 | 01h | Check sum LSB |
8 | 00h | Check sum MSB |
9 | 0Dh | Packet end 1 |
10 | 0Ah | Packet end 2 |
NOTE: Power cycle is required for baudrate settings to take effect
CANOpen and Sequential CAN Protocols
In CANOpen and sequential CAN transmission modes, two or more output words of measurement data can be assigned to a CAN channel. In sequential CAN mode the channel addressing can be individually controlled. In CANOpen mode, 4 TPDO (Transmission Data Process Object) messages and a heartbeat message are transmitted.
NOTE: In CANOpen mode a heartbeat message is transmitted with a frequency between 0.1 Hz and 2 Hz.
In CANOpen mode, the message base address is calculated in the following way:
CAN ID1 = Base CAN ID = Start ID + IMU ID
CAN ID2 = CAN ID1 + 100h
CAN ID3 = CAN ID2 + 100h
CAN ID4 = CAN ID3 + 100h
CAN ID5 = 700h + IMU ID
Note: In CANOpen mode, Start ID is fixed at 180h
In sequential CAN mode, the message base address is calculated in the following way:
CAN ID1 = Base CAN ID = Start ID + IMU ID
CAN ID2 = CAN ID1 + 1h
CAN ID3 = CAN ID2 + 1h
CAN ID4 = CAN ID3 + 1h
NOTE: In sequential CAN mode, Start ID is set to 514h (1300d) by default. This value can be changed via IG1Control interface
CAN Data Output Format
Each CAN message can be assigned multiple channels representing the sensor data. The number of assignable sensor data will depend on the data output precision, i.e. 32bit data or 16bit data output. By utilizing 4 CAN message with 16bit sensor data precision, the sensor can output a maximum of 16 different sensor data for a given instance.
CAN channel mapping (16bit data output)
CANOpen ID | Sequential CAN | Output data |
|
|
|
181h | 515h | channel 1 | channel 2 | channel 3 | channel 4 |
281h | 516h | channel 5 | channel 6 | channel 7 | channel 8 |
381h | 517h | channel 9 | channel 10 | channel 11 | channel 12 |
481h | 518h | channel 13 | channel 14 | channel 15 | channel 16 |
701h | - |
|
|
|
|
CAN channel mapping (32bit data output)
CANOpen ID | Sequential CAN | Output data |
|
181h | 515h | channel 1 | channel 2 |
281h | 516h | channel 3 | channel 4 |
381h | 517h | channel 5 | channel 6 |
481h | 518h | channel 7 | channel 8 |
701h | - |
|
|
CAN Mapping
Each channel can be assigned different sensor data by changing the CAN mapping via IG1Control. The table below summarizes the available sensor output data.
Mapping index | Data | Unit | 16bit data scaling factor |
0 | Not assigned |
|
|
1 | Raw Accelerometer X | g | 1000 |
2 | Raw Accelerometer Y | g | 1000 |
3 | Raw Accelerometer Z | g | 1000 |
4 | Calibrated Accelerometer X | g | 1000 |
5 | Calibrated Accelerometer Y | g | 1000 |
6 | Calibrated Accelerometer Z | g | 1000 |
7 | Raw GyroI X | dps or rad/s | 10 (dps), 100 (rad/s) |
8 | Raw GyroI Y | dps or rad/s | 10 (dps), 100 (rad/s) |
9 | Raw GyroI Z | dps or rad/s | 10 (dps), 100 (rad/s) |
10 | Raw GyroII X | dps or rad/s | 10 (dps), 100 (rad/s) |
11 | Raw GyroII Y | dps or rad/s | 10 (dps), 100 (rad/s) |
12 | Raw GyroII Z | dps or rad/s | 10 (dps), 100 (rad/s) |
13 | Bias calibrated GyroI X | dps or rad/s | 10 (dps), 100 (rad/s) |
14 | Bias calibrated GyroI Y | dps or rad/s | 10 (dps), 100 (rad/s) |
15 | Bias calibrated GyroI Z | dps or rad/s | 10 (dps), 100 (rad/s) |
16 | Bias calibrated GyroII X | dps or rad/s | 10 (dps), 100 (rad/s) |
17 | Bias calibrated GyroII Y | dps or rad/s | 10 (dps), 100 (rad/s) |
18 | Bias calibrated GyroII Z | dps or rad/s | 10 (dps), 100 (rad/s) |
19 | Alignment calibrated GyroI X | dps or rad/s | 10 (dps), 100 (rad/s) |
20 | Alignment calibrated GyroI Y | dps or rad/s | 10 (dps), 100 (rad/s) |
21 | Alignment calibrated GyroI Z | dps or rad/s | 10 (dps), 100 (rad/s) |
22 | Alignment calibrated GyroII X | dps or rad/s | 10 (dps), 100 (rad/s) |
23 | Alignment calibrated GyroII Y | dps or rad/s | 10 (dps), 100 (rad/s) |
24 | Alignment calibrated GyroII Z | dps or rad/s | 10 (dps), 100 (rad/s) |
25 | Raw magnetometer X | uT | 100 |
26 | Raw magnetometer Y | uT | 100 |
27 | Raw magnetometer Z | uT | 100 |
28 | Calibrated magnetometer X | uT | 100 |
29 | Calibrated magnetometer Y | uT | 100 |
30 | Calibrated magnetometer Z | uT | 100 |
31 | Angular Velocity X | dps or rad/s | 10 (dps), 100 (rad/s) |
32 | Angular Velocity Y | dps or rad/s | 10 (dps), 100 (rad/s) |
33 | Angular Velocity Z | dps or rad/s | 10 (dps), 100 (rad/s) |
34 | Quaternion W |
| 10000 |
35 | Quaternion X |
| 10000 |
36 | Quaternion Y |
| 10000 |
37 | Quaternion Z |
| 10000 |
38 | Euler X | deg or rad | 100 (deg), 10000 (rad) |
39 | Euler X | deg or rad | 100 (deg), 10000 (rad) |
40 | Euler Z | deg or rad | 100 (deg), 10000 (rad) |
41 | Linear Acceleration X | g | 1000 |
42 | Linear Acceleration Y | g | 1000 |
43 | Linear Acceleration Z | g | 1000 |
44 | Pressure | kPa | 100 |
45 | Temperature | °C | 100 |
Example
Assuming default sensor settings, the CAN bus settings and corresponding data output are shown below:
Here we can decode the data for CAN-ID 181h as follow:
181h | Byte [0:1] | Byte [2:3] | Byte [4:5] | Byte [6:7] |
---|---|---|---|---|
Byte | 22 FF | 39 00 | C9 03 | FA FF |
Integer value | -222 | 57 | 969 | -6 |
Corresponding data | Acc Calibrated X | Acc Calibrated Y | Acc Calibrated Z | GyroII Align. Calibrated X |
Scaled data | -0.222g | -0.057g | 0.969g | -0.6dps |
Like wise, the raw data can be decoded for 281h, 381h, 481h as follow:
281h | Byte [0:1] | Byte [2:3] | Byte [4:5] | Byte [6:7] |
---|---|---|---|---|
Byte | FF FF | 00 00 | 75 07 | 75 09 |
Integer value | -1 | 1 | 1909 | 2421 |
Corresponding data | GyroII Align. Calibrated Y | GyroII Align. Calibrated Z | Mag Calibrated X | Mag Calibrated Y |
Scaled data | -0.1dps | 0.1dps | 19.09uT |