[examples] Add RomiGyro to the Romi Reference example (#3037)

This commit is contained in:
Zhiquan Yeo
2021-01-03 00:59:57 -05:00
committed by GitHub
parent 94f8525721
commit e45a0f6ce2
6 changed files with 399 additions and 0 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

@@ -4,9 +4,11 @@
package edu.wpi.first.wpilibj.examples.romireference.subsystems;
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.examples.romireference.sensors.RomiGyro;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
public class Drivetrain extends SubsystemBase {
@@ -26,6 +28,12 @@ public class Drivetrain extends SubsystemBase {
// Set up the differential drive controller
private final DifferentialDrive m_diffDrive = new DifferentialDrive(m_leftMotor, m_rightMotor);
// Set up the RomiGyro
private final RomiGyro m_gyro = new RomiGyro();
// Set up the BuiltInAccelerometer
private final BuiltInAccelerometer m_accelerometer = new BuiltInAccelerometer();
/** Creates a new Drivetrain. */
public Drivetrain() {
// Use inches as unit for encoder distances
@@ -63,6 +71,65 @@ public class Drivetrain extends SubsystemBase {
return (getLeftDistanceInch() + getRightDistanceInch()) / 2.0;
}
/**
* The acceleration in the X-axis.
*
* @return The acceleration of the Romi along the X-axis in Gs
*/
public double getAccelX() {
return m_accelerometer.getX();
}
/**
* The acceleration in the Y-axis.
*
* @return The acceleration of the Romi along the Y-axis in Gs
*/
public double getAccelY() {
return m_accelerometer.getY();
}
/**
* The acceleration in the Z-axis.
*
* @return The acceleration of the Romi along the Z-axis in Gs
*/
public double getAccelZ() {
return m_accelerometer.getZ();
}
/**
* Current angle of the Romi around the X-axis.
*
* @return The current angle of the Romi in degrees
*/
public double getGyroAngleX() {
return m_gyro.getAngleX();
}
/**
* Current angle of the Romi around the Y-axis.
*
* @return The current angle of the Romi in degrees
*/
public double getGyroAngleY() {
return m_gyro.getAngleY();
}
/**
* Current angle of the Romi around the Z-axis.
*
* @return The current angle of the Romi in degrees
*/
public double getGyroAngleZ() {
return m_gyro.getAngleZ();
}
/** Reset the gyro. */
public void resetGyro() {
m_gyro.reset();
}
@Override
public void periodic() {
// This method will be called once per scheduler run