Cleaned up C++ examples (#672)

This commit is contained in:
Tyler Veness
2017-11-03 13:22:56 -07:00
committed by Peter Johnson
parent 6401aa1fde
commit 45d48d6b5a
69 changed files with 672 additions and 598 deletions

View File

@@ -7,8 +7,6 @@
#include "Autonomous.h"
#include <iostream>
#include "CloseClaw.h"
#include "DriveStraight.h"
#include "Pickup.h"

View File

@@ -11,17 +11,17 @@
CloseClaw::CloseClaw()
: frc::Command("CloseClaw") {
Requires(Robot::claw.get());
Requires(&Robot::claw);
}
// Called just before this Command runs the first time
void CloseClaw::Initialize() {
Robot::claw->Close();
Robot::claw.Close();
}
// Make this return true when this Command no longer needs to run execute()
bool CloseClaw::IsFinished() {
return Robot::claw->IsGripping();
return Robot::claw.IsGripping();
}
// Called once after isFinished returns true
@@ -30,6 +30,6 @@ void CloseClaw::End() {
// fall out
// + there is no need to worry about stalling the motor or crushing the can.
#ifndef SIMULATION
Robot::claw->Stop();
Robot::claw.Stop();
#endif
}

View File

@@ -7,42 +7,38 @@
#include "DriveStraight.h"
#include <PIDController.h>
#include "../Robot.h"
DriveStraight::DriveStraight(double distance) {
Requires(Robot::drivetrain.get());
pid = new frc::PIDController(4, 0, 0, new DriveStraightPIDSource(),
new DriveStraightPIDOutput());
pid->SetAbsoluteTolerance(0.01);
pid->SetSetpoint(distance);
Requires(&Robot::drivetrain);
m_pid.SetAbsoluteTolerance(0.01);
m_pid.SetSetpoint(distance);
}
// Called just before this Command runs the first time
void DriveStraight::Initialize() {
// Get everything in a safe starting state.
Robot::drivetrain->Reset();
pid->Reset();
pid->Enable();
Robot::drivetrain.Reset();
m_pid.Reset();
m_pid.Enable();
}
// Make this return true when this Command no longer needs to run execute()
bool DriveStraight::IsFinished() {
return pid->OnTarget();
return m_pid.OnTarget();
}
// Called once after isFinished returns true
void DriveStraight::End() {
// Stop PID and the wheels
pid->Disable();
Robot::drivetrain->Drive(0, 0);
m_pid.Disable();
Robot::drivetrain.Drive(0, 0);
}
double DriveStraightPIDSource::PIDGet() {
return Robot::drivetrain->GetDistance();
double DriveStraight::DriveStraightPIDSource::PIDGet() {
return Robot::drivetrain.GetDistance();
}
void DriveStraightPIDOutput::PIDWrite(double d) {
Robot::drivetrain->Drive(d, d);
void DriveStraight::DriveStraightPIDOutput::PIDWrite(double d) {
Robot::drivetrain.Drive(d, d);
}

View File

@@ -8,13 +8,10 @@
#pragma once
#include <Commands/Command.h>
#include <PIDController.h>
#include <PIDOutput.h>
#include <PIDSource.h>
namespace frc {
class PIDController;
} // namespace frc
/**
* Drive the given distance straight (negative values go backwards).
* Uses a local PID controller to run a simple PID loop that is only
@@ -28,18 +25,20 @@ public:
bool IsFinished() override;
void End() override;
class DriveStraightPIDSource : public frc::PIDSource {
public:
virtual ~DriveStraightPIDSource() = default;
double PIDGet() override;
};
class DriveStraightPIDOutput : public frc::PIDOutput {
public:
virtual ~DriveStraightPIDOutput() = default;
void PIDWrite(double d) override;
};
private:
frc::PIDController* pid;
};
class DriveStraightPIDSource : public PIDSource {
public:
virtual ~DriveStraightPIDSource() = default;
double PIDGet() override;
};
class DriveStraightPIDOutput : public PIDOutput {
public:
virtual ~DriveStraightPIDOutput() = default;
void PIDWrite(double d) override;
DriveStraightPIDSource m_source;
DriveStraightPIDOutput m_output;
frc::PIDController m_pid{4, 0, 0, &m_source, &m_output};
};

View File

@@ -11,13 +11,13 @@
OpenClaw::OpenClaw()
: frc::Command("OpenClaw") {
Requires(Robot::claw.get());
Requires(&Robot::claw);
SetTimeout(1);
}
// Called just before this Command runs the first time
void OpenClaw::Initialize() {
Robot::claw->Open();
Robot::claw.Open();
}
// Make this return true when this Command no longer needs to run execute()
@@ -27,5 +27,5 @@ bool OpenClaw::IsFinished() {
// Called once after isFinished returns true
void OpenClaw::End() {
Robot::claw->Stop();
Robot::claw.Stop();
}

View File

@@ -12,37 +12,35 @@
#include "../Robot.h"
SetDistanceToBox::SetDistanceToBox(double distance) {
Requires(Robot::drivetrain.get());
pid = new frc::PIDController(-2, 0, 0, new SetDistanceToBoxPIDSource(),
new SetDistanceToBoxPIDOutput());
pid->SetAbsoluteTolerance(0.01);
pid->SetSetpoint(distance);
Requires(&Robot::drivetrain);
m_pid.SetAbsoluteTolerance(0.01);
m_pid.SetSetpoint(distance);
}
// Called just before this Command runs the first time
void SetDistanceToBox::Initialize() {
// Get everything in a safe starting state.
Robot::drivetrain->Reset();
pid->Reset();
pid->Enable();
Robot::drivetrain.Reset();
m_pid.Reset();
m_pid.Enable();
}
// Make this return true when this Command no longer needs to run execute()
bool SetDistanceToBox::IsFinished() {
return pid->OnTarget();
return m_pid.OnTarget();
}
// Called once after isFinished returns true
void SetDistanceToBox::End() {
// Stop PID and the wheels
pid->Disable();
Robot::drivetrain->Drive(0, 0);
m_pid.Disable();
Robot::drivetrain.Drive(0, 0);
}
double SetDistanceToBoxPIDSource::PIDGet() {
return Robot::drivetrain->GetDistanceToObstacle();
double SetDistanceToBox::SetDistanceToBoxPIDSource::PIDGet() {
return Robot::drivetrain.GetDistanceToObstacle();
}
void SetDistanceToBoxPIDOutput::PIDWrite(double d) {
Robot::drivetrain->Drive(d, d);
void SetDistanceToBox::SetDistanceToBoxPIDOutput::PIDWrite(double d) {
Robot::drivetrain.Drive(d, d);
}

View File

@@ -8,13 +8,10 @@
#pragma once
#include <Commands/Command.h>
#include <PIDController.h>
#include <PIDOutput.h>
#include <PIDSource.h>
namespace frc {
class PIDController;
} // namespace frc
/**
* Drive until the robot is the given distance away from the box. Uses a local
* PID controller to run a simple PID loop that is only enabled while this
@@ -28,18 +25,20 @@ public:
bool IsFinished() override;
void End() override;
class SetDistanceToBoxPIDSource : public frc::PIDSource {
public:
virtual ~SetDistanceToBoxPIDSource() = default;
double PIDGet() override;
};
class SetDistanceToBoxPIDOutput : public frc::PIDOutput {
public:
virtual ~SetDistanceToBoxPIDOutput() = default;
void PIDWrite(double d) override;
};
private:
frc::PIDController* pid;
};
class SetDistanceToBoxPIDSource : public frc::PIDSource {
public:
virtual ~SetDistanceToBoxPIDSource() = default;
double PIDGet() override;
};
class SetDistanceToBoxPIDOutput : public frc::PIDOutput {
public:
virtual ~SetDistanceToBoxPIDOutput() = default;
void PIDWrite(double d) override;
SetDistanceToBoxPIDSource m_source;
SetDistanceToBoxPIDOutput m_output;
frc::PIDController m_pid{-2, 0, 0, &m_source, &m_output};
};

View File

@@ -13,17 +13,17 @@
SetElevatorSetpoint::SetElevatorSetpoint(double setpoint)
: frc::Command("SetElevatorSetpoint") {
this->setpoint = setpoint;
Requires(Robot::elevator.get());
m_setpoint = setpoint;
Requires(&Robot::elevator);
}
// Called just before this Command runs the first time
void SetElevatorSetpoint::Initialize() {
Robot::elevator->SetSetpoint(setpoint);
Robot::elevator->Enable();
Robot::elevator.SetSetpoint(m_setpoint);
Robot::elevator.Enable();
}
// Make this return true when this Command no longer needs to run execute()
bool SetElevatorSetpoint::IsFinished() {
return Robot::elevator->OnTarget();
return Robot::elevator.OnTarget();
}

View File

@@ -23,5 +23,5 @@ public:
bool IsFinished() override;
private:
double setpoint;
double m_setpoint;
};

View File

@@ -11,17 +11,17 @@
SetWristSetpoint::SetWristSetpoint(double setpoint)
: frc::Command("SetWristSetpoint") {
this->setpoint = setpoint;
Requires(Robot::wrist.get());
m_setpoint = setpoint;
Requires(&Robot::wrist);
}
// Called just before this Command runs the first time
void SetWristSetpoint::Initialize() {
Robot::wrist->SetSetpoint(setpoint);
Robot::wrist->Enable();
Robot::wrist.SetSetpoint(m_setpoint);
Robot::wrist.Enable();
}
// Make this return true when this Command no longer needs to run execute()
bool SetWristSetpoint::IsFinished() {
return Robot::wrist->OnTarget();
return Robot::wrist.OnTarget();
}

View File

@@ -21,5 +21,5 @@ public:
bool IsFinished() override;
private:
double setpoint;
double m_setpoint;
};

View File

@@ -11,12 +11,13 @@
TankDriveWithJoystick::TankDriveWithJoystick()
: frc::Command("TankDriveWithJoystick") {
Requires(Robot::drivetrain.get());
Requires(&Robot::drivetrain);
}
// Called repeatedly when this Command is scheduled to run
void TankDriveWithJoystick::Execute() {
Robot::drivetrain->Drive(Robot::oi->GetJoystick());
auto& joystick = Robot::oi.GetJoystick();
Robot::drivetrain.Drive(-joystick.GetY(), -joystick.GetRawAxis(4));
}
// Make this return true when this Command no longer needs to run execute()
@@ -26,5 +27,5 @@ bool TankDriveWithJoystick::IsFinished() {
// Called once after isFinished returns true
void TankDriveWithJoystick::End() {
Robot::drivetrain->Drive(0, 0);
Robot::drivetrain.Drive(0, 0);
}

View File

@@ -22,17 +22,17 @@ OI::OI() {
frc::SmartDashboard::PutData("Close Claw", new CloseClaw());
// Connect the buttons to commands
d_up.WhenPressed(new SetElevatorSetpoint(0.2));
d_down.WhenPressed(new SetElevatorSetpoint(-0.2));
d_right.WhenPressed(new CloseClaw());
d_left.WhenPressed(new OpenClaw());
m_dUp.WhenPressed(new SetElevatorSetpoint(0.2));
m_dDown.WhenPressed(new SetElevatorSetpoint(-0.2));
m_dRight.WhenPressed(new CloseClaw());
m_dLeft.WhenPressed(new OpenClaw());
r1.WhenPressed(new PrepareToPickup());
r2.WhenPressed(new Pickup());
l1.WhenPressed(new Place());
l2.WhenPressed(new Autonomous());
m_r1.WhenPressed(new PrepareToPickup());
m_r2.WhenPressed(new Pickup());
m_l1.WhenPressed(new Place());
m_l2.WhenPressed(new Autonomous());
}
frc::Joystick* OI::GetJoystick() {
return &joy;
frc::Joystick& OI::GetJoystick() {
return m_joy;
}

View File

@@ -13,18 +13,18 @@
class OI {
public:
OI();
frc::Joystick* GetJoystick();
frc::Joystick& GetJoystick();
private:
frc::Joystick joy{0};
frc::Joystick m_joy{0};
// Create some buttons
frc::JoystickButton d_up{&joy, 5};
frc::JoystickButton d_right{&joy, 6};
frc::JoystickButton d_down{&joy, 7};
frc::JoystickButton d_left{&joy, 8};
frc::JoystickButton l2{&joy, 9};
frc::JoystickButton r2{&joy, 10};
frc::JoystickButton l1{&joy, 11};
frc::JoystickButton r1{&joy, 12};
frc::JoystickButton m_dUp{&m_joy, 5};
frc::JoystickButton m_dRight{&m_joy, 6};
frc::JoystickButton m_dDown{&m_joy, 7};
frc::JoystickButton m_dLeft{&m_joy, 8};
frc::JoystickButton m_l2{&m_joy, 9};
frc::JoystickButton m_r2{&m_joy, 10};
frc::JoystickButton m_l1{&m_joy, 11};
frc::JoystickButton m_r1{&m_joy, 12};
};

View File

@@ -9,22 +9,22 @@
#include <iostream>
std::shared_ptr<DriveTrain> Robot::drivetrain = std::make_shared<DriveTrain>();
std::shared_ptr<Elevator> Robot::elevator = std::make_shared<Elevator>();
std::shared_ptr<Wrist> Robot::wrist = std::make_shared<Wrist>();
std::shared_ptr<Claw> Robot::claw = std::make_shared<Claw>();
std::unique_ptr<OI> Robot::oi = std::make_unique<OI>();
DriveTrain Robot::drivetrain;
Elevator Robot::elevator;
Wrist Robot::wrist;
Claw Robot::claw;
OI Robot::oi;
void Robot::RobotInit() {
// Show what command your subsystem is running on the SmartDashboard
frc::SmartDashboard::PutData(drivetrain.get());
frc::SmartDashboard::PutData(elevator.get());
frc::SmartDashboard::PutData(wrist.get());
frc::SmartDashboard::PutData(claw.get());
frc::SmartDashboard::PutData(&drivetrain);
frc::SmartDashboard::PutData(&elevator);
frc::SmartDashboard::PutData(&wrist);
frc::SmartDashboard::PutData(&claw);
}
void Robot::AutonomousInit() {
autonomousCommand.Start();
m_autonomousCommand.Start();
std::cout << "Starting Auto" << std::endl;
}
@@ -37,7 +37,7 @@ void Robot::TeleopInit() {
// teleop starts running. If you want the autonomous to
// continue until interrupted by another command, remove
// this line or comment it out.
autonomousCommand.Cancel();
m_autonomousCommand.Cancel();
std::cout << "Starting Teleop" << std::endl;
}
@@ -46,7 +46,7 @@ void Robot::TeleopPeriodic() {
}
void Robot::TestPeriodic() {
lw->Run();
m_lw.Run();
}
START_ROBOT_CLASS(Robot)

View File

@@ -7,8 +7,6 @@
#pragma once
#include <memory>
#include <Commands/Command.h>
#include <IterativeRobot.h>
#include <LiveWindow/LiveWindow.h>
@@ -22,15 +20,15 @@
class Robot : public frc::IterativeRobot {
public:
static std::shared_ptr<DriveTrain> drivetrain;
static std::shared_ptr<Elevator> elevator;
static std::shared_ptr<Wrist> wrist;
static std::shared_ptr<Claw> claw;
static std::unique_ptr<OI> oi;
static DriveTrain drivetrain;
static Elevator elevator;
static Wrist wrist;
static Claw claw;
static OI oi;
private:
Autonomous autonomousCommand;
frc::LiveWindow* lw = frc::LiveWindow::GetInstance();
Autonomous m_autonomousCommand;
frc::LiveWindow& m_lw = *frc::LiveWindow::GetInstance();
void RobotInit() override;
void AutonomousInit() override;

View File

@@ -18,19 +18,19 @@ Claw::Claw()
void Claw::InitDefaultCommand() {}
void Claw::Open() {
motor.Set(-1);
m_motor.Set(-1);
}
void Claw::Close() {
motor.Set(1);
m_motor.Set(1);
}
void Claw::Stop() {
motor.Set(0);
m_motor.Set(0);
}
bool Claw::IsGripping() {
return contact.Get();
return m_contact.Get();
}
void Claw::Log() {}

View File

@@ -9,7 +9,7 @@
#include <Commands/Subsystem.h>
#include <DigitalInput.h>
#include <Victor.h>
#include <Spark.h>
/**
* The claw subsystem is a simple system with a motor for opening and closing.
@@ -46,6 +46,6 @@ public:
void Log();
private:
frc::Victor motor{7};
frc::DigitalInput contact{5};
frc::Spark m_motor{7};
frc::DigitalInput m_contact{5};
};

View File

@@ -20,36 +20,36 @@ DriveTrain::DriveTrain()
// simulate 360 tick encoders. This if statement allows for the
// real robot to handle this difference in devices.
#ifndef SIMULATION
leftEncoder.SetDistancePerPulse(0.042);
rightEncoder.SetDistancePerPulse(0.042);
m_leftEncoder.SetDistancePerPulse(0.042);
m_rightEncoder.SetDistancePerPulse(0.042);
#else
// Circumference in ft = 4in/12(in/ft)*PI
leftEncoder.SetDistancePerPulse(
m_leftEncoder.SetDistancePerPulse(
static_cast<double>(4.0 / 12.0 * M_PI) / 360.0);
rightEncoder.SetDistancePerPulse(
m_rightEncoder.SetDistancePerPulse(
static_cast<double>(4.0 / 12.0 * M_PI) / 360.0);
#endif
// Let's show everything on the LiveWindow
// frc::LiveWindow::GetInstance()->AddActuator("Drive Train",
// "Front_Left Motor", &frontLeft);
// "Front_Left Motor", &m_frontLeft);
// frc::LiveWindow::GetInstance()->AddActuator("Drive Train",
// "Rear Left Motor", &rearLeft);
// "Rear Left Motor", &m_rearLeft);
// frc::LiveWindow::GetInstance()->AddActuator("Drive Train",
// "Front Right Motor", &frontRight);
// "Front Right Motor", &m_frontRight);
// frc::LiveWindow::GetInstance()->AddActuator("Drive Train",
// "Rear Right Motor", &rearRight);
// "Rear Right Motor", &m_rearRight);
// frc::LiveWindow::GetInstance()->AddSensor("Drive Train", "Left
// Encoder",
// &leftEncoder);
// &m_leftEncoder);
// frc::LiveWindow::GetInstance()->AddSensor("Drive Train", "Right
// Encoder",
// &rightEncoder);
// &m_rightEncoder);
// frc::LiveWindow::GetInstance()->AddSensor("Drive Train",
// "Rangefinder",
// &rangefinder);
// &m_rangefinder);
// frc::LiveWindow::GetInstance()->AddSensor("Drive Train", "Gyro",
// &gyro);
// &m_gyro);
}
/**
@@ -65,37 +65,34 @@ void DriveTrain::InitDefaultCommand() {
*/
void DriveTrain::Log() {
frc::SmartDashboard::PutNumber(
"Left Distance", leftEncoder.GetDistance());
"Left Distance", m_leftEncoder.GetDistance());
frc::SmartDashboard::PutNumber(
"Right Distance", rightEncoder.GetDistance());
frc::SmartDashboard::PutNumber("Left Speed", leftEncoder.GetRate());
frc::SmartDashboard::PutNumber("Right Speed", rightEncoder.GetRate());
frc::SmartDashboard::PutNumber("Gyro", gyro.GetAngle());
"Right Distance", m_rightEncoder.GetDistance());
frc::SmartDashboard::PutNumber("Left Speed", m_leftEncoder.GetRate());
frc::SmartDashboard::PutNumber("Right Speed", m_rightEncoder.GetRate());
frc::SmartDashboard::PutNumber("Gyro", m_gyro.GetAngle());
}
void DriveTrain::Drive(double left, double right) {
drive.TankDrive(left, right);
}
void DriveTrain::Drive(frc::Joystick* joy) {
Drive(-joy->GetY(), -joy->GetRawAxis(4));
m_robotDrive.TankDrive(left, right);
}
double DriveTrain::GetHeading() {
return gyro.GetAngle();
return m_gyro.GetAngle();
}
void DriveTrain::Reset() {
gyro.Reset();
leftEncoder.Reset();
rightEncoder.Reset();
m_gyro.Reset();
m_leftEncoder.Reset();
m_rightEncoder.Reset();
}
double DriveTrain::GetDistance() {
return (leftEncoder.GetDistance() + rightEncoder.GetDistance()) / 2;
return (m_leftEncoder.GetDistance() + m_rightEncoder.GetDistance())
/ 2.0;
}
double DriveTrain::GetDistanceToObstacle() {
// Really meters in simulation since it's a rangefinder...
return rangefinder.GetAverageVoltage();
return m_rangefinder.GetAverageVoltage();
}

View File

@@ -10,9 +10,10 @@
#include <AnalogGyro.h>
#include <AnalogInput.h>
#include <Commands/Subsystem.h>
#include <Drive/DifferentialDrive.h>
#include <Encoder.h>
#include <RobotDrive.h>
#include <Talon.h>
#include <Spark.h>
#include <SpeedControllerGroup.h>
namespace frc {
class Joystick;
@@ -45,11 +46,6 @@ public:
*/
void Drive(double left, double right);
/**
* @param joy The ps3 style joystick to use to drive tank style.
*/
void Drive(frc::Joystick* joy);
/**
* @return The robots heading in degrees.
*/
@@ -71,13 +67,18 @@ public:
double GetDistanceToObstacle();
private:
frc::Talon frontLeft{1};
frc::Talon rearLeft{2};
frc::Talon frontRight{3};
frc::Talon rearRight{4};
frc::RobotDrive drive{frontLeft, rearLeft, frontRight, rearRight};
frc::Encoder leftEncoder{1, 2};
frc::Encoder rightEncoder{3, 4};
frc::AnalogInput rangefinder{6};
frc::AnalogGyro gyro{1};
frc::Spark m_frontLeft{1};
frc::Spark m_rearLeft{2};
frc::SpeedControllerGroup m_left{m_frontLeft, m_rearLeft};
frc::Spark m_frontRight{3};
frc::Spark m_rearRight{4};
frc::SpeedControllerGroup m_right{m_frontRight, m_rearRight};
frc::DifferentialDrive m_robotDrive{m_left, m_right};
frc::Encoder m_leftEncoder{1, 2};
frc::Encoder m_rightEncoder{3, 4};
frc::AnalogInput m_rangefinder{6};
frc::AnalogGyro m_gyro{1};
};

View File

@@ -19,8 +19,8 @@ Elevator::Elevator()
// Let's show everything on the LiveWindow
// frc::LiveWindow::GetInstance()->AddActuator("Elevator", "Motor",
// &motor);
// frc::LiveWindow::GetInstance()->AddSensor("Elevator", "Pot", &pot);
// &m_motor);
// frc::LiveWindow::GetInstance()->AddSensor("Elevator", "Pot", &m_pot);
// frc::LiveWindow::GetInstance()->AddActuator("Elevator", "PID",
// GetPIDController());
}
@@ -28,13 +28,13 @@ Elevator::Elevator()
void Elevator::InitDefaultCommand() {}
void Elevator::Log() {
// frc::SmartDashboard::PutData("Wrist Pot", &pot);
// frc::SmartDashboard::PutData("Wrist Pot", &m_pot);
}
double Elevator::ReturnPIDInput() {
return pot.Get();
return m_pot.Get();
}
void Elevator::UsePIDOutput(double d) {
motor.Set(d);
m_motor.Set(d);
}

View File

@@ -9,7 +9,7 @@
#include <AnalogPotentiometer.h>
#include <Commands/PIDSubsystem.h>
#include <Victor.h>
#include <Spark.h>
/**
* The elevator subsystem uses PID to go to a given height. Unfortunately, in
@@ -42,14 +42,14 @@ public:
void UsePIDOutput(double d);
private:
frc::Victor motor{5};
frc::Spark m_motor{5};
// Conversion value of potentiometer varies between the real world and
// simulation
#ifndef SIMULATION
frc::AnalogPotentiometer pot{2, -2.0 / 5};
frc::AnalogPotentiometer m_pot{2, -2.0 / 5};
#else
frc::AnalogPotentiometer pot{2}; // Defaults to meters
frc::AnalogPotentiometer m_pot{2}; // Defaults to meters
#endif
static constexpr double kP_real = 4;

View File

@@ -28,13 +28,13 @@ Wrist::Wrist()
void Wrist::InitDefaultCommand() {}
void Wrist::Log() {
// frc::SmartDashboard::PutData("Wrist Angle", &pot);
// frc::SmartDashboard::PutData("Wrist Angle", &m_pot);
}
double Wrist::ReturnPIDInput() {
return pot.Get();
return m_pot.Get();
}
void Wrist::UsePIDOutput(double d) {
motor.Set(d);
m_motor.Set(d);
}

View File

@@ -9,7 +9,7 @@
#include <AnalogPotentiometer.h>
#include <Commands/PIDSubsystem.h>
#include <Victor.h>
#include <Spark.h>
/**
* The wrist subsystem is like the elevator, but with a rotational joint instead
@@ -40,14 +40,14 @@ public:
void UsePIDOutput(double d) override;
private:
frc::Victor motor{6};
frc::Spark m_motor{6};
// Conversion value of potentiometer varies between the real world and
// simulation
#ifndef SIMULATION
frc::AnalogPotentiometer pot{3, -270.0 / 5};
frc::AnalogPotentiometer m_pot{3, -270.0 / 5};
#else
frc::AnalogPotentiometer pot{3}; // Defaults to degrees
frc::AnalogPotentiometer m_pot{3}; // Defaults to degrees
#endif
static constexpr double kP_real = 1;