모듈 참조: 콘트롤러 
airship_att_control 
Source: modules/airship_att_control
설명 
이것은 비행선 자세 및 속도 컨트롤러를 구현합니다. Ideally it would take attitude setpoints (vehicle_attitude_setpoint) or rate setpoints (in acro mode via manual_control_setpoint topic) as inputs and outputs actuator control messages.
Currently it is feeding the manual_control_setpoint topic directly to the actuators.
구현 
제어 대기 시간을 줄이기 위하여, 모듈은 IMU 드라이버에서 게시한 자이로 주제를 직접 폴링합니다.
Usage 
airship_att_control <command> [arguments...]
 Commands:
   start
   stop
   status        print status infocontrol_allocator 
Source: modules/control_allocator
설명 
This implements control allocation. It takes torque and thrust setpoints as inputs and outputs actuator setpoint messages.
Usage 
control_allocator <command> [arguments...]
 Commands:
   start
   stop
   status        print status infoflight_mode_manager 
Source: modules/flight_mode_manager
설명 
This implements the setpoint generation for all modes. It takes the current mode state of the vehicle as input and outputs setpoints for controllers.
Usage 
flight_mode_manager <command> [arguments...]
 Commands:
   start
   stop
   status        print status infofw_att_control 
Source: modules/fw_att_control
설명 
fw_att_control is the fixed wing attitude controller.
Usage 
fw_att_control <command> [arguments...]
 Commands:
   start
     [vtol]      VTOL mode
   stop
   status        print status infofw_lat_lon_control 
Source: modules/fw_lateral_longitudinal_control
설명 
fw_lat_lon_control computes attitude and throttle setpoints from lateral and longitudinal control setpoints.
Usage 
fw_lat_lon_control <command> [arguments...]
 Commands:
   start
     [vtol]      VTOL mode
   stop
   status        print status infofw_mode_manager 
Source: modules/fw_mode_manager
설명 
This implements the setpoint generation for all PX4-internal fixed-wing modes, height-rate control and higher. It takes the current mode state of the vehicle as input and outputs setpoints consumed by the fixed-wing lateral-longitudinal controller and and controllers below that (attitude, rate).
Usage 
fw_mode_manager <command> [arguments...]
 Commands:
   start
   stop
   status        print status infofw_rate_control 
Source: modules/fw_rate_control
설명 
fw_rate_control is the fixed-wing rate controller.
Usage 
fw_rate_control <command> [arguments...]
 Commands:
   start
     [vtol]      VTOL mode
   stop
   status        print status infomc_att_control 
Source: modules/mc_att_control
설명 
This implements the multicopter attitude controller. It takes attitude setpoints (vehicle_attitude_setpoint) as inputs and outputs a rate setpoint.
The controller has a P loop for angular error
Publication documenting the implemented Quaternion Attitude Control: Nonlinear Quadrocopter Attitude Control (2013) by Dario Brescianini, Markus Hehn and Raffaello D'Andrea Institute for Dynamic Systems and Control (IDSC), ETH Zurich
https://www.research-collection.ethz.ch/bitstream/handle/20.500.11850/154099/eth-7387-01.pdf
Usage 
mc_att_control <command> [arguments...]
 Commands:
   start
     [vtol]      VTOL mode
   stop
   status        print status infomc_nn_control 
Source: modules/mc_nn_control
설명 
Multicopter Neural Network Control module. This module is an end-to-end neural network control system for multicopters. It takes in 15 input values and outputs 4 control actions. Inputs: [pos_err(3), att(6), vel(3), ang_vel(3)] Outputs: [Actuator motors(4)]
Usage 
mc_nn_control <command> [arguments...]
 Commands:
   start
   stop
   status        print status infomc_pos_control 
Source: modules/mc_pos_control
설명 
The controller has two loops: a P loop for position error and a PID loop for velocity error. Output of the velocity controller is thrust vector that is split to thrust direction (i.e. rotation matrix for multicopter orientation) and thrust scalar (i.e. multicopter thrust itself).
The controller doesn't use Euler angles for its work, they are generated only for more human-friendly control and logging.
Usage 
mc_pos_control <command> [arguments...]
 Commands:
   start
     [vtol]      VTOL mode
   stop
   status        print status infomc_rate_control 
Source: modules/mc_rate_control
설명 
This implements the multicopter rate controller. It takes rate setpoints (in acro mode via manual_control_setpoint topic) as inputs and outputs actuator control messages.
The controller has a PID loop for angular rate error.
Usage 
mc_rate_control <command> [arguments...]
 Commands:
   start
     [vtol]      VTOL mode
   stop
   status        print status infonavigator 
Source: modules/navigator
설명 
Module that is responsible for autonomous flight modes. This includes missions (read from dataman), takeoff and RTL. It is also responsible for geofence violation checking.
구현 
The different internal modes are implemented as separate classes that inherit from a common base class NavigatorMode. The member _navigation_mode contains the current active mode.
Navigator publishes position setpoint triplets (position_setpoint_triplet_s), which are then used by the position controller.
Usage 
navigator <command> [arguments...]
 Commands:
   start
   fencefile     load a geofence file from SD card, stored at etc/geofence.txt
   fake_traffic  publishes 24 fake transponder_report_s uORB messages
   stop
   status        print status inforover_ackermann 
Source: modules/rover_ackermann
설명 
Rover ackermann module.
Usage 
rover_ackermann <command> [arguments...]
 Commands:
   start
   stop
   status        print status inforover_differential 
Source: modules/rover_differential
설명 
Rover differential module.
Usage 
rover_differential <command> [arguments...]
 Commands:
   start
   stop
   status        print status inforover_mecanum 
Source: modules/rover_mecanum
설명 
Rover mecanum module.
Usage 
rover_mecanum <command> [arguments...]
 Commands:
   start
   stop
   status        print status infospacecraft 
Source: modules/spacecraft
### Description
This implements control allocation for spacecraft vehicles.
It takes torque and thrust setpoints as inputs and outputs
actuator setpoint messages.Usage 
spacecraft <command> [arguments...]
 Commands:
   start
   status
   stop
   status        print status infouuv_att_control 
Source: modules/uuv_att_control
설명 
Controls the attitude of an unmanned underwater vehicle (UUV).
Publishes vehicle_thrust_setpont and vehicle_torque_setpoint messages at a constant 250Hz.
구현 
Currently, this implementation supports only a few modes:
- Full manual: Roll, pitch, yaw, and throttle controls are passed directly through to the actuators
- Auto mission: The uuv runs missions
예 
CLI usage example:
uuv_att_control start
uuv_att_control status
uuv_att_control stopUsage 
uuv_att_control <command> [arguments...]
 Commands:
   start
   stop
   status        print status infouuv_pos_control 
Source: modules/uuv_pos_control
설명 
Controls the attitude of an unmanned underwater vehicle (UUV). Publishes attitude_setpoint messages.
구현 
Currently, this implementation supports only a few modes:
- Full manual: Roll, pitch, yaw, and throttle controls are passed directly through to the actuators
- Auto mission: The uuv runs missions
예 
CLI usage example:
uuv_pos_control start
uuv_pos_control status
uuv_pos_control stopUsage 
uuv_pos_control <command> [arguments...]
 Commands:
   start
   stop
   status        print status infovtol_att_control 
Source: modules/vtol_att_control
설명 
fw_att_control is the fixed wing attitude controller.
Usage 
vtol_att_control <command> [arguments...]
 Commands:
   stop
   status        print status info