APIs description¶
Doxygen complete API documentation¶
Available classes¶
MAVLINK_UTILS¶
-
class MAVLINK_UTILS¶
A utility class for handling MAVLink messages.
This class provides functions to add messages to the monitoring list, add messages to the sending list, add a MAVLink serial stream, update monitored messages, and send messages that are ready to be sent. It also provides functions to get the MAVLINK_MSG_LIST of all monitored messages and all messages to send.
- Param streamObj:
A pointer to a streamLogger object.
Public Functions
-
bool initiateLogging()¶
Initiates the logging process of the sent/received messages.
This function initiates the logging process by setting up the necessary parameters and starting the logging thread. Returns true if the logging process was successfully initiated, false otherwise.
Warning
This function should be called after all messages to monitor and send have been added!
- Returns:
true if the logging process was successfully initiated, false otherwise.
-
void addMsgToMonitor(uint32_t msgID)¶
Adds a message to the monitoring list.
This function adds a message to the list of messages that are being monitored and automatically retrived by the system.
- Parameters:
msgID – The ID of the message to add to the monitoring list.
-
void addMsgToSendingList(uint32_t msgID, const std::vector<MAVLINK_SOURCE> &sendingInterfaces)¶
Adds a message to the sending list.
- Parameters:
msgID – The ID of the message to add.
sendingInterfaces – A vector of MAVLINK_SOURCE objects representing the interfaces to send the message on.
-
bool addMavlinkStream(HardwareSerial *serialObj)¶
Adds a MAVLink serial stream for mavlink reception/emission.
This function adds a MAVLink serial stream to the library, which can be used to send and receive MAVLink messages.
- Parameters:
serialObj – A pointer to the HardwareSerial object that represents the serial port to use for the MAVLink stream.
- Returns:
true if the MAVLink stream was added successfully, false otherwise.
-
void updateMonitoredMessages(const uint8_t *buffer, size_t bufferLength)¶
Updates all monitored message information.
This function updates all monitored messages information by checking for new messages and updating the information for existing messages. It should be called periodically to ensure that the monitored messages information is up-to-date. This function updates the received messages using the buffer provided by the caller. This function does not directly use hardware buffers to avoid pruning it if multiple protocols are used for the same interface. For example if mavlink and protobuf are used on the same serial bus, the caller has to copy the serial buffer into a temporary buffer and provide it to this function.
- Parameters:
buffer – A pointer to the buffer containing the received messages.
bufferLength – The length of the buffer in bytes.
-
void sendMessages()¶
Sends messages that are ready to be sent.
This function sends messages that are ready to be sent. It should be called periodically to ensure that all messages are sent in a timely manner.
-
bool sendMessage(MAVLINK_SOURCE source, const mavlink_message_t &msg)¶
Sends message immediately on specified interface.
This function sends message immediately on specified interface. It can be called by application to send the message on an interface even if the MAVLINK_MSG mSendInterfaces does not contain it. Of course the the configured hardware interface has to be provided at least one time with addMavlinkStream() for sendMessage() to succeed. doSend field is not updated by this function.
- Parameters:
source – The MAVLink source to send the message from.
msg – The MAVLink message to send.
- Returns:
True if the message was sent successfully, false otherwise.
-
bool sendMessage(const std::vector<MAVLINK_SOURCE> &sources, const mavlink_message_t &msg)¶
Sends message immediately on specified interfaces.
- Parameters:
sources – A vector of MAVLINK_SOURCE objects representing the sources to send the message to.
msg – The MAVLink message to send.
- Returns:
True if the message was sent successfully, false otherwise.
-
inline const MAVLINK_MSG_LIST *getMonitoredMsgsList()¶
Returns a pointer to the list of all monitored MAVLink messages.
Warning
This list should not be modified by the caller. Instead the caller should use the MAVLINK_MSG_LIST::getSubset() function to get a subset of the messages it wants to follow.
- Returns:
A pointer to the list of monitored MAVLink messages.
-
inline const MAVLINK_MSG_LIST *getMsgsToSendList()¶
Returns the MAVLINK_MSG_LIST of all messages to send.
This function returns a constant reference to the MAVLINK_MSG_LIST of all messages that are currently queued to be sent.
Warning
The returned reference should not be modified by the caller. Instead, the caller should use the MAVLINK_MSG_LIST::getSubset() function to get a subset of the messages to send and modify the messages in the subset.
- Returns:
A constant reference to the MAVLINK_MSG_LIST of all messages to send.
MAVLINK_MSG¶
-
struct MAVLINK_MSG¶
Internal struct to handle any mavlink message and extract any information using the ID.
To simplify the comprehension of the code, the choice has been made to store only binary representation of the messages. Decoding has to be done by the user using the mavlink autogenerated code.
Public Functions
-
inline explicit MAVLINK_MSG(uint32_t msgId)¶
A class representing a MAVLink message.
This class provides a convenient way to construct and manipulate MAVLink messages. It contains fields for the message ID, payload, and checksum, as well as methods for encoding and decoding the message.
-
inline const mavlink_message_t &getMavlinkMsg(bool isNewFlagToFalse = true)¶
Returns the last received MAVLink message (raw generci mavlink struct)
- Parameters:
isNewFlagToFalse – If true, sets the “is new” flag to false after returning the message.
- Returns:
A reference to the last received MAVLink message raw struct.
-
inline void updateMsgForRead(const mavlink_message_t &msg)¶
Updates the internal state of the library with the data from a received MAVLink message.
This function should be called whenever a new MAVLink message is received by the library. It updates the internal state of the library with the data from the message, so that the data can be read by the user.
- Parameters:
msg – The MAVLink message to update the internal state with.
-
inline void updateMsgForSend(const mavlink_message_t &msg)¶
Updates the message for sending.
This function updates the message that needs to be sent on the hardware stream.
- Parameters:
msg – The
mavlink_message_t
object to update.
-
inline void printInfos(streamLogger *streamObj) const¶
Prints the message information.
This function prints the message informations which include message ID, message name, and message length.
- Parameters:
streamObj – A pointer to the streamLogger object to use for printing and logging.
-
inline bool isSendingInterface(const MAVLINK_SOURCE source)¶
Checks if the specified interface is available for sending messages.
- Parameters:
source – The MAVLink source to check.
- Returns:
True if the interface is available for sending messages, false otherwise.
-
inline explicit MAVLINK_MSG(uint32_t msgId)¶
MAVLINK_MSG_LIST¶
-
struct MAVLINK_MSG_LIST¶
MAVLINK_MSG_LIST is a vector of subset of references to MAVLINK_MSG stored in mMsgs.
It allows to avoid search in the mMsgs vector when wanting to access a specific message
Warning
Do not try to create this struct directly, extract a subset of MAVLINK_UTILS::getMonitoredMsgsList() or MAVLINK_UTILS::getMsgsToSendList
Public Functions
-
inline MAVLINK_MSG *getMsg(uint32_t msgID, bool isNewFlagToFalse = true) const¶
Returns the last message of the given ID.
This function returns the last message of the given ID that was received by the MAVLink communication interface. If the
isNewFlagToFalse
parameter is set totrue
(default), the “isNew” flag of the returned message will be set tofalse
when calling the function- Parameters:
msgID – The ID of the message to retrieve.
isNewFlagToFalse – If
true
, the “isNew” flag of the returned message will be set tofalse
.
- Returns:
A pointer to the last message of the given ID.
-
inline bool getIsNew(uint32_t msgID)¶
Get the isNew flag of the given message ID.
- Parameters:
msgID – The ID of the message to check.
- Returns:
True if the message is new, false otherwise.
-
inline bool getReadyForSend(uint32_t msgID)¶
Gets the isReadyForSend flag of the given message ID.
- Parameters:
msgID – The ID of the message to check.
- Returns:
True if the message is ready to be sent, false otherwise.
-
inline const std::vector<MAVLINK_MSG*> &getMsgRefsList()¶
Returns a const reference to the list of MAVLink message pointers.
- Returns:
const std::vector<MAVLINK_MSG*>& A const reference to the list of MAVLink message pointers.
-
inline void addMsg(MAVLINK_MSG *msg)¶
Adds a MAVLink message to the list.
- Parameters:
msg – Pointer to the MAVLink message to add.
-
inline MAVLINK_MSG_LIST getSubset(const std::vector<uint32_t> &msgIDList) const¶
Returns a subset of the MAVLINK_MSG_LIST containing only messages with IDs in the provided list.
- Parameters:
msgIDList – A vector of uint32_t values representing the IDs of the messages to include in the subset.
- Returns:
A MAVLINK_MSG_LIST object containing only the messages with IDs in the provided list.
-
inline MAVLINK_MSG *getMsg(uint32_t msgID, bool isNewFlagToFalse = true) const¶