Class GSpeedController
- java.lang.Object
-
- com.thegongoliers.output.actuators.GSpeedController
-
- All Implemented Interfaces:
edu.wpi.first.wpilibj.PIDOutput
,edu.wpi.first.wpilibj.SpeedController
public class GSpeedController extends java.lang.Object implements edu.wpi.first.wpilibj.SpeedController
-
-
Constructor Summary
Constructors Constructor Description GSpeedController(edu.wpi.first.wpilibj.SpeedController speedController, DistanceSensor distanceSensor, VelocitySensor velocitySensor, com.kylecorry.pid.PID distancePID, com.kylecorry.pid.PID velocityPID)
A speed controller with added functionalityGSpeedController(edu.wpi.first.wpilibj.SpeedController speedController, edu.wpi.first.wpilibj.Encoder encoder, com.kylecorry.pid.PID distancePID, com.kylecorry.pid.PID velocityPID)
A speed controller with added functionalityGSpeedController(edu.wpi.first.wpilibj.SpeedController speedController, edu.wpi.first.wpilibj.interfaces.Potentiometer potentiometer, com.kylecorry.pid.PID distancePID)
A speed controller with added functionality Potentiometers can not use velocity control!
-
Method Summary
All Methods Instance Methods Concrete Methods Modifier and Type Method Description void
disable()
double
get()
double
getDistance()
boolean
getInverted()
double
getVelocity()
void
pidWrite(double output)
void
set(double speed)
void
setDistance(double distance)
void
setInverted(boolean isInverted)
void
setVelocity(double velocity)
void
stopMotor()
-
-
-
Constructor Detail
-
GSpeedController
public GSpeedController(edu.wpi.first.wpilibj.SpeedController speedController, edu.wpi.first.wpilibj.Encoder encoder, com.kylecorry.pid.PID distancePID, com.kylecorry.pid.PID velocityPID)
A speed controller with added functionality- Parameters:
speedController
- the underlying speed controllerencoder
- the encoder which senses the movement of the motor controlled by the speed controllerdistancePID
- the PID for setting a distance (ex. 0.1 when distance is in feet)velocityPID
- the PID for setting a velocity (ex. 1 / max velocity)
-
GSpeedController
public GSpeedController(edu.wpi.first.wpilibj.SpeedController speedController, edu.wpi.first.wpilibj.interfaces.Potentiometer potentiometer, com.kylecorry.pid.PID distancePID)
A speed controller with added functionality Potentiometers can not use velocity control!- Parameters:
speedController
- the underlying speed controllerpotentiometer
- the potentiometer which senses the movement of the motor controlled by the speed controllerdistancePID
- the PID for setting a distance
-
GSpeedController
public GSpeedController(edu.wpi.first.wpilibj.SpeedController speedController, DistanceSensor distanceSensor, VelocitySensor velocitySensor, com.kylecorry.pid.PID distancePID, com.kylecorry.pid.PID velocityPID)
A speed controller with added functionality- Parameters:
speedController
- the underlying speed controllerdistanceSensor
-velocitySensor
-distancePID
- the PID for setting a distancevelocityPID
- the PID for setting a velocity
-
-
Method Detail
-
pidWrite
public void pidWrite(double output)
- Specified by:
pidWrite
in interfaceedu.wpi.first.wpilibj.PIDOutput
-
set
public void set(double speed)
- Specified by:
set
in interfaceedu.wpi.first.wpilibj.SpeedController
-
setVelocity
public void setVelocity(double velocity)
- Parameters:
velocity
- the velocity of the motor in encoder units / second
-
getVelocity
public double getVelocity()
- Returns:
- the velocity of the motor in encoder units / second
-
setDistance
public void setDistance(double distance)
- Parameters:
distance
- the distance of the motor in encoder units
-
getDistance
public double getDistance()
- Returns:
- the distance of the motor in encoder units
-
get
public double get()
- Specified by:
get
in interfaceedu.wpi.first.wpilibj.SpeedController
-
setInverted
public void setInverted(boolean isInverted)
- Specified by:
setInverted
in interfaceedu.wpi.first.wpilibj.SpeedController
-
getInverted
public boolean getInverted()
- Specified by:
getInverted
in interfaceedu.wpi.first.wpilibj.SpeedController
-
disable
public void disable()
- Specified by:
disable
in interfaceedu.wpi.first.wpilibj.SpeedController
-
stopMotor
public void stopMotor()
- Specified by:
stopMotor
in interfaceedu.wpi.first.wpilibj.SpeedController
-
-