git clone https://github.com/mavlink/mavlink.git
Create a file named custom.xml
with these contents:
<?xml version="1.0"?>
<mavlink>
<messages>
<message id="0" name="MY_CUSTOM_MSG">
<description>My Custom Message</description>
<field type="char[10]" name="sensor_name">Sensor Name</field>
<field type="uint8_t" name="sensor_id">Sensor ID</field>
<field type="double" name="sensor_value">Sensor Value</field>
</message>
</messages>
</mavlink>
If you want more examples you can check out the examples in the directory message_defintions/v1.0
Open the mavgenerate.py
program inside the MAVLink toolchain:
./mavgenerate.py
- In the XML field enter the file path for your custom message.
- In the Out field enter a directory name for where you want to put the genreated source code.
- In the Language field enter what language you'd like. For this README I will choose C.
- In the Protcol field enter what protocol you'd like. For this README I will choose 2.0.
- Click on "Generate"
Here is a simple example of message SENDER in C using the generated headers:
#include <iostream>
#include <cstring>
#include <sys/socket.h>
#include <netinet/in.h>
#include <arpa/inet.h>
#include <thread>
#include "mavlink/custom/mavlink.h"
int main()
{
mavlink_message_t msg;
uint16_t len;
uint8_t buf[2041];
ssize_t bytes_sent;
int sock;
struct sockaddr_in destAddr;
// open a socket
sock = socket(PF_INET, SOCK_DGRAM, IPPROTO_UDP);
// set a destination address
memset(&destAddr, 0, sizeof(destAddr));
destAddr.sin_family = AF_INET;
destAddr.sin_addr.s_addr = inet_addr("127.0.0.1");
destAddr.sin_port = htons(14550);
while(true) {
// send custom message
mavlink_msg_my_custom_msg_pack(2, 100, &msg, "sensor125", 125, 66.66);
len = mavlink_msg_to_send_buffer(buf, &msg);
bytes_sent = sendto(sock, buf, len, 0, (struct sockaddr*)&destAddr, sizeof(struct sockaddr_in));
// wait a second
std::this_thread::sleep_for(std::chrono::seconds(1));
}
return 0;
}
Here is a simple example of message RECEIVER in C using the generated headers:
#include <iostream>
#include <cstring>
#include <sys/socket.h>
#include <netinet/in.h>
#include <arpa/inet.h>
#include <thread>
#include "mavlink/custom/mavlink.h"
int main()
{
mavlink_message_t msg;
mavlink_status_t status;
socklen_t clientLen;
uint8_t buf[2041];
ssize_t n;
int sock;
struct sockaddr_in bindAddr;
struct sockaddr_in clientAddr;
// open a socket
sock = socket(AF_INET, SOCK_DGRAM, 0);
// set bind address
memset(&bindAddr, 0, sizeof(bindAddr));
bindAddr.sin_family = AF_INET;
bindAddr.sin_addr.s_addr = htonl(INADDR_ANY);
bindAddr.sin_port = htons(14550);
bind(sock, (struct sockaddr *) &bindAddr, sizeof(bindAddr));
while(true) {
n = recvfrom(sock, buf, 2041, 0, (struct sockaddr *) &clientAddr, &clientLen);
if(n > 0) {
for(int i = 0; i < n; ++i) {
if (mavlink_parse_char(MAVLINK_COMM_0, buf[i], &msg, &status))
{
printf("Received packet: SYS: %d, COMP: %d, LEN: %d, MSG ID: %d\n",
msg.sysid, msg.compid, msg.len, msg.msgid);
if(msg.msgid == MAVLINK_MSG_ID_MY_CUSTOM_MSG) {
double sensor_value = mavlink_msg_my_custom_msg_get_sensor_value(&msg);
printf("It's a custom message: SENSOR VALUE: %f\n", sensor_value);
}
}
}
}
}
return 0;
}
Thanks for the guide.
Bug: for me it didn't work if I declare the "double" instead "float" worked flawlessly.