mirror of https://github.com/ArduPilot/ardupilot
Copter: added comments to include libraries in copter.h and attitude.cpp
fixed typo in a comment and added more comments for included libraries in copter.h and fixed a comment in attitude.cpp
This commit is contained in:
parent
a7f31929ea
commit
4a39424d6b
|
@ -8,7 +8,7 @@
|
|||
// called at 100hz
|
||||
void Copter::update_throttle_hover()
|
||||
{
|
||||
// if not armed or landed exit
|
||||
// if not armed or landed or on standby then exit
|
||||
if (!motors->armed() || ap.land_complete || standby_active) {
|
||||
return;
|
||||
}
|
||||
|
|
|
@ -28,46 +28,46 @@
|
|||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
// Common dependencies
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_Common/Location.h>
|
||||
#include <AP_Param/AP_Param.h>
|
||||
#include <StorageManager/StorageManager.h>
|
||||
#include <AP_Common/AP_Common.h> // Common definitions and utility routines for the ArduPilot libraries
|
||||
#include <AP_Common/Location.h> // Library having the implementation of location class
|
||||
#include <AP_Param/AP_Param.h> // A system for managing and storing variables that are of general interest to the system.
|
||||
#include <StorageManager/StorageManager.h> // library for Management for hal.storage to allow for backwards compatible mapping of storage offsets to available storage
|
||||
|
||||
// Application dependencies
|
||||
#include <GCS_MAVLink/GCS.h>
|
||||
#include <AP_Logger/AP_Logger.h> // ArduPilot Mega Flash Memory Library
|
||||
#include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
|
||||
#include <AP_AccelCal/AP_AccelCal.h> // interface and maths for accelerometer calibration
|
||||
#include <AP_InertialSensor/AP_InertialSensor.h> // ArduPilot Mega Inertial Sensor (accel & gyro) Library
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
#include <AP_Mission/AP_Mission.h> // Mission command library
|
||||
#include <AC_AttitudeControl/AC_AttitudeControl_Multi.h> // Attitude control library
|
||||
#include <AC_AttitudeControl/AC_AttitudeControl_Multi_6DoF.h> // 6DoF Attitude control library
|
||||
#include <AC_AttitudeControl/AC_AttitudeControl_Heli.h> // Attitude control library for traditional helicopter
|
||||
#include <AC_AttitudeControl/AC_PosControl.h> // Position control library
|
||||
#include <AP_Motors/AP_Motors.h> // AP Motors library
|
||||
#include <AP_Stats/AP_Stats.h> // statistics library
|
||||
#include <Filter/Filter.h> // Filter library
|
||||
#include <GCS_MAVLink/GCS.h> // Library for Interface definition for the various Ground Control System
|
||||
#include <AP_Logger/AP_Logger.h> // ArduPilot Mega Flash Memory Library
|
||||
#include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
|
||||
#include <AP_AccelCal/AP_AccelCal.h> // interface and maths for accelerometer calibration
|
||||
#include <AP_InertialSensor/AP_InertialSensor.h> // ArduPilot Mega Inertial Sensor (accel & gyro) Library
|
||||
#include <AP_AHRS/AP_AHRS.h> // AHRS (Attitude Heading Reference System) interface library for ArduPilot
|
||||
#include <AP_Mission/AP_Mission.h> // Mission command library
|
||||
#include <AC_AttitudeControl/AC_AttitudeControl_Multi.h> // Attitude control library
|
||||
#include <AC_AttitudeControl/AC_AttitudeControl_Multi_6DoF.h> // 6DoF Attitude control library
|
||||
#include <AC_AttitudeControl/AC_AttitudeControl_Heli.h> // Attitude control library for traditional helicopter
|
||||
#include <AC_AttitudeControl/AC_PosControl.h> // Position control library
|
||||
#include <AP_Motors/AP_Motors.h> // AP Motors library
|
||||
#include <AP_Stats/AP_Stats.h> // statistics library
|
||||
#include <Filter/Filter.h> // Filter library
|
||||
#include <AP_Airspeed/AP_Airspeed.h> // needed for AHRS build
|
||||
#include <AP_Vehicle/AP_Vehicle.h> // needed for AHRS build
|
||||
#include <AP_InertialNav/AP_InertialNav.h> // ArduPilot Mega inertial navigation library
|
||||
#include <AC_WPNav/AC_WPNav.h> // ArduCopter waypoint navigation library
|
||||
#include <AC_WPNav/AC_Loiter.h>
|
||||
#include <AC_WPNav/AC_Circle.h> // circle navigation library
|
||||
#include <AP_Declination/AP_Declination.h> // ArduPilot Mega Declination Helper Library
|
||||
#include <AP_Vehicle/AP_Vehicle.h> // needed for AHRS build
|
||||
#include <AP_InertialNav/AP_InertialNav.h> // ArduPilot Mega inertial navigation library
|
||||
#include <AC_WPNav/AC_WPNav.h> // ArduCopter waypoint navigation library
|
||||
#include <AC_WPNav/AC_Loiter.h> // ArduCopter Loiter Mode Library
|
||||
#include <AC_WPNav/AC_Circle.h> // circle navigation library
|
||||
#include <AP_Declination/AP_Declination.h> // ArduPilot Mega Declination Helper Library
|
||||
#include <AP_RCMapper/AP_RCMapper.h> // RC input mapping library
|
||||
#include <AP_BattMonitor/AP_BattMonitor.h> // Battery monitor library
|
||||
#include <AP_LandingGear/AP_LandingGear.h> // Landing Gear library
|
||||
#include <AP_BattMonitor/AP_BattMonitor.h> // Battery monitor library
|
||||
#include <AP_LandingGear/AP_LandingGear.h> // Landing Gear library
|
||||
#include <AC_InputManager/AC_InputManager.h> // Pilot input handling library
|
||||
#include <AC_InputManager/AC_InputManager_Heli.h> // Heli specific pilot input handling library
|
||||
#include <AP_Arming/AP_Arming.h>
|
||||
#include <AP_SmartRTL/AP_SmartRTL.h>
|
||||
#include <AP_TempCalibration/AP_TempCalibration.h>
|
||||
#include <AC_AutoTune/AC_AutoTune.h>
|
||||
#include <AP_Parachute/AP_Parachute.h>
|
||||
#include <AC_Sprayer/AC_Sprayer.h>
|
||||
#include <AP_ADSB/AP_ADSB.h>
|
||||
#include <AP_Proximity/AP_Proximity.h>
|
||||
#include <AP_Arming/AP_Arming.h> // ArduPilot motor arming library
|
||||
#include <AP_SmartRTL/AP_SmartRTL.h> // ArduPilot Smart Return To Launch Mode (SRTL) library
|
||||
#include <AP_TempCalibration/AP_TempCalibration.h> // temperature calibration library
|
||||
#include <AC_AutoTune/AC_AutoTune.h> // ArduCopter autotune library. support for autotune of multirotors.
|
||||
#include <AP_Parachute/AP_Parachute.h> // ArduPilot parachute release library
|
||||
#include <AC_Sprayer/AC_Sprayer.h> // Crop sprayer library
|
||||
#include <AP_ADSB/AP_ADSB.h> // ADS-B RF based collision avoidance module library
|
||||
#include <AP_Proximity/AP_Proximity.h> // ArduPilot proximity sensor library
|
||||
|
||||
// Configuration
|
||||
#include "defines.h"
|
||||
|
|
Loading…
Reference in New Issue