无人机电机库(Copter Motors Library)(6)
无人机电机库(Copter Motors Library)(6)
This page covers the basics of the Copter motors library
As a reference the diagram below provides a high level view of Copter’s architecture. The motors library can be seen near the bottom right just above the “Hardware Abstraction Layer”
ArduPilot supports over 22 different multicopter frames. The Motors library is designed to consolidate the majority of the differences in these frame types from the
higher level code including the attitude controllers and vehicle specific code. In other words the library provides a common interface so that all
vehicles can be controlled in the same way without special handling being required in higher level code.
The image below shows a categorisation of these frames which is consistent with the class structure
-
Multicopter Matrix : vehicles with mostly downward facing propellers and no servos. These are the most commonly used frames and the code can be found in the AP_MotorsMatrix class
-
Multicopter Tri and Single: vehicles with a combination of motors and servos. These are peers of each other and Multicopter Matrix and can be found in the AP_MotorsTri and AP_MotorsSingle classes
-
Helicopter Single, Quad: vehicles with swashplates that can provide reverse thrust. These are peers of each other and children of the AP_MotorsHeli class.
Below is a diagram of the Motors library’s class hierarchy
Inputs to the Motors Library
The Attitude Controller provides high level roll, pitch, yaw and throttle commands to the Motors library in the range of -1 to +1 (for roll, pitch and yaw) or 0 to +1 (for throttle). The exact point where the attitude controller issues these commands can be found in AC_AttitudeControl_Multi’s rate_controller_run() method
void AC_AttitudeControl_Multi::rate_controller_run() { Vector3f gyro_latest = _ahrs.get_gyro_latest(); _motors.set_roll(rate_target_to_motor_roll(gyro_latest.x, _rate_target_ang_vel.x)); _motors.set_pitch(rate_target_to_motor_pitch(gyro_latest.y, _rate_target_ang_vel.y)); _motors.set_yaw(rate_target_to_motor_yaw(gyro_latest.z, _rate_target_ang_vel.z));
and the definitions of the methods used can be seen in AP_Motors_Class.h
// set_roll, set_pitch, set_yaw, set_throttle void set_roll(float roll_in) { _roll_in = roll_in; }; // range -1 ~ +1 void set_pitch(float pitch_in) { _pitch_in = pitch_in; }; // range -1 ~ +1 void set_yaw(float yaw_in) { _yaw_in = yaw_in; }; // range -1 ~ +1 void set_throttle(float throttle_in) { _throttle_in = throttle_in; }; // range 0 ~ 1
Outputs and Responsibilities
All motors libraries must do two things:
-
Convert the high level inputs from the attitude controller to individual motor and servo outputs
Roll input of +1.0 should cause motor and servo outputs that provide maximum roll rotation to the right
Pitch input of +1.0 should result in maximum pitch back
Yaw input of +1.0 should result in maximum yaw in the clockwise direction
Throttle input of +1.0 should result in maximum acceleration upwards (in the vehicle’s body frame). Throttle of zero should result in minimum acceleration upwards (or maximum acceleration downwards in the case of helicopters)
-
Set the limit flags to avoid “I-term build-up” in the attitude and throttle controllers. Although a vehicle will be flyable without setting these flags, they are important for protecting against overshoot in lean angle control and also for automatic landing detection. The limits are held in the AP_Motors_Class::limit variable.
// structure for holding motor limit flags struct AP_Motors_limit { uint8_t roll_pitch : 1; // we have reached roll or pitch limit uint8_t yaw : 1; // we have reached yaw limit uint8_t throttle_lower : 1; // we have reached throttle's lower limit uint8_t throttle_upper : 1; // we have reached throttle's upper limit } limit;