[examples] Rename DriveTrain classes to Drivetrain (#3594)

Drivetrain is one word, not two.
This commit is contained in:
Tyler Veness
2021-09-22 13:27:26 -07:00
committed by GitHub
parent 118a27be2f
commit f9e976467f
25 changed files with 74 additions and 74 deletions

View File

@@ -15,7 +15,7 @@
#include "commands/SetWristSetpoint.h"
Autonomous::Autonomous(Claw* claw, Wrist* wrist, Elevator* elevator,
DriveTrain* drivetrain) {
Drivetrain* drivetrain) {
SetName("Autonomous");
AddCommands(
// clang-format off

View File

@@ -8,7 +8,7 @@
#include "Robot.h"
DriveStraight::DriveStraight(double distance, DriveTrain* drivetrain)
DriveStraight::DriveStraight(double distance, Drivetrain* drivetrain)
: frc2::CommandHelper<frc2::PIDCommand, DriveStraight>(
frc2::PIDController(4, 0, 0),
[drivetrain] { return drivetrain->GetDistance(); }, distance,

View File

@@ -8,7 +8,7 @@
#include "Robot.h"
SetDistanceToBox::SetDistanceToBox(double distance, DriveTrain* drivetrain)
SetDistanceToBox::SetDistanceToBox(double distance, Drivetrain* drivetrain)
: frc2::CommandHelper<frc2::PIDCommand, SetDistanceToBox>(
frc2::PIDController(-2, 0, 0),
[drivetrain] { return drivetrain->GetDistanceToObstacle(); },

View File

@@ -9,7 +9,7 @@
#include "Robot.h"
TankDrive::TankDrive(std::function<double()> left,
std::function<double()> right, DriveTrain* drivetrain)
std::function<double()> right, Drivetrain* drivetrain)
: m_left(std::move(left)),
m_right(std::move(right)),
m_drivetrain(drivetrain) {

View File

@@ -2,14 +2,14 @@
// 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 "subsystems/DriveTrain.h"
#include "subsystems/Drivetrain.h"
#include <frc/Joystick.h>
#include <frc/smartdashboard/SmartDashboard.h>
#include <units/length.h>
#include <wpi/numbers>
DriveTrain::DriveTrain() {
Drivetrain::Drivetrain() {
// We need to invert one side of the drivetrain so that positive voltages
// result in both sides moving forward. Depending on how your robot's
// gearbox is constructed, you might have to invert the left side instead.
@@ -30,7 +30,7 @@ DriveTrain::DriveTrain() {
m_rightEncoder.SetDistancePerPulse(units::foot_t{4_in}.to<double>() *
wpi::numbers::pi / 360.0);
#endif
SetName("DriveTrain");
SetName("Drivetrain");
// Let's show everything on the LiveWindow
AddChild("Front_Left Motor", &m_frontLeft);
AddChild("Rear Left Motor", &m_rearLeft);
@@ -42,7 +42,7 @@ DriveTrain::DriveTrain() {
AddChild("Gyro", &m_gyro);
}
void DriveTrain::Log() {
void Drivetrain::Log() {
frc::SmartDashboard::PutNumber("Left Distance", m_leftEncoder.GetDistance());
frc::SmartDashboard::PutNumber("Right Distance",
m_rightEncoder.GetDistance());
@@ -51,29 +51,29 @@ void DriveTrain::Log() {
frc::SmartDashboard::PutNumber("Gyro", m_gyro.GetAngle());
}
void DriveTrain::Drive(double left, double right) {
void Drivetrain::Drive(double left, double right) {
m_robotDrive.TankDrive(left, right);
}
double DriveTrain::GetHeading() {
double Drivetrain::GetHeading() {
return m_gyro.GetAngle();
}
void DriveTrain::Reset() {
void Drivetrain::Reset() {
m_gyro.Reset();
m_leftEncoder.Reset();
m_rightEncoder.Reset();
}
double DriveTrain::GetDistance() {
double Drivetrain::GetDistance() {
return (m_leftEncoder.GetDistance() + m_rightEncoder.GetDistance()) / 2.0;
}
double DriveTrain::GetDistanceToObstacle() {
double Drivetrain::GetDistanceToObstacle() {
// Really meters in simulation since it's a rangefinder...
return m_rangefinder.GetAverageVoltage();
}
void DriveTrain::Periodic() {
void Drivetrain::Periodic() {
Log();
}

View File

@@ -9,7 +9,7 @@
#include "commands/Autonomous.h"
#include "subsystems/Claw.h"
#include "subsystems/DriveTrain.h"
#include "subsystems/Drivetrain.h"
#include "subsystems/Elevator.h"
#include "subsystems/Wrist.h"
@@ -33,7 +33,7 @@ class RobotContainer {
Claw m_claw;
Wrist m_wrist;
Elevator m_elevator;
DriveTrain m_drivetrain;
Drivetrain m_drivetrain;
Autonomous m_autonomousCommand;

View File

@@ -8,7 +8,7 @@
#include <frc2/command/SequentialCommandGroup.h>
#include "subsystems/Claw.h"
#include "subsystems/DriveTrain.h"
#include "subsystems/Drivetrain.h"
#include "subsystems/Elevator.h"
#include "subsystems/Wrist.h"
@@ -19,5 +19,5 @@ class Autonomous
: public frc2::CommandHelper<frc2::SequentialCommandGroup, Autonomous> {
public:
Autonomous(Claw* claw, Wrist* wrist, Elevator* elevator,
DriveTrain* drivetrain);
Drivetrain* drivetrain);
};

View File

@@ -7,7 +7,7 @@
#include <frc2/command/CommandHelper.h>
#include <frc2/command/PIDCommand.h>
#include "subsystems/DriveTrain.h"
#include "subsystems/Drivetrain.h"
/**
* Drive the given distance straight (negative values go backwards).
@@ -18,10 +18,10 @@
class DriveStraight
: public frc2::CommandHelper<frc2::PIDCommand, DriveStraight> {
public:
explicit DriveStraight(double distance, DriveTrain* drivetrain);
explicit DriveStraight(double distance, Drivetrain* drivetrain);
void Initialize() override;
bool IsFinished() override;
private:
DriveTrain* m_drivetrain;
Drivetrain* m_drivetrain;
};

View File

@@ -7,7 +7,7 @@
#include <frc2/command/CommandHelper.h>
#include <frc2/command/PIDCommand.h>
#include "subsystems/DriveTrain.h"
#include "subsystems/Drivetrain.h"
/**
* Drive until the robot is the given distance away from the box. Uses a local
@@ -18,10 +18,10 @@
class SetDistanceToBox
: public frc2::CommandHelper<frc2::PIDCommand, SetDistanceToBox> {
public:
explicit SetDistanceToBox(double distance, DriveTrain* drivetrain);
explicit SetDistanceToBox(double distance, Drivetrain* drivetrain);
void Initialize() override;
bool IsFinished() override;
private:
DriveTrain* m_drivetrain;
Drivetrain* m_drivetrain;
};

View File

@@ -7,7 +7,7 @@
#include <frc2/command/CommandBase.h>
#include <frc2/command/CommandHelper.h>
#include "subsystems/DriveTrain.h"
#include "subsystems/Drivetrain.h"
/**
* Have the robot drive tank style using the PS3 Joystick until interrupted.
@@ -15,7 +15,7 @@
class TankDrive : public frc2::CommandHelper<frc2::CommandBase, TankDrive> {
public:
TankDrive(std::function<double()> left, std::function<double()> right,
DriveTrain* drivetrain);
Drivetrain* drivetrain);
void Execute() override;
bool IsFinished() override;
void End(bool interrupted) override;
@@ -23,5 +23,5 @@ class TankDrive : public frc2::CommandHelper<frc2::CommandBase, TankDrive> {
private:
std::function<double()> m_left;
std::function<double()> m_right;
DriveTrain* m_drivetrain;
Drivetrain* m_drivetrain;
};

View File

@@ -17,13 +17,13 @@ class Joystick;
} // namespace frc
/**
* The DriveTrain subsystem incorporates the sensors and actuators attached to
* The Drivetrain subsystem incorporates the sensors and actuators attached to
* the robots chassis. These include four drive motors, a left and right encoder
* and a gyro.
*/
class DriveTrain : public frc2::SubsystemBase {
class Drivetrain : public frc2::SubsystemBase {
public:
DriveTrain();
Drivetrain();
/**
* The log method puts interesting information to the SmartDashboard.
@@ -31,7 +31,7 @@ class DriveTrain : public frc2::SubsystemBase {
void Log();
/**
* Tank style driving for the DriveTrain.
* Tank style driving for the Drivetrain.
* @param left Speed in range [-1,1]
* @param right Speed in range [-1,1]
*/

View File

@@ -10,7 +10,7 @@
#include <frc/livewindow/LiveWindow.h>
#include <frc/smartdashboard/SmartDashboard.h>
DriveTrain Robot::drivetrain;
Drivetrain Robot::drivetrain;
Pivot Robot::pivot;
Collector Robot::collector;
Shooter Robot::shooter;

View File

@@ -2,7 +2,7 @@
// 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 "subsystems/DriveTrain.h"
#include "subsystems/Drivetrain.h"
#include <frc/Joystick.h>
#include <units/length.h>
@@ -10,7 +10,7 @@
#include "commands/DriveWithJoystick.h"
DriveTrain::DriveTrain() : frc::Subsystem("DriveTrain") {
Drivetrain::Drivetrain() : frc::Subsystem("Drivetrain") {
// AddChild("Front Left CIM", m_frontLeftCIM);
// AddChild("Front Right CIM", m_frontRightCIM);
// AddChild("Back Left CIM", m_backLeftCIM);
@@ -46,26 +46,26 @@ DriveTrain::DriveTrain() : frc::Subsystem("DriveTrain") {
AddChild("Gyro", m_gyro);
}
void DriveTrain::InitDefaultCommand() {
void Drivetrain::InitDefaultCommand() {
SetDefaultCommand(new DriveWithJoystick());
}
void DriveTrain::TankDrive(double leftAxis, double rightAxis) {
void Drivetrain::TankDrive(double leftAxis, double rightAxis) {
m_robotDrive.TankDrive(leftAxis, rightAxis);
}
void DriveTrain::Stop() {
void Drivetrain::Stop() {
m_robotDrive.TankDrive(0.0, 0.0);
}
frc::Encoder& DriveTrain::GetLeftEncoder() {
frc::Encoder& Drivetrain::GetLeftEncoder() {
return m_leftEncoder;
}
frc::Encoder& DriveTrain::GetRightEncoder() {
frc::Encoder& Drivetrain::GetRightEncoder() {
return m_rightEncoder;
}
double DriveTrain::GetAngle() {
double Drivetrain::GetAngle() {
return m_gyro.GetAngle();
}

View File

@@ -12,14 +12,14 @@
#include "commands/DriveAndShootAutonomous.h"
#include "commands/DriveForward.h"
#include "subsystems/Collector.h"
#include "subsystems/DriveTrain.h"
#include "subsystems/Drivetrain.h"
#include "subsystems/Pivot.h"
#include "subsystems/Pneumatics.h"
#include "subsystems/Shooter.h"
class Robot : public frc::TimedRobot {
public:
static DriveTrain drivetrain;
static Drivetrain drivetrain;
static Pivot pivot;
static Collector collector;
static Shooter shooter;

View File

@@ -16,12 +16,12 @@ class Joystick;
} // namespace frc
/**
* The DriveTrain subsystem controls the robot's chassis and reads in
* The Drivetrain subsystem controls the robot's chassis and reads in
* information about it's speed and position.
*/
class DriveTrain : public frc::Subsystem {
class Drivetrain : public frc::Subsystem {
public:
DriveTrain();
Drivetrain();
/**
* When other commands aren't using the drivetrain, allow tank drive