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

@@ -13,67 +13,19 @@
using namespace frc;
/**
* Allocate a PID object with the given constants for P, I, D.
*
* @param Kp the proportional coefficient
* @param Ki the integral coefficient
* @param Kd the derivative coefficient
* @param source The PIDSource object that is used to get values
* @param output The PIDOutput object that is set to the output value
* @param period the loop time for doing calculations. This particularly
* effects calculations of the integral and differental terms.
* The default is 50ms.
*/
PIDController::PIDController(double Kp, double Ki, double Kd, PIDSource* source,
PIDOutput* output, double period)
: PIDController(Kp, Ki, Kd, 0.0, *source, *output, period) {}
/**
* Allocate a PID object with the given constants for P, I, D.
*
* @param Kp the proportional coefficient
* @param Ki the integral coefficient
* @param Kd the derivative coefficient
* @param source The PIDSource object that is used to get values
* @param output The PIDOutput object that is set to the output value
* @param period the loop time for doing calculations. This particularly
* effects calculations of the integral and differental terms.
* The default is 50ms.
*/
PIDController::PIDController(double Kp, double Ki, double Kd, double Kf,
PIDSource* source, PIDOutput* output,
double period)
: PIDController(Kp, Ki, Kd, Kf, *source, *output, period) {}
/**
* Allocate a PID object with the given constants for P, I, D.
*
* @param Kp the proportional coefficient
* @param Ki the integral coefficient
* @param Kd the derivative coefficient
* @param source The PIDSource object that is used to get values
* @param output The PIDOutput object that is set to the output value
* @param period the loop time for doing calculations. This particularly
* effects calculations of the integral and differental terms.
* The default is 50ms.
*/
PIDController::PIDController(double Kp, double Ki, double Kd, PIDSource& source,
PIDOutput& output, double period)
: PIDController(Kp, Ki, Kd, 0.0, source, output, period) {}
/**
* Allocate a PID object with the given constants for P, I, D.
*
* @param Kp the proportional coefficient
* @param Ki the integral coefficient
* @param Kd the derivative coefficient
* @param source The PIDSource object that is used to get values
* @param output The PIDOutput object that is set to the output value
* @param period the loop time for doing calculations. This particularly
* effects calculations of the integral and differental terms.
* The default is 50ms.
*/
PIDController::PIDController(double Kp, double Ki, double Kd, double Kf,
PIDSource& source, PIDOutput& output,
double period)
@@ -87,9 +39,6 @@ PIDController::~PIDController() {
m_controlLoop->Stop();
}
/**
* Begin running the PIDController.
*/
void PIDController::Enable() {
{
std::lock_guard<wpi::mutex> lock(m_thisMutex);
@@ -97,9 +46,6 @@ void PIDController::Enable() {
}
}
/**
* Stop running the PIDController, this sets the output to zero before stopping.
*/
void PIDController::Disable() {
{
// Ensures m_enabled modification and PIDWrite() call occur atomically
@@ -113,9 +59,6 @@ void PIDController::Disable() {
}
}
/**
* Set the enabled state of the PIDController.
*/
void PIDController::SetEnabled(bool enable) {
if (enable) {
Enable();
@@ -124,17 +67,11 @@ void PIDController::SetEnabled(bool enable) {
}
}
/**
* Return true if PIDController is enabled.
*/
bool PIDController::IsEnabled() const {
std::lock_guard<wpi::mutex> lock(m_thisMutex);
return m_enabled;
}
/**
* Reset the previous error, the integral term, and disable the controller.
*/
void PIDController::Reset() {
Disable();