Moved C++ comments from source files to headers (#1111)

Also sorted functions in C++ sources to match order in related headers.
This commit is contained in:
Tyler Veness
2018-05-31 20:47:15 -07:00
committed by Peter Johnson
parent d9971a705a
commit 8c680a26f8
234 changed files with 9936 additions and 9309 deletions

View File

@@ -19,39 +19,12 @@ using namespace frc;
constexpr double kPi = 3.14159265358979323846;
/**
* Construct a Killough drive with the given motors and default motor angles.
*
* The default motor angles make the wheels on each corner parallel to their
* respective opposite sides.
*
* If a motor needs to be inverted, do so before passing it in.
*
* @param leftMotor The motor on the left corner.
* @param rightMotor The motor on the right corner.
* @param backMotor The motor on the back corner.
*/
KilloughDrive::KilloughDrive(SpeedController& leftMotor,
SpeedController& rightMotor,
SpeedController& backMotor)
: KilloughDrive(leftMotor, rightMotor, backMotor, kDefaultLeftMotorAngle,
kDefaultRightMotorAngle, kDefaultBackMotorAngle) {}
/**
* Construct a Killough drive with the given motors.
*
* Angles are measured in degrees clockwise from the positive X axis.
*
* @param leftMotor The motor on the left corner.
* @param rightMotor The motor on the right corner.
* @param backMotor The motor on the back corner.
* @param leftMotorAngle The angle of the left wheel's forward direction of
* travel.
* @param rightMotorAngle The angle of the right wheel's forward direction of
* travel.
* @param backMotorAngle The angle of the back wheel's forward direction of
* travel.
*/
KilloughDrive::KilloughDrive(SpeedController& leftMotor,
SpeedController& rightMotor,
SpeedController& backMotor, double leftMotorAngle,
@@ -71,21 +44,6 @@ KilloughDrive::KilloughDrive(SpeedController& leftMotor,
SetName("KilloughDrive", instances);
}
/**
* Drive method for Killough platform.
*
* Angles are measured clockwise from the positive X axis. The robot's speed is
* independent from its angle or rotation rate.
*
* @param ySpeed The robot's speed along the Y axis [-1.0..1.0]. Right is
* positive.
* @param xSpeed The robot's speed along the X axis [-1.0..1.0]. Forward is
* positive.
* @param zRotation The robot's rotation rate around the Z axis [-1.0..1.0].
* Clockwise is positive.
* @param gyroAngle The current angle reading from the gyro in degrees around
* the Z axis. Use this to implement field-oriented controls.
*/
void KilloughDrive::DriveCartesian(double ySpeed, double xSpeed,
double zRotation, double gyroAngle) {
if (!reported) {
@@ -118,19 +76,6 @@ void KilloughDrive::DriveCartesian(double ySpeed, double xSpeed,
m_safetyHelper.Feed();
}
/**
* Drive method for Killough platform.
*
* Angles are measured clockwise from the positive X axis. The robot's speed is
* independent from its angle or rotation rate.
*
* @param magnitude The robot's speed at a given angle [-1.0..1.0]. Forward is
* positive.
* @param angle The angle around the Z axis at which the robot drives in
* degrees [-180..180].
* @param zRotation The robot's rotation rate around the Z axis [-1.0..1.0].
* Clockwise is positive.
*/
void KilloughDrive::DrivePolar(double magnitude, double angle,
double zRotation) {
if (!reported) {