Send and receive custom message over mavlink

Hi
i try to send custom message from mission planner to copter and receive response i but i newbe on this project can anyone help me or send me your document what function must be add and where or send my some example
thank for help

Follow this guide: Adding a new MAVLink Message β€” Dev documentation

For additional clarity (First refer to the above guide!), Example:

I defined a message definition in ardupilotmega.xml:

<message id="333" name="CUSTOMMSG">
      <description>Custom Data</description>
      <field type="char[4]" name="Packet" units="packet">Packet Number</field>
      <field type="char[251]" name="Data" units="unit">Data Values</field>
    </message>

Defining variables in …/ArduCopter/GCS_Mavlink.h:

// Test vars
const char* custom_data;
const char* packet_number;

Handling the message in the GCS_MAVLINK_Copter::handle_message(const mavlink_message_t &msg) function of …/ArduCopter/GCS_Mavlink.cpp:

case MAVLINK_MSG_ID_CUSTOMMSG:   // MAV ID: 333
        {
            // decode packet
            mavlink_custommsg_t packet;
            mavlink_msg_custommsg_decode(&msg, &packet);

            custom_data = packet.Data;
            packet_number = packet.Packet;

            mavlink_msg_custommsg_send(chan, packet_number, custom_data);
            break;
        }

Further, on the GCS side,
To send data:

from pymavlink import mavutil

connection = mavutil.mavlink_connection('udp:127.0.0.1:14550')
connection.wait_heartbeat()

packet_num = 1
msg  = "Hello! This is a Custom Message"

connection.mav.send(
            mavutil.mavlink.MAVLink_custommsg_message(
                Packet = f"{packet_num}".encode(),
                Data = msg.encode(),
            )
        )

For receiving the message:

from pymavlink import mavutil

connection = mavutil.mavlink_connection('udp:127.0.0.1:145502)
connection.wait_heartbeat()

msg = connection.recv_msg()
        if msg:
            msg = msg.to_dict()

            if msg["mavpackettype"] == "CUSTOMMSG":
                print(msg)
2 Likes

Thanks for your help its very helpful
But how can i send messages in the firmware without py script and receive message on firmware send by mission planner
i want to send command from mission planner to sensor and view sensor output on mission planner
its that possible?

ill try to send message by your example but i have this error when i try build firmware:

/home/β€”/.espressif/tools/xtensa-esp32-elf/esp-2021r2-patch5-8.4.0/xtensa-esp32-elf/bin/…/lib/gcc/xtensa-esp32-elf/8.4.0/…/…/…/…/xtensa-esp32-elf/bin/ld: /home/β€”/ardupilot/build/esp32empty/lib/bin/libarduplane.a(failsafe.cpp.50.o):/home/β€”/ardupilot/build/esp32empty/…/…/ArduPlane/GCS_Mavlink.h:9: multiple definition of `custom_data’; /home/β€”/ardupilot/build/esp32empty/lib/bin/libarduplane.a(ArduPlane.cpp.50.o):/home/β€”/ardupilot/build/esp32empty/…/…/ArduPlane/GCS_Mavlink.h:9: first defined here

rebuild for copter in problem solved