diff --git a/gradle/wrapper/gradle-wrapper.properties b/gradle/wrapper/gradle-wrapper.properties index 731147b..a4fd840 100644 --- a/gradle/wrapper/gradle-wrapper.properties +++ b/gradle/wrapper/gradle-wrapper.properties @@ -2,4 +2,4 @@ distributionUrl=https\://services.gradle.org/distributions/gradle-4.2.1-bin.zip distributionBase=GRADLE_USER_HOME distributionPath=wrapper/dists zipStorePath=wrapper/dists -zipStoreBase=GRADLE_USER_HOME +zipStoreBase=GRADLE_USER_HOME \ No newline at end of file diff --git a/src/main/java/org/usfirst/frc/team449/robot/BallbasaurIntake.java b/src/main/java/org/usfirst/frc/team449/robot/BallbasaurIntake.java new file mode 100644 index 0000000..acd8499 --- /dev/null +++ b/src/main/java/org/usfirst/frc/team449/robot/BallbasaurIntake.java @@ -0,0 +1,74 @@ +package org.usfirst.frc.team449.robot; + +import edu.wpi.first.wpilibj.DoubleSolenoid; +import edu.wpi.first.wpilibj.Solenoid; +import org.jetbrains.annotations.NotNull; +import com.fasterxml.jackson.annotation.JsonCreator; +import org.usfirst.frc.team449.robot.jacksonWrappers.YamlSubsystem; +import com.fasterxml.jackson.annotation.JsonProperty; +import org.usfirst.frc.team449.robot.jacksonWrappers.MappedDoubleSolenoid; +import org.usfirst.frc.team449.robot.subsystem.interfaces.intake.SubsystemIntake; +import org.usfirst.frc.team449.robot.subsystem.interfaces.solenoid.SubsystemSolenoid; + +public class BallbasaurIntake extends YamlSubsystem implements SubsystemSolenoid, SubsystemIntake { + + /** + * Piston for pushing gears + */ + @NotNull + private final DoubleSolenoid piston; + + /** + * The piston's current position + */ + private DoubleSolenoid.Value pistonPos; + /** + * first: + */ + private final double intakeRollerSpeedSlow; + private final double intakeRollerSpeedFast; + /** + * Default constructor + * + * @param piston The piston that comprises this subsystem. + */ + @JsonCreator + public BallbasaurIntake(@NotNull @JsonProperty(required = true) MappedDoubleSolenoid piston, + double intakeRollerSpeedSlow, double intakeRollerSpeedFast) { + this.piston = piston; + this.intakeRollerSpeedFast = intakeRollerSpeedFast; + this.intakeRollerSpeedSlow = intakeRollerSpeedSlow; + } + + + /** + * @param value The position to set the solenoid to. + */ + public void setSolenoid(@NotNull DoubleSolenoid.Value value){ + piston.set(value); + pistonPos= value; + } + + /** + * @return the current position of the solenoid. + */ + @NotNull + public DoubleSolenoid.Value getSolenoidPosition(){ + return pistonPos; + } + + @Override + protected void initDefaultCommand() { + } + + @NotNull + @Override + public IntakeMode getMode() { + return null; + } + + @Override + public void setMode(@NotNull IntakeMode mode) { + + } +} diff --git a/src/main/java/org/usfirst/frc/team449/robot/Robot.java b/src/main/java/org/usfirst/frc/team449/robot/Robot.java new file mode 100644 index 0000000..53ef5d4 --- /dev/null +++ b/src/main/java/org/usfirst/frc/team449/robot/Robot.java @@ -0,0 +1,265 @@ +package org.usfirst.frc.team449.robot; + +import com.fasterxml.jackson.annotation.JsonCreator; +import com.fasterxml.jackson.annotation.JsonIdentityInfo; +import com.fasterxml.jackson.annotation.ObjectIdGenerators; +import com.fasterxml.jackson.dataformat.yaml.YAMLMapper; +import com.fasterxml.jackson.module.paramnames.ParameterNamesModule; +import edu.wpi.first.wpilibj.I2C; +import edu.wpi.first.wpilibj.IterativeRobot; +import edu.wpi.first.wpilibj.Notifier; +import edu.wpi.first.wpilibj.command.Scheduler; +import org.jetbrains.annotations.NotNull; +import org.jetbrains.annotations.Nullable; +import org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonCluster; +import org.usfirst.frc.team449.robot.other.Clock; +import org.yaml.snakeyaml.Yaml; + +import java.io.FileReader; +import java.io.IOException; +import java.util.Map; + +/** + * The main class of the robot, constructs all the subsystems and initializes default commands. + */ +@JsonIdentityInfo(generator = ObjectIdGenerators.StringIdGenerator.class) +public class Robot extends IterativeRobot { + + /** + * The absolute filepath to the resources folder containing the config files. + */ + @NotNull + public static final String RESOURCES_PATH = "/home/lvuser/449_resources/"; + + /** + * The drive + */ + private DriveTalonCluster driveSubsystem; + + /** + * The object constructed directly from the yaml map. + */ + private RobotMap robotMap; + + /** + * The Notifier running the logging thread. + */ + private Notifier loggerNotifier; + + /** + * The string version of the alliance we're on ("red" or "blue"). Used for string concatenation to pick which + * profile to execute. + */ + @Nullable + private String allianceString; + + /** + * The I2C channel for communicating with the RIOduino. + */ + @Nullable + private I2C robotInfo; + + /** + * Whether or not the robot has been enabled yet. + */ + private boolean enabled; + + /** + * The method that runs when the robot is turned on. Initializes all subsystems from the map. + */ + public void robotInit() { + //Set up start time + Clock.setStartTime(); + Clock.updateTime(); + + enabled = false; + + //Yes this should be a print statement, it's useful to know that robotInit started. + System.out.println("Started robotInit."); + + Yaml yaml = new Yaml(); + try { + //Read the yaml file with SnakeYaml so we can use anchors and merge syntax. +// Map normalized = (Map) yaml.load(new FileReader(RESOURCES_PATH+"ballbasaur_map.yml")); +// Map normalized = (Map) yaml.load(new FileReader(RESOURCES_PATH + "naveen_map.yml")); +// Map normalized = (Map) yaml.load(new FileReader(RESOURCES_PATH + "nate_map.yml")); + Map normalized = (Map) yaml.load(new FileReader(RESOURCES_PATH + "map.yml")); + YAMLMapper mapper = new YAMLMapper(); + //Turn the Map read by SnakeYaml into a String so Jackson can read it. + String fixed = mapper.writeValueAsString(normalized); + //Use a parameter name module so we don't have to specify name for every field. + mapper.registerModule(new ParameterNamesModule(JsonCreator.Mode.PROPERTIES)); + //Deserialize the map into an object. + robotMap = mapper.readValue(fixed, RobotMap.class); + } catch (IOException e) { + //This is either the map file not being in the file system OR it being improperly formatted. + System.out.println("Config file is bad/nonexistent!"); + e.printStackTrace(); + } + + //Read sensors + this.robotMap.getUpdater().run(); + + //Set fields from the map. + this.loggerNotifier = new Notifier(robotMap.getLogger()); + this.driveSubsystem = robotMap.getDrive(); + + //Set up RIOduino I2C channel if it's in the map. + if (robotMap.getRIOduinoPort() != null) { + robotInfo = new I2C(I2C.Port.kOnboard, robotMap.getRIOduinoPort()); + } + + //Set up the motion profiles if we're doing motion profiling + + //Run the logger to write all the events that happened during initialization to a file. + robotMap.getLogger().run(); + Clock.updateTime(); + } + + /** + * Run when we first enable in teleop. + */ + @Override + public void teleopInit() { + //Do the startup tasks + doStartupTasks(); + + //Read sensors + this.robotMap.getUpdater().run(); + + //Run startup command if we start in teleop. + if (!enabled) { + if (robotMap.getStartupCommand() != null) { + robotMap.getStartupCommand().start(); + } + enabled = true; + } + + driveSubsystem.stopMPProcesses(); + + if (robotMap.getTeleopStartupCommand() != null) { + robotMap.getTeleopStartupCommand().start(); + } + + //Set the default command + driveSubsystem.setDefaultCommandManual(robotMap.getDefaultDriveCommand()); + } + + /** + * Run every tick in teleop. + */ + @Override + public void teleopPeriodic() { + //Refresh the current time. + Clock.updateTime(); + + //Read sensors + this.robotMap.getUpdater().run(); + + //Run all commands. This is a WPILib thing you don't really have to worry about. + Scheduler.getInstance().run(); + } + + /** + * Run when we first enable in autonomous + */ + @Override + public void autonomousInit() { + //Do startup tasks + doStartupTasks(); + + //Read sensors + this.robotMap.getUpdater().run(); + + //Run startup command if we start in auto. + if (!enabled) { + if (robotMap.getStartupCommand() != null) { + robotMap.getStartupCommand().start(); + } + enabled = true; + } + + //Tell the RIOduino we're in autonomous + sendModeOverI2C(robotInfo, "auto"); + } + + /** + * Runs every tick in autonomous. + */ + @Override + public void autonomousPeriodic() { + //Update the current time + Clock.updateTime(); + //Read sensors + this.robotMap.getUpdater().run(); + //Run all commands. This is a WPILib thing you don't really have to worry about. + Scheduler.getInstance().run(); + } + + /** + * Run when we disable. + */ + @Override + public void disabledInit() { + //Fully stop the drive + driveSubsystem.fullStop(); + //Tell the RIOduino we're disabled. + sendModeOverI2C(robotInfo, "disabled"); + } + + /** + * Run when we first enable in test mode. + */ + @Override + public void testInit() { + //Run startup command if we start in test mode. + if (!enabled) { + if (robotMap.getStartupCommand() != null) { + robotMap.getStartupCommand().start(); + } + enabled = true; + } + } + + /** + * Run every tic while disabled + */ + @Override + public void disabledPeriodic() { + Clock.updateTime(); + //Read sensors + this.robotMap.getUpdater().run(); + } + + /** + * Sends the current mode (auto, teleop, or disabled) over I2C. + * + * @param i2C The I2C channel to send the data over. + * @param mode The current mode, represented as a String. + */ + private void sendModeOverI2C(I2C i2C, String mode) { + //If the I2C exists + if (i2C != null) { + //Turn the alliance and mode into a character array. + char[] CharArray = (allianceString + "_" + mode).toCharArray(); + //Transfer the character array to a byte array. + byte[] WriteData = new byte[CharArray.length]; + for (int i = 0; i < CharArray.length; i++) { + WriteData[i] = (byte) CharArray[i]; + } + //Send the byte array. + i2C.transaction(WriteData, WriteData.length, null, 0); + } + } + + /** + * Do tasks that should be done when we first enable, in both auto and teleop. + */ + private void doStartupTasks() { + //Refresh the current time. + Clock.updateTime(); + + //Start running the logger + loggerNotifier.startPeriodic(robotMap.getLogger().getLoopTimeSecs()); + } +} diff --git a/src/main/java/org/usfirst/frc/team449/robot/RobotMap.java b/src/main/java/org/usfirst/frc/team449/robot/RobotMap.java new file mode 100644 index 0000000..a9618ad --- /dev/null +++ b/src/main/java/org/usfirst/frc/team449/robot/RobotMap.java @@ -0,0 +1,292 @@ +package org.usfirst.frc.team449.robot; + +import com.fasterxml.jackson.annotation.JsonCreator; +import com.fasterxml.jackson.annotation.JsonProperty; +import edu.wpi.first.wpilibj.command.Command; +import org.jetbrains.annotations.NotNull; +import org.jetbrains.annotations.Nullable; +import org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonCluster; +import org.usfirst.frc.team449.robot.jacksonWrappers.MappedDigitalInput; +import org.usfirst.frc.team449.robot.jacksonWrappers.MappedRunnable; +import org.usfirst.frc.team449.robot.jacksonWrappers.YamlCommand; +import org.usfirst.frc.team449.robot.oi.OI; +import org.usfirst.frc.team449.robot.oi.buttons.CommandButton; +import org.usfirst.frc.team449.robot.other.Logger; +import org.usfirst.frc.team449.robot.other.MotionProfileData; +import org.usfirst.frc.team449.robot.subsystem.complex.intake.IntakeFixedAndActuated; +import org.usfirst.frc.team449.robot.subsystem.complex.shooter.LoggingFlywheel; +import org.usfirst.frc.team449.robot.subsystem.interfaces.solenoid.SolenoidSimple; +import org.usfirst.frc.team449.robot.subsystem.singleImplementation.camera.CameraNetwork; +import org.usfirst.frc.team449.robot.subsystem.singleImplementation.pneumatics.Pneumatics; + +import java.util.ArrayList; +import java.util.List; +import java.util.Map; + +/** + * The Jackson-compatible object representing the entire robot. + */ +public class RobotMap { + /** + * The buttons for controlling this robot. + */ + @NotNull + private final List buttons; + + /** + * The OI for controlling this robot's drive. + */ + @NotNull + private final OI oi; + + /** + * The logger for recording events and telemetry data. + */ + @NotNull + private final Logger logger; + + /** + * The drive. + */ + @NotNull + private final DriveTalonCluster drive; + + /** + * The command for the drive to run during the teleoperated period. + */ + @NotNull + private final Command defaultDriveCommand; + + /** + * A runnable that updates cached variables. + */ + @NotNull + private final Runnable updater; + + + + /** + * The pneumatics on this robot. Can be null. + */ + @Nullable + private final Pneumatics pneumatics; + + + /** + * The I2C port of the RIOduino plugged into this robot. Can be null. + */ + @Nullable + private final Integer RIOduinoPort; + + /** + * The switch for selecting which alliance we're on. Can be null if doMP is false or testMP is true, but otherwise + * must have a value. + */ + @Nullable + private final MappedDigitalInput allianceSwitch; + + /** + * The dial for selecting which side of the field the robot is on. Can be null if doMP is false or testMP is true, + * but otherwise must have a value. + */ + @Nullable + private final MappedDigitalInput locationDial; + + /** + * The command to be run when first enabled in teleoperated mode. + */ + @Nullable + private final Command teleopStartupCommand; + + /** + * The command to be run when first enabled. + */ + @Nullable + private final Command startupCommand; + + /** + * Whether to run the test or real motion profile during autonomous. + */ + private final boolean testMP; + + /** + * Whether to run a motion profile during autonomous. + */ + private final boolean doMP; + + /** + * Default constructor. + * + * @param buttons The buttons for controlling this robot. Can be null for an empty list. + * @param oi The OI for controlling this robot's drive. + * @param logger The logger for recording events and telemetry data. + * @param drive The drive. + * @param defaultDriveCommand The command for the drive to run during the teleoperated period. + * @param updater A runnable that updates cached variables. + * @param pneumatics The pneumatics on this robot. Can be null. + * @param RIOduinoPort The I2C port of the RIOduino plugged into this robot. Can be null. + * @param allianceSwitch The switch for selecting which alliance we're on. Can be null if doMP is false or + * testMP is true, but otherwise must have a value. + * @param locationDial The dial for selecting which side of the field the robot is on. Can be null if doMP + * is false or testMP is true, but otherwise must have a value. + * @param leftTestProfile The profile for the left side of the drive to run in test mode. Can be null if either + * testMP or doMP are false, but otherwise must have a value. + * @param rightTestProfile The profile for the right side of the drive to run in test mode. Can be null if + * either testMP or doMP are false, but otherwise must have a value. + * @param leftProfiles The starting position to peg profiles for the left side. Should have options for + * "red_right", "red_center", "red_left", "blue_right", "blue_center", and "blue_left". + * Can be null if doMP is false or testMP is true, but otherwise must have a value. + * @param rightProfiles The starting position to peg profiles for the right side. Should have options for + * "red_right", "red_center", "red_left", "blue_right", "blue_center", and "blue_left". + * Can be null if doMP is false or testMP is true, but otherwise must have a value. + * @param teleopStartupCommand The command to be run when first enabled in teleoperated mode. + * @param startupCommand The command to be run when first enabled. + * @param testMP Whether to run the test or real motion profile during autonomous. Defaults to false. + * @param doMP Whether to run a motion profile during autonomous. Defaults to true. + */ + @JsonCreator + public RobotMap(@Nullable List buttons, + @NotNull @JsonProperty(required = true) OI oi, + @NotNull @JsonProperty(required = true) Logger logger, + @NotNull @JsonProperty(required = true) DriveTalonCluster drive, + @NotNull @JsonProperty(required = true) YamlCommand defaultDriveCommand, + @NotNull @JsonProperty(required = true) MappedRunnable updater, + @Nullable IntakeFixedAndActuated intake, + @Nullable Pneumatics pneumatics, + @Nullable Integer RIOduinoPort, + @Nullable MappedDigitalInput allianceSwitch, + @Nullable MappedDigitalInput locationDial, + @Nullable MotionProfileData leftTestProfile, @Nullable MotionProfileData rightTestProfile, + @Nullable Map leftProfiles, @Nullable Map rightProfiles, + @Nullable YamlCommand teleopStartupCommand, + @Nullable YamlCommand startupCommand, + boolean testMP, + @Nullable Boolean doMP) { + this.buttons = buttons != null ? buttons : new ArrayList<>(); + this.oi = oi; + this.drive = drive; + this.pneumatics = pneumatics; + this.logger = logger; + this.updater = updater; + this.RIOduinoPort = RIOduinoPort; + this.allianceSwitch = allianceSwitch; + this.locationDial = locationDial; + this.defaultDriveCommand = defaultDriveCommand.getCommand(); + this.teleopStartupCommand = teleopStartupCommand != null ? teleopStartupCommand.getCommand() : null; + this.startupCommand = startupCommand != null ? startupCommand.getCommand() : null; + this.testMP = testMP; + this.doMP = doMP != null ? doMP : true; + } + + /** + * @return The buttons for controlling this robot. + */ + @NotNull + public List getButtons() { + return buttons; + } + + /** + * @return The OI for controlling this robot's drive. + */ + @NotNull + public OI getOI() { + return oi; + } + + /** + * @return The logger for recording events and telemetry data. + */ + @NotNull + public Logger getLogger() { + return logger; + } + + /** + * @return The drive. + */ + @NotNull + public DriveTalonCluster getDrive() { + return drive; + } + + /** + * @return The command for the drive to run during the teleoperated period. + */ + @NotNull + public Command getDefaultDriveCommand() { + return defaultDriveCommand; + } + + /** + * @return The pneumatics on this robot. Can be null. + */ + @Nullable + public Pneumatics getPneumatics() { + return pneumatics; + } + + /** + * @return The I2C port of the RIOduino plugged into this robot. Can be null. + */ + @Nullable + public Integer getRIOduinoPort() { + return RIOduinoPort; + } + + /** + * @return The switch for selecting which alliance we're on. Can be null if getDoMP returns false or getTestMP + * returns true, but otherwise has a value. + */ + @Nullable + public MappedDigitalInput getAllianceSwitch() { + return allianceSwitch; + } + + /** + * @return The dial for selecting which side of the field the robot is on. Can be null if getDoMP returns false or + * getTestMP returns true, but otherwise has a value. + */ + @Nullable + public MappedDigitalInput getLocationDial() { + return locationDial; + } + + /** + * @return Whether to run the test or real motion profile during autonomous. + */ + public boolean getTestMP() { + return testMP; + } + + /** + * @return The command to be run when first enabled in teleoperated mode. + */ + @Nullable + public Command getTeleopStartupCommand() { + return teleopStartupCommand; + } + + /** + * @return Whether to run a motion profile during autonomous. + */ + public boolean getDoMP() { + return doMP; + } + + /** + * @return The command to be run when first enabled. + */ + @Nullable + public Command getStartupCommand() { + return startupCommand; + } + + /** + * @return A runnable that updates cached variables. + */ + @NotNull + public Runnable getUpdater() { + return updater; + } +} diff --git a/src/main/resources/map.yml b/src/main/resources/map.yml index e69de29..3995aca 100644 --- a/src/main/resources/map.yml +++ b/src/main/resources/map.yml @@ -0,0 +1,166 @@ +--- +doMP: false +testMP: true +leftTestProfile: + &leftTest + '@id': leftTest + filename: "forward100InProfile.csv" + inverted: true + velocityOnly: true +rightTestProfile: + <<: *leftTest + '@id': rightTest +drive: + org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonCluster: + '@id': drive + leftMaster: + org.usfirst.frc.team449.robot.jacksonWrappers.FPSTalon: + &leftMaster + '@id': leftMaster + port: 5 + invertInVoltage: false + enableBrakeMode: true + feetPerRotation: 1.002 + currentLimit: 40 + feedbackDevice: QuadEncoder + encoderCPR: 512 + reverseSensor: false + reverseOutput: false + perGearSettings: + - &gearSettings + fwdPeakOutputVoltage: 12 + fwdNominalOutputVoltage: 0.0 + maxSpeed: 11.8 + kP: 0.1 + kI: 0.0 + kD: 1.0 + motionProfilePFwd: 1.0 + motionProfileIFwd: 0.0 + motionProfileDFwd: 20.0 + maxAccelFwd: 54 + maxSpeedMPFwd: 15.132 + frictionCompFPSFwd: 1.55 + slaves: + - '@id': talon1 + port: 6 + inverted: false + - '@id': talon2 + port: 1 + inverted: false + rightMaster: + org.usfirst.frc.team449.robot.jacksonWrappers.FPSTalon: + <<: *leftMaster + '@id': rightMaster + port: 2 + invertInVoltage: true + reverseSensor: true + reverseOutput: true + perGearSettings: + - <<: *gearSettings + maxSpeedMPFwd: 13.619 + frictionCompFPSFwd: 1.705 + slaves: + - '@id': talon3 + port: 9 + inverted: false + - '@id': talon5 + port: 8 + inverted: false + VelScale: 0.9 + ahrs: + '@id': driveNavX + port: kMXP +pneumatics: + org.usfirst.frc.team449.robot.subsystem.singleImplementation.pneumatics.Pneumatics: + '@id': pneumatics + nodeID: 15 +oi: + org.usfirst.frc.team449.robot.oi.unidirectional.arcade.OIArcadeWithDPad: + '@id': oi + gamepad: + org.usfirst.frc.team449.robot.jacksonWrappers.MappedJoystick: + '@id': driverGamepad + port: 1 + rotThrottle: + org.usfirst.frc.team449.robot.oi.throttles.ThrottleDeadbanded: + &rotThrottle + '@id': rotThrottle + stick: driverGamepad + axis: 0 + smoothingTimeSecs: 0.04 + deadband: 0.05 + inverted: false + fwdThrottle: + org.usfirst.frc.team449.robot.oi.throttles.ThrottleDeadbanded: + <<: *rotThrottle + '@id': fwdThrottle + axis: 5 + inverted: true + invertDPad: false + dPadShift: 0.1 + turnInPlaceRotScale: 0.6 + scaleRotByFwdPoly: + '@id': scaleRotByFwdPoly + powerToCoefficientMap: !!map + 0.5: 0.6 + 0: 0.1 +defaultDriveCommand: + org.usfirst.frc.team449.robot.commands.multiInterface.drive.UnidirectionalNavXDefaultDrive: + '@id': defaultDriveCommand + kP: 0.01 + toleranceBuffer: 25 + absoluteTolerance: 1 + maximumOutput: 0.3333 + maxAngularVelToEnterLoop: 1 + driveStraightLoopEntryTimer: + '@id': driveStraightLoopEntryTimer + bufferTimeSeconds: 0.15 + inverted: false + subsystem: + org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonCluster: + drive + oi: + org.usfirst.frc.team449.robot.oi.unidirectional.arcade.OIArcadeWithDPad: + oi +teleopStartupCommand: + org.usfirst.frc.team449.robot.commands.general.ParallelCommandGroup: + '@id': startTeleopCommand + commandSet: + - org.usfirst.frc.team449.robot.subsystem.singleImplementation.pneumatics.commands.StartCompressor: + '@id': startCompressor + subsystem: + org.usfirst.frc.team449.robot.subsystem.singleImplementation.pneumatics.Pneumatics: + pneumatics + - org.usfirst.frc.team449.robot.drive.commands.EnableMotors: + '@id': enableMotorsTeleop + subsystem: + org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonClusterShiftable: + drive +startupCommand: + org.usfirst.frc.team449.robot.commands.general.RunRunnables: + '@id': runRunnables + runnables: + - org.usfirst.frc.team449.robot.other.UnidirectionalPoseEstimator: + '@id': poseEstimator + subsystem: + org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonCluster: + drive + absolutePosAngleTolerance: 5 +logger: + '@id': logger + subsystems: + - org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonCluster: + drive + - org.usfirst.frc.team449.robot.other.UnidirectionalPoseEstimator: + poseEstimator + loopTimeSecs: 0.02 + eventLogFilename: "/home/lvuser/logs/eventLog-" + telemetryLogFilename: "/home/lvuser/logs/telemetryLog-" +updater: + org.usfirst.frc.team449.robot.other.Updater: + '@id': updater + updatables: + - org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonClusterShiftable: + drive + - org.usfirst.frc.team449.robot.oi.unidirectional.arcade.OIArcadeWithDPad: + oi \ No newline at end of file