Skip to content
Draft
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
24 changes: 24 additions & 0 deletions .run/Build Robot.run.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,24 @@
<component name="ProjectRunConfigurationManager">
<configuration default="false" name="Build Robot" type="GradleRunConfiguration" factoryName="Gradle">
<ExternalSystemSettings>
<option name="executionName" />
<option name="externalProjectPath" value="$PROJECT_DIR$" />
<option name="externalSystemIdString" value="GRADLE" />
<option name="scriptParameters" value="" />
<option name="taskDescriptions">
<list />
</option>
<option name="taskNames">
<list>
<option value="build" />
</list>
</option>
<option name="vmOptions" />
</ExternalSystemSettings>
<ExternalSystemDebugServerProcess>true</ExternalSystemDebugServerProcess>
<ExternalSystemReattachDebugProcess>true</ExternalSystemReattachDebugProcess>
<DebugAllEnabled>false</DebugAllEnabled>
<RunAsTest>false</RunAsTest>
<method v="2" />
</configuration>
</component>
9 changes: 8 additions & 1 deletion .vscode/settings.json
Original file line number Diff line number Diff line change
Expand Up @@ -15,5 +15,12 @@
"coverage-gutters.coverageFileNames": [
"jacocoTestReport.xml"
],
"java.jdt.ls.vmargs": "-XX:+UseParallelGC -XX:GCTimeRatio=4 -XX:AdaptiveSizePolicyWeight=90 -Dsun.zip.disableMemoryMapping=true -Xmx2G -Xms100m"
"java.jdt.ls.vmargs": "-XX:+UseParallelGC -XX:GCTimeRatio=4 -XX:AdaptiveSizePolicyWeight=90 -Dsun.zip.disableMemoryMapping=true -Xmx2G -Xms100m",
"files.watcherExclude": {
"**/target": true
},
"workbench.colorCustomizations": {
"minimap.background": "#00000000",
"scrollbar.shadow": "#00000000"
}
}
6 changes: 4 additions & 2 deletions src/main/java/edu/wpi/first/wpilibj/MockDigitalInput.java
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@
import dagger.assisted.AssistedFactory;
import dagger.assisted.AssistedInject;

import xbot.common.command.DataFrameRegistry;
import xbot.common.controls.io_inputs.XDigitalInputs;
import xbot.common.controls.sensors.XDigitalInput;
import xbot.common.injection.DevicePolice;
Expand All @@ -29,8 +30,9 @@ public abstract MockDigitalInput create(
public MockDigitalInput(
@Assisted("info") DeviceInfo info,
@Assisted("owningSystemPrefix") String owningSystemPrefix,
DevicePolice police) {
super(police, info, owningSystemPrefix);
DevicePolice police,
DataFrameRegistry dataFrameRegistry) {
super(police, info, owningSystemPrefix, dataFrameRegistry);
this.channel = info.channel;
}

Expand Down
6 changes: 3 additions & 3 deletions src/main/java/edu/wpi/first/wpilibj/MockServo.java
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
import dagger.assisted.Assisted;
import dagger.assisted.AssistedFactory;
import dagger.assisted.AssistedInject;

import xbot.common.command.DataFrameRegistry;
import xbot.common.controls.actuators.XServo;
import xbot.common.injection.DevicePolice;

Expand All @@ -17,8 +17,8 @@ public abstract static class MockServoFactory implements XServoFactory {
}

@AssistedInject
public MockServo(@Assisted("channel") int channel, @Assisted("name") String name, DevicePolice police) {
super(channel, name, police);
public MockServo(@Assisted("channel") int channel, @Assisted("name") String name, DevicePolice police, DataFrameRegistry dataFrameRegistry) {
super(channel, name, police, dataFrameRegistry);
}

@Override
Expand Down
19 changes: 14 additions & 5 deletions src/main/java/xbot/common/command/BaseRobot.java
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,6 @@
import org.littletonrobotics.junction.wpilog.WPILOGWriter;

import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.PowerDistribution;
import edu.wpi.first.wpilibj.RobotController;
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
Expand Down Expand Up @@ -49,9 +48,10 @@ public abstract class BaseRobot extends LoggedRobot {
protected AutonomousCommandSelector autonomousCommandSelector;

protected WebotsClient webots;

protected DevicePolice devicePolice;
protected SimulationPayloadDistributor simulationPayloadDistributor;

protected DataFrameRegistry deviceDataFrameRegistry;
protected List<DataFrameRefreshable> dataFrameRefreshables = new ArrayList<>();

boolean forceWebots = true; // TODO: figure out a better way to swap between simulation and replay.
Expand Down Expand Up @@ -124,6 +124,8 @@ public void robotInit() {
PropertyFactory pf = injectorComponent.propertyFactory();

devicePolice = injectorComponent.devicePolice();
deviceDataFrameRegistry = injectorComponent.dataFrameRegistry();

if (forceWebots) {
simulationPayloadDistributor = injectorComponent.simulationPayloadDistributor();
}
Expand Down Expand Up @@ -261,9 +263,7 @@ protected void sharedPeriodic() {

// Then, refresh any Subsystem or other components that implement DataFrameRefreshable.
double dataFrameStart = getPerformanceTimestampInMs();
for (DataFrameRefreshable refreshable : dataFrameRefreshables) {
refreshable.refreshDataFrame();
}
refreshAllDataFrames();
double dataFrameEnd = getPerformanceTimestampInMs();
Logger.recordOutput("RefreshDevicesMs", dataFrameEnd - dataFrameStart);

Expand All @@ -275,6 +275,15 @@ protected void sharedPeriodic() {
outsidePeriodicStart = getPerformanceTimestampInMs();
}

public void refreshAllDataFrames() {
// all devices are refreshed first, order doesn't matter
deviceDataFrameRegistry.refreshAll();

// other things like subsystems refreshed here, they should be done in order
for (DataFrameRefreshable refreshable : dataFrameRefreshables) {
refreshable.refreshDataFrame();
}
}

@Override
public void simulationInit() {
Expand Down
19 changes: 2 additions & 17 deletions src/main/java/xbot/common/command/BaseSubsystem.java
Original file line number Diff line number Diff line change
@@ -1,23 +1,19 @@
package xbot.common.command;

import java.util.ArrayList;
import java.util.List;

import org.apache.logging.log4j.LogManager;
import org.apache.logging.log4j.Logger;

import edu.wpi.first.wpilibj2.command.SubsystemBase;
import xbot.common.advantage.AKitLogger;
import xbot.common.advantage.DataFrameRefreshable;
import xbot.common.properties.IPropertySupport;

public abstract class BaseSubsystem extends SubsystemBase implements IPropertySupport, DataFrameRefreshable {
public abstract class BaseSubsystem extends SubsystemBase implements IPropertySupport {

protected final Logger log;
protected final AKitLogger aKitLog;
protected final List<DataFrameRefreshable> dataFrameRefreshables = new ArrayList<>();

public BaseSubsystem() {
super();
log = LogManager.getLogger(this.getName());
aKitLog = new AKitLogger(this);
}
Expand All @@ -26,10 +22,6 @@ public String getPrefix() {
return this.getName() + "/";
}

protected void registerDataFrameRefreshable(DataFrameRefreshable refreshable) {
dataFrameRefreshables.add(refreshable);
}

/**
* This method is called on each {@link edu.wpi.first.wpilibj2.command.CommandScheduler} loop.
* @apiNote Subsystem periodic() methods are not executed in a predictable order.
Expand All @@ -40,11 +32,4 @@ protected void registerDataFrameRefreshable(DataFrameRefreshable refreshable) {
public void periodic() {
super.periodic();
}

@Override
public void refreshDataFrame() {
for (DataFrameRefreshable refreshable : dataFrameRefreshables) {
refreshable.refreshDataFrame();
}
}
}
33 changes: 33 additions & 0 deletions src/main/java/xbot/common/command/DataFrameRegistry.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,33 @@
package xbot.common.command;

import java.util.ArrayList;
import java.util.List;

import javax.inject.Inject;
import javax.inject.Singleton;

import xbot.common.advantage.DataFrameRefreshable;

/**
* A registry for components that implement {@link DataFrameRefreshable}, which allows them to be refreshed on a regular basis by the {@link BaseRobot}.
*/
@Singleton
public final class DataFrameRegistry {
private final List<DataFrameRefreshable> refreshables = new ArrayList<>();

@Inject
public DataFrameRegistry() {}

public void register(DataFrameRefreshable refreshable) {
if (refreshables.contains(refreshable)) {
return;
}
refreshables.add(refreshable);
}

public void refreshAll() {
for (DataFrameRefreshable refreshable : refreshables) {
refreshable.refreshDataFrame();
}
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@
import org.littletonrobotics.junction.Logger;

import xbot.common.advantage.DataFrameRefreshable;
import xbot.common.command.DataFrameRegistry;
import xbot.common.controls.io_inputs.XCANMotorControllerInputs;
import xbot.common.controls.io_inputs.XCANMotorControllerInputsAutoLogged;
import xbot.common.injection.DevicePolice;
Expand Down Expand Up @@ -135,7 +136,8 @@ protected XCANMotorController(
PropertyFactory propertyFactory,
DevicePolice police,
String pidPropertyPrefix,
XCANMotorControllerPIDProperties defaultPIDProperties
XCANMotorControllerPIDProperties defaultPIDProperties,
DataFrameRegistry dataFrameRegistry
) {
this.busId = info.busId();
this.deviceId = info.deviceId();
Expand Down Expand Up @@ -189,6 +191,8 @@ protected XCANMotorController(
}
this.propertyFactory.setPrefix(this.defaultPropertyPrefix);
}

dataFrameRegistry.register(this);
}

public abstract void setConfiguration(CANMotorControllerOutputConfig outputConfig);
Expand Down
4 changes: 3 additions & 1 deletion src/main/java/xbot/common/controls/actuators/XServo.java
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,7 @@

import org.littletonrobotics.junction.Logger;
import xbot.common.advantage.DataFrameRefreshable;
import xbot.common.command.DataFrameRegistry;
import xbot.common.controls.XBaseIO;
import xbot.common.injection.DevicePolice;
import xbot.common.injection.DevicePolice.DeviceType;
Expand Down Expand Up @@ -32,10 +33,11 @@ default XServo create(int channel) {
* @param name The name of the servo for logging.
* @param police The device police to register the servo with.
*/
protected XServo(int channel, String name, DevicePolice police) {
protected XServo(int channel, String name, DevicePolice police, DataFrameRegistry dataFrameRegistry) {
this.channel = channel;
this.name = name;
police.registerDevice(DeviceType.PWM, channel, this);
dataFrameRegistry.register(this);
}

/**
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@
import edu.wpi.first.units.measure.Time;
import edu.wpi.first.units.measure.Velocity;
import edu.wpi.first.units.measure.Voltage;
import xbot.common.command.DataFrameRegistry;
import xbot.common.controls.actuators.XCANMotorController;
import xbot.common.controls.actuators.XCANMotorControllerPIDProperties;
import xbot.common.controls.io_inputs.XCANMotorControllerInputs;
Expand Down Expand Up @@ -74,9 +75,10 @@ public MockCANMotorController(
PropertyFactory propertyFactory,
DevicePolice police,
@Assisted("pidPropertyPrefix") String pidPropertyPrefix,
@Assisted("defaultPIDProperties") XCANMotorControllerPIDProperties defaultPIDProperties
@Assisted("defaultPIDProperties") XCANMotorControllerPIDProperties defaultPIDProperties,
DataFrameRegistry dataFrameRegistry
) {
super(info, owningSystemPrefix, propertyFactory, police, pidPropertyPrefix, defaultPIDProperties);
super(info, owningSystemPrefix, propertyFactory, police, pidPropertyPrefix, defaultPIDProperties, dataFrameRegistry);
}

@Override
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@
import edu.wpi.first.units.measure.Voltage;
import org.apache.logging.log4j.LogManager;
import org.apache.logging.log4j.Logger;
import xbot.common.command.DataFrameRegistry;
import xbot.common.controls.actuators.XCANMotorController;
import xbot.common.controls.actuators.XCANMotorControllerPIDProperties;
import xbot.common.controls.io_inputs.XCANMotorControllerInputs;
Expand Down Expand Up @@ -69,9 +70,10 @@ public CANSparkMaxWpiAdapter(
DevicePolice police,
RobotAssertionManager assertionManager,
@Assisted("pidPropertyPrefix") String pidPropertyPrefix,
@Assisted("defaultPIDProperties") XCANMotorControllerPIDProperties defaultPIDProperties
@Assisted("defaultPIDProperties") XCANMotorControllerPIDProperties defaultPIDProperties,
DataFrameRegistry dataFrameRegistry
) {
super(info, owningSystemPrefix, propertyFactory, police, pidPropertyPrefix, defaultPIDProperties);
super(info, owningSystemPrefix, propertyFactory, police, pidPropertyPrefix, defaultPIDProperties, dataFrameRegistry);
this.internalSparkMax = new SparkMax(info.deviceId(), SparkLowLevel.MotorType.kBrushless);
this.assertionManager = assertionManager;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,7 @@
import edu.wpi.first.units.measure.Voltage;
import edu.wpi.first.wpilibj.Alert;
import org.apache.logging.log4j.LogManager;
import xbot.common.command.DataFrameRegistry;
import xbot.common.controls.actuators.XCANMotorController;
import xbot.common.controls.actuators.XCANMotorControllerPIDProperties;
import xbot.common.controls.io_inputs.XCANMotorControllerInputs;
Expand Down Expand Up @@ -77,9 +78,10 @@ public CANTalonFxWpiAdapter(
PropertyFactory propertyFactory,
DevicePolice police,
@Assisted("pidPropertyPrefix") String pidPropertyPrefix,
@Assisted("defaultPIDProperties") XCANMotorControllerPIDProperties defaultPIDProperties
@Assisted("defaultPIDProperties") XCANMotorControllerPIDProperties defaultPIDProperties,
DataFrameRegistry dataFrameRegistry
) {
super(info, owningSystemPrefix, propertyFactory, police, pidPropertyPrefix, defaultPIDProperties);
super(info, owningSystemPrefix, propertyFactory, police, pidPropertyPrefix, defaultPIDProperties, dataFrameRegistry);
this.internalTalonFx = new TalonFX(info.deviceId(), info.busId().toPhoenixCANBus());

this.rotorPositionSignal = this.internalTalonFx.getRotorPosition(false);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
import edu.wpi.first.units.measure.Voltage;
import org.apache.logging.log4j.LogManager;
import org.apache.logging.log4j.Logger;
import xbot.common.command.DataFrameRegistry;
import xbot.common.controls.actuators.XCANMotorController;
import xbot.common.controls.actuators.XCANMotorControllerPIDProperties;
import xbot.common.controls.io_inputs.XCANMotorControllerInputs;
Expand Down Expand Up @@ -57,9 +58,10 @@ public CANVictorSPXWpiAdapter(
DevicePolice police,
RobotAssertionManager assertionManager,
@Assisted("pidPropertyPrefix") String pidPropertyPrefix,
@Assisted("defaultPIDProperties") XCANMotorControllerPIDProperties defaultPIDProperties
@Assisted("defaultPIDProperties") XCANMotorControllerPIDProperties defaultPIDProperties,
DataFrameRegistry dataFrameRegistry
) {
super(info, owningSystemPrefix, propertyFactory, police, pidPropertyPrefix, defaultPIDProperties);
super(info, owningSystemPrefix, propertyFactory, police, pidPropertyPrefix, defaultPIDProperties, dataFrameRegistry);
this.internalVictor = new VictorSPX(info.deviceId());
this.assertionManager = assertionManager;

Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
package xbot.common.controls.actuators.wpi_adapters;

import xbot.common.command.DataFrameRegistry;
import xbot.common.controls.actuators.XServo;
import xbot.common.injection.DevicePolice;
import dagger.assisted.Assisted;
Expand All @@ -18,8 +19,8 @@ public abstract static class ServoWPIAdapterFactory implements XServoFactory {
}

@AssistedInject
public ServoWPIAdapter(@Assisted("channel") int channel, @Assisted("name") String name, DevicePolice police) {
super(channel, name, police);
public ServoWPIAdapter(@Assisted("channel") int channel, @Assisted("name") String name, DevicePolice police, DataFrameRegistry dataFrameRegistry) {
super(channel, name, police, dataFrameRegistry);
this.servo = new Servo(channel);
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@
import org.littletonrobotics.junction.Logger;

import xbot.common.advantage.DataFrameRefreshable;
import xbot.common.command.DataFrameRegistry;
import xbot.common.controls.io_inputs.XAbsoluteEncoderInputs;
import xbot.common.controls.io_inputs.XAbsoluteEncoderInputsAutoLogged;
import xbot.common.injection.electrical_contract.DeviceInfo;
Expand All @@ -19,9 +20,10 @@ public interface XAbsoluteEncoderFactory {
XAbsoluteEncoder create(DeviceInfo deviceInfo, String owningSystemPrefix);
}

public XAbsoluteEncoder(DeviceInfo info) {
public XAbsoluteEncoder(DeviceInfo info, DataFrameRegistry dataFrameRegistry) {
inputs = new XAbsoluteEncoderInputsAutoLogged();
this.info = info;
dataFrameRegistry.register(this);
}

public abstract int getDeviceId();
Expand Down
Loading
Loading