[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,79 @@
// 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.
#include "sensors/RomiGyro.h"
RomiGyro::RomiGyro() : m_simDevice("Gyro:RomiGyro") {
if (m_simDevice) {
m_simDevice.CreateBoolean("init", hal::SimDevice::kOutput, true);
m_simRateX =
m_simDevice.CreateDouble("rate_x", hal::SimDevice::kInput, 0.0);
m_simRateY =
m_simDevice.CreateDouble("rate_y", hal::SimDevice::kInput, 0.0);
m_simRateZ =
m_simDevice.CreateDouble("rate_z", hal::SimDevice::kInput, 0.0);
m_simAngleX =
m_simDevice.CreateDouble("angle_x", hal::SimDevice::kInput, 0.0);
m_simAngleY =
m_simDevice.CreateDouble("angle_y", hal::SimDevice::kInput, 0.0);
m_simAngleZ =
m_simDevice.CreateDouble("angle_z", hal::SimDevice::kInput, 0.0);
}
}
double RomiGyro::GetRateX() {
if (m_simRateX) {
return m_simRateX.Get();
}
return 0.0;
}
double RomiGyro::GetRateY() {
if (m_simRateY) {
return m_simRateY.Get();
}
return 0.0;
}
double RomiGyro::GetRateZ() {
if (m_simRateZ) {
return m_simRateZ.Get();
}
return 0.0;
}
double RomiGyro::GetAngleX() {
if (m_simAngleX) {
return m_simAngleX.Get() - m_angleXOffset;
}
return 0.0;
}
double RomiGyro::GetAngleY() {
if (m_simAngleY) {
return m_simAngleY.Get() - m_angleYOffset;
}
return 0.0;
}
double RomiGyro::GetAngleZ() {
if (m_simAngleZ) {
return m_simAngleZ.Get() - m_angleZOffset;
}
return 0.0;
}
void RomiGyro::Reset() {
if (m_simAngleX) {
m_angleXOffset = m_simAngleX.Get();
m_angleYOffset = m_simAngleY.Get();
m_angleZOffset = m_simAngleZ.Get();
}
}

View File

@@ -54,3 +54,31 @@ units::meter_t Drivetrain::GetRightDistance() {
units::meter_t Drivetrain::GetAverageDistance() {
return (GetLeftDistance() + GetRightDistance()) / 2.0;
}
double Drivetrain::GetAccelX() {
return m_accelerometer.GetX();
}
double Drivetrain::GetAccelY() {
return m_accelerometer.GetY();
}
double Drivetrain::GetAccelZ() {
return m_accelerometer.GetZ();
}
double Drivetrain::GetGyroAngleX() {
return m_gyro.GetAngleX();
}
double Drivetrain::GetGyroAngleY() {
return m_gyro.GetAngleY();
}
double Drivetrain::GetGyroAngleZ() {
return m_gyro.GetAngleZ();
}
void Drivetrain::ResetGyro() {
m_gyro.Reset();
}

View File

@@ -0,0 +1,60 @@
// 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.
#pragma once
#include <hal/SimDevice.h>
class RomiGyro {
public:
RomiGyro();
/**
* Gets the rate of turn in degrees-per-second around the X-axis
*/
double GetRateX();
/**
* Gets the rate of turn in degrees-per-second around the Y-axis
*/
double GetRateY();
/**
* Gets the rate of turn in degrees-per-second around the Z-axis
*/
double GetRateZ();
/**
* Gets the currently reported angle around the X-axis
*/
double GetAngleX();
/**
* Gets the currently reported angle around the X-axis
*/
double GetAngleY();
/**
* Gets the currently reported angle around the X-axis
*/
double GetAngleZ();
/**
* Resets the gyro
*/
void Reset();
private:
hal::SimDevice m_simDevice;
hal::SimDouble m_simRateX;
hal::SimDouble m_simRateY;
hal::SimDouble m_simRateZ;
hal::SimDouble m_simAngleX;
hal::SimDouble m_simAngleY;
hal::SimDouble m_simAngleZ;
double m_angleXOffset = 0;
double m_angleYOffset = 0;
double m_angleZOffset = 0;
};

View File

@@ -4,12 +4,15 @@
#pragma once
#include <frc/BuiltInAccelerometer.h>
#include <frc/Encoder.h>
#include <frc/Spark.h>
#include <frc/drive/DifferentialDrive.h>
#include <frc2/command/SubsystemBase.h>
#include <units/length.h>
#include "sensors/RomiGyro.h"
class Drivetrain : public frc2::SubsystemBase {
public:
static constexpr double kCountsPerRevolution = 1440.0;
@@ -70,6 +73,41 @@ class Drivetrain : public frc2::SubsystemBase {
*/
units::meter_t GetAverageDistance();
/**
* Returns the acceleration along the X-axis, in Gs.
*/
double GetAccelX();
/**
* Returns the acceleration along the Y-axis, in Gs.
*/
double GetAccelY();
/**
* Returns the acceleration along the Z-axis, in Gs.
*/
double GetAccelZ();
/**
* Returns the current angle of the Romi around the X-axis, in degrees.
*/
double GetGyroAngleX();
/**
* Returns the current angle of the Romi around the Y-axis, in degrees.
*/
double GetGyroAngleY();
/**
* Returns the current angle of the Romi around the Z-axis, in degrees.
*/
double GetGyroAngleZ();
/**
* Reset the gyro.
*/
void ResetGyro();
private:
frc::Spark m_leftMotor{0};
frc::Spark m_rightMotor{1};
@@ -78,4 +116,7 @@ class Drivetrain : public frc2::SubsystemBase {
frc::Encoder m_rightEncoder{6, 7};
frc::DifferentialDrive m_drive{m_leftMotor, m_rightMotor};
RomiGyro m_gyro;
frc::BuiltInAccelerometer m_accelerometer;
};