mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-21 01:01:43 +00:00
@@ -45,6 +45,7 @@ public class ADXRS450_Gyro extends GyroBase implements Gyro, PIDSource, Sendable
|
||||
private static final int kSNLowRegister = 0x10;
|
||||
|
||||
private SPI m_spi;
|
||||
private SPI.Port m_port;
|
||||
|
||||
private SimDevice m_simDevice;
|
||||
private SimBoolean m_simConnected;
|
||||
@@ -65,6 +66,7 @@ public class ADXRS450_Gyro extends GyroBase implements Gyro, PIDSource, Sendable
|
||||
*/
|
||||
public ADXRS450_Gyro(SPI.Port port) {
|
||||
m_spi = new SPI(port);
|
||||
m_port = port;
|
||||
|
||||
// simulation
|
||||
m_simDevice = SimDevice.create("ADXRS450_Gyro", port.value);
|
||||
@@ -129,6 +131,15 @@ public class ADXRS450_Gyro extends GyroBase implements Gyro, PIDSource, Sendable
|
||||
m_spi.resetAccumulator();
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the SPI port number.
|
||||
*
|
||||
* @return The SPI port number.
|
||||
*/
|
||||
public int getPort() {
|
||||
return m_port.value;
|
||||
}
|
||||
|
||||
private boolean calcParity(int value) {
|
||||
boolean parity = false;
|
||||
while (value != 0) {
|
||||
|
||||
@@ -0,0 +1,49 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2020 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
package edu.wpi.first.wpilibj.simulation;
|
||||
|
||||
import edu.wpi.first.hal.SimDouble;
|
||||
import edu.wpi.first.wpilibj.ADXRS450_Gyro;
|
||||
|
||||
/**
|
||||
* Class to control a simulated ADXRS450 gyroscope.
|
||||
*/
|
||||
@SuppressWarnings("TypeName")
|
||||
public class ADXRS450_GyroSim {
|
||||
private final SimDouble m_simAngle;
|
||||
private final SimDouble m_simRate;
|
||||
|
||||
/**
|
||||
* Constructs from an ADXRS450_Gyro object.
|
||||
*
|
||||
* @param gyro ADXRS450_Gyro to simulate
|
||||
*/
|
||||
public ADXRS450_GyroSim(ADXRS450_Gyro gyro) {
|
||||
SimDeviceSim wrappedSimDevice = new SimDeviceSim("ADXRS450_Gyro" + "[" + gyro.getPort() + "]");
|
||||
m_simAngle = wrappedSimDevice.getDouble("Angle");
|
||||
m_simRate = wrappedSimDevice.getDouble("Rate");
|
||||
}
|
||||
|
||||
/**
|
||||
* Sets the angle in degrees (clockwise positive).
|
||||
*
|
||||
* @param angleDegrees The angle.
|
||||
*/
|
||||
public void setAngle(double angleDegrees) {
|
||||
m_simAngle.set(angleDegrees);
|
||||
}
|
||||
|
||||
/**
|
||||
* Sets the angular rate in degrees per second (clockwise positive).
|
||||
*
|
||||
* @param rateDegreesPerSecond The angular rate.
|
||||
*/
|
||||
public void setRate(double rateDegreesPerSecond) {
|
||||
m_simRate.set(rateDegreesPerSecond);
|
||||
}
|
||||
}
|
||||
Reference in New Issue
Block a user