Skip to content

Commit

Permalink
Fix map errors
Browse files Browse the repository at this point in the history
  • Loading branch information
Noah Gleason committed Nov 3, 2017
1 parent ac456c7 commit aa28f89
Show file tree
Hide file tree
Showing 8 changed files with 144 additions and 10 deletions.
29 changes: 25 additions & 4 deletions RoboRIO/src/main/java/org/usfirst/frc/team449/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -107,6 +107,10 @@ public void robotInit() {
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();
Expand Down Expand Up @@ -179,6 +183,12 @@ public void robotInit() {
*/
@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) {
Expand All @@ -187,9 +197,8 @@ public void teleopInit() {
enabled = true;
}

//Do the startup tasks
driveSubsystem.stopMPProcesses();
doStartupTasks();

if (robotMap.getTeleopStartupCommand() != null) {
robotMap.getTeleopStartupCommand().start();
}
Expand All @@ -208,6 +217,10 @@ public void teleopInit() {
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();
}
Expand All @@ -217,6 +230,12 @@ public void teleopPeriodic() {
*/
@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) {
Expand All @@ -225,8 +244,6 @@ public void autonomousInit() {
enabled = true;
}

//Do startup tasks
doStartupTasks();
if (robotMap.getAutoStartupCommand() != null) {
robotMap.getAutoStartupCommand().start();
}
Expand All @@ -247,6 +264,8 @@ public void autonomousInit() {
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();
}
Expand Down Expand Up @@ -282,6 +301,8 @@ public void testInit() {
@Override
public void disabledPeriodic() {
Clock.updateTime();
//Read sensors
this.robotMap.getUpdater().run();
}

/**
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@
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.buttons.CommandButton;
import org.usfirst.frc.team449.robot.oi.unidirectional.OIUnidirectional;
Expand Down Expand Up @@ -58,6 +59,12 @@ public class RobotMap2017 {
@NotNull
private final Command defaultDriveCommand;

/**
* A runnable that updates cached variables.
*/
@NotNull
private final Runnable updater;

/**
* The climber for boarding the airship. Can be null.
*/
Expand Down Expand Up @@ -215,6 +222,7 @@ public class RobotMap2017 {
* @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 climber The climber for boarding the airship. Can be null.
* @param shooter The multiSubsystem for shooting fuel. Can be null.
* @param camera The cameras on this robot. Can be null.
Expand Down Expand Up @@ -258,6 +266,7 @@ public RobotMap2017(@Nullable List<CommandButton> buttons,
@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 ClimberCurrentLimited climber,
@Nullable LoggingShooter shooter,
@Nullable CameraNetwork camera,
Expand Down Expand Up @@ -289,6 +298,7 @@ public RobotMap2017(@Nullable List<CommandButton> buttons,
this.pneumatics = pneumatics;
this.gearHandler = gearHandler;
this.logger = logger;
this.updater = updater;
this.RIOduinoPort = RIOduinoPort;
this.allianceSwitch = allianceSwitch;
this.dropGearSwitch = dropGearSwitch;
Expand Down Expand Up @@ -542,4 +552,12 @@ public boolean getDoMP() {
public Command getStartupCommand() {
return startupCommand;
}

/**
* @return A runnable that updates cached variables.
*/
@NotNull
public Runnable getUpdater() {
return updater;
}
}
Original file line number Diff line number Diff line change
@@ -1,8 +1,11 @@
package org.usfirst.frc.team449.robot.generalInterfaces.updatable;

import com.fasterxml.jackson.annotation.JsonTypeInfo;

/**
* An interface for any object that caches values.
*/
@JsonTypeInfo(use = JsonTypeInfo.Id.CLASS, include = JsonTypeInfo.As.WRAPPER_OBJECT, property = "@class")
public interface Updatable {

/**
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,42 @@
package org.usfirst.frc.team449.robot.other;

import com.fasterxml.jackson.annotation.JsonCreator;
import com.fasterxml.jackson.annotation.JsonIdentityInfo;
import com.fasterxml.jackson.annotation.JsonProperty;
import com.fasterxml.jackson.annotation.ObjectIdGenerators;
import org.jetbrains.annotations.NotNull;
import org.usfirst.frc.team449.robot.generalInterfaces.updatable.Updatable;
import org.usfirst.frc.team449.robot.jacksonWrappers.MappedRunnable;

/**
* A Runnable for updating cached variables.
*/
@JsonIdentityInfo(generator = ObjectIdGenerators.StringIdGenerator.class)
public class Updater implements MappedRunnable{

/**
* The objects to update.
*/
@NotNull
private final Updatable[] updatables;

/**
* Default constructor
*
* @param updatables The objects to update.
*/
@JsonCreator
public Updater(@NotNull @JsonProperty(required = true) Updatable[] updatables) {
this.updatables = updatables;
}

/**
* Update all the updatables.
*/
@Override
public void run() {
for (Updatable updatable : updatables){
updatable.update();
}
}
}
10 changes: 9 additions & 1 deletion RoboRIO/src/main/resources/ballbasaur_map.yml
Original file line number Diff line number Diff line change
Expand Up @@ -179,4 +179,12 @@ logger:
eliPoseEstimator
loopTimeSecs: 0.02
eventLogFilename: "/home/lvuser/logs/eventLog-"
telemetryLogFilename: "/home/lvuser/logs/telemetryLog-"
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
20 changes: 19 additions & 1 deletion RoboRIO/src/main/resources/calcifer_outreach_map.yml
Original file line number Diff line number Diff line change
Expand Up @@ -354,4 +354,22 @@ buttons:
subsystem:
org.usfirst.frc.team449.robot.subsystem.interfaces.solenoid.SolenoidSimple:
gearHandler
action: WHEN_RELEASED
action: WHEN_RELEASED
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.subsystem.complex.climber.ClimberCurrentLimited:
climber
- org.usfirst.frc.team449.robot.oi.unidirectional.OIOutreach:
oi
- org.usfirst.frc.team449.robot.oi.throttles.ThrottleBasic:
overridenPushGearThrottle
- org.usfirst.frc.team449.robot.oi.throttles.ThrottleBasic:
overridenClimbButtonThrottle
- org.usfirst.frc.team449.robot.oi.throttles.ThrottleBasic:
overridingPushGearThrottle
- org.usfirst.frc.team449.robot.oi.throttles.ThrottleBasic:
overridingClimbButtonThrottle
16 changes: 13 additions & 3 deletions RoboRIO/src/main/resources/nate_map.yml
Original file line number Diff line number Diff line change
Expand Up @@ -662,7 +662,7 @@ buttons:
climber
action: WHEN_PRESSED
- button:
org.usfirst.frc.team449.robot.oi.buttons.TriggerButton:
org.usfirst.frc.team449.robot.oi.buttons.SimpleButton:
climbButton
command:
org.usfirst.frc.team449.robot.subsystem.interfaces.binaryMotor.commands.TurnMotorOffWithRequires:
Expand Down Expand Up @@ -719,12 +719,22 @@ buttons:
'@id': openGearHandlerCommand
action: WHEN_PRESSED
- button:
org.usfirst.frc.team449.robot.oi.buttons.TriggerButton:
org.usfirst.frc.team449.robot.oi.buttons.SimpleButton:
pushGearButton
command:
org.usfirst.frc.team449.robot.subsystem.interfaces.solenoid.commands.SolenoidForward:
'@id': closeGearHandlerCommand
subsystem:
org.usfirst.frc.team449.robot.subsystem.interfaces.solenoid.SolenoidSimple:
gearHandler
action: WHEN_RELEASED
action: WHEN_RELEASED
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.subsystem.complex.climber.ClimberCurrentLimited:
climber
- org.usfirst.frc.team449.robot.oi.unidirectional.arcade.OIArcadeWithDPad:
oi
16 changes: 15 additions & 1 deletion RoboRIO/src/main/resources/naveen_map.yml
Original file line number Diff line number Diff line change
Expand Up @@ -723,4 +723,18 @@ buttons:
subsystem:
org.usfirst.frc.team449.robot.subsystem.interfaces.solenoid.SolenoidSimple:
gearHandler
action: WHEN_RELEASED
action: WHEN_RELEASED
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.subsystem.complex.climber.ClimberCurrentLimited:
climber
- org.usfirst.frc.team449.robot.oi.unidirectional.arcade.OIArcadeWithDPad:
oi
- org.usfirst.frc.team449.robot.oi.throttles.ThrottleBasic:
pushGearThrottle
- org.usfirst.frc.team449.robot.oi.throttles.ThrottleBasic:
climbButtonThrottle

0 comments on commit aa28f89

Please sign in to comment.