APIs description

Doxygen complete API documentation

Doxygen documentation Link to doxygen API documentation

Available classes

MSG_CENTER

class MSG_CENTER

Class for managing the transmission and reception of messages through different protocols.

This class provides methods to send and receive messages through UART, CAN with MAVLink, Protobuf and CAN protocols. It also allows the user to configure the hardware interface for each protocol and to add messages to be sent or received.

Note

The class is designed to work with a specific set of configuurable message structures defined in libDM_msg_center_structs.hpp

Public Functions

inline explicit MSG_CENTER(streamLogger *streamObj, timerTool *timerObj)

Constructs a new MSG_CENTER object.

Parameters:
  • streamObj – Pointer to the streamLogger object used for logging messages.

  • timerObj – Pointer to the timerTool object used for timing purposes.

bool begin()

Initializes the message center.

Note

This function must be called before any other functions in the message center can be used.

Returns:

true if the message center was successfully initialized, false otherwise.

void sendMessages()

Sends all configured messages with timestamping.

This function sends all messages that have been configured in libDM_msg_center_struct.hpp, on specified interfaces.

Note

The user is supposed to get the message to send struct with getMessagesToSend(), modify it and then call this function.

Note

Timestamping is done automatically by the function, no need to complete the struct with time fields

void receiveMessages()

Receives all configured messages.

This function receives all messages that have been configured in libDM_msg_center_struct.hpp, on specified interfaces.

void updateReceivedMessagesState(MSG_CENTER_STRUCTS::PROTOCOL protocol)

Updates the state of messages to receive for a given protocol.

This function updates the state of messages for a given protocol. The user is supposed to call getConfig(), update configuration and call this function to update the messages list that the library will receive.

Note

The messages sending is handled directly when sendMessages() is called, so the only thing to do for configuring messages to send is calling getMessagesToSend() and update configuration.

Parameters:

protocol – The protocol for which to update the message state.

bool attachHardwareInterface(HardwareSerial *serialObj, uint32_t serialSpeed, uint8_t pinRx, uint8_t pinTx, bool reconfigureUart = true)

Attaches a hardware serial interface to the message center.

Parameters:
  • serialObj – Pointer to the HardwareSerial object to attach.

  • serialSpeed – The baud rate of the serial interface.

  • pinRx – The RX pin of the serial interface.

  • pinTx – The TX pin of the serial interface.

  • reconfigureUart – Whether to reconfigure the UART interface.

Returns:

True if the attachment was successful, false otherwise.

bool configureCanInterface(CAN_ENUM::BAUDRATE baudrate, gpio_num_t pinRx, gpio_num_t pinTx)

Configures the CAN interface that will be used by msg_center with the specified baudrate and pins.

Note

With the call to this function, all messages configured for can protocol will be added on specified frames. The frames activated finally will be considered during sending/receiving messages

Parameters:
  • baudrate – The desired baudrate for the CAN interface.

  • pinRx – The GPIO pin number to use for receiving CAN messages.

  • pinTx – The GPIO pin number to use for transmitting CAN messages.

Returns:

true if the CAN interface was successfully configured, false otherwise.

inline MSG_CENTER_STRUCTS::MSG_CENTER_MSG *getMessagesToSend() const

Returns a pointer to the messages to send msg_center struct.

Note

The user is supposed to get the message to send struct with this function, modify it and call sendMessages() to send the messages.

Returns:

A const pointer to the messages that are ready to be sent.

inline MSG_CENTER_STRUCTS::MSG_CENTER_MSG *getReceivedMessages() const

Returns a pointer to the msg_center struct that stores received messages.

Returns:

A pointer to the list of messages that are waiting to be received.

inline MSG_CENTER_STRUCTS::MSG_CENTER_CONFIG *getReceptionConfig() const

Returns a pointer to the current configuration settings for the message center.

The user is supposed to get the configuration struct with this function, modify it, and call updateReceivedMessagesState() to update the messages list that the library will receive.

Returns:

A pointer to the current MSG_CENTER_STRUCTS::MSG_CENTER_CONFIG object.

inline MSG_CENTER_STRUCTS::MSG_CENTER_CONFIG *getEmissionConfig() const

Returns a pointer to the emission configuration for the message center.

The user is supposed to get the configuration struct with this function then modify it. The configuration will be used automatically when sendMessages() is called.

Returns:

MSG_CENTER_STRUCTS::MSG_CENTER_CONFIG* A pointer to the emission configuration.

MSG_CENTER_STRUCTS

namespace MSG_CENTER_STRUCTS

Enums

enum class PROTOCOL : uint8_t

Values:

enumerator PROTOCOL_MAVLINK
enumerator PROTOCOL_PROTOBUF
enumerator PROTOCOL_CAN
enum class HW_INTERFACE : uint8_t

Values:

enumerator INT_SERIAL
enumerator INT_WIFI
enumerator INT_BLE
enumerator INT_CAN

MAVLINK messages enumeration for indexation.

Values:

enum class CAN_MSG_FRAMES : uint32_t

CAN messages frame identifiers used on can bus.

Values:

enumerator ATTITUDE_QUATERNION_0
enumerator ATTITUDE_QUATERNION_1
enumerator BODY_RATES_0
enumerator BODY_RATES_1
enumerator LOCAL_POSITION_0
enumerator LOCAL_POSITION_1
enumerator LOCAL_POSITION_2
enumerator OFFSET_LOCAL_TO_GLOBAL_NED_0
enumerator OFFSET_LOCAL_TO_GLOBAL_NED_1_OFFSET_YAW
enum class CAN_MSG_IDX : uint32_t

CAN messages enumeration for indexation.

Values:

enumerator ATTITUDE_QUATERNION
enumerator BODY_RATES
enumerator LOCAL_POSITION
enumerator OFFSET_LOCAL_TO_GLOBAL_NED
enumerator OFFSET_YAW_LOCAL_TO_GLOBAL_NED

Variables

ID of selected MAVLINK messages.

constexpr uint8_t CAN_MSG_NB = 5U
constexpr uint8_t CAN_FRAMES_NB = 9U
const std::map<CAN_MSG_FRAMES, std::vector<String>> CAN_MSG_NAMES_MAP = {{CAN_MSG_FRAMES::ATTITUDE_QUATERNION_0, {"0x1", "qw", "qx"}}, {CAN_MSG_FRAMES::ATTITUDE_QUATERNION_1, {"0x2", "qy", "qz"}}, {CAN_MSG_FRAMES::BODY_RATES_0, {"0x3", "p", "q"}}, {CAN_MSG_FRAMES::BODY_RATES_1, {"0x4", "r"}}, {CAN_MSG_FRAMES::LOCAL_POSITION_0, {"0x5", "x", "vx"}}, {CAN_MSG_FRAMES::LOCAL_POSITION_1, {"0x6", "y", "vy"}}, {CAN_MSG_FRAMES::LOCAL_POSITION_2, {"0x7", "z", "vz"}}, {CAN_MSG_FRAMES::OFFSET_LOCAL_TO_GLOBAL_NED_0, {"0x8", "x", "y"}}, {CAN_MSG_FRAMES::OFFSET_LOCAL_TO_GLOBAL_NED_1_OFFSET_YAW, {"0x9", "z", "yaw"}}}

A map that associates CAN message frames with their corresponding identifier and included signals.

The map is implemented as a std::map object, where the keys are of type CAN_MSG_FRAMES and the values are of type std::vector<String>. Each vector contains the names of the fields that compose the corresponding CAN message frame.

struct CAN_MSG_DEF
#include <libDM_msg_center_structs.hpp>

Struct containing the CAN messages definitions and providing storage.

User can add new messages if needed

Public Functions

inline bool getIsNewMsg(CAN_MSG_IDX msgIdx)

Returns whether a CAN message with the given index is new.

A new message means that all the frames constituting the message have been received.

Parameters:

msgIdx – The index of the CAN message to check.

Returns:

true if the message is new, false otherwise.

inline bool getIsNewFrame(CAN_MSG_FRAMES frameIdx)

Returns whether the given CAN message frame index is a new frame.

Parameters:

frameIdx – The index of the CAN message frame to check.

Returns:

true if the frame is new, false otherwise.

inline void resetFrameTimestamp(CAN_MSG_FRAMES frameIdx)

Resets the timestamp of a given CAN message frame with setting previous timestamp to the current one.

As the frames constituting a single message can be received at different times, more than 2 frames is diffucult to handle. The reset has to be done by the user, when the message is complete.

Parameters:

frameIdx – The index of the CAN message frame to reset.

inline void setFrameTimeStamp(CAN_MSG_FRAMES frameIdx, uint64_t timestamp)

Sets the timestamp for a given CAN message frame.

Parameters:
  • frameIdx – The index of the CAN message frame to set the timestamp for.

  • timestamp – The timestamp to set for the specified CAN message frame.

inline void setMsgTimeStamp(CAN_MSG_IDX msgIdx, uint64_t timestamp)

Sets the timestamp for a given CAN message index.

Parameters:
  • msgIdx – The index of the CAN message to set the timestamp for.

  • timestamp – The timestamp to set for the given CAN message index.

struct CAN_MSG_ENABLED
#include <libDM_msg_center_structs.hpp>

Configuration struct containing boolean flags for CAN messages activation.

The flags indicate whether the CAN message is enabled or not. The user can change the default values and add new messages if needed

Public Functions

inline void reset()

Resets the messages activation states.

struct CAN_MSG_REFS
#include <libDM_msg_center_structs.hpp>

CAN messages refs linked with libDM_can added signals, and used as alias for messages emission.

struct HW_INTERFACE_ENABLED
#include <libDM_msg_center_structs.hpp>

Struct representing the enabled hardware interfaces for msg_center.

Public Functions

inline HW_INTERFACE_ENABLED(bool serial, bool wifi, bool ble, bool can)

Constructor for HW_INTERFACE_ENABLED.

Parameters:
  • serial – Whether the serial interface is enabled.

  • wifi – Whether the WiFi interface is enabled.

  • ble – Whether the Bluetooth Low Energy interface is enabled.

  • can – Whether the Controller Area Network interface is enabled.

Public Members

bool INT_SERIAL = false

Whether the serial interface is enabled.

bool INT_WIFI = false

Whether the WiFi interface is enabled.

bool INT_BLE = false

Whether the Bluetooth Low Energy interface is enabled.

bool INT_CAN = false

Whether the Controller Area Network interface is enabled.

#include <libDM_msg_center_structs.hpp>

Struct containing the MAVLINK messages definitions and providing storage.

User can add new messages if needed

Public Functions

Checks if a message with the given index is new.

Parameters:

msgIdx – The index of the message to check.

Returns:

True if the message is new, false otherwise.

Sets the timestamp of a specific message.

Parameters:
  • msgIdx – The index of the message to set the timestamp for.

  • timestamp – The timestamp to set for the message.

#include <libDM_msg_center_structs.hpp>

Configuration struct containing boolean flags for mavlink messages activation.

The flags indicate whether the mavlink message is enabled or not. The user can change the default values and add new messages if needed

Public Functions

Resets the messages activation states.

#include <libDM_msg_center_structs.hpp>

MAVLINK messages refs linked with libDM_mavlink added signals, and used as alias for messages reception.

struct MSG_CENTER_CONFIG
#include <libDM_msg_center_structs.hpp>

MSG_CENTER_CONFIG struct containing the enabled/disabled state of MAVLink, Protobuf and CAN message types configured by user.

Public Functions

inline void reset()

Resets the messages activation states.

struct MSG_CENTER_MSG
#include <libDM_msg_center_structs.hpp>

Struct containing instances of message definitions for MAVLink, Protobuf and CAN.

struct PROTOBUF_MSG_DEF
#include <libDM_msg_center_structs.hpp>

A struct representing a message to be sent or received using the protobuf library.

This struct contains a pointer to a protobuf message object, which must be linked to the protobuf library in order to send or receive messages.

Public Functions

inline bool getIsNewMsg()

Returns whether there is a new message.

Returns:

true if there is a new message, false otherwise.

inline void setMsgTimeStamp(uint64_t timestamp)

Sets the timestamp of the message.

Parameters:

timestamp – The timestamp to set.

struct PROTOBUF_MSG_ENABLED
#include <libDM_msg_center_structs.hpp>

Configuration struct containing boolean flags for protobuf messages activation.

The flags indicate whether the protobuf message is enabled or not. The user can change the default values and add new messages if needed

Public Functions

inline void reset()

Resets the messages activation states.