How to use

Platform support

Framework:

  • Arduino

This library is made to be used with:

  • ESP32 family

Necessary inclusions

If all the messages are included in the protoframe, you can just include the following files in your project:

#include "libDM_msg_center.hpp"

The needed headers (mavlink, protobuf, can…) are included in the library for the basic messages set. If some messages are added, the relatives headers have to be included in the project.

Message center configuration

1. Create a MSG_CENTER object and initialize it

Important

API ref: MSG_CENTER, MSG_CENTER::begin()

Example

timerTool myTimer;
SDIO_CONF sdioConf(sdioClock,
             pinSdioClk,
             pinSdioCmd,
             pinSdioDat0,
             pinSdioDat1,
             pinSdioDat2,
             pinSdioDat3,
             sdioMountpoint,
             false);
streamLogger streamObj(&myTimer, sdioConf);
MSG_CENTER msgCenter(&streamObj, &myTimer);

msgCenter.begin();

Note

The messages sent or received using supported protocols (mavlink, protobuf) are automatically configure with the call to MSG_CENTER::begin(). If an SD card is used, everything will be logged as documented in:

2. Grab configuration and messages structs

The library configuration messages filling is done using structs.

The structs details are available in the APIs description section:

Example

1   MSG_CENTER_STRUCTS::MSG_CENTER_CONFIG* msgCenterEmissionConfig = msgCenter.getEmissionConfig();
2   MSG_CENTER_STRUCTS::MSG_CENTER_CONFIG* msgCenterReceptionConfig =
3   msgCenter.getReceptionConfig();
4   MSG_CENTER_STRUCTS::MSG_CENTER_MSG* msgCenterEmissionMessages = msgCenter.getMessagesToSend();
5   MSG_CENTER_STRUCTS::MSG_CENTER_MSG* msgCenterReceptionMessages =
6      msgCenter.getReceivedMessages();

3. Attach and configure hardware interfaces

Can interface is available but need configuration. Serial interfaces have to be added and associated to the protocols (protobuf, mavlink …)

The used struct references are available in the APIs description section:

Example

 1  // Can interface is added by default, just need to be configured
 2msgCenter.attachHardwareInterface(&Serial2, 921600, pinProtocolRx, pinProtocolTx);
 3
 4// Configure hardware interface
 5msgCenter.configureCanInterface(CAN_ENUM::BAUDRATE::_500kbps, pinCanRx, pinCanTx);
 6msgCenter.setProtocolHardwareInterface(MSG_CENTER_STRUCTS::PROTOCOL::PROTOCOL_CAN,
 7                                       MSG_CENTER_STRUCTS::HW_INTERFACE::INT_CAN); // No need
 8msgCenter.setProtocolHardwareInterface(MSG_CENTER_STRUCTS::PROTOCOL::PROTOCOL_MAVLINK,
 9                                       MSG_CENTER_STRUCTS::HW_INTERFACE::INT_SERIAL);
10msgCenter.setProtocolHardwareInterface(MSG_CENTER_STRUCTS::PROTOCOL::PROTOCOL_PROTOBUF,
11                                       MSG_CENTER_STRUCTS::HW_INTERFACE::INT_SERIAL);

Attention

The MSG_CENTER::attachHardwareInterface() will reconfigure uart peripheral by default. If the configuration of the current UART object seems sufficient, the function last parameter can be set to false to avoid reconfiguration.

4. Send and receive messages

The following example shows how to send and receive messages using the message center. We will use for example: - CAN for attitude quaternion - MAVLINK for attitude quaternion and highres imu - PROTOBUF for ProtoFrame (only option)

4.1 Reception

The reception configuration is generally configured only one time. The messages to be received have to be specified and the hardware interfaces configurations have to be updated with MSG_CENTER::updateReceivedMessagesState().

With the configuration example chosen.

Example

1msgCenterReceptionConfig->CAN_MSG_STATE.ATTITUDE_QUATERNION = true;
2msgCenter.updateReceivedMessagesState(MSG_CENTER_STRUCTS::PROTOCOL::PROTOCOL_CAN);
3msgCenterReceptionConfig->MAVLINK_MSG_STATE.ATTITUDE_QUATERNION = true;
4msgCenterReceptionConfig->MAVLINK_MSG_STATE.HIGHRES_IMU         = true;
5msgCenter.updateReceivedMessagesState(MSG_CENTER_STRUCTS::PROTOCOL::PROTOCOL_MAVLINK);
6msgCenterReceptionConfig->PROTOBUF_MSG_STATE.MSG = true;
7msgCenter.updateReceivedMessagesState(MSG_CENTER_STRUCTS::PROTOCOL::PROTOCOL_PROTOBUF);

Then in the main loop, the messages can be read using the MSG_CENTER::readReceivedMessages() function. The getIsNewMsg function can be used to check if the message has been updated.

Example

 1  while (true) // 200Hz loop
 2  {
 3      // Reception
 4      msgCenter.receiveMessages();
 5
 6      if (msgCenterReceptionMessages->CAN_MSG.getIsNewMsg(
 7                  MSG_CENTER_STRUCTS::CAN_MSG_IDX::ATTITUDE_QUATERNION))
 8      {
 9            Serial.println("CAN quaternion received");
10            Serial.println(
11                  "qw = " + String(msgCenterReceptionMessages->CAN_MSG.ATTITUDE_QUATERNION.qw)
12                  + " qx = " + String(msgCenterReceptionMessages->CAN_MSG.ATTITUDE_QUATERNION.qx)
13                  + " qy = " + String(msgCenterReceptionMessages->CAN_MSG.ATTITUDE_QUATERNION.qy)
14                  + " qz = "
15                  + String(msgCenterReceptionMessages->CAN_MSG.ATTITUDE_QUATERNION.qz));
16      }
17      if (msgCenterReceptionMessages->MAVLINK_MSG.getIsNewMsg(
18                  MSG_CENTER_STRUCTS::MAVLINK_MSG_IDX::ATTITUDE_QUATERNION))
19      {
20            Serial.println("MAVLINK quaternion received");
21            Serial.println("qw = "
22                        + String(msgCenterReceptionMessages->MAVLINK_MSG.ATTITUDE_QUATERNION.q1)
23                        + " qx = "
24                        + String(msgCenterReceptionMessages->MAVLINK_MSG.ATTITUDE_QUATERNION.q2)
25                        + " qy = "
26                        + String(msgCenterReceptionMessages->MAVLINK_MSG.ATTITUDE_QUATERNION.q3)
27                        + " qz = "
28                        + String(msgCenterReceptionMessages->MAVLINK_MSG.ATTITUDE_QUATERNION.q4));
29      }
30      if (msgCenterReceptionMessages->MAVLINK_MSG.getIsNewMsg(
31                  MSG_CENTER_STRUCTS::MAVLINK_MSG_IDX::HIGHRES_IMU))
32      {
33            Serial.println("MAVLINK highres imu received");
34            Serial.println(
35                  "xacc = " + String(msgCenterReceptionMessages->MAVLINK_MSG.HIGHRES_IMU.xacc)
36                  + " yacc = " + String(msgCenterReceptionMessages->MAVLINK_MSG.HIGHRES_IMU.yacc)
37                  + " zacc = "
38                  + String(msgCenterReceptionMessages->MAVLINK_MSG.HIGHRES_IMU.zacc));
39      }
40      if (msgCenterReceptionMessages->PROTOBUF_MSG.getIsNewMsg())
41      {
42            Serial.println("PROTOBUF msg received");
43            ProtoFrame& frame = msgCenterReceptionMessages->PROTOBUF_MSG.MSG->getFrame();
44            if (frame.has_attitude)
45            {
46               if (frame.attitude.has_attitude_local)
47               {
48                  if (frame.attitude.attitude_local.has_quaternion)
49                  {
50                        Serial.println("PROTOBUF quaternion received");
51                        Serial.println(
52                              "qw = " + String(frame.attitude.attitude_local.quaternion.qw)
53                              + " qx = " + String(frame.attitude.attitude_local.quaternion.qx)
54                              + " qy = " + String(frame.attitude.attitude_local.quaternion.qy)
55                              + " qz = " + String(frame.attitude.attitude_local.quaternion.qz));
56                  }
57               }
58            }
59            if (frame.has_sensors)
60            {
61               if (frame.sensors.has_accelerometer_raw)
62               {
63                  Serial.println("PROTOBUF accelerometer received");
64                  Serial.println(" xacc = " + String(frame.sensors.accelerometer_raw.xyz.x)
65                                 + " yacc = " + String(frame.sensors.accelerometer_raw.xyz.y)
66                                 + " zacc = " + String(frame.sensors.accelerometer_raw.xyz.z));
67               }
68            }
69      }
70
71      delay(5);
72  }
  • Resultat:

Texte alternatif de l'image

4.1. Emission

We will send the same messages as the reception example. To schedule the messages emission, the following, we will use timerTool helpers.

Contrary to the reception, the emission configuration is generally done at the moment we want to send to message.

Example

 1// Schedule messages sending (5ms ticks for the 200Hz loop)
 2timerTool::counterAndThreshold counterQuaternionCan(5U, 100U);     // 100ms, 10Hz
 3timerTool::counterAndThreshold counterQuaternionMavlink(5U, 100U); // 100ms, 10Hz
 4timerTool::counterAndThreshold counterHighresImuMavlink(5U, 20U);  // 20ms, 50Hz
 5timerTool::counterAndThreshold counterMsgProtobuf(5U, 100U);       // 100ms, 10Hz
 6
 7while (true) // 200
 8{
 9   // Emission
10   msgCenterEmissionConfig->reset();
11   if (counterQuaternionCan.step(true))
12   {
13         msgCenterEmissionMessages->CAN_MSG.ATTITUDE_QUATERNION.qw = 0.9F;
14         msgCenterEmissionMessages->CAN_MSG.ATTITUDE_QUATERNION.qx = 0.1F;
15         msgCenterEmissionMessages->CAN_MSG.ATTITUDE_QUATERNION.qy = 0.2F;
16         msgCenterEmissionMessages->CAN_MSG.ATTITUDE_QUATERNION.qz = 0.3F;
17
18         msgCenterEmissionConfig->CAN_MSG_STATE.ATTITUDE_QUATERNION = true;
19   }
20   if (counterQuaternionMavlink.step(true))
21   {
22         msgCenterEmissionMessages->MAVLINK_MSG.ATTITUDE_QUATERNION.q1 = 0.9F;
23         msgCenterEmissionMessages->MAVLINK_MSG.ATTITUDE_QUATERNION.q2 = 0.1F;
24         msgCenterEmissionMessages->MAVLINK_MSG.ATTITUDE_QUATERNION.q3 = 0.2F;
25         msgCenterEmissionMessages->MAVLINK_MSG.ATTITUDE_QUATERNION.q4 = 0.3F;
26
27         msgCenterEmissionConfig->MAVLINK_MSG_STATE.ATTITUDE_QUATERNION = true;
28   }
29   if (counterHighresImuMavlink.step(true))
30   {
31         msgCenterEmissionMessages->MAVLINK_MSG.HIGHRES_IMU.xacc = 0.1F;
32         msgCenterEmissionMessages->MAVLINK_MSG.HIGHRES_IMU.yacc = 0.2F;
33
34         msgCenterEmissionConfig->MAVLINK_MSG_STATE.HIGHRES_IMU = true;
35   }
36   if (counterMsgProtobuf.step(true))
37   {
38         msgCenterEmissionMessages->PROTOBUF_MSG.MSG->resetFrame();
39         ProtoFrame& frame  = msgCenterEmissionMessages->PROTOBUF_MSG.MSG->getFrame();
40         frame.has_attitude = true;
41         frame.attitude.has_attitude_local               = true;
42         frame.attitude.attitude_local.has_quaternion    = true;
43         frame.attitude.attitude_local.quaternion.qw     = 0.9F;
44         frame.attitude.attitude_local.quaternion.qx     = 0.1F;
45         frame.attitude.attitude_local.quaternion.qy     = 0.2F;
46         frame.attitude.attitude_local.quaternion.qz     = 0.3F;
47         frame.has_sensors                               = true;
48         frame.sensors.has_accelerometer_raw             = true;
49         frame.sensors.accelerometer_raw.has_xyz         = true;
50         frame.sensors.accelerometer_raw.xyz.x           = 0.1F;
51         frame.sensors.accelerometer_raw.xyz.y           = 0.2F;
52
53         msgCenterEmissionConfig->PROTOBUF_MSG_STATE.MSG = true;
54   }
55
56   msgCenter.sendMessages();
57   delay(5);
58}