기수 방향과 속도 변경

저작권: 쿼드(QUAD) 드론연구소 https://smartstore.naver.com/maponarooo

기수 방향(Yaw) 제어

기체의 기수 방향(Yaw)를 변경하기 위해서는 MAV_CMD_CONDITION_YAW 커맨드를 사용 합니다.

매개변수를 사용하면 대상 방향이 현재 요 방향에 대해 절대적인지 또는 상대적인지를 지정할 수 있습니다. 방향이 상대적인 경우 현재 방향에서 값을 더하거나 뺄 것인지 여부를 (별도로) 지정할 수도 있습니다(차량은 항상 param3 값에 관계없이 새 대상 방향으로 가장 빠르게 이동하는 방향으로 회전합니다).

명령 매개변수

명령 필드

미션 플래너 필드

설명

param1

If param4=0(절대): 대상 방향[0-360](0은 북쪽). If param4=1(상대적): 방향의 변화(각도).

param2

속도 deg/s

요 변경 중 속도:[deg per second].

param3

방향 1=CW

목표 각도를 달성하기 위한 회전 방향을 나타내는 데 사용됩니다(-1=CCW, 1=CW, 0=차량은 항상 새 목표 방향으로 가장 빠르게 도달하는 방향으로 회전하지만 (절대)인 경우에만, 그렇지 않은 경우에만 param4=0) 0 = CW).

param4

0=절대 1=상대

param1("Deg" 필드)가 절대 방향(0)인지 아니면 현재 요 방향(1)에 상대적인지 지정합니다 .

param5

사용 안함

param6

사용 안함

param7

사용 안함

실습

아래의 코드를 takeoff.py 에 추가하여 speed_yaw.py 파일로기저장한 후 실행하여 Yaw가 어떻게 움직이는지 관찰해 봅시다.

# MAV_CMD_CONDITION_YAW
the_connection.mav.command_long_send(the_connection.target_system, the_connection.target_component, 
                                     mavutil.mavlink.MAV_CMD_CONDITION_YAW, 90, 10, 1, 1, 0, 0, 0, 10)

# check response COMMAND_ACK
msg = the_connection.recv_match(type='COMMAND_ACK', blocking=True)
print(msg)

이륙과 동시에 기수 방향이 시계 방향으로 90도 회전하는걸 볼 수 있습니다.

다음은 비행중에 기체의 속도를 제어하는 방법에 대해 알아 보도록 하겠습니다.

속도(Velocity) 제어

드론의 이동 속도는 MAV_CMD_DO_CHANGE_SPEED 명령으로 변경 합니다.

원하는 최대 속도를 미터/초 단위로 설정합니다(전용). 속도 유형 및 스로틀 설정이 모두 무시됩니다.

명령 매개변수

명령 필드

미션 플래너 필드

설명

param1

속도 m/s

속도 유형(0,1=지면 속도, 2=상승 속도, 3=하강 속도).

param2

속도(m/s)

목표 속도(m/s).

param3

스로틀을 백분율(0-100%)로 트림합니다. -1 값은 변경 사항이 없음을 나타냅니다.

param4

비어 있는

param5

비어 있는

param6

비어 있는

param7

비어 있는

실습

아래의 코드를 speed_yaw.py 에 추가하여 기체의 속도가 어떻게 변경는되지 관찰해 봅시다.

# MAV_CMD_DO_CHANGE_SPEED
the_connection.mav.command_long_send(the_connection.target_system, the_connection.target_component, 
                                     mavutil.mavlink.MAV_CMD_DO_CHANGE_SPEED, 0, 0, 10, 0, 0, 0, 0, 0)

전체 프로그램 코드는 아래와 같습니다.

from pymavlink import mavutil
import time

# Start a connection listening on a UDP port
# UDP 14550 for primary GSC, 14551 is secondary mavlink port.
the_connection = mavutil.mavlink_connection('udpin:localhost:14551')

# 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))

# change MODE to GUIDED into COMMAND_LONG
the_connection.mav.command_long_send(the_connection.target_system, the_connection.target_component, 
                                     mavutil.mavlink.MAV_CMD_DO_SET_MODE, 0, 1, 
                                     4, 0, 0, 0, 0, 0)

# check response COMMAND_ACK
msg = the_connection.recv_match(type='COMMAND_ACK', blocking=True)
print(msg)

# 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)

# Takeoff COMMAND_LONG
the_connection.mav.command_long_send(the_connection.target_system, the_connection.target_component, 
                                     mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, 0, 0, 0, 0, 0, 0, 0, 10)

# check response COMMAND_ACK
msg = the_connection.recv_match(type='COMMAND_ACK', blocking=True)
print(msg)

# MAV_CMD_CONDITION_YAW
the_connection.mav.command_long_send(the_connection.target_system, the_connection.target_component, 
                                     mavutil.mavlink.MAV_CMD_CONDITION_YAW, 90, 10, 1, 1, 0, 0, 0, 10)

# check response COMMAND_ACK
msg = the_connection.recv_match(type='COMMAND_ACK', blocking=True)
print(msg)

# MAV_CMD_DO_CHANGE_SPEED
the_connection.mav.command_long_send(the_connection.target_system, the_connection.target_component, 
                                     mavutil.mavlink.MAV_CMD_DO_CHANGE_SPEED, 0, 0, 5, 0, 0, 0, 0, 0)

# check response COMMAND_ACK
msg = the_connection.recv_match(type='COMMAND_ACK', blocking=True)
print(msg)

QgroundControl 에서 "Go here" 명령으로 기체를 이동시켜 속도가 변경 되는지 확인해 봅시다.

Last updated