Send MAVLink command with MATLAB
21 次查看(过去 30 天)
显示 更早的评论
Hello, I'm searching if there is a way for interact and send commands to my quadcopter with MATLAB, instead of a Ground Control Station. I tried with MATMAV but seems not working. I also tried with MAVLink Support and also this seems not working for send command to my quadcopter. This is my code:
dialect = mavlinkdialect('common.xml');
mavlink = mavlinkio(dialect);
connect(mavlink, 'UDP', 'LocalPort', 14550);
%%
client = mavlinkclient(mavlink, 1, 1) % specify client (1 client = 1 drone)
connectionList = listConnections(mavlink)
clientsList = listClients(mavlink)
topicsList = listTopics(mavlink)
%%
message_num = 400;
cmdMsg = createcmd(dialect, 'int', message_num)
cmdMsg
num2enum(dialect,"MAV_CMD", message_num)
%%
sendudpmsg(mavlink, cmdMsg, '0.0.0.0', 14550)
There are other approaches to send commands to quadcopter through MATLAB?
Thanks in advance!
0 个评论
采纳的回答
Jianxin Sun
2022-10-7
Hi Paolo,
First the mavlink message needs to be refined:
For arm UAV:
cmd = dialect.createcmd("LONG", "MAV_CMD_COMPONENT_ARM_DISARM");
cmd.Payload.target_component(:) = 1;
cmd.Payload.target_system(:) = 1;
cmd.Payload.param1(:) = 1;
For disarm UAV
cmd = dialect.createcmd("LONG", "MAV_CMD_COMPONENT_ARM_DISARM");
cmd.Payload.target_component(:) = 1;
cmd.Payload.target_system(:) = 1;
cmd.Payload.param1(:) = 0;
Also since you are emulating a ground control station in MATLAB, you will need to keep sending out heartbeat from MATLAB to help the UAV find it:
heartbeat = createmsg(dialect,"HEARTBEAT");
heartbeat.Payload.system_status(:) = enum2num(obj.Dialect,'MAV_STATE',"MAV_STATE_STANDBY");
heartbeatTimer = timer;
heartbeatTimer.ExecutionMode = 'fixedRate';
heartbeatTimer.TimerFcn = @(~,~)sendmsg(obj.IO,heartbeat);
start(heartbeatTimer);
If UAV is also broadcasting its heartbeat, your listClient call should show UAV client as well, then you can send message to the uav client:
sendmsg(mavlink, client);
2 个评论
vahe
2023-1-11
I have written the following codes to monitor gimbal variables for UAV through Mavlink codes in MATLAB:
--------------------------------------------------------------------
dialect = mavlinkdialect('common.xml');
sender = mavlinkio(dialect,'SystemID',1,'ComponentID',1,...
'AutopilotType',"MAV_AUTOPILOT_GENERIC",...
'ComponentType',"MAV_TYPE_FIXED_WING");
connect(sender,'UDP');
destinationPort = 14551;
destinationHost = '127.0.0.1';
receiver = mavlinkio(dialect);
connect(receiver,'UDP','LocalPort',destinationPort);
info = msginfo(dialect,"GIMBAL_DEVICE_ATTITUDE_STATUS");
msg = createmsg(dialect,info.MessageName);
info.Fields{:};
subscriber = mavlinksub(receiver,'GIMBAL_DEVICE_ATTITUDE_STATUS',...
'NewMessageFcn',@(~,msg)disp(msg.Payload));
for msgIdx = 1:10
sendudpmsg(sender,msg,destinationHost,destinationPort);
pause(1/50);
end
--------- in the command window ------
time_boot_ms: 0
q: [0 0 0 0]
angular_velocity_x: 0
angular_velocity_y: 0
angular_velocity_z: 0
failure_flags: 0
flags: 0
target_system: 0
target_component: 0
---------------------------------------------
--------- But how can I show only 'q' in the command window?
Because I want to convert it to Euler angles = quat2eul(q)
更多回答(1 个)
Michal
2025-7-29
Hi, I see in this topic were were answering people who might help me resolve the issue.
I am opening the SITL Simulation in Mission Planner (Simulation Tab -> Mulitrotor).
My aim is to setup a Bidirectional Mavlink2 communication between Matlab and Mission Planner simulation. I want to be able to send commands from Matlab to MP and se the behaviour of the dron.
I am able to receive forwarded messages from Mission Planer. I set up Ctrl + F, then open Connection to 14552 Port.
However if I want to send something Back, Mission Planner dose not see it. In Mavlink Inspector I can see only
Vechicle 1
- Comp 1 MAV_COMP_ID_AUTOPILOT1
Mechicle 255
- Comp 190 MAV_COMP_ID_MISSIONPLANNER
The code below I use to try to send a HEARTBEAT messages to Mission Planner.
% === CONNECTION CONFIGURATION ===
localPort = 14552; % Local UDP port (match SITL config)
targetSys = 1;
targetComp = 1;
% === Initialize MAVLinkIO ===
dialect = mavlinkdialect("common.xml", 2);
mav = mavlinkio(dialect);
connect(mav, "UDP", "LocalPort", localPort);
% === Create drone target client ===
client = mavlinkclient(mav, targetSys, targetComp);
% === Register MATLAB as GCS client (sysid 255, compid 1) ===
gcs = mavlinkclient(mav, 255, 1);
% === Subscriptions for responses ===
ackSub = mavlinksub(mav, client, "COMMAND_ACK");
statustextSub = mavlinksub(mav, client, "STATUSTEXT");
% === Send HEARTBEATs periodically ===
disp("📡 Sending HEARTBEAT every 1 second...");
heartbeat = createmsg(dialect, "HEARTBEAT");
heartbeat.Payload.autopilot = 8; % MAV_AUTOPILOT_INVALID
heartbeat.Payload.base_mode = 0;
heartbeat.Payload.custom_mode = uint32(0);
heartbeat.Payload.system_status = 0;
heartbeat.Payload.type = 6; % MAV_TYPE_GCS (Ground Station)
duration = 30; % seconds
startTime = tic;
while toc(startTime) < duration
sendmsg(mav, heartbeat);
fprintf("❤️ Sent HEARTBEAT at t=%.1f sec\n", toc(startTime));
pause(1.0);
end
% === Check COMMAND_ACKs ===
ackMsgs = latestmsgs(ackSub, 1);
for i = 1:numel(ackMsgs)
fprintf("✅ COMMAND_ACK: cmd=%d, result=%d\n", ...
ackMsgs(i).Payload.Command, ackMsgs(i).Payload.Result);
end
% === Check STATUS_TEXTs ===
statusMsgs = latestmsgs(statustextSub, 1);
for i = 1:numel(statusMsgs)
txt = native2unicode(char(statusMsgs(i).Payload.Text'), 'UTF-8');
txt = erase(txt, char(0));
fprintf("📥 STATUS: [%d] %s\n", ...
statusMsgs(i).Payload.Severity, strtrim(txt));
end
% === Cleanup ===
disconnect(mav);
delete(mav);
disp("✅ Done");
I do not know how to solve it. Maybe I have to switch something in Mission Planner, but it is not clear to me what. Is it possible to set a connection I would like to have. All help will be appreciated.
1 个评论
Jianxin Sun
2025-7-30
Here is an example sending message to port 14552:
% === CONNECTION CONFIGURATION ===
remotePort = 14552; % Remote UDP port (match SITL config)
targetSys = 1;
targetComp = 1;
% === Create IO object in MATLAB as GCS client (sysid 255, compid 1) ===
gcs = mavlinkio("common.xml", SystemID=255, ComponentID=1);
gcs.connect("UDP")
% === Create drone target client ===
client = mavlinkclient(gcs, targetSys, targetComp);
% === Subscriptions for responses ===
ackSub = mavlinksub(gcs, client, "COMMAND_ACK");
statustextSub = mavlinksub(gcs, client, "STATUSTEXT");
% === Send HEARTBEATs periodically ===
disp("📡 Sending HEARTBEAT every 1 second...");
heartbeat = createmsg(gcs.Dialect, "HEARTBEAT");
% It is important to preserve the field data type using (:)= assignement
heartbeat = createmsg(gcsNode.Dialect,"HEARTBEAT");
heartbeat.Payload.type(:) = enum2num(dialect,'MAV_TYPE',gcsNode.LocalClient.ComponentType);
heartbeat.Payload.autopilot(:) = enum2num(dialect,'MAV_AUTOPILOT',gcsNode.LocalClient.AutopilotType);
heartbeatTimer = timer;
heartbeatTimer.ExecutionMode = 'fixedRate';
heartbeatTimer.TimerFcn = @(~,~)sendserialmsg(gcsNode,heartbeat,uavSerialPort);
start(heartbeatTimer);
% If you haven't sent any command, you probably won't receive any command
% ack or status message either. You probably need to start with sending
% command or request parameter, etc.
% === Request parameters ===
paramValueSub = mavlinksub(gcs,client,'PARAM_VALUE','BufferSize',100,...
'NewMessageFcn', @(~,msg)disp(msg.Payload));
msg = createmsg(gcs.Dialect,"PARAM_REQUEST_LIST");
msg.Payload.target_system(:) = targetSys;
msg.Payload.target_component(:) = targetComp;
sendmsg(gcs,msg,client)
% === Cleanup ===
stop(heartbeatTimer);
delete(heartbeatTimer);
disconnect(mav);
delete(mav);
disp("✅ Done");
另请参阅
Community Treasure Hunt
Find the treasures in MATLAB Central and discover how the community can help you!
Start Hunting!