Skip to content

Accelerometer Implementation [AARD-1924] #1234

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Open
wants to merge 11 commits into
base: dev
Choose a base branch
from
2 changes: 1 addition & 1 deletion fission/src/systems/simulation/wpilib_brain/SimInput.ts
Original file line number Diff line number Diff line change
Expand Up @@ -6,4 +6,4 @@ export abstract class SimInput {
public get device(): string {
return this._device
}
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -93,7 +93,7 @@ class WPILibBrain extends Brain {
}

this.addSimInput(new SimGyroInput("Test Gyro[1]", this._mechanism))
this.addSimInput(new SimAccelInput("ADXL362[4]", this._mechanism))
this.addSimInput(new SimAccelInput("Test Accel[4]", this._mechanism))
this.addSimInput(new SimDigitalInput("SYN DI[0]", () => random() > 0.5))
this.addSimOutput(new SimDigitalOutput("SYN DO[1]"))
this.addSimInput(new SimAnalogInput("SYN AI[0]", () => random() * 12))
Expand Down
3 changes: 3 additions & 0 deletions simulation/SyntheSimJava/build.gradle
Original file line number Diff line number Diff line change
Expand Up @@ -54,6 +54,9 @@ dependencies {
implementation "edu.wpi.first.wpiutil:wpiutil-java:$WPI_Version"
implementation "edu.wpi.first.hal:hal-java:$WPI_Version"

// NetworkTables
implementation "edu.wpi.first.ntcore:ntcore-java:$WPI_Version"

// REVRobotics
implementation "com.revrobotics.frc:REVLib-java:$REV_Version"

Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,80 @@
package com.autodesk.synthesis;

import edu.wpi.first.hal.SimBoolean;
import edu.wpi.first.hal.SimDevice;
import edu.wpi.first.hal.SimDevice.Direction;
import edu.wpi.first.hal.SimDouble;

/**
* Accelerometer class for easy implementation of documentation-compliant simulation data.
*
* See https://github.com/wpilibsuite/allwpilib/blob/6478ba6e3fa317ee041b8a41e562d925602b6ea4/simulation/halsim_ws_core/doc/hardware_ws_api.md
* for documentation on the WebSocket API Specification.
*/
public class Accel {
private SimDevice m_device;
private SimDouble m_range;
private SimBoolean m_connected;
private SimDouble m_x, m_y, m_z;

/**
* Creates a CANMotor sim device in accordance with the WebSocket API Specification.
*
* @param name Name of the Accel. This is generally the class name of the originating gyro (i.e. "ADXRS450").
* @param deviceId ID of the Gyro.
*/
public Accel(String name, int deviceId) {
m_device = SimDevice.create("Accel:" + name, deviceId);

m_range = m_device.createDouble("range", Direction.kOutput, 0.0);
m_connected = m_device.createBoolean("connected", Direction.kOutput, false);
m_x = m_device.createDouble("x", Direction.kInput, 0);
m_y = m_device.createDouble("y", Direction.kInput, 0);
m_z = m_device.createDouble("z", Direction.kInput, 0);
}

/**
* Set the range of the accel.
*
* @param range Range of the accel
*/
public void setRange(double range) {
if (Double.isNaN(range) || Double.isInfinite(range)) {
range = 0.0;
}

m_range.set(range);
}

public void setConnected(boolean connected) {
m_connected.set(connected);
}

/**
* Get the x position of the accel.
*
* @return x
*/
public double getX() {
return m_x.get();
}

/**
* Get the y position of the accel.
*
* @return y
*/
public double getY() {
return m_y.get();
}

/**
* Get the z position of the accel.
*
* @return z
*/
public double getZ() {
return m_z.get();
}

}
Original file line number Diff line number Diff line change
@@ -0,0 +1,87 @@
package com.autodesk.synthesis.wpilibj;

import com.autodesk.synthesis.Accel;

import edu.wpi.first.wpilibj.SPI;

/**
* ADXL362 wrapper for simulation support.
* Extends the original WPILib ADXL362 accelerometer class to provide
* simulated accelerometer data during simulation.
*/
public class ADXL362 extends edu.wpi.first.wpilibj.ADXL362 {
private Accel m_Accel;

/**
* Constructor for ADXL362 accelerometer.
*
* @param port SPI port the accelerometer is connected to
* @param range The range of the accelerometer
*/
public ADXL362(SPI.Port port, Range range) {
super(port, range);
init("SPI", port.value, range);
}

/**
* Constructor with default range.
*
* @param port SPI port the accelerometer is connected to
*/
public ADXL362(SPI.Port port) {
this(port, Range.k2G);
}

private void init(String commType, int port, Range range) {
this.m_Accel = new Accel("Accel: " + commType, port);
this.m_Accel.setConnected(true);

double rangeValue;
switch (range) {
case k2G:
rangeValue = 2.0;
break;
case k4G:
rangeValue = 4.0;
break;
case k8G:
rangeValue = 8.0;
break;
default:
rangeValue = 2.0;
break;
}

this.m_Accel.setRange(rangeValue);
}

/**
* Get the acceleration in the X-axis.
*
* @return X-axis acceleration in g-forces
*/
@Override
public double getX() {
return m_Accel.getX();
}

/**
* Get the acceleration in the Y-axis.
*
* @return Y-axis acceleration in g-forces
*/
@Override
public double getY() {
return m_Accel.getY();
}

/**
* Get the acceleration in the Z-axis.
*
* @return Z-axis acceleration in g-forces
*/
@Override
public double getZ() {
return m_Accel.getZ();
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,6 @@

import edu.wpi.first.wpilibj.SPI;

import edu.wpi.first.wpilibj.ADXL362;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.motorcontrol.Spark;
import edu.wpi.first.wpilibj.smartdashboard.SendableChooser;
Expand All @@ -21,6 +20,7 @@
import com.autodesk.synthesis.revrobotics.RelativeEncoder;
import com.autodesk.synthesis.revrobotics.SparkAbsoluteEncoder;
import com.kauailabs.navx.frc.AHRS;
import com.autodesk.synthesis.wpilibj.ADXL362;
import com.autodesk.synthesis.CANEncoder;
import com.autodesk.synthesis.ctre.TalonFX;

Expand All @@ -39,7 +39,7 @@ public class Robot extends TimedRobot {
private String m_autoSelected;
private final SendableChooser<String> m_chooser = new SendableChooser<>();

private ADXL362 m_Accelerometer = new ADXL362(SPI.Port.kMXP, ADXL362.Range.k8G);
private ADXL362 m_Accel = new ADXL362(SPI.Port.kMXP, ADXL362.Range.k8G);
private AHRS m_Gyro = new AHRS();

private CANSparkMax m_sparkLeft = new CANSparkMax(1, MotorType.kBrushless);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,6 @@

import edu.wpi.first.wpilibj.SPI;

import edu.wpi.first.wpilibj.ADXL362;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.motorcontrol.Spark;
import edu.wpi.first.wpilibj.smartdashboard.SendableChooser;
Expand All @@ -20,6 +19,7 @@
import com.autodesk.synthesis.revrobotics.CANSparkMax;
import com.kauailabs.navx.frc.AHRS;
import com.autodesk.synthesis.ctre.TalonFX;
import com.autodesk.synthesis.wpilibj.ADXL362;

/**
* The VM is configured to automatically run this class, and to call the
Expand All @@ -41,7 +41,7 @@ public class Robot extends TimedRobot {
private TalonFX m_Talon = new TalonFX(7);
private XboxController m_Controller = new XboxController(0);

private ADXL362 m_Accelerometer = new ADXL362(SPI.Port.kMXP, ADXL362.Range.k8G);
private ADXL362 m_Accel = new ADXL362(SPI.Port.kMXP, ADXL362.Range.k8G);
private AHRS m_Gyro = new AHRS();

private DigitalInput m_DI = new DigitalInput(0);
Expand Down
Loading