이동하기(SET_POSITION_TARGET_GLOBAL_INT)

저작권: 쿼드(QUAD) 드론연구소 https://www.youtube.com/@quad-robotics

SET_POSITION_TARGET_GLOBAL_INT

SET_POSITION_TARGET_GLOBAL_INT 명령은 드론의목표 위치(WGS84 좌표), 속도, 방향 또는 선회율을 설정합니다. 이는 위치가 위도 및 경도 값으로 제공되고 고도가 집 또는 지형에 상대적인 해수면보다 높을 수 있다는 점을 제외하면 SET_POSITION_TARGET_LOCAL_NED 메시지와 유사합니다.

메시지 정의는 여기에서 찾을 수 있습니다.

명령 매개변수

명령 필드

설명

time_boot_ms

부팅 이후 보낸 사람의 시스템 시간(밀리초)

target_system

차량의 시스템 ID

target_component

비행 컨트롤러의 구성 요소 ID 또는 0

coordinate_frame

유효한 옵션은 다음과 같습니다.

type_mask

차량에서 무시 해야 하는 필드를 나타내는 비트 마스크 (POSITION_TARGET_TYPEMASK 열거형 참조)

bit1:PosX, bit2:PosY, bit3:PosZ, bit4:VelX, bit5:VelY, bit6:VelZ, bit7:AccX, bit8:AccY, bit9:AccZ, bit11:yaw, bit12:yaw 비율

Pos, Vel 및/또는 Accel을 제공할 때 3축을 모두 제공해야 합니다. Pos, Vel 및 Accel 중 하나 이상을 제공해야 합니다(예: Yaw 또는 YawRate만 제공하는 것은 지원되지 않음).

  • 위치 : 0b110111111000 / 0x0DF8 / 3576(십진수)

  • 속도 : 0b110111000111 / 0x0DC7 / 3527(십진수)

  • 가속 사용 : 0b110000111000 / 0x0C38 / 3128 (십진수)

  • Pos+Vel 사용 : 0b110111000000 / 0x0DC0 / 3520(십진수)

  • Pos+Vel+Accel 사용 : 0b110000000000 / 0x0C00 / 3072(십진수)

  • 요 사용 : 0b100111111111 / 0x09FF / 2559(십진수)

  • 요레이트 사용 : 0b010111111111 / 0x05FF / 1535(십진수)

lat_int

위도 * 1e7

lon_int

경도 * 1e7

alt

해발 고도, 집 또는 지형(coordinate_frame 필드 참조)

vx

X 속도(m/s)(양수는 북쪽)

vy

Y 속도(m/s)(양수는 동쪽)

vz

Z 속도(m/s)(양수는 아래)

afx

X 가속도(m/s/s)(양수는 북쪽)

afy

Y 가속도(m/s/s)(양수는 동쪽)

afz

Z 가속도(m/s/s)(양수는 Down)

yaw

yaw 또는 라디안 방향(0은 전방)

yaw_rate

요레이트(rad/s)

메모

속도나 가속도 명령을 보내면 1초마다 다시 보내야 함(명령을 받지 않으면 3초 후 차량 정지)

다음은 이 명령을 테스트하기 위해 MAVProxy(일명 SITL)에 복사하여 붙여넣을 수 있는 몇 가지 예제 명령입니다. 이 명령을 실행하기 전에 다음을 실행 하십시오.

  • module load message

  • GUIDED 모드 변경

  • 암 스로틀

  • 이륙 10m

MAVProxy/SITL 명령의 예

설명

message SET_POSITION_TARGET_GLOBAL_INT 0 0 0 6 3576 -35.3621474 149.1651746 10 0 0 0 0 0 0 0 0

-35.36,149.16의 위도, 경도 및 집 위 10m까지 비행

message SET_POSITION_TARGET_GLOBAL_INT 0 0 0 5 3576 -35.3621474 149.1651746 600 0 0 0 0 0 0 0 0

-35.36,149.16의 위도, 경도 및 해발 600m까지 비행

message SET_POSITION_TARGET_GLOBAL_INT 0 0 0 11 3576 -35.3621474 149.1651746 10 0 0 0 0 0 0 0 0

-35.36,149.16의 위도, 경도 및 지형 위 10m까지 비행

message SET_POSITION_TARGET_GLOBAL_INT 0 0 0 6 3527 0 0 0 1 0 0 0 0 0 0 0

북쪽으로 1m/s로 비행

message SET_POSITION_TARGET_GLOBAL_INT 0 0 0 6 3135 0 0 0 0 0 0 1 0 0 0 0

북쪽으로 1m/s로 가속

message SET_POSITION_TARGET_GLOBAL_INT 0 0 0 6 2503 0 0 0 0 0 0 0 0 0 0.7854 0

북동쪽으로 회전(Yaw 대상 + 속도 0)

message SET_POSITION_TARGET_GLOBAL_INT 0 0 0 6 1479 0 0 0 0 0 0 0 0 0 0 0.174

시계 방향으로 10deg/sec로 회전(속도 0)

실습

이번에는 SET_POSITION_TARGET_GLOBAL_INT 명령을 사용하여 기체를 이동해 보겠습니다.

위도 30도, 경도 30도 위치로기체를 이동 시킵니다.

다음 코드를 movement.py 끝에 붙여 넣습니다.

# set_position_target_global_int - move to lat 30, long 30, alt 20m
the_connection.mav.send(mavutil.mavlink.MAVLink_set_position_target_global_int_message(10, the_connection.target_system, 
                        the_connection.target_component, mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT, 
                        int(0b110111111000), 30, 30, -20, 0,0,0,0,0,0,0,0))

# check response NAV_CONTROLLER_OUTPUT
while 1:
    msg = the_connection.recv_match(type='NAV_CONTROLLER_OUTPUT', blocking=True)
    print(msg)

# # check response NAV_CONTROLLER_OUTPUT
# while 1:
#     msg = the_connection.recv_match(type='LOCAL_POSITION_NED', blocking=True)
#     print(msg)

결과는 다음과 같습니다.