글은 다음 순서대로 설명한다.
- QGC에서 비행체 상태가 업데이트 되는 방식
- Mavlink 메시지를 보내는 장치의 전송 속도 자체를 높이는 방법
- 일시적으로 특정 Mavlink 메시지를 추가하거나 Stream rate를 조절하는 방법 (Mavlink Console @ QGC)
- 영구적으로 특정 Mavlink 메시지를 추가하거나 Stream rate를 조절하는 방법 (/etc/extras.txt @ MicroSD Card)
1. QGC에서 비행체 상태가 업데이트 되는 방식
QGC에서 일반적인 915MHz 텔레메트리로 데이터를 받으면 체감 상 아래처럼 상태가 업데이트 되는 것을 볼 수 있다.
- 자세는 10Hz
- 위치는 5Hz
- RC 조종기 포지션은 5Hz
이는 PX4 SW 내의 mavlink_main.cpp 에 사전 정의된 stream rate 에 따라서 데이터를 보내고 있는 것이다.
그리고 이는 MAV_X_MODE 라고 하는 파라미터의 값으로 확인할 수 있으며 이는 NORMAL 모드 일 때 이다.
Normal 모드는 아래와 같이 정의되어 있다.
참고로 ATTITUDE 가 자세 상태 메시지 이고
GLOBAL_POSITION_INT 가 지도 상 위치 메시지이다.
비행체와 텔레메트리와 연결해서 확인하면 다음과 같다. TELEM1에 NORMAL MODE으로 연결된 것을 확인할 수 있다.
SER_TEL1_BAUD 에서 TELEM1의 전송속도는 57600 bps 으로 연결되어 있으나, MAV_0_RATE 에서 전송속도를 1200 bps으로 제한하고 있음을 볼 수 있다. 그래서 업데이트 속도가 전체적으로 느리면 전송속도 제한 때문일 수 있으니, MAV_0_RATE을 조절하는 것도 방법이다.
다른 MAV_X_MODE 으로 CONFIG 모드가 존재하는데 이는 USB 또는 WiFi 등 네트워크에 연결되었을 때, 전송 속도가 훨씬 높으므로 높은 Stream Rate을 가진다.
따라서 정리하면 다음과 같다.
- PX4 코드 상, 하드 코딩으로 Mavlink 메시지 집합과 Stream Rate이 Mavlink 모드로 사전 정의되어 있다.
- Mavlink 모드는 PX4의 파라미터로 MAV_X_MODE에 대응되며, GCS에서 선택할 수 있다.
- 통신 매체에 따라서 전송 속도가 다르므로, 이에 맞추어 더 빠른 Stream Rate를 가진 MAV_X_MODE를 고를 수 있다.
- 사전 정의된 메시지 이외에도 사용자 임의로 메시지를 추가하거나 업데이트 속도를 조절할 수 있다.
2. Mavlink 메시지를 보내는 장치의 전송 속도 자체를 높이는 방법
앞선 설명에서 Mavlink 으로 보낼 메시지 집합과 업데이트 속도를 사전 정의해두었으나, 보낼 전송 장치에 제약으로 인해 메시지를 다 보내지 못할 수도 있다. 이때 MAV_X_RATE를 설정해서 바꿀 수 있다.
통신 장치의 전송속도 SER_TEL1_BAUD (Telemetry 915MHz는 57600 bps) 는 정해져 있으나, Mavlink 메시지를 어떤 속도로 보낼지가 MAV_X_RATE에 정의되어있다. 이를 최대로 해서 한계를 해소할 수도 있다. 0 으로 설정하면 통신 장치가 허용하는 최대 속도로 전송시킬 수 있다.
아래는 MAV_X_RATE을 Default(1200 bps) 값과 Maximum(2880 bps) 으로 설정한 결과를 볼 수 있다. 전송 속도가 최대로 올라갔음을 확인할 수 있다.
아래 업데이트 창은 QGC > Analyze Tools > Mavlink Inspector 에서 확인할 수 있다.
Tip. Mavlink으로 메시지를 주고 받는데, 이때 최대 전송량에 비해서 현재 어느정도 전송량을 사용하고 있는지 아래와 같이 확인 할 수 있다.
QGC > Analyze Tools > Mavlink Console으로 가서 아래의 명령어를 입력해서 확인하자.
mavlink status
천천히 설명하면 다음과 같다.
- MAV_X 의 인스턴스 번호가 0번임을 나타낸다.
- Pixhawk에서 텔레메트리를 통해서 메시지 전송에 사용하는 전송량이다.
- Pixhawk에서 텔레메트리의 최대 전송량을 나타낸다. 현재 전송량 보다 크다.
- MAV_X_MODE 가 Normal 임을 확인할 수 있다.
- 전송 장치와 포트 (Serial, /dev/ttyS1), 전송 장치의 전송 속도 (57600 bps)를 확인할 수 있다.
3. 일시적으로 특정 Mavlink 메시지를 추가하거나 Stream rate를 조절하는 방법
QGC에서 비행체에 콘솔 명령을 통해서 메시지를 추가하거나 Stream rate를 조절할 수 있다. 다만 Pixhawk를 재부팅하면 초기화된다.
QGC > Analyze Tools > Mavlink Console으로 가서 명령어를 입력할 수 있다.
Mavlink Console에서 다음의 명령을 입력할 수 있다.
>> Mavlink 메시지를 추가하거나 특정 메시지의 업데이트 속도 바꾸기
mavlink stream -r RATE_HZ -s MESSAGE_NAME -d PORT_NAME
>> Mavlink 메시지를 보내는 장치 상태 보기
mavlink status
>> Mavlink 로 보내고 있는 메시지 리스트 보기
mavlink status streams
>> Mavlink 앱 도움말 보기
mavlink -h
예시로 다음과 같이 ATTITUDE 메시지를 10 Hz 으로 장치 /dev/ttyS1를 선택하여 조절해볼 수 있다.
mavlink stream -r 10 -s ATTITUDE -d /dev/ttyS1
위 명령의 결과를 아래처럼 확인할 수 있다.
각각을 확인하는 방법은 다음과 같다.
>> Mavlink 로 보내고 있는 메시지 리스트 보기
어떤 메시지를 어떤 업데이트 속도로 보내는지 확인할 수 있다.
mavlink status streams
>> Mavlink 메시지를 보내는 장치 상태 보기
아래 명령어로 어떤 instance가 어떤 장치로 보내는지 확인할 수 있다. (/dev/ttyS1)
mavlink status
4. 영구적으로 특정 Mavlink 메시지를 추가하거나 Stream rate를 조절하는 방법 [2,3]
QGC에서 Mavlink Console 으로 세팅하는 것은 재부팅하면 초기화된다. 그렇다면 다른 방법으로, 시스템 시작 과정을 수정함으로써 이를 바꿔볼 수 있다. 달리 말하면 부팅할 때 메시지 수정하는 구문을 넣어두는 것이다. [2,3]
그 방법으로 Pixhawk에 장착된 MicroSD 카드에 부팅 옵션을 추가하는 것이다.
아래와 같이 해보자.
- MicroSD 카드에 etc 폴더를 만든다.
- etc 폴더에 extras.txt 파일을 만든다.
- extras.txt 파일에 3번에서 만들었던 명령처럼 명령어 리스트를 구성해서 아래처럼 입력한다.
mavlink start -d /dev/ttyS1 -b 57600
mavlink stream -d /dev/ttyS1 -s ATTITUDE -r 20
mavlink stream -d /dev/ttyS1 -s GLOBAL_POSITION_INT -r 10
usleep 100000
명령어 리스트를 해석하면 다음과 같다.
1. 텔레메트리를 연결한 포트인 /dev/ttyS1 에 전송속도 57600 bps 으로 세팅하고 mavlink 메시지 전송을 시작한다.
2. 텔레메트리 포트에 ATTITUDE 메시지를 20Hz으로 전송하기 시작한다. (자세 정보)
3. 텔레메트리 포트에 GLOBAL_POSITION_INT 메시지를 10Hz으로 전송하기 시작한다. (지도 상 위치 정보)
4. 100,000 us (0.1s) 동안 쉰다.
Tip. QGC에서 위의 extras.txt 파일 만들기
Mavlink Console에서 아래와 같이 명령어를 입력한다.
# 폴더 만들기
cd /fs/microsd/
mkdir etc
cd etc
# extras.txt 파일 만들기
echo "mavlink start -d /dev/ttyS1 -b 57600" > extras.txt
echo "mavlink stream -d /dev/ttyS1 -s ATTITUDE -r 20" >> extras.txt
echo "mavlink stream -d /dev/ttyS1 -s GLOBAL_POSITION_INT -r 10" >> extras.txt
echo "usleep 100000" >> extras.txt
# extras.txt 파일 확인하기
cat extras.txt
파일을 만든 후, 재부팅하면 아래와 같이 잘 적용되었음을 확인할 수 있다.
Reference
[1] https://discuss.px4.io/t/increase-stream-rate-of-highres-imu-message/4789
[2] PX4, "System Startup/Customizing the System Startup", https://docs.px4.io/main/en/concept/system_startup.html#customizing-the-system-startup
[3] https://discuss.px4.io/t/how-to-adjust-the-sample-rate-of-distance-sensor-rangefinder/30575/5
*** EOF ***
'UAV > PX4' 카테고리의 다른 글
PX4 Fixed-Wing 이륙 절차 정리 (0) | 2022.11.26 |
---|---|
[작성중] PX4 Mixer 설정을 이용하여 짐벌 제어하기 (0) | 2021.06.08 |
[PX4] ROS + AirSim with CV - 참고 (0) | 2020.12.07 |