mavlink-router를 이용하면 serial, udp, tcp endpoint로 데이터를 보내거나 받을 수 있다.
이 기능이 지금 나에게는 굉장히 도움이 되는데, 간단하게 어떻게 사용하는지 미래의 나를 위해 기록해두겠다!
아래 github 주소에 들어가서 git clone 해온 후에 meson으로 build하면 mavlink-router를 실행할 수 있다.
https://github.com/mavlink-router/mavlink-router
cd ~/mavlink-router
mavlink-routerd -c ~~.conf
mavlink-routerd -c 커맨드를 사용하면 미리 저장해놓은 .conf 파일을 실행할 수 있다.
다시 말해, config file에는 보내거나 받고 싶은 udp, tcp, serial 주소와 포트를 프리셋해놓을 수 있다.
위에서 말한 것처럼 한번에 여러 디바이스에 데이터를 뿌리고 싶으면 config file을 미리 만들어서 실행하는 것이 더 편리하다!(훨 씬!)
config file은 mavlink-router github에 example이 올라와 있으니 잘 확인해서 원하는 형식으로 작성하면 된다.
#test.conf
[UartEndpoint UAVTelemetry]
Device = /dev/ttyUSB0
Baud = 921600
[UdpEndpoint localDesktop]
Mode = Normal
Address = 127.0.0.1
Port = 14541 # 예시
위의 [UartEndpoint UAVTelemetry]는 GCS에 연결되어 있는 텔레메트리이고, 이 텔레메트리는 이미 드론에 연결되어있는 텔레메트리와 연결되어 있다.
아래의 [UdpEndpoint localDesktop]은 GCS 자체에서 UDP로 받을 내용이다.
만약 Address가 127.0.0.1이 아닌 고정 IP 혹은 유동 IP(GCS 데탑과 같은 인터넷 망에 잡혀있을 때만 가능)를 적어주고, Port만 맞춰주면 된다.
그니까 같은 와이파이에 잡혀있는 2대의 컴이 있다고 가정해보자.
컴1은 QGC가 돌아가고 있고, 텔레메트리가 연결되어있으면 이 컴에서 mavlink-router를 실행하면 되고, 이 컴1 자체에서 udp로 받을때는 127.0.0.1로 설정해주고, port를 14541로 설정했다면 ~~.conf에는 위의 test.conf의 [UdpEndpoint localDesktop] 부분과 동일하게 작성하면 된다.
컴2에서는 mavlink-router로 보낸 데이터를 받기 위해서는 test.conf 파일에 아래와 같이 추가해주면 된다.
[UdpEndpoint localDesktop2]
Mode = Normal
Address = 192.168.111.222 # 예시
Port = 14542 # 예시
mavlink-router로 데이터를 보내면 어떻게 받아서 사용할지 생각해야한다.
나는 pymavlink의 mavutil을 이용해서 받아온다.
일단 코드를 먼저 보자!
from time import sleep
from pymavlink import mavutil
the_connection = mavutil.mavlink_connection('udpin:127.0.0.1:14541')
print("code start")
the_connection.wait_heartbeat()
print("Heartbeat from system (system %u component %u)" % (the_connection.target_system, the_connection.target_component))
print(type(the_connection.target_system))
while True:
msg = the_connection.recv_match(type='ATTITUDE', blocking=True)
print("Heartbeat from system (system %u component %u)" % (the_connection.target_system, the_connection.target_component))
print(the_connection.target_system)
print(msg)
the_connection = mavutil.mavlink_connection('udpin:127.0.0.1:14541') 이 부분에서 udpin으로 localhost에 14542 포트를 이용하여 데이터를 전송하겠다는 것을 알 수 있다.
udpin, udpout, udp 등이 있는데, 이 부분은 더 알아봐야할 것 같다.
만약 컴2로 받고 싶으면 the_connection = mavutil.mavlink_connection('udpin:192.168.111.222:14542') 로 변경해주어 컴2에서 실행해주면 된다.
while문 안은 ATTITUDE type을 가지는 메시지를 파싱해와서 print하는 것을 알 수 있다.
그래서 꼭 ATTITUDE type이 아니더라도 다른 type을 가지는 메시지를 파싱해올 수 있다.
다른 type 메시지는 아래 링크에서 확인할 수 있다.
https://mavlink.io/en/messages/common.html
캡처하는 시간 차이가 있어서 사진에는 다른 데이터가 들어오는 것 처럼 보이지만, 동일한 시간에 동일한 데이터가 받아와진다.
드론의 roll, pitch, yaw가 바뀔때마다(내가 잡고 돌리면) 데이터가 동일하게 들어와지는 것을 확인했다.
SITL에서 받을 때는 확실히 빠른데, 실제 드론과 연결했을 때는 비교적 느리게 들어온다.
실외에서 GPS가 연결되면 데이터가 들어오는 속도가 더 빨라지지 않을까? 확인해봐야겠다!
안녕하세요~
ROS2, Pixhawk를 이용해서 offboard비행을 해보려하는데요,
SBC에서 랩탑 QGC로 mavlink_router를 통해서 보내는 것이 가능할까요/?