비행 작업
Flight Tasks are used within Flight Modes to provide specific movement behaviours: e.g. follow me, or flight smoothing.
개요
비행 작업은 기본 클래스 FlightTask에서 파생된 비행 작업 프레임워크의 클래스입니다. 목표는 각 작업이 특정 모드의 기체 동작을 구현하는 임의의 입력 데이터에서 콘트롤러에 대한 설정값을 생성하는 것입니다. 프로그래머는 일반적으로 기본 작업의 최소 구현을 호출하고 원하는 동작의 구현으로 확장하여 activate()
및 update()
가상 메서드를 재정의합니다. activate()
메서드는 작업 전환시에 호출되며, 상태를 초기화하고 이전 작업이 방금 적용한 전달된 설정점에서 부드럽게 인계되도록 합니다.
update()
는 실행 중 모든 루프 반복에서 호출되며, 설정값을 생성하는 핵심 기능을 구현합니다.
규칙에 따라 작업은 작업 이름을 따서 명명된 PX4-Autopilot/src/modules/flight_mode_manager/tasks의 하위 폴더에 포함되며, 소스 파일에는 접두사 "FlightTask"로 이름이 지정됩니다.
:::note PX4 개발자 회의의 비디오 개요는 아래에서 제공합니다. :::
비행 작업 생성
The instructions below might be used to create a task named MyTask:
PX4-Autopilot/src/modules/flight_mode_manager/tasks에 새 비행 작업에 대한 디렉터리를 생성합니다. 규칙에 따라 디렉토리 이름은 작업 이름을 따서 지정되므로 /MyTask라고 합니다.
shmkdir PX4-Autopilot/src/lib/flight_tasks/tasks/MyTask
Create empty source code and cmake files for the new flight task in the MyTask directory using the prefix "FlightTask":
- CMakeLists.txt
- FlightTaskMyTask.hpp
- FlightTaskMyTask.cpp
Update CMakeLists.txt for the new task
Copy the contents of the CMakeLists.txt for another task - e.g. Orbit/CMakeLists.txt
Update the copyright to the current year
cmake############################################################################ # # Copyright (c) 2021 PX4 Development Team. All rights reserved. #
Modify the code to reflect the new task - e.g. replace
FlightTaskOrbit
withFlightTaskMyTask
. The code will look something like this:cmakepx4_add_library(FlightTaskMyTask FlightTaskMyTask.cpp ) target_link_libraries(FlightTaskMyTask PUBLIC FlightTask) target_include_directories(FlightTaskMyTask PUBLIC ${CMAKE_CURRENT_SOURCE_DIR})
헤더 파일 업데이트(이 경우 FlightTaskMyTask.hpp): 대부분의 작업은 가상 메서드
activate()
및update()
를 다시 구현하며, 이 예에서는 개인 변수도 있습니다.cpp#pragma once #include "FlightTask.hpp" class FlightTaskMyTask : public FlightTask { public: FlightTaskMyTask() = default; virtual ~FlightTaskMyTask() = default; bool update(); bool activate(const trajectory_setpoint_s &last_setpoint) override; private: float _origin_z{0.f}; };
cpp 파일을 적절하게 업데이트 합니다. 이 예는 단순히 작업 메서드가 호출되었음을 나타내는 FlightTaskMyTask.cpp의 간단한 구현을 제공합니다.
cpp#include "FlightTaskMyTask.hpp" bool FlightTaskMyTask::activate(const trajectory_setpoint_s &last_setpoint) { bool ret = FlightTask::activate(last_setpoint); PX4_INFO("FlightTaskMyTask activate was called! ret: %d", ret); // report if activation was successful return ret; } bool FlightTaskMyTask::update() { PX4_INFO("FlightTaskMyTask update was called!"); // report update return true; }
Add the new task to the list of tasks to be built in PX4-Autopilot/src/modules/flight_mode_manager/CMakeLists.txt.
cmake... list(APPEND flight_tasks_all Auto Descend ... ManualPositionSmoothVel Transition MyTask ) ...
TIP
The task added above will be built on all boards, including those with constrained flash such as Pixhawk FMUv2. If your task is not indended for use on boards with constrained flash it should instead be added to the conditional block shown below (as shown).
cmake... if(NOT px4_constrained_flash_build) list(APPEND flight_tasks_all AutoFollowTarget Orbit MyTask ) endif() ...
:::
작업이 호출되도록 비행 모드를 업데이트합니다. 일반적으로, 매개변수는 특정 비행 작업을 사용해야 하는 시기를 선택합니다.
예를 들어, 멀티콥터 위치 모드에서 새로운
MyTask
를 활성화하려면:Update
MPC_POS_MODE
(multicopter_position_mode_params.c) to add an option for selecting "MyTask" if the parameter has a previously unused value like 5:c... * @value 0 Direct velocity * @value 3 Smoothed velocity * @value 4 Acceleration based * @value 5 My task * @group Multicopter Position Control */ PARAM_DEFINE_INT32(MPC_POS_MODE, 5);
_param_mpc_pos_mode
에 올바른 값이 있을 때 작업을 활성화하려면 FlightModeManager.cpp 매개변수의 스위치에 새 옵션에 대한 사례를 추가하십시오.cpp... // manual position control ... switch (_param_mpc_pos_mode.get()) { ... case 3: error = switchTask(FlightTaskIndex::ManualPositionSmoothVel); break; case 5: // Add case for new task: MyTask error = switchTask(FlightTaskIndex::MyTask); break; case 4: .... ...
신규 비행 작업 테스트
비행 작업을 테스트하려면, 작업이 활성화된 상태에서 기체를 실행하여야 합니다. For the example above, this means setting the parameter MPC_POS_MODE
to 5, taking off, and switching the vehicle to Position mode.
:::note 위에 정의된 작업은 시뮬레이터에서만 테스트하여야 합니다. 코드는 실제로 설정값을 생성하지 않으므로 기체는 비행하지 않습니다. :::
Build SITL simulation (gazebo-classic)
sh
make px4_sitl gazebo-classic
Open QGroundControl (if not open, no message information will be printed out). In the console, takeoff and switch to Position mode:
sh
pxh> commander takeoff
pxh> commander mode posctl
The console will continuously display: INFO [FlightTaskMyTask] FlightTaskMyTask update was called!
. If you want to change to another flight mode, you can type a command to change the mode, such as commander mode altctl
.
비디오
다음 비디오는 PX4의 비행 작업에 대한 개요를 제공합니다. 첫 번째는 PX4 v1.9의 비행 작업 프레임워크 상태를 다룹니다. 두 번째는 PX4 v1.11의 변경 사항을 다루는 업데이트입니다.
PX4 Flight Task Architecture 개요(PX4 개발자 회의 2019)
PX4 v1.9의 비행 모드 작동 방식 설명(Dennis Mannhart, Matthias Grob).
센서에서 모터에 이르는 멀티콥터 제어 개요(PX4 가상 개발자 회의 2020)
The relevant section of this video is an update of flight tasks in PX4 v11.1 at (9min 20sec). 슬라이드는 이 PDF을 참고하십시오. - 슬라이드 9와 12가 관련이 있습니다.