Rename Gyro to AnalogGyro and make Gyro an interface.

Refactor common implementation parts of AnalogGyro into GyroBase.

This will make it possible to add digital gyros in a similar way to how
digital accelerometers were added.

Change-Id: I437ef259e9ecb81f18a91a95c5a58b6607db5e15
This commit is contained in:
Peter Johnson
2015-11-06 12:05:40 -08:00
parent e2a4556669
commit c20d34c2b6
22 changed files with 391 additions and 210 deletions

View File

@@ -1,9 +1,9 @@
package $package.subsystems;
import edu.wpi.first.wpilibj.AnalogGyro;
import edu.wpi.first.wpilibj.AnalogInput;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.Joystick.AxisType;
import edu.wpi.first.wpilibj.Gyro;
import edu.wpi.first.wpilibj.Joystick;
import edu.wpi.first.wpilibj.RobotDrive;
import edu.wpi.first.wpilibj.SpeedController;
@@ -25,7 +25,7 @@ public class DriveTrain extends Subsystem {
private RobotDrive drive;
private Encoder left_encoder, right_encoder;
private AnalogInput rangefinder;
private Gyro gyro;
private AnalogGyro gyro;
public DriveTrain() {
super();
@@ -53,7 +53,7 @@ public class DriveTrain extends Subsystem {
}
rangefinder = new AnalogInput(6);
gyro = new Gyro(1);
gyro = new AnalogGyro(1);
// Let's show everything on the LiveWindow
LiveWindow.addActuator("Drive Train", "Front_Left Motor", (Talon) front_left_motor);

View File

@@ -1,8 +1,8 @@
package $package;
import edu.wpi.first.wpilibj.AnalogGyro;
import edu.wpi.first.wpilibj.CANTalon;
import edu.wpi.first.wpilibj.Gyro;
import edu.wpi.first.wpilibj.SampleRobot;
import edu.wpi.first.wpilibj.RobotDrive;
import edu.wpi.first.wpilibj.Joystick;
@@ -35,7 +35,7 @@ public class Robot extends SampleRobot {
final double voltsPerDegreePerSecond = .0128;
RobotDrive myRobot;
Gyro gyro;
AnalogGyro gyro;
Joystick joystick;
public Robot()
@@ -44,7 +44,7 @@ public class Robot extends SampleRobot {
myRobot = new RobotDrive(new CANTalon(leftMotorChannel), new CANTalon(
leftRearMotorChannel), new CANTalon(rightMotorChannel),
new CANTalon(rightRearMotorChannel));
gyro = new Gyro(gyroChannel);
gyro = new AnalogGyro(gyroChannel);
joystick = new Joystick(joystickChannel);
}

View File

@@ -1,8 +1,8 @@
package $package;
import edu.wpi.first.wpilibj.AnalogGyro;
import edu.wpi.first.wpilibj.CANTalon;
import edu.wpi.first.wpilibj.Gyro;
import edu.wpi.first.wpilibj.SampleRobot;
import edu.wpi.first.wpilibj.RobotDrive;
import edu.wpi.first.wpilibj.Joystick;
@@ -20,7 +20,7 @@ import edu.wpi.first.wpilibj.RobotDrive.MotorType;
public class Robot extends SampleRobot {
RobotDrive myRobot;
Joystick joystick;
Gyro gyro;
AnalogGyro gyro;
//channels for motors
final int leftMotorChannel = 1;
@@ -42,7 +42,7 @@ public class Robot extends SampleRobot {
myRobot.setInvertedMotor(MotorType.kRearLeft, true); // you may need to change or remove this to match your robot
joystick = new Joystick(0);
gyro = new Gyro(gyroChannel);
gyro = new AnalogGyro(gyroChannel);
}
/**

View File

@@ -3,9 +3,9 @@ package $package.subsystems;
import $package.Robot;
import $package.commands.DriveWithJoystick;
import edu.wpi.first.wpilibj.AnalogGyro;
import edu.wpi.first.wpilibj.CounterBase.EncodingType;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.Gyro;
import edu.wpi.first.wpilibj.Joystick;
import edu.wpi.first.wpilibj.PIDSource.PIDSourceParameter;
import edu.wpi.first.wpilibj.RobotDrive;
@@ -24,7 +24,7 @@ public class DriveTrain extends Subsystem {
private SpeedController backLeftCIM, backRightCIM;
private RobotDrive drive;
private Encoder rightEncoder, leftEncoder;
private Gyro gyro;
private AnalogGyro gyro;
public DriveTrain() {
// Configure drive motors
@@ -67,7 +67,7 @@ public class DriveTrain extends Subsystem {
LiveWindow.addSensor("DriveTrain", "Left Encoder", leftEncoder);
// Configure gyro
gyro = new Gyro(2);
gyro = new AnalogGyro(2);
if (Robot.isReal()) {
gyro.setSensitivity(0.007); // TODO: Handle more gracefully?
}
@@ -124,4 +124,4 @@ public class DriveTrain extends Subsystem {
public double getAngle() {
return gyro.getAngle();
}
}
}