模块参考:控制器 
fw_att_control 
Source: modules/airship_att_control
描述 
This implements the airship attitude and rate controller. 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.
参数描述 
To reduce control latency, the module directly polls on the gyro topic published by the IMU driver.
实现 
airship_att_control <command> [arguments...]
 wind_estimator <command> [arguments...]
 Commands:
   start
   stop
   status        打印状态信息control_allocator 
Source: modules/control_allocator
描述 
This implements control allocation. It takes torque and thrust setpoints as inputs and outputs actuator setpoint messages.
描述 
control_allocator <command> [arguments...]
 Commands:
   start
   stop
   status        print status infodifferential_drive 
Source: modules/differential_drive
参数描述 
Rover Differential Drive controller.
用法 
differential_drive <command> [arguments...]
 Commands:
   start
   stop
   status        print status infofw_pos_control_l1 
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.
用法 
fw_pos_control_l1 <command> [arguments...]
 Commands:
   start
   stop
   status        打印状态信息
 Commands:
   start
   stop
   status        print status infomc_att_control 
Source: modules/fw_att_control
描述 
fw_att_control is the fixed wing attitude controller.
用法 
fw_att_control <command> [arguments...]
 Commands:
   start
     [vtol]      VTOL mode
   stop
   status        print status infofw_pos_control 
Source: modules/fw_pos_control
参数描述 
fw_pos_control is the fixed-wing position controller.
用法 
fw_pos_control <command> [arguments...]
 Commands:
   start
     [vtol]      VTOL mode
   stop
   status        print status infofw_rate_control 
Source: modules/fw_rate_control
参数描述 
fw_rate_control is the fixed-wing rate controller.
实现 
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
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.
https://www.research-collection.ethz.ch/bitstream/handle/20.500.11850/154099/eth-7387-01.pdf
参数描述 
mc_att_control <command> [arguments...]
 navigator <command> [arguments...]
 Commands:
   start
   fencefile     load a geofence file from SD card, stored at etc/geofence.txt
   fake_traffic  publishes 3 fake transponder_report_s uORB messages
   stop
   status        print status infonavigator 
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.
用法 
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.
用法 
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
Description 
Rover state machine.
Usage 
rover_ackermann <command> [arguments...]
 Commands:
   start
   stop
   status        print status inforover_pos_control 
Source: modules/rover_pos_control
Description 
Controls the position of a ground rover using an L1 controller.
Publishes vehicle_thrust_setpoint (only in x) and vehicle_torque_setpoint (only yaw) messages at IMU_GYRO_RATEMAX.
实现 
Currently, this implementation supports only a few modes:
- Full manual: Throttle and yaw controls are passed directly through to the actuators
 - Auto mission: The rover runs missions
 - Loiter: The rover will navigate to within the loiter radius, then stop the motors
 
示例 
CLI usage example:
rover_pos_control start
rover_pos_control status
rover_pos_control stopUsage 
rover_pos_control <command> [arguments...]
 Commands:
   start
   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
 
Examples 
CLI usage example:
uuv_att_control start
uuv_att_control status
uuv_att_control stop实现 
uuv_att_control <command> [arguments...]
 Commands:
   start
   stop
   status        print status infouuv_pos_control 
Source: modules/uuv_pos_control
Description 
Controls the attitude of an unmanned underwater vehicle (UUV). Publishes attitude_setpoint messages.
Implementation 
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
 
Examples 
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
Description 
fw_att_control is the fixed wing attitude controller.
Usage 
vtol_att_control <command> [arguments...]
 Commands:
   stop
   status        print status info