드론에 시동걸기(MAV_CMD_COMPONENT_ARM_DISARM)
저작권: 쿼드(QUAD) 드론연구소 https://smartstore.naver.com/maponarooo
개요
MAVLINK를 통해 드론에 명령을 내릴때는 COMMAND_LONG 메시지에 MAV_CMD 값을 사용하여 MAVLINK 커멘드를 전달합니다.
MAV_CMD에는 이미 정의된 여러개의 명령 메시지들이 정의되어 있으며 COMMAND_LONG 메시지에 7개파라메터에 정확한 전문의 값을 채워 전달 합니다.
MAV_CMD에 대한 목록은 아래 링크를 참고 하세요.
이번 시간에는 드론에 시동을 걸고 끄는 MAV_CMD(MAV_CMD_COMPONENT_ARM_DISARM)를 알아 보고 실습을 통해 드론에 시동을 걸고 꺼 보도록 하겠습니다.
MAV_CMD_COMPONENT_ARM_DISARM (400 )
[Command] Arms / Disarms a component
1: Arm
0: disarm, 1: arm
min:0 max:1 increment:1
2: Force
0: arm-disarm unless prevented by safety checks (i.e. when landed), 21196: force arming/disarming (e.g. allow arming to override preflight checks and disarming in flight)
min:0 max:21196 increment:21196
실습
전시간에 작성한 프로그램에 덧붙여 새로운 arm.py 코드를 작성해 봅시다.
from pymavlink import mavutil
# Start a connection listening on a UDP port
# UDP 14550 for primary GSC
#the_connection = mavutil.mavlink_connection('udpin:localhost:14550')
#for ArduPilot
#the_connection = mavutil.mavlink_connection('tcp:localhost:5763')
#for PX4-SITL
the_connection = mavutil.mavlink_connection('udp:localhost:14540')
# Wait for the first heartbeat
# This sets the system and component ID of remote system for the link
the_connection.wait_heartbeat()
print("Heartbeat from system (system %u component %u)" % (the_connection.target_system, the_connection.target_component))
# Arming COMMAND_LONG
the_connection.mav.command_long_send(the_connection.target_system, the_connection.target_component,
mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM, 0, 1, 0, 0, 0, 0, 0, 0)
# check response COMMAND_ACK
msg = the_connection.recv_match(type='COMMAND_ACK', blocking=True)
print(msg)
결과는 다음과 같습니다.
COMMAND_ACK 메시지를 통해 MAV_CMD 명령이 정상적으로 수행 되었는지 확인할 수 있습니다.
$ python3 arm.py
Heartbeat from system (system 1 component 0)
COMMAND_ACK {command : 400, result : 0, progress : 0, result_param2 : 0, target_system : 255, target_component : 0}

Last updated