[wpilib] Revert move of RomiGyro into main wpilibc/j (#3296)

This reverts commit 69e8d0b65d (#3143).

We haven't released a version with this yet, and plan to make a vendor
library instead.
This commit is contained in:
Peter Johnson
2021-04-10 10:27:44 -07:00
committed by GitHub
parent a1c87e1e15
commit 01d0e12603
6 changed files with 82 additions and 157 deletions

View File

@@ -0,0 +1,124 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.
package edu.wpi.first.wpilibj.examples.romireference.sensors;
import edu.wpi.first.hal.SimDevice;
import edu.wpi.first.hal.SimDevice.Direction;
import edu.wpi.first.hal.SimDouble;
public class RomiGyro {
private SimDouble m_simRateX;
private SimDouble m_simRateY;
private SimDouble m_simRateZ;
private SimDouble m_simAngleX;
private SimDouble m_simAngleY;
private SimDouble m_simAngleZ;
private double m_angleXOffset;
private double m_angleYOffset;
private double m_angleZOffset;
/** Create a new RomiGyro. */
public RomiGyro() {
SimDevice gyroSimDevice = SimDevice.create("Gyro:RomiGyro");
if (gyroSimDevice != null) {
gyroSimDevice.createBoolean("init", Direction.kOutput, true);
m_simRateX = gyroSimDevice.createDouble("rate_x", Direction.kInput, 0.0);
m_simRateY = gyroSimDevice.createDouble("rate_y", Direction.kInput, 0.0);
m_simRateZ = gyroSimDevice.createDouble("rate_z", Direction.kInput, 0.0);
m_simAngleX = gyroSimDevice.createDouble("angle_x", Direction.kInput, 0.0);
m_simAngleY = gyroSimDevice.createDouble("angle_y", Direction.kInput, 0.0);
m_simAngleZ = gyroSimDevice.createDouble("angle_z", Direction.kInput, 0.0);
}
}
/**
* Get the rate of turn in degrees-per-second around the X-axis.
*
* @return rate of turn in degrees-per-second
*/
public double getRateX() {
if (m_simRateX != null) {
return m_simRateX.get();
}
return 0.0;
}
/**
* Get the rate of turn in degrees-per-second around the Y-axis.
*
* @return rate of turn in degrees-per-second
*/
public double getRateY() {
if (m_simRateY != null) {
return m_simRateY.get();
}
return 0.0;
}
/**
* Get the rate of turn in degrees-per-second around the Z-axis.
*
* @return rate of turn in degrees-per-second
*/
public double getRateZ() {
if (m_simRateZ != null) {
return m_simRateZ.get();
}
return 0.0;
}
/**
* Get the currently reported angle around the X-axis.
*
* @return current angle around X-axis in degrees
*/
public double getAngleX() {
if (m_simAngleX != null) {
return m_simAngleX.get() - m_angleXOffset;
}
return 0.0;
}
/**
* Get the currently reported angle around the X-axis.
*
* @return current angle around Y-axis in degrees
*/
public double getAngleY() {
if (m_simAngleY != null) {
return m_simAngleY.get() - m_angleYOffset;
}
return 0.0;
}
/**
* Get the currently reported angle around the Z-axis.
*
* @return current angle around Z-axis in degrees
*/
public double getAngleZ() {
if (m_simAngleZ != null) {
return m_simAngleZ.get() - m_angleZOffset;
}
return 0.0;
}
/** Reset the gyro angles to 0. */
public void reset() {
if (m_simAngleX != null) {
m_angleXOffset = m_simAngleX.get();
m_angleYOffset = m_simAngleY.get();
m_angleZOffset = m_simAngleZ.get();
}
}
}

View File

@@ -8,7 +8,7 @@ import edu.wpi.first.wpilibj.BuiltInAccelerometer;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.Spark;
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
import edu.wpi.first.wpilibj.romi.RomiGyro;
import edu.wpi.first.wpilibj.examples.romireference.sensors.RomiGyro;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
public class Drivetrain extends SubsystemBase {