1.引入maven坐标
<dependency>
<groupId>io.dronefleet.mavlink</groupId>
<artifactId>mavlink</artifactId>
<version>1.1.11</version>
</dependency>
2.连接
通过socket 建立tcp连接,并传入 InputStream,OutputStream 创建完成后该MavlinkConnection为最总连接对象,发送消息与接收消息通过该对象进行操作
Socket socket = new Socket(ip,port);
MavlinkConnection mavlinkConnect = MavlinkConnection.create(socket.getInputStream(), socket.getOutputStream());
3.建立消息监听
下面列举了常用的一些消息信息
MavlinkMessage message;
while ((message = mavlinkConnect.next()) != null) {
if (message instanceof Mavlink2Message) {
Mavlink2Message msg2 = (Mavlink2Message)message;
//System.out.println(msg2);
// 接收的消息其负载类型不是静态可知的,我们可通过负载来识别消息类型:
if (message.getPayload() instanceof Heartbeat) {
// 心跳消息
MavlinkMessage<Heartbeat> heartbeatMsg = (MavlinkMessage<Heartbeat>)message;
}else if(message.getPayload() instanceof GlobalPositionInt){
//gps消息
MavlinkMessage<GlobalPositionInt> globalPositionIntMavlinkMessage = (MavlinkMessage<GlobalPositionInt>)message;
GlobalPositionInt payload = globalPositionIntMavlinkMessage.getPayload();
//System.out.println("GPS消息:"+payload);
}else if(message.getPayload() instanceof VfrHud){
//hud消息
MavlinkMessage<VfrHud> vfrHudMavlinkMessage = (MavlinkMessage<VfrHud>)message;
VfrHud vfrHud = vfrHudMavlinkMessage.getPayload();
//System.out.println("HUD消息"+vfrHud);
}else if(message.getPayload() instanceof GpsStatus){
//gps状态消息
MavlinkMessage<GpsStatus> gpsStatusMavlinkMessage = (MavlinkMessage<GpsStatus>)message;
GpsStatus gpsStatus = gpsStatusMavlinkMessage.getPayload();
//System.out.println("gps状态"+gpsStatus);
}else if(message.getPayload() instanceof GpsRawInt){
//gps信息
MavlinkMessage<GpsRawInt> gpsRawIntMavlinkMessage = (MavlinkMessage<GpsRawInt>)message;
GpsRawInt gpsRawInt = gpsRawIntMavlinkMessage.getPayload();
//System.out.println("GPS_RAW_INT信息:"+gpsRawInt);
}else if(message.getPayload() instanceof Attitude){
//姿态
MavlinkMessage<Attitude> attitudeMavlinkMessage = (MavlinkMessage<Attitude>)message;
Attitude attitude = attitudeMavlinkMessage.getPayload();
//System.out.println("姿态信息:"+attitude);
}else if(message.getPayload() instanceof RcChannels){
//通道,油门通道值
MavlinkMessage<RcChannels> rcChannelsMavlinkMessage = (MavlinkMessage<RcChannels>)message;
RcChannels rcChannels = rcChannelsMavlinkMessage.getPayload();
//System.out.println("油门通道信息:"+rcChannels);
}else if(message.getPayload() instanceof BatteryStatus){
//电池状态
MavlinkMessage<BatteryStatus> batteryStatusMavlinkMessage = (MavlinkMessage<BatteryStatus>)message;
BatteryStatus batteryStatus = batteryStatusMavlinkMessage.getPayload();
//System.out.println("电池状态信息:"+batteryStatus);
}else if(message.getPayload() instanceof SysStatus){
MavlinkMessage<SysStatus> sysStatusMavlinkMessage = (MavlinkMessage<SysStatus>)message;
SysStatus sysStatus = sysStatusMavlinkMessage.getPayload();
//System.out.println("系统状态信息:"+sysStatus);
}else if(message.getPayload() instanceof CommandAck ){
//命令回调信息
MavlinkMessage<CommandAck> commandAckMavlinkMessage = (MavlinkMessage<CommandAck>)message;
CommandAck commandAck = commandAckMavlinkMessage.getPayload();
EnumValue<MavResult> result = commandAck.result();
System.out.println("命令状态信息:"+commandAck);
}else if(message.getPayload() instanceof Statustext){
//状态文本,该消息会返回相关的异常信息
MavlinkMessage<Statustext> statustextMavlinkMessage = (MavlinkMessage<Statustext>)message;
Statustext statustext = statustextMavlinkMessage.getPayload();
System.out.println("状态文本信息:"+statustext);
}
} else {
// Mavlink1消息
}
}
其中CommandAck消息比较重要,发送的命令是否执行成功通过该消息进行通知
具体内容可以在mavlink官网查看 mavlink.io/en/messages…
Statustext消息为 会返回相关的异常信息,比如模式为AUTO时,解锁会报Arm: AUTO mode not armable
Statustext{severity=EnumValue{value=2, entry=MAV_SEVERITY_CRITICAL}, text=Arm: AUTO mode not armable, id=0, chunkSeq=0}
4.设置周期回传信息
通过 RequestDataStream进行构建,并发送
下面为构建streamId为11的信息
int sysId = 255; int compId = 0;
//启用hud
RequestDataStream requestDataStream = RequestDataStream.builder()
.targetSystem(1)
.targetComponent(1)
.reqMessageRate(1)
.startStop(1)
.reqStreamId(11).build();
Thread.sleep(3000);
mavlinkConnect.send2(sysId,compId,requestDataStream);
下图为streamId值,具体streamId值查看mavlink官网 mavlink.io/en/messages…
5.发送CommandLong 类型消息
下面为发送解锁代码
command为操作类型,具体操作类型查看mavlink官网
sdk中 MavCmd枚举类中包含具体的类型值
CommandLong commandLong = CommandLong.builder()
.targetSystem(1)
.targetComponent(1)
.command(MavCmd.MAV_CMD_COMPONENT_ARM_DISARM)
.confirmation(0)
.param1(1)
.param2(0).build();
mavlinkConnect.send2(sysId,compId,commandLong);
下图为CommandLong(76)格式,具体查看mavlink官网 mavlink.io/en/messages…
6.整体逻辑代码
package com.wwy.demo;
import io.dronefleet.mavlink.Mavlink2Message;
import io.dronefleet.mavlink.MavlinkConnection;
import io.dronefleet.mavlink.MavlinkMessage;
import io.dronefleet.mavlink.common.*;
import io.dronefleet.mavlink.minimal.Heartbeat;
import io.dronefleet.mavlink.util.EnumValue;
import java.io.EOFException;
import java.io.IOException;
import java.net.Socket;
import java.net.UnknownHostException;
/**
* @Author: wwy
* @Date: 2025-05-28 9:18
*/
public class MavlinkExample {
/**
* 连接对象
*/
public MavlinkConnection connect(String ip,int port) throws IOException {
// 此处用TCP套接字举例,实际上也可以用UDP套接字(通过PipedInputStream/PipedOutputStream注入MavlinkConnection),甚至USB(需实现最终提供InputStream和OutputStream的接口)。
Socket socket = new Socket(ip,port);
MavlinkConnection mavlinkConnect = MavlinkConnection.create(socket.getInputStream(), socket.getOutputStream());
return mavlinkConnect;
}
public void messageCallBack(MavlinkConnection mavlinkConnect) throws IOException {
MavlinkMessage message;
while ((message = mavlinkConnect.next()) != null) {
if (message instanceof Mavlink2Message) {
Mavlink2Message msg2 = (Mavlink2Message)message;
//System.out.println(msg2);
// 接收的消息其负载类型不是静态可知的,我们可通过负载来识别消息类型:
if (message.getPayload() instanceof Heartbeat) {
// 心跳消息
MavlinkMessage<Heartbeat> heartbeatMsg = (MavlinkMessage<Heartbeat>)message;
}else if(message.getPayload() instanceof GlobalPositionInt){
//gps消息
MavlinkMessage<GlobalPositionInt> globalPositionIntMavlinkMessage = (MavlinkMessage<GlobalPositionInt>)message;
GlobalPositionInt payload = globalPositionIntMavlinkMessage.getPayload();
//System.out.println("GPS消息:"+payload);
}else if(message.getPayload() instanceof VfrHud){
//hud消息
MavlinkMessage<VfrHud> vfrHudMavlinkMessage = (MavlinkMessage<VfrHud>)message;
VfrHud vfrHud = vfrHudMavlinkMessage.getPayload();
//System.out.println("HUD消息"+vfrHud);
}else if(message.getPayload() instanceof GpsStatus){
//gps状态消息
MavlinkMessage<GpsStatus> gpsStatusMavlinkMessage = (MavlinkMessage<GpsStatus>)message;
GpsStatus gpsStatus = gpsStatusMavlinkMessage.getPayload();
//System.out.println("gps状态"+gpsStatus);
}else if(message.getPayload() instanceof GpsRawInt){
//gps信息
MavlinkMessage<GpsRawInt> gpsRawIntMavlinkMessage = (MavlinkMessage<GpsRawInt>)message;
GpsRawInt gpsRawInt = gpsRawIntMavlinkMessage.getPayload();
//System.out.println("GPS_RAW_INT信息:"+gpsRawInt);
}else if(message.getPayload() instanceof Attitude){
//姿态
MavlinkMessage<Attitude> attitudeMavlinkMessage = (MavlinkMessage<Attitude>)message;
Attitude attitude = attitudeMavlinkMessage.getPayload();
//System.out.println("姿态信息:"+attitude);
}else if(message.getPayload() instanceof RcChannels){
//通道,油门通道值
MavlinkMessage<RcChannels> rcChannelsMavlinkMessage = (MavlinkMessage<RcChannels>)message;
RcChannels rcChannels = rcChannelsMavlinkMessage.getPayload();
//System.out.println("油门通道信息:"+rcChannels);
}else if(message.getPayload() instanceof BatteryStatus){
//电池状态
MavlinkMessage<BatteryStatus> batteryStatusMavlinkMessage = (MavlinkMessage<BatteryStatus>)message;
BatteryStatus batteryStatus = batteryStatusMavlinkMessage.getPayload();
//System.out.println("电池状态信息:"+batteryStatus);
}else if(message.getPayload() instanceof SysStatus){
MavlinkMessage<SysStatus> sysStatusMavlinkMessage = (MavlinkMessage<SysStatus>)message;
SysStatus sysStatus = sysStatusMavlinkMessage.getPayload();
//System.out.println("系统状态信息:"+sysStatus);
}else if(message.getPayload() instanceof CommandAck ){
//命令回调信息
MavlinkMessage<CommandAck> commandAckMavlinkMessage = (MavlinkMessage<CommandAck>)message;
CommandAck commandAck = commandAckMavlinkMessage.getPayload();
EnumValue<MavResult> result = commandAck.result();
System.out.println("命令状态信息:"+commandAck);
}else if(message.getPayload() instanceof Statustext){
//状态文本,该消息会返回相关的异常信息
MavlinkMessage<Statustext> statustextMavlinkMessage = (MavlinkMessage<Statustext>)message;
Statustext statustext = statustextMavlinkMessage.getPayload();
System.out.println("状态文本信息:"+statustext);
}
} else {
// Mavlink1消息
}
}
}
public static void main(String[] args) throws IOException, InterruptedException {
MavlinkExample mavlinkExample = new MavlinkExample();
MavlinkConnection mavlinkConnect = mavlinkExample.connect("127.0.0.1", 5762);
//设置周期性回调信息
int sysId = 255; int compId = 0;
//启用hud
RequestDataStream requestDataStream = RequestDataStream.builder()
.targetSystem(1)
.targetComponent(1)
.reqMessageRate(1)
.startStop(1)
.reqStreamId(11).build();
Thread.sleep(3000);
mavlinkConnect.send2(sysId,compId,requestDataStream);
//启用 gps
RequestDataStream requestDataStream1 = RequestDataStream.builder()
.targetSystem(1)
.targetComponent(1)
.reqMessageRate(1)
.startStop(1)
.reqStreamId(6).build();
mavlinkConnect.send2(sysId,compId,requestDataStream1);
//启用GPS_STATUS
RequestDataStream requestDataStream2 = RequestDataStream.builder()
.targetSystem(1)
.targetComponent(1)
.reqMessageRate(1)
.startStop(1)
.reqStreamId(0).build();
mavlinkConnect.send2(sysId,compId,requestDataStream2);
//发送解锁
CommandLong commandLong = CommandLong.builder()
.targetSystem(1)
.targetComponent(1)
.command(MavCmd.MAV_CMD_COMPONENT_ARM_DISARM)
.confirmation(0)
.param1(1)
.param2(0).build();
mavlinkConnect.send2(sysId,compId,commandLong);
//调用消息监听
mavlinkExample.messageCallBack(mavlinkConnect);
}
}