Run wpiformat on merged repo (#1021)

This commit is contained in:
Tyler Veness
2018-05-13 17:09:56 -07:00
committed by Peter Johnson
parent 0babbf317c
commit 6729a7d6b1
481 changed files with 9581 additions and 6828 deletions

View File

@@ -15,17 +15,16 @@
#include "SetDistanceToBox.h"
#include "SetWristSetpoint.h"
Autonomous::Autonomous()
: frc::CommandGroup("Autonomous") {
AddSequential(new PrepareToPickup());
AddSequential(new Pickup());
AddSequential(new SetDistanceToBox(0.10));
// AddSequential(new DriveStraight(4)); // Use Encoders if ultrasonic
// is broken
AddSequential(new Place());
AddSequential(new SetDistanceToBox(0.60));
// AddSequential(new DriveStraight(-2)); // Use Encoders if ultrasonic
// is broken
AddParallel(new SetWristSetpoint(-45));
AddSequential(new CloseClaw());
Autonomous::Autonomous() : frc::CommandGroup("Autonomous") {
AddSequential(new PrepareToPickup());
AddSequential(new Pickup());
AddSequential(new SetDistanceToBox(0.10));
// AddSequential(new DriveStraight(4)); // Use Encoders if ultrasonic
// is broken
AddSequential(new Place());
AddSequential(new SetDistanceToBox(0.60));
// AddSequential(new DriveStraight(-2)); // Use Encoders if ultrasonic
// is broken
AddParallel(new SetWristSetpoint(-45));
AddSequential(new CloseClaw());
}

View File

@@ -13,6 +13,6 @@
* The main autonomous command to pickup and deliver the soda to the box.
*/
class Autonomous : public frc::CommandGroup {
public:
Autonomous();
public:
Autonomous();
};

View File

@@ -9,20 +9,13 @@
#include "../Robot.h"
CloseClaw::CloseClaw()
: frc::Command("CloseClaw") {
Requires(&Robot::claw);
}
CloseClaw::CloseClaw() : frc::Command("CloseClaw") { Requires(&Robot::claw); }
// Called just before this Command runs the first time
void CloseClaw::Initialize() {
Robot::claw.Close();
}
void CloseClaw::Initialize() { Robot::claw.Close(); }
// Make this return true when this Command no longer needs to run execute()
bool CloseClaw::IsFinished() {
return Robot::claw.IsGripping();
}
bool CloseClaw::IsFinished() { return Robot::claw.IsGripping(); }
// Called once after isFinished returns true
void CloseClaw::End() {
@@ -30,6 +23,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

@@ -14,9 +14,9 @@
* motors is BAD!
*/
class CloseClaw : public frc::Command {
public:
CloseClaw();
void Initialize() override;
bool IsFinished() override;
void End() override;
public:
CloseClaw();
void Initialize() override;
bool IsFinished() override;
void End() override;
};

View File

@@ -10,35 +10,33 @@
#include "../Robot.h"
DriveStraight::DriveStraight(double distance) {
Requires(&Robot::drivetrain);
m_pid.SetAbsoluteTolerance(0.01);
m_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();
m_pid.Reset();
m_pid.Enable();
// Get everything in a safe starting state.
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 m_pid.OnTarget();
}
bool DriveStraight::IsFinished() { return m_pid.OnTarget(); }
// Called once after isFinished returns true
void DriveStraight::End() {
// Stop PID and the wheels
m_pid.Disable();
Robot::drivetrain.Drive(0, 0);
// Stop PID and the wheels
m_pid.Disable();
Robot::drivetrain.Drive(0, 0);
}
double DriveStraight::DriveStraightPIDSource::PIDGet() {
return Robot::drivetrain.GetDistance();
return Robot::drivetrain.GetDistance();
}
void DriveStraight::DriveStraightPIDOutput::PIDWrite(double d) {
Robot::drivetrain.Drive(d, d);
Robot::drivetrain.Drive(d, d);
}

View File

@@ -19,26 +19,26 @@
* values of the left and right encoders.
*/
class DriveStraight : public frc::Command {
public:
explicit DriveStraight(double distance);
void Initialize() override;
bool IsFinished() override;
void End() override;
public:
explicit DriveStraight(double distance);
void Initialize() override;
bool IsFinished() override;
void End() override;
class DriveStraightPIDSource : public frc::PIDSource {
public:
virtual ~DriveStraightPIDSource() = default;
double PIDGet() 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;
};
class DriveStraightPIDOutput : public frc::PIDOutput {
public:
virtual ~DriveStraightPIDOutput() = default;
void PIDWrite(double d) override;
};
private:
DriveStraightPIDSource m_source;
DriveStraightPIDOutput m_output;
frc::PIDController m_pid{4, 0, 0, &m_source, &m_output};
private:
DriveStraightPIDSource m_source;
DriveStraightPIDOutput m_output;
frc::PIDController m_pid{4, 0, 0, &m_source, &m_output};
};

View File

@@ -9,23 +9,16 @@
#include "../Robot.h"
OpenClaw::OpenClaw()
: frc::Command("OpenClaw") {
Requires(&Robot::claw);
SetTimeout(1);
OpenClaw::OpenClaw() : frc::Command("OpenClaw") {
Requires(&Robot::claw);
SetTimeout(1);
}
// Called just before this Command runs the first time
void OpenClaw::Initialize() {
Robot::claw.Open();
}
void OpenClaw::Initialize() { Robot::claw.Open(); }
// Make this return true when this Command no longer needs to run execute()
bool OpenClaw::IsFinished() {
return IsTimedOut();
}
bool OpenClaw::IsFinished() { return IsTimedOut(); }
// Called once after isFinished returns true
void OpenClaw::End() {
Robot::claw.Stop();
}
void OpenClaw::End() { Robot::claw.Stop(); }

View File

@@ -14,9 +14,9 @@
* motors is BAD!
*/
class OpenClaw : public frc::Command {
public:
OpenClaw();
void Initialize() override;
bool IsFinished() override;
void End() override;
public:
OpenClaw();
void Initialize() override;
bool IsFinished() override;
void End() override;
};

View File

@@ -11,9 +11,8 @@
#include "SetElevatorSetpoint.h"
#include "SetWristSetpoint.h"
Pickup::Pickup()
: frc::CommandGroup("Pickup") {
AddSequential(new CloseClaw());
AddParallel(new SetWristSetpoint(-45));
AddSequential(new SetElevatorSetpoint(0.25));
Pickup::Pickup() : frc::CommandGroup("Pickup") {
AddSequential(new CloseClaw());
AddParallel(new SetWristSetpoint(-45));
AddSequential(new SetElevatorSetpoint(0.25));
}

View File

@@ -14,6 +14,6 @@
* get it in a safe state to drive around.
*/
class Pickup : public frc::CommandGroup {
public:
Pickup();
public:
Pickup();
};

View File

@@ -11,9 +11,8 @@
#include "SetElevatorSetpoint.h"
#include "SetWristSetpoint.h"
Place::Place()
: frc::CommandGroup("Place") {
AddSequential(new SetElevatorSetpoint(0.25));
AddSequential(new SetWristSetpoint(0));
AddSequential(new OpenClaw());
Place::Place() : frc::CommandGroup("Place") {
AddSequential(new SetElevatorSetpoint(0.25));
AddSequential(new SetWristSetpoint(0));
AddSequential(new OpenClaw());
}

View File

@@ -13,6 +13,6 @@
* Place a held soda can onto the platform.
*/
class Place : public frc::CommandGroup {
public:
Place();
public:
Place();
};

View File

@@ -11,9 +11,8 @@
#include "SetElevatorSetpoint.h"
#include "SetWristSetpoint.h"
PrepareToPickup::PrepareToPickup()
: frc::CommandGroup("PrepareToPickup") {
AddParallel(new OpenClaw());
AddParallel(new SetWristSetpoint(0));
AddSequential(new SetElevatorSetpoint(0));
PrepareToPickup::PrepareToPickup() : frc::CommandGroup("PrepareToPickup") {
AddParallel(new OpenClaw());
AddParallel(new SetWristSetpoint(0));
AddSequential(new SetElevatorSetpoint(0));
}

View File

@@ -13,6 +13,6 @@
* Make sure the robot is in a state to pickup soda cans.
*/
class PrepareToPickup : public frc::CommandGroup {
public:
PrepareToPickup();
public:
PrepareToPickup();
};

View File

@@ -12,35 +12,33 @@
#include "../Robot.h"
SetDistanceToBox::SetDistanceToBox(double distance) {
Requires(&Robot::drivetrain);
m_pid.SetAbsoluteTolerance(0.01);
m_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();
m_pid.Reset();
m_pid.Enable();
// Get everything in a safe starting state.
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 m_pid.OnTarget();
}
bool SetDistanceToBox::IsFinished() { return m_pid.OnTarget(); }
// Called once after isFinished returns true
void SetDistanceToBox::End() {
// Stop PID and the wheels
m_pid.Disable();
Robot::drivetrain.Drive(0, 0);
// Stop PID and the wheels
m_pid.Disable();
Robot::drivetrain.Drive(0, 0);
}
double SetDistanceToBox::SetDistanceToBoxPIDSource::PIDGet() {
return Robot::drivetrain.GetDistanceToObstacle();
return Robot::drivetrain.GetDistanceToObstacle();
}
void SetDistanceToBox::SetDistanceToBoxPIDOutput::PIDWrite(double d) {
Robot::drivetrain.Drive(d, d);
Robot::drivetrain.Drive(d, d);
}

View File

@@ -19,26 +19,26 @@
* encoders.
*/
class SetDistanceToBox : public frc::Command {
public:
explicit SetDistanceToBox(double distance);
void Initialize() override;
bool IsFinished() override;
void End() override;
public:
explicit SetDistanceToBox(double distance);
void Initialize() override;
bool IsFinished() override;
void End() override;
class SetDistanceToBoxPIDSource : public frc::PIDSource {
public:
virtual ~SetDistanceToBoxPIDSource() = default;
double PIDGet() 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;
};
class SetDistanceToBoxPIDOutput : public frc::PIDOutput {
public:
virtual ~SetDistanceToBoxPIDOutput() = default;
void PIDWrite(double d) override;
};
private:
SetDistanceToBoxPIDSource m_source;
SetDistanceToBoxPIDOutput m_output;
frc::PIDController m_pid{-2, 0, 0, &m_source, &m_output};
private:
SetDistanceToBoxPIDSource m_source;
SetDistanceToBoxPIDOutput m_output;
frc::PIDController m_pid{-2, 0, 0, &m_source, &m_output};
};

View File

@@ -13,17 +13,15 @@
SetElevatorSetpoint::SetElevatorSetpoint(double setpoint)
: frc::Command("SetElevatorSetpoint") {
m_setpoint = setpoint;
Requires(&Robot::elevator);
m_setpoint = setpoint;
Requires(&Robot::elevator);
}
// Called just before this Command runs the first time
void SetElevatorSetpoint::Initialize() {
Robot::elevator.SetSetpoint(m_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();
}
bool SetElevatorSetpoint::IsFinished() { return Robot::elevator.OnTarget(); }

View File

@@ -17,11 +17,11 @@
* commands using the elevator should make sure they disable PID!
*/
class SetElevatorSetpoint : public frc::Command {
public:
explicit SetElevatorSetpoint(double setpoint);
void Initialize() override;
bool IsFinished() override;
public:
explicit SetElevatorSetpoint(double setpoint);
void Initialize() override;
bool IsFinished() override;
private:
double m_setpoint;
private:
double m_setpoint;
};

View File

@@ -11,17 +11,15 @@
SetWristSetpoint::SetWristSetpoint(double setpoint)
: frc::Command("SetWristSetpoint") {
m_setpoint = setpoint;
Requires(&Robot::wrist);
m_setpoint = setpoint;
Requires(&Robot::wrist);
}
// Called just before this Command runs the first time
void SetWristSetpoint::Initialize() {
Robot::wrist.SetSetpoint(m_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();
}
bool SetWristSetpoint::IsFinished() { return Robot::wrist.OnTarget(); }

View File

@@ -15,11 +15,11 @@
* Other commands using the wrist should make sure they disable PID!
*/
class SetWristSetpoint : public frc::Command {
public:
explicit SetWristSetpoint(double setpoint);
void Initialize() override;
bool IsFinished() override;
public:
explicit SetWristSetpoint(double setpoint);
void Initialize() override;
bool IsFinished() override;
private:
double m_setpoint;
private:
double m_setpoint;
};

View File

@@ -11,21 +11,17 @@
TankDriveWithJoystick::TankDriveWithJoystick()
: frc::Command("TankDriveWithJoystick") {
Requires(&Robot::drivetrain);
Requires(&Robot::drivetrain);
}
// Called repeatedly when this Command is scheduled to run
void TankDriveWithJoystick::Execute() {
auto& joystick = Robot::oi.GetJoystick();
Robot::drivetrain.Drive(-joystick.GetY(), -joystick.GetRawAxis(4));
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()
bool TankDriveWithJoystick::IsFinished() {
return false;
}
bool TankDriveWithJoystick::IsFinished() { return false; }
// Called once after isFinished returns true
void TankDriveWithJoystick::End() {
Robot::drivetrain.Drive(0, 0);
}
void TankDriveWithJoystick::End() { Robot::drivetrain.Drive(0, 0); }

View File

@@ -13,9 +13,9 @@
* Have the robot drive tank style using the PS3 Joystick until interrupted.
*/
class TankDriveWithJoystick : public frc::Command {
public:
TankDriveWithJoystick();
void Execute() override;
bool IsFinished() override;
void End() override;
public:
TankDriveWithJoystick();
void Execute() override;
bool IsFinished() override;
void End() override;
};

View File

@@ -18,21 +18,19 @@
#include "Commands/SetElevatorSetpoint.h"
OI::OI() {
frc::SmartDashboard::PutData("Open Claw", new OpenClaw());
frc::SmartDashboard::PutData("Close Claw", new CloseClaw());
frc::SmartDashboard::PutData("Open Claw", new OpenClaw());
frc::SmartDashboard::PutData("Close Claw", new CloseClaw());
// Connect the buttons to commands
m_dUp.WhenPressed(new SetElevatorSetpoint(0.2));
m_dDown.WhenPressed(new SetElevatorSetpoint(-0.2));
m_dRight.WhenPressed(new CloseClaw());
m_dLeft.WhenPressed(new OpenClaw());
// Connect the buttons to commands
m_dUp.WhenPressed(new SetElevatorSetpoint(0.2));
m_dDown.WhenPressed(new SetElevatorSetpoint(-0.2));
m_dRight.WhenPressed(new CloseClaw());
m_dLeft.WhenPressed(new OpenClaw());
m_r1.WhenPressed(new PrepareToPickup());
m_r2.WhenPressed(new Pickup());
m_l1.WhenPressed(new Place());
m_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 m_joy;
}
frc::Joystick& OI::GetJoystick() { return m_joy; }

View File

@@ -11,20 +11,20 @@
#include <Joystick.h>
class OI {
public:
OI();
frc::Joystick& GetJoystick();
public:
OI();
frc::Joystick& GetJoystick();
private:
frc::Joystick m_joy{0};
private:
frc::Joystick m_joy{0};
// Create some buttons
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};
// Create some buttons
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

@@ -16,34 +16,29 @@ Claw Robot::claw;
OI Robot::oi;
void Robot::RobotInit() {
// Show what command your subsystem is running on the SmartDashboard
frc::SmartDashboard::PutData(&drivetrain);
frc::SmartDashboard::PutData(&elevator);
frc::SmartDashboard::PutData(&wrist);
frc::SmartDashboard::PutData(&claw);
// Show what command your subsystem is running on the SmartDashboard
frc::SmartDashboard::PutData(&drivetrain);
frc::SmartDashboard::PutData(&elevator);
frc::SmartDashboard::PutData(&wrist);
frc::SmartDashboard::PutData(&claw);
}
void Robot::AutonomousInit() {
m_autonomousCommand.Start();
std::cout << "Starting Auto" << std::endl;
m_autonomousCommand.Start();
std::cout << "Starting Auto" << std::endl;
}
void Robot::AutonomousPeriodic() {
frc::Scheduler::GetInstance()->Run();
}
void Robot::AutonomousPeriodic() { frc::Scheduler::GetInstance()->Run(); }
void Robot::TeleopInit() {
// This makes sure that the autonomous stops running when
// teleop starts running. If you want the autonomous to
// continue until interrupted by another command, remove
// this line or comment it out.
m_autonomousCommand.Cancel();
std::cout << "Starting Teleop" << std::endl;
// This makes sure that the autonomous stops running when teleop starts
// running. If you want the autonomous to continue until interrupted by
// another command, remove this line or comment it out.
m_autonomousCommand.Cancel();
std::cout << "Starting Teleop" << std::endl;
}
void Robot::TeleopPeriodic() {
frc::Scheduler::GetInstance()->Run();
}
void Robot::TeleopPeriodic() { frc::Scheduler::GetInstance()->Run(); }
void Robot::TestPeriodic() {}

View File

@@ -21,21 +21,21 @@
#include "Subsystems/Wrist.h"
class Robot : public frc::IterativeRobot {
public:
static DriveTrain drivetrain;
static Elevator elevator;
static Wrist wrist;
static Claw claw;
static OI oi;
public:
static DriveTrain drivetrain;
static Elevator elevator;
static Wrist wrist;
static Claw claw;
static OI oi;
private:
Autonomous m_autonomousCommand;
frc::LiveWindow& m_lw = *frc::LiveWindow::GetInstance();
private:
Autonomous m_autonomousCommand;
frc::LiveWindow& m_lw = *frc::LiveWindow::GetInstance();
void RobotInit() override;
void AutonomousInit() override;
void AutonomousPeriodic() override;
void TeleopInit() override;
void TeleopPeriodic() override;
void TestPeriodic() override;
void RobotInit() override;
void AutonomousInit() override;
void AutonomousPeriodic() override;
void TeleopInit() override;
void TeleopPeriodic() override;
void TestPeriodic() override;
};

View File

@@ -7,28 +7,19 @@
#include "Claw.h"
Claw::Claw()
: frc::Subsystem("Claw") {
// Let's show everything on the LiveWindow
AddChild("Motor", m_motor);
Claw::Claw() : frc::Subsystem("Claw") {
// Let's show everything on the LiveWindow
AddChild("Motor", m_motor);
}
void Claw::InitDefaultCommand() {}
void Claw::Open() {
m_motor.Set(-1);
}
void Claw::Open() { m_motor.Set(-1); }
void Claw::Close() {
m_motor.Set(1);
}
void Claw::Close() { m_motor.Set(1); }
void Claw::Stop() {
m_motor.Set(0);
}
void Claw::Stop() { m_motor.Set(0); }
bool Claw::IsGripping() {
return m_contact.Get();
}
bool Claw::IsGripping() { return m_contact.Get(); }
void Claw::Log() {}

View File

@@ -17,35 +17,35 @@
* motors don't stall.
*/
class Claw : public frc::Subsystem {
public:
Claw();
public:
Claw();
void InitDefaultCommand() override;
void InitDefaultCommand() override;
/**
* Set the claw motor to move in the open direction.
*/
void Open();
/**
* Set the claw motor to move in the open direction.
*/
void Open();
/**
* Set the claw motor to move in the close direction.
*/
void Close();
/**
* Set the claw motor to move in the close direction.
*/
void Close();
/**
* Stops the claw motor from moving.
*/
void Stop();
/**
* Stops the claw motor from moving.
*/
void Stop();
/**
* Return true when the robot is grabbing an object hard enough
* to trigger the limit switch.
*/
bool IsGripping();
/**
* Return true when the robot is grabbing an object hard enough
* to trigger the limit switch.
*/
bool IsGripping();
void Log();
void Log();
private:
frc::Spark m_motor{7};
frc::DigitalInput m_contact{5};
private:
frc::Spark m_motor{7};
frc::DigitalInput m_contact{5};
};

View File

@@ -12,33 +12,32 @@
#include "../Commands/TankDriveWithJoystick.h"
DriveTrain::DriveTrain()
: frc::Subsystem("DriveTrain") {
DriveTrain::DriveTrain() : frc::Subsystem("DriveTrain") {
// Encoders may measure differently in the real world and in
// simulation. In this example the robot moves 0.042 barleycorns
// per tick in the real world, but the simulated encoders
// simulate 360 tick encoders. This if statement allows for the
// real robot to handle this difference in devices.
#ifndef SIMULATION
m_leftEncoder.SetDistancePerPulse(0.042);
m_rightEncoder.SetDistancePerPulse(0.042);
m_leftEncoder.SetDistancePerPulse(0.042);
m_rightEncoder.SetDistancePerPulse(0.042);
#else
// Circumference in ft = 4in/12(in/ft)*PI
m_leftEncoder.SetDistancePerPulse(
static_cast<double>(4.0 / 12.0 * M_PI) / 360.0);
m_rightEncoder.SetDistancePerPulse(
static_cast<double>(4.0 / 12.0 * M_PI) / 360.0);
// Circumference in ft = 4in/12(in/ft)*PI
m_leftEncoder.SetDistancePerPulse(static_cast<double>(4.0 / 12.0 * M_PI) /
360.0);
m_rightEncoder.SetDistancePerPulse(static_cast<double>(4.0 / 12.0 * M_PI) /
360.0);
#endif
// Let's show everything on the LiveWindow
// AddChild("Front_Left Motor", m_frontLeft);
// AddChild("Rear Left Motor", m_rearLeft);
// AddChild("Front Right Motor", m_frontRight);
// AddChild("Rear Right Motor", m_rearRight);
AddChild("Left Encoder", m_leftEncoder);
AddChild("Right Encoder", m_rightEncoder);
AddChild("Rangefinder", m_rangefinder);
AddChild("Gyro", m_gyro);
// Let's show everything on the LiveWindow
// AddChild("Front_Left Motor", m_frontLeft);
// AddChild("Rear Left Motor", m_rearLeft);
// AddChild("Front Right Motor", m_frontRight);
// AddChild("Rear Right Motor", m_rearRight);
AddChild("Left Encoder", m_leftEncoder);
AddChild("Right Encoder", m_rightEncoder);
AddChild("Rangefinder", m_rangefinder);
AddChild("Gyro", m_gyro);
}
/**
@@ -46,42 +45,38 @@ DriveTrain::DriveTrain()
* using the PS3 joystick.
*/
void DriveTrain::InitDefaultCommand() {
SetDefaultCommand(new TankDriveWithJoystick());
SetDefaultCommand(new TankDriveWithJoystick());
}
/**
* The log method puts interesting information to the SmartDashboard.
*/
void DriveTrain::Log() {
frc::SmartDashboard::PutNumber(
"Left Distance", m_leftEncoder.GetDistance());
frc::SmartDashboard::PutNumber(
"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());
frc::SmartDashboard::PutNumber("Left Distance", m_leftEncoder.GetDistance());
frc::SmartDashboard::PutNumber("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) {
m_robotDrive.TankDrive(left, right);
m_robotDrive.TankDrive(left, right);
}
double DriveTrain::GetHeading() {
return m_gyro.GetAngle();
}
double DriveTrain::GetHeading() { return m_gyro.GetAngle(); }
void DriveTrain::Reset() {
m_gyro.Reset();
m_leftEncoder.Reset();
m_rightEncoder.Reset();
m_gyro.Reset();
m_leftEncoder.Reset();
m_rightEncoder.Reset();
}
double DriveTrain::GetDistance() {
return (m_leftEncoder.GetDistance() + m_rightEncoder.GetDistance())
/ 2.0;
return (m_leftEncoder.GetDistance() + m_rightEncoder.GetDistance()) / 2.0;
}
double DriveTrain::GetDistanceToObstacle() {
// Really meters in simulation since it's a rangefinder...
return m_rangefinder.GetAverageVoltage();
// Really meters in simulation since it's a rangefinder...
return m_rangefinder.GetAverageVoltage();
}

View File

@@ -25,60 +25,60 @@ class Joystick;
* and a gyro.
*/
class DriveTrain : public frc::Subsystem {
public:
DriveTrain();
public:
DriveTrain();
/**
* When no other command is running let the operator drive around
* using the PS3 joystick.
*/
void InitDefaultCommand() override;
/**
* When no other command is running let the operator drive around
* using the PS3 joystick.
*/
void InitDefaultCommand() override;
/**
* The log method puts interesting information to the SmartDashboard.
*/
void Log();
/**
* The log method puts interesting information to the SmartDashboard.
*/
void Log();
/**
* Tank style driving for the DriveTrain.
* @param left Speed in range [-1,1]
* @param right Speed in range [-1,1]
*/
void Drive(double left, double right);
/**
* Tank style driving for the DriveTrain.
* @param left Speed in range [-1,1]
* @param right Speed in range [-1,1]
*/
void Drive(double left, double right);
/**
* @return The robots heading in degrees.
*/
double GetHeading();
/**
* @return The robots heading in degrees.
*/
double GetHeading();
/**
* Reset the robots sensors to the zero states.
*/
void Reset();
/**
* Reset the robots sensors to the zero states.
*/
void Reset();
/**
* @return The distance driven (average of left and right encoders).
*/
double GetDistance();
/**
* @return The distance driven (average of left and right encoders).
*/
double GetDistance();
/**
* @return The distance to the obstacle detected by the rangefinder.
*/
double GetDistanceToObstacle();
/**
* @return The distance to the obstacle detected by the rangefinder.
*/
double GetDistanceToObstacle();
private:
frc::Spark m_frontLeft{1};
frc::Spark m_rearLeft{2};
frc::SpeedControllerGroup m_left{m_frontLeft, m_rearLeft};
private:
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::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::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};
frc::Encoder m_leftEncoder{1, 2};
frc::Encoder m_rightEncoder{3, 4};
frc::AnalogInput m_rangefinder{6};
frc::AnalogGyro m_gyro{1};
};

View File

@@ -10,28 +10,23 @@
#include <LiveWindow/LiveWindow.h>
#include <SmartDashboard/SmartDashboard.h>
Elevator::Elevator()
: frc::PIDSubsystem("Elevator", kP_real, kI_real, 0.0) {
Elevator::Elevator() : frc::PIDSubsystem("Elevator", kP_real, kI_real, 0.0) {
#ifdef SIMULATION // Check for simulation and update PID values
GetPIDController()->SetPID(kP_simulation, kI_simulation, 0, 0);
GetPIDController()->SetPID(kP_simulation, kI_simulation, 0, 0);
#endif
SetAbsoluteTolerance(0.005);
SetAbsoluteTolerance(0.005);
// Let's show everything on the LiveWindow
AddChild("Motor", m_motor);
AddChild("Pot", &m_pot);
// Let's show everything on the LiveWindow
AddChild("Motor", m_motor);
AddChild("Pot", &m_pot);
}
void Elevator::InitDefaultCommand() {}
void Elevator::Log() {
// frc::SmartDashboard::PutData("Wrist Pot", &m_pot);
// frc::SmartDashboard::PutData("Wrist Pot", &m_pot);
}
double Elevator::ReturnPIDInput() {
return m_pot.Get();
}
double Elevator::ReturnPIDInput() { return m_pot.Get(); }
void Elevator::UsePIDOutput(double d) {
m_motor.Set(d);
}
void Elevator::UsePIDOutput(double d) { m_motor.Set(d); }

View File

@@ -18,42 +18,42 @@
* minor differences.
*/
class Elevator : public frc::PIDSubsystem {
public:
Elevator();
public:
Elevator();
void InitDefaultCommand() override;
void InitDefaultCommand() override;
/**
* The log method puts interesting information to the SmartDashboard.
*/
void Log();
/**
* The log method puts interesting information to the SmartDashboard.
*/
void Log();
/**
* Use the potentiometer as the PID sensor. This method is automatically
* called by the subsystem.
*/
double ReturnPIDInput() override;
/**
* Use the potentiometer as the PID sensor. This method is automatically
* called by the subsystem.
*/
double ReturnPIDInput() override;
/**
* Use the motor as the PID output. This method is automatically called
* by
* the subsystem.
*/
void UsePIDOutput(double d) override;
/**
* Use the motor as the PID output. This method is automatically called
* by
* the subsystem.
*/
void UsePIDOutput(double d) override;
private:
frc::Spark m_motor{5};
private:
frc::Spark m_motor{5};
// Conversion value of potentiometer varies between the real world and
// simulation
#ifndef SIMULATION
frc::AnalogPotentiometer m_pot{2, -2.0 / 5};
frc::AnalogPotentiometer m_pot{2, -2.0 / 5};
#else
frc::AnalogPotentiometer m_pot{2}; // Defaults to meters
frc::AnalogPotentiometer m_pot{2}; // Defaults to meters
#endif
static constexpr double kP_real = 4;
static constexpr double kI_real = 0.07;
static constexpr double kP_simulation = 18;
static constexpr double kI_simulation = 0.2;
static constexpr double kP_real = 4;
static constexpr double kI_real = 0.07;
static constexpr double kP_simulation = 18;
static constexpr double kI_simulation = 0.2;
};

View File

@@ -9,28 +9,23 @@
#include <SmartDashboard/SmartDashboard.h>
Wrist::Wrist()
: frc::PIDSubsystem("Wrist", kP_real, 0.0, 0.0) {
Wrist::Wrist() : frc::PIDSubsystem("Wrist", kP_real, 0.0, 0.0) {
#ifdef SIMULATION // Check for simulation and update PID values
GetPIDController()->SetPID(kP_simulation, 0, 0, 0);
GetPIDController()->SetPID(kP_simulation, 0, 0, 0);
#endif
SetAbsoluteTolerance(2.5);
SetAbsoluteTolerance(2.5);
// Let's show everything on the LiveWindow
AddChild("Motor", m_motor);
AddChild("Pot", m_pot);
// Let's show everything on the LiveWindow
AddChild("Motor", m_motor);
AddChild("Pot", m_pot);
}
void Wrist::InitDefaultCommand() {}
void Wrist::Log() {
// frc::SmartDashboard::PutData("Wrist Angle", &m_pot);
// frc::SmartDashboard::PutData("Wrist Angle", &m_pot);
}
double Wrist::ReturnPIDInput() {
return m_pot.Get();
}
double Wrist::ReturnPIDInput() { return m_pot.Get(); }
void Wrist::UsePIDOutput(double d) {
m_motor.Set(d);
}
void Wrist::UsePIDOutput(double d) { m_motor.Set(d); }

View File

@@ -16,40 +16,40 @@
* of a linear joint.
*/
class Wrist : public PIDSubsystem {
public:
Wrist();
public:
Wrist();
void InitDefaultCommand() override;
void InitDefaultCommand() override;
/**
* The log method puts interesting information to the SmartDashboard.
*/
void Log();
/**
* The log method puts interesting information to the SmartDashboard.
*/
void Log();
/**
* Use the potentiometer as the PID sensor. This method is automatically
* called by the subsystem.
*/
double ReturnPIDInput() override;
/**
* Use the potentiometer as the PID sensor. This method is automatically
* called by the subsystem.
*/
double ReturnPIDInput() override;
/**
* Use the motor as the PID output. This method is automatically called
* by
* the subsystem.
*/
void UsePIDOutput(double d) override;
/**
* Use the motor as the PID output. This method is automatically called
* by
* the subsystem.
*/
void UsePIDOutput(double d) override;
private:
frc::Spark m_motor{6};
private:
frc::Spark m_motor{6};
// Conversion value of potentiometer varies between the real world and
// simulation
#ifndef SIMULATION
frc::AnalogPotentiometer m_pot{3, -270.0 / 5};
frc::AnalogPotentiometer m_pot{3, -270.0 / 5};
#else
frc::AnalogPotentiometer m_pot{3}; // Defaults to degrees
frc::AnalogPotentiometer m_pot{3}; // Defaults to degrees
#endif
static constexpr double kP_real = 1;
static constexpr double kP_simulation = 0.05;
static constexpr double kP_real = 1;
static constexpr double kP_simulation = 0.05;
};