mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-20 00:51:42 +00:00
Cleaned up C++ examples (#672)
This commit is contained in:
committed by
Peter Johnson
parent
6401aa1fde
commit
45d48d6b5a
@@ -15,5 +15,5 @@ CheckForHotGoal::CheckForHotGoal(double time) {
|
||||
|
||||
// Make this return true when this Command no longer needs to run execute()
|
||||
bool CheckForHotGoal::IsFinished() {
|
||||
return IsTimedOut() || Robot::shooter->GoalIsHot();
|
||||
return IsTimedOut() || Robot::shooter.GoalIsHot();
|
||||
}
|
||||
|
||||
@@ -10,10 +10,10 @@
|
||||
#include "../Robot.h"
|
||||
|
||||
CloseClaw::CloseClaw() {
|
||||
Requires(Robot::collector.get());
|
||||
Requires(&Robot::collector);
|
||||
}
|
||||
|
||||
// Called just before this Command runs the first time
|
||||
void CloseClaw::Initialize() {
|
||||
Robot::collector->Close();
|
||||
Robot::collector.Close();
|
||||
}
|
||||
|
||||
@@ -12,9 +12,9 @@
|
||||
#include "../Robot.h"
|
||||
|
||||
void DriveForward::init(double dist, double maxSpeed) {
|
||||
Requires(Robot::drivetrain.get());
|
||||
distance = dist;
|
||||
driveForwardSpeed = maxSpeed;
|
||||
Requires(&Robot::drivetrain);
|
||||
m_distance = dist;
|
||||
m_driveForwardSpeed = maxSpeed;
|
||||
}
|
||||
|
||||
DriveForward::DriveForward() {
|
||||
@@ -31,29 +31,29 @@ DriveForward::DriveForward(double dist, double maxSpeed) {
|
||||
|
||||
// Called just before this Command runs the first time
|
||||
void DriveForward::Initialize() {
|
||||
Robot::drivetrain->GetRightEncoder()->Reset();
|
||||
Robot::drivetrain.GetRightEncoder().Reset();
|
||||
SetTimeout(2);
|
||||
}
|
||||
|
||||
// Called repeatedly when this Command is scheduled to run
|
||||
void DriveForward::Execute() {
|
||||
error = (distance
|
||||
- Robot::drivetrain->GetRightEncoder()->GetDistance());
|
||||
if (driveForwardSpeed * kP * error >= driveForwardSpeed) {
|
||||
Robot::drivetrain->TankDrive(
|
||||
driveForwardSpeed, driveForwardSpeed);
|
||||
m_error = (m_distance
|
||||
- Robot::drivetrain.GetRightEncoder().GetDistance());
|
||||
if (m_driveForwardSpeed * kP * m_error >= m_driveForwardSpeed) {
|
||||
Robot::drivetrain.TankDrive(
|
||||
m_driveForwardSpeed, m_driveForwardSpeed);
|
||||
} else {
|
||||
Robot::drivetrain->TankDrive(driveForwardSpeed * kP * error,
|
||||
driveForwardSpeed * kP * error);
|
||||
Robot::drivetrain.TankDrive(m_driveForwardSpeed * kP * m_error,
|
||||
m_driveForwardSpeed * kP * m_error);
|
||||
}
|
||||
}
|
||||
|
||||
// Make this return true when this Command no longer needs to run execute()
|
||||
bool DriveForward::IsFinished() {
|
||||
return (std::fabs(error) <= kTolerance) || IsTimedOut();
|
||||
return (std::fabs(m_error) <= kTolerance) || IsTimedOut();
|
||||
}
|
||||
|
||||
// Called once after isFinished returns true
|
||||
void DriveForward::End() {
|
||||
Robot::drivetrain->Stop();
|
||||
Robot::drivetrain.Stop();
|
||||
}
|
||||
|
||||
@@ -24,9 +24,9 @@ public:
|
||||
void End() override;
|
||||
|
||||
private:
|
||||
double driveForwardSpeed;
|
||||
double distance;
|
||||
double error = 0;
|
||||
double m_driveForwardSpeed;
|
||||
double m_distance;
|
||||
double m_error = 0;
|
||||
static constexpr double kTolerance = 0.1;
|
||||
static constexpr double kP = -1.0 / 5.0;
|
||||
|
||||
|
||||
@@ -10,12 +10,13 @@
|
||||
#include "../Robot.h"
|
||||
|
||||
DriveWithJoystick::DriveWithJoystick() {
|
||||
Requires(Robot::drivetrain.get());
|
||||
Requires(&Robot::drivetrain);
|
||||
}
|
||||
|
||||
// Called repeatedly when this Command is scheduled to run
|
||||
void DriveWithJoystick::Execute() {
|
||||
Robot::drivetrain->TankDrive(Robot::oi->GetJoystick());
|
||||
auto& joystick = Robot::oi.GetJoystick();
|
||||
Robot::drivetrain.TankDrive(joystick.GetY(), joystick.GetRawAxis(4));
|
||||
}
|
||||
|
||||
// Make this return true when this Command no longer needs to run execute()
|
||||
@@ -25,5 +26,5 @@ bool DriveWithJoystick::IsFinished() {
|
||||
|
||||
// Called once after isFinished returns true
|
||||
void DriveWithJoystick::End() {
|
||||
Robot::drivetrain->Stop();
|
||||
Robot::drivetrain.Stop();
|
||||
}
|
||||
|
||||
@@ -11,15 +11,15 @@
|
||||
|
||||
ExtendShooter::ExtendShooter()
|
||||
: frc::TimedCommand(1.0) {
|
||||
Requires(Robot::shooter.get());
|
||||
Requires(&Robot::shooter);
|
||||
}
|
||||
|
||||
// Called just before this Command runs the first time
|
||||
void ExtendShooter::Initialize() {
|
||||
Robot::shooter->ExtendBoth();
|
||||
Robot::shooter.ExtendBoth();
|
||||
}
|
||||
|
||||
// Called once after isFinished returns true
|
||||
void ExtendShooter::End() {
|
||||
Robot::shooter->RetractBoth();
|
||||
Robot::shooter.RetractBoth();
|
||||
}
|
||||
|
||||
@@ -10,15 +10,15 @@
|
||||
#include "../Robot.h"
|
||||
|
||||
OpenClaw::OpenClaw() {
|
||||
Requires(Robot::collector.get());
|
||||
Requires(&Robot::collector);
|
||||
}
|
||||
|
||||
// Called just before this Command runs the first time
|
||||
void OpenClaw::Initialize() {
|
||||
Robot::collector->Open();
|
||||
Robot::collector.Open();
|
||||
}
|
||||
|
||||
// Make this return true when this Command no longer needs to run execute()
|
||||
bool OpenClaw::IsFinished() {
|
||||
return Robot::collector->IsOpen();
|
||||
return Robot::collector.IsOpen();
|
||||
}
|
||||
|
||||
@@ -10,11 +10,11 @@
|
||||
#include "../Robot.h"
|
||||
|
||||
SetCollectionSpeed::SetCollectionSpeed(double speed) {
|
||||
Requires(Robot::collector.get());
|
||||
this->speed = speed;
|
||||
Requires(&Robot::collector);
|
||||
m_speed = speed;
|
||||
}
|
||||
|
||||
// Called just before this Command runs the first time
|
||||
void SetCollectionSpeed::Initialize() {
|
||||
Robot::collector->SetSpeed(speed);
|
||||
Robot::collector.SetSpeed(m_speed);
|
||||
}
|
||||
|
||||
@@ -20,5 +20,5 @@ public:
|
||||
void Initialize() override;
|
||||
|
||||
private:
|
||||
double speed;
|
||||
double m_speed;
|
||||
};
|
||||
|
||||
@@ -10,17 +10,17 @@
|
||||
#include "../Robot.h"
|
||||
|
||||
SetPivotSetpoint::SetPivotSetpoint(double setpoint) {
|
||||
this->setpoint = setpoint;
|
||||
Requires(Robot::pivot.get());
|
||||
m_setpoint = setpoint;
|
||||
Requires(&Robot::pivot);
|
||||
}
|
||||
|
||||
// Called just before this Command runs the first time
|
||||
void SetPivotSetpoint::Initialize() {
|
||||
Robot::pivot->Enable();
|
||||
Robot::pivot->SetSetpoint(setpoint);
|
||||
Robot::pivot.Enable();
|
||||
Robot::pivot.SetSetpoint(m_setpoint);
|
||||
}
|
||||
|
||||
// Make this return true when this Command no longer needs to run execute()
|
||||
bool SetPivotSetpoint::IsFinished() {
|
||||
return Robot::pivot->OnTarget();
|
||||
return Robot::pivot.OnTarget();
|
||||
}
|
||||
|
||||
@@ -21,5 +21,5 @@ public:
|
||||
bool IsFinished() override;
|
||||
|
||||
private:
|
||||
double setpoint;
|
||||
double m_setpoint;
|
||||
};
|
||||
|
||||
@@ -10,10 +10,10 @@
|
||||
#include "../Robot.h"
|
||||
|
||||
WaitForBall::WaitForBall() {
|
||||
Requires(Robot::collector.get());
|
||||
Requires(&Robot::collector);
|
||||
}
|
||||
|
||||
// Make this return true when this Command no longer needs to run execute()
|
||||
bool WaitForBall::IsFinished() {
|
||||
return Robot::collector->HasBall();
|
||||
return Robot::collector.HasBall();
|
||||
}
|
||||
|
||||
@@ -10,10 +10,10 @@
|
||||
#include "../Robot.h"
|
||||
|
||||
WaitForPressure::WaitForPressure() {
|
||||
Requires(Robot::pneumatics.get());
|
||||
Requires(&Robot::pneumatics);
|
||||
}
|
||||
|
||||
// Make this return true when this Command no longer needs to run execute()
|
||||
bool WaitForPressure::IsFinished() {
|
||||
return Robot::pneumatics->IsPressurized();
|
||||
return Robot::pneumatics.IsPressurized();
|
||||
}
|
||||
|
||||
@@ -17,13 +17,13 @@
|
||||
#include "Subsystems/Pivot.h"
|
||||
|
||||
OI::OI() {
|
||||
R1.WhenPressed(new LowGoal());
|
||||
R2.WhenPressed(new Collect());
|
||||
m_r1.WhenPressed(new LowGoal());
|
||||
m_r2.WhenPressed(new Collect());
|
||||
|
||||
L1.WhenPressed(new SetPivotSetpoint(Pivot::kShoot));
|
||||
L2.WhenPressed(new SetPivotSetpoint(Pivot::kShootNear));
|
||||
m_l1.WhenPressed(new SetPivotSetpoint(Pivot::kShoot));
|
||||
m_l2.WhenPressed(new SetPivotSetpoint(Pivot::kShootNear));
|
||||
|
||||
sticks.WhenActive(new Shoot());
|
||||
m_sticks.WhenActive(new Shoot());
|
||||
|
||||
// SmartDashboard Buttons
|
||||
frc::SmartDashboard::PutData("Drive Forward", new DriveForward(2.25));
|
||||
@@ -36,6 +36,6 @@ OI::OI() {
|
||||
new SetCollectionSpeed(Collector::kReverse));
|
||||
}
|
||||
|
||||
frc::Joystick* OI::GetJoystick() {
|
||||
return &joystick;
|
||||
frc::Joystick& OI::GetJoystick() {
|
||||
return m_joystick;
|
||||
}
|
||||
|
||||
@@ -15,15 +15,15 @@
|
||||
class OI {
|
||||
public:
|
||||
OI();
|
||||
frc::Joystick* GetJoystick();
|
||||
frc::Joystick& GetJoystick();
|
||||
|
||||
private:
|
||||
frc::Joystick joystick{0};
|
||||
frc::Joystick m_joystick{0};
|
||||
|
||||
frc::JoystickButton L1{&joystick, 11};
|
||||
frc::JoystickButton L2{&joystick, 9};
|
||||
frc::JoystickButton R1{&joystick, 12};
|
||||
frc::JoystickButton R2{&joystick, 10};
|
||||
frc::JoystickButton m_l1{&m_joystick, 11};
|
||||
frc::JoystickButton m_l2{&m_joystick, 9};
|
||||
frc::JoystickButton m_r1{&m_joystick, 12};
|
||||
frc::JoystickButton m_r2{&m_joystick, 10};
|
||||
|
||||
DoubleButton sticks{&joystick, 2, 3};
|
||||
DoubleButton m_sticks{&m_joystick, 2, 3};
|
||||
};
|
||||
|
||||
@@ -11,32 +11,32 @@
|
||||
|
||||
#include <SmartDashboard/SmartDashboard.h>
|
||||
|
||||
std::shared_ptr<DriveTrain> Robot::drivetrain = std::make_shared<DriveTrain>();
|
||||
std::shared_ptr<Pivot> Robot::pivot = std::make_shared<Pivot>();
|
||||
std::shared_ptr<Collector> Robot::collector = std::make_shared<Collector>();
|
||||
std::shared_ptr<Shooter> Robot::shooter = std::make_shared<Shooter>();
|
||||
std::shared_ptr<Pneumatics> Robot::pneumatics = std::make_shared<Pneumatics>();
|
||||
std::unique_ptr<OI> Robot::oi = std::make_unique<OI>();
|
||||
DriveTrain Robot::drivetrain;
|
||||
Pivot Robot::pivot;
|
||||
Collector Robot::collector;
|
||||
Shooter Robot::shooter;
|
||||
Pneumatics Robot::pneumatics;
|
||||
OI Robot::oi;
|
||||
|
||||
void Robot::RobotInit() {
|
||||
// Show what command your subsystem is running on the SmartDashboard
|
||||
frc::SmartDashboard::PutData(drivetrain.get());
|
||||
frc::SmartDashboard::PutData(pivot.get());
|
||||
frc::SmartDashboard::PutData(collector.get());
|
||||
frc::SmartDashboard::PutData(shooter.get());
|
||||
frc::SmartDashboard::PutData(pneumatics.get());
|
||||
frc::SmartDashboard::PutData(&drivetrain);
|
||||
frc::SmartDashboard::PutData(&pivot);
|
||||
frc::SmartDashboard::PutData(&collector);
|
||||
frc::SmartDashboard::PutData(&shooter);
|
||||
frc::SmartDashboard::PutData(&pneumatics);
|
||||
|
||||
// instantiate the command used for the autonomous period
|
||||
autoChooser.AddDefault("Drive and Shoot", driveAndShootAuto.get());
|
||||
autoChooser.AddObject("Drive Forward", driveForwardAuto.get());
|
||||
frc::SmartDashboard::PutData("Auto Mode", &autoChooser);
|
||||
m_autoChooser.AddDefault("Drive and Shoot", &m_driveAndShootAuto);
|
||||
m_autoChooser.AddObject("Drive Forward", &m_driveForwardAuto);
|
||||
frc::SmartDashboard::PutData("Auto Mode", &m_autoChooser);
|
||||
|
||||
pneumatics->Start(); // Pressurize the pneumatics.
|
||||
pneumatics.Start(); // Pressurize the pneumatics.
|
||||
}
|
||||
|
||||
void Robot::AutonomousInit() {
|
||||
autonomousCommand = autoChooser.GetSelected();
|
||||
autonomousCommand->Start();
|
||||
m_autonomousCommand = m_autoChooser.GetSelected();
|
||||
m_autonomousCommand->Start();
|
||||
}
|
||||
|
||||
void Robot::AutonomousPeriodic() {
|
||||
@@ -49,8 +49,8 @@ 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.
|
||||
if (autonomousCommand != nullptr) {
|
||||
autonomousCommand->Cancel();
|
||||
if (m_autonomousCommand != nullptr) {
|
||||
m_autonomousCommand->Cancel();
|
||||
}
|
||||
std::cout << "Starting Teleop" << std::endl;
|
||||
}
|
||||
@@ -65,7 +65,7 @@ void Robot::TestPeriodic() {
|
||||
}
|
||||
|
||||
void Robot::DisabledInit() {
|
||||
shooter->Unlatch();
|
||||
shooter.Unlatch();
|
||||
}
|
||||
|
||||
void Robot::DisabledPeriodic() {
|
||||
@@ -76,12 +76,12 @@ void Robot::DisabledPeriodic() {
|
||||
* Log interesting values to the SmartDashboard.
|
||||
*/
|
||||
void Robot::Log() {
|
||||
Robot::pneumatics->WritePressure();
|
||||
frc::SmartDashboard::PutNumber("Pivot Pot Value", pivot->GetAngle());
|
||||
Robot::pneumatics.WritePressure();
|
||||
frc::SmartDashboard::PutNumber("Pivot Pot Value", pivot.GetAngle());
|
||||
frc::SmartDashboard::PutNumber("Left Distance",
|
||||
drivetrain->GetLeftEncoder()->GetDistance());
|
||||
drivetrain.GetLeftEncoder().GetDistance());
|
||||
frc::SmartDashboard::PutNumber("Right Distance",
|
||||
drivetrain->GetRightEncoder()->GetDistance());
|
||||
drivetrain.GetRightEncoder().GetDistance());
|
||||
}
|
||||
|
||||
START_ROBOT_CLASS(Robot)
|
||||
|
||||
@@ -7,8 +7,6 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <memory>
|
||||
|
||||
#include <Commands/Command.h>
|
||||
#include <IterativeRobot.h>
|
||||
#include <SmartDashboard/SendableChooser.h>
|
||||
@@ -24,19 +22,18 @@
|
||||
|
||||
class Robot : public IterativeRobot {
|
||||
public:
|
||||
static std::shared_ptr<DriveTrain> drivetrain;
|
||||
static std::shared_ptr<Pivot> pivot;
|
||||
static std::shared_ptr<Collector> collector;
|
||||
static std::shared_ptr<Shooter> shooter;
|
||||
static std::shared_ptr<Pneumatics> pneumatics;
|
||||
static std::unique_ptr<OI> oi;
|
||||
static DriveTrain drivetrain;
|
||||
static Pivot pivot;
|
||||
static Collector collector;
|
||||
static Shooter shooter;
|
||||
static Pneumatics pneumatics;
|
||||
static OI oi;
|
||||
|
||||
private:
|
||||
frc::Command* autonomousCommand = nullptr;
|
||||
std::unique_ptr<frc::Command> driveAndShootAuto{
|
||||
new DriveAndShootAutonomous()};
|
||||
std::unique_ptr<frc::Command> driveForwardAuto{new DriveForward()};
|
||||
SendableChooser<frc::Command*> autoChooser;
|
||||
frc::Command* m_autonomousCommand = nullptr;
|
||||
DriveAndShootAutonomous m_driveAndShootAuto;
|
||||
DriveForward m_driveForwardAuto;
|
||||
SendableChooser<frc::Command*> m_autoChooser;
|
||||
|
||||
void RobotInit() override;
|
||||
void AutonomousInit() override;
|
||||
|
||||
@@ -13,36 +13,37 @@ Collector::Collector()
|
||||
: frc::Subsystem("Collector") {
|
||||
// Put everything to the LiveWindow for testing.
|
||||
// XXX: LiveWindow::GetInstance()->AddActuator("Collector", "Roller
|
||||
// Motor", &rollerMotor);
|
||||
// Motor", &m_rollerMotor);
|
||||
LiveWindow::GetInstance()->AddSensor(
|
||||
"Collector", "Ball Detector", &ballDetector);
|
||||
"Collector", "Ball Detector", &m_ballDetector);
|
||||
LiveWindow::GetInstance()->AddSensor(
|
||||
"Collector", "Claw Open Detector", &openDetector);
|
||||
LiveWindow::GetInstance()->AddActuator("Collector", "Piston", &piston);
|
||||
"Collector", "Claw Open Detector", &m_openDetector);
|
||||
LiveWindow::GetInstance()->AddActuator(
|
||||
"Collector", "Piston", &m_piston);
|
||||
}
|
||||
|
||||
bool Collector::HasBall() {
|
||||
return ballDetector.Get(); // TODO: prepend ! to reflect real robot
|
||||
return m_ballDetector.Get(); // TODO: prepend ! to reflect real robot
|
||||
}
|
||||
|
||||
void Collector::SetSpeed(double speed) {
|
||||
rollerMotor.Set(-speed);
|
||||
m_rollerMotor.Set(-speed);
|
||||
}
|
||||
|
||||
void Collector::Stop() {
|
||||
rollerMotor.Set(0);
|
||||
m_rollerMotor.Set(0);
|
||||
}
|
||||
|
||||
bool Collector::IsOpen() {
|
||||
return openDetector.Get(); // TODO: prepend ! to reflect real robot
|
||||
return m_openDetector.Get(); // TODO: prepend ! to reflect real robot
|
||||
}
|
||||
|
||||
void Collector::Open() {
|
||||
piston.Set(true);
|
||||
m_piston.Set(true);
|
||||
}
|
||||
|
||||
void Collector::Close() {
|
||||
piston.Set(false);
|
||||
m_piston.Set(false);
|
||||
}
|
||||
|
||||
void Collector::InitDefaultCommand() {}
|
||||
|
||||
@@ -10,7 +10,7 @@
|
||||
#include <Commands/Subsystem.h>
|
||||
#include <DigitalInput.h>
|
||||
#include <Solenoid.h>
|
||||
#include <Victor.h>
|
||||
#include <Spark.h>
|
||||
|
||||
/**
|
||||
* The Collector subsystem has one motor for the rollers, a limit switch for
|
||||
@@ -69,8 +69,8 @@ public:
|
||||
|
||||
private:
|
||||
// Subsystem devices
|
||||
frc::Victor rollerMotor{6};
|
||||
frc::DigitalInput ballDetector{10};
|
||||
frc::Solenoid piston{1};
|
||||
frc::DigitalInput openDetector{6};
|
||||
frc::Spark m_rollerMotor{6};
|
||||
frc::DigitalInput m_ballDetector{10};
|
||||
frc::Solenoid m_piston{1};
|
||||
frc::DigitalInput m_openDetector{6};
|
||||
};
|
||||
|
||||
@@ -17,77 +17,70 @@
|
||||
DriveTrain::DriveTrain()
|
||||
: frc::Subsystem("DriveTrain") {
|
||||
// frc::LiveWindow::GetInstance()->AddActuator("DriveTrain", "Front Left
|
||||
// CIM", &frontLeftCIM);
|
||||
// CIM", &m_frontLeftCIM);
|
||||
// frc::LiveWindow::GetInstance()->AddActuator("DriveTrain", "Front
|
||||
// Right CIM", &frontRightCIM);
|
||||
// Right CIM", &m_frontRightCIM);
|
||||
// frc::LiveWindow::GetInstance()->AddActuator("DriveTrain", "Back Left
|
||||
// CIM", &backLeftCIM);
|
||||
// CIM", &m_backLeftCIM);
|
||||
// frc::LiveWindow::GetInstance()->AddActuator("DriveTrain", "Back Right
|
||||
// CIM", &backRightCIM);
|
||||
// CIM", &m_backRightCIM);
|
||||
|
||||
// Configure the RobotDrive to reflect the fact that all our motors are
|
||||
// wired backwards and our drivers sensitivity preferences.
|
||||
drive.SetSafetyEnabled(false);
|
||||
drive.SetExpiration(0.1);
|
||||
drive.SetSensitivity(0.5);
|
||||
drive.SetMaxOutput(1.0);
|
||||
drive.SetInvertedMotor(RobotDrive::kFrontLeftMotor, true);
|
||||
drive.SetInvertedMotor(RobotDrive::kRearLeftMotor, true);
|
||||
drive.SetInvertedMotor(RobotDrive::kFrontRightMotor, true);
|
||||
drive.SetInvertedMotor(RobotDrive::kRearRightMotor, true);
|
||||
m_robotDrive.SetSafetyEnabled(false);
|
||||
m_robotDrive.SetExpiration(0.1);
|
||||
m_robotDrive.SetMaxOutput(1.0);
|
||||
m_leftCIMs.SetInverted(true);
|
||||
m_rightCIMs.SetInverted(true);
|
||||
|
||||
// Configure encoders
|
||||
rightEncoder->SetPIDSourceType(PIDSourceType::kDisplacement);
|
||||
leftEncoder->SetPIDSourceType(PIDSourceType::kDisplacement);
|
||||
m_rightEncoder.SetPIDSourceType(PIDSourceType::kDisplacement);
|
||||
m_leftEncoder.SetPIDSourceType(PIDSourceType::kDisplacement);
|
||||
|
||||
#ifndef SIMULATION
|
||||
// Converts to feet
|
||||
rightEncoder->SetDistancePerPulse(0.0785398);
|
||||
leftEncoder->SetDistancePerPulse(0.0785398);
|
||||
m_rightEncoder.SetDistancePerPulse(0.0785398);
|
||||
m_leftEncoder.SetDistancePerPulse(0.0785398);
|
||||
#else
|
||||
// Convert to feet 4in diameter wheels with 360 tick simulated encoders
|
||||
rightEncoder->SetDistancePerPulse(
|
||||
m_rightEncoder.SetDistancePerPulse(
|
||||
(4.0 /*in*/ * M_PI) / (360.0 * 12.0 /*in/ft*/));
|
||||
leftEncoder->SetDistancePerPulse(
|
||||
m_leftEncoder.SetDistancePerPulse(
|
||||
(4.0 /*in*/ * M_PI) / (360.0 * 12.0 /*in/ft*/));
|
||||
#endif
|
||||
|
||||
LiveWindow::GetInstance()->AddSensor(
|
||||
"DriveTrain", "Right Encoder", rightEncoder);
|
||||
"DriveTrain", "Right Encoder", m_rightEncoder);
|
||||
LiveWindow::GetInstance()->AddSensor(
|
||||
"DriveTrain", "Left Encoder", leftEncoder);
|
||||
"DriveTrain", "Left Encoder", m_leftEncoder);
|
||||
|
||||
// Configure gyro
|
||||
#ifndef SIMULATION
|
||||
gyro.SetSensitivity(0.007); // TODO: Handle more gracefully?
|
||||
m_gyro.SetSensitivity(0.007); // TODO: Handle more gracefully?
|
||||
#endif
|
||||
LiveWindow::GetInstance()->AddSensor("DriveTrain", "Gyro", &gyro);
|
||||
LiveWindow::GetInstance()->AddSensor("DriveTrain", "Gyro", &m_gyro);
|
||||
}
|
||||
|
||||
void DriveTrain::InitDefaultCommand() {
|
||||
SetDefaultCommand(new DriveWithJoystick());
|
||||
}
|
||||
|
||||
void DriveTrain::TankDrive(Joystick* joy) {
|
||||
drive.TankDrive(joy->GetY(), joy->GetRawAxis(4));
|
||||
}
|
||||
|
||||
void DriveTrain::TankDrive(double leftAxis, double rightAxis) {
|
||||
drive.TankDrive(leftAxis, rightAxis);
|
||||
m_robotDrive.TankDrive(leftAxis, rightAxis);
|
||||
}
|
||||
|
||||
void DriveTrain::Stop() {
|
||||
drive.TankDrive(0.0, 0.0);
|
||||
m_robotDrive.TankDrive(0.0, 0.0);
|
||||
}
|
||||
|
||||
std::shared_ptr<Encoder> DriveTrain::GetLeftEncoder() {
|
||||
return leftEncoder;
|
||||
Encoder& DriveTrain::GetLeftEncoder() {
|
||||
return m_leftEncoder;
|
||||
}
|
||||
|
||||
std::shared_ptr<Encoder> DriveTrain::GetRightEncoder() {
|
||||
return rightEncoder;
|
||||
Encoder& DriveTrain::GetRightEncoder() {
|
||||
return m_rightEncoder;
|
||||
}
|
||||
|
||||
double DriveTrain::GetAngle() {
|
||||
return gyro.GetAngle();
|
||||
return m_gyro.GetAngle();
|
||||
}
|
||||
|
||||
@@ -7,13 +7,12 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <memory>
|
||||
|
||||
#include <AnalogGyro.h>
|
||||
#include <Commands/Subsystem.h>
|
||||
#include <Drive/DifferentialDrive.h>
|
||||
#include <Encoder.h>
|
||||
#include <RobotDrive.h>
|
||||
#include <Victor.h>
|
||||
#include <Spark.h>
|
||||
#include <SpeedControllerGroup.h>
|
||||
|
||||
namespace frc {
|
||||
class Joystick;
|
||||
@@ -34,11 +33,6 @@ public:
|
||||
*/
|
||||
void InitDefaultCommand();
|
||||
|
||||
/**
|
||||
* @param joy PS3 style joystick to use as the input for tank drive.
|
||||
*/
|
||||
void TankDrive(frc::Joystick* joy);
|
||||
|
||||
/**
|
||||
* @param leftAxis Left sides value
|
||||
* @param rightAxis Right sides value
|
||||
@@ -54,13 +48,13 @@ public:
|
||||
* @return The encoder getting the distance and speed of left side of
|
||||
* the drivetrain.
|
||||
*/
|
||||
std::shared_ptr<Encoder> GetLeftEncoder();
|
||||
Encoder& GetLeftEncoder();
|
||||
|
||||
/**
|
||||
* @return The encoder getting the distance and speed of right side of
|
||||
* the drivetrain.
|
||||
*/
|
||||
std::shared_ptr<Encoder> GetRightEncoder();
|
||||
Encoder& GetRightEncoder();
|
||||
|
||||
/**
|
||||
* @return The current angle of the drivetrain.
|
||||
@@ -69,17 +63,17 @@ public:
|
||||
|
||||
private:
|
||||
// Subsystem devices
|
||||
frc::Victor frontLeftCIM{1};
|
||||
frc::Victor rearLeftCIM{2};
|
||||
frc::Victor frontRightCIM{3};
|
||||
frc::Victor rearRightCIM{4};
|
||||
frc::RobotDrive drive{frontRightCIM, rearLeftCIM, frontRightCIM,
|
||||
rearRightCIM};
|
||||
std::shared_ptr<frc::Encoder> rightEncoder =
|
||||
std::make_shared<frc::Encoder>(
|
||||
1, 2, true, Encoder::k4X);
|
||||
std::shared_ptr<frc::Encoder> leftEncoder =
|
||||
std::make_shared<frc::Encoder>(
|
||||
3, 4, false, Encoder::k4X);
|
||||
frc::AnalogGyro gyro{0};
|
||||
frc::Spark m_frontLeftCIM{1};
|
||||
frc::Spark m_rearLeftCIM{2};
|
||||
frc::SpeedControllerGroup m_leftCIMs{m_frontLeftCIM, m_rearLeftCIM};
|
||||
|
||||
frc::Spark m_frontRightCIM{3};
|
||||
frc::Spark m_rearRightCIM{4};
|
||||
frc::SpeedControllerGroup m_rightCIMs{m_frontRightCIM, m_rearRightCIM};
|
||||
|
||||
frc::DifferentialDrive m_robotDrive{m_leftCIMs, m_rightCIMs};
|
||||
|
||||
frc::Encoder m_rightEncoder{1, 2, true, Encoder::k4X};
|
||||
frc::Encoder m_leftEncoder{3, 4, false, Encoder::k4X};
|
||||
frc::AnalogGyro m_gyro{0};
|
||||
};
|
||||
|
||||
@@ -21,12 +21,13 @@ Pivot::Pivot()
|
||||
|
||||
// Put everything to the LiveWindow for testing.
|
||||
frc::LiveWindow::GetInstance()->AddSensor(
|
||||
"Pivot", "Upper Limit Switch", &upperLimitSwitch);
|
||||
"Pivot", "Upper Limit Switch", &m_upperLimitSwitch);
|
||||
frc::LiveWindow::GetInstance()->AddSensor(
|
||||
"Pivot", "Lower Limit Switch", &lowerLimitSwitch);
|
||||
// XXX: frc::LiveWindow::GetInstance()->AddSensor("Pivot", "Pot", &pot);
|
||||
"Pivot", "Lower Limit Switch", &m_lowerLimitSwitch);
|
||||
// XXX: frc::LiveWindow::GetInstance()->AddSensor("Pivot", "Pot",
|
||||
// &m_pot);
|
||||
// XXX: frc::LiveWindow::GetInstance()->AddActuator("Pivot", "Motor",
|
||||
// &motor);
|
||||
// &m_motor);
|
||||
frc::LiveWindow::GetInstance()->AddActuator(
|
||||
"Pivot", "PIDSubsystem Controller", GetPIDController());
|
||||
}
|
||||
@@ -34,23 +35,23 @@ Pivot::Pivot()
|
||||
void InitDefaultCommand() {}
|
||||
|
||||
double Pivot::ReturnPIDInput() {
|
||||
return pot.Get();
|
||||
return m_pot.Get();
|
||||
}
|
||||
|
||||
void Pivot::UsePIDOutput(double output) {
|
||||
motor.PIDWrite(output);
|
||||
m_motor.PIDWrite(output);
|
||||
}
|
||||
|
||||
bool Pivot::IsAtUpperLimit() {
|
||||
return upperLimitSwitch.Get(); // TODO: inverted from real robot
|
||||
// (prefix with !)
|
||||
return m_upperLimitSwitch.Get(); // TODO: inverted from real robot
|
||||
// (prefix with !)
|
||||
}
|
||||
|
||||
bool Pivot::IsAtLowerLimit() {
|
||||
return lowerLimitSwitch.Get(); // TODO: inverted from real robot
|
||||
// (prefix with !)
|
||||
return m_lowerLimitSwitch.Get(); // TODO: inverted from real robot
|
||||
// (prefix with !)
|
||||
}
|
||||
|
||||
double Pivot::GetAngle() {
|
||||
return pot.Get();
|
||||
return m_pot.Get();
|
||||
}
|
||||
|
||||
@@ -10,7 +10,7 @@
|
||||
#include <AnalogPotentiometer.h>
|
||||
#include <Commands/PIDSubsystem.h>
|
||||
#include <DigitalInput.h>
|
||||
#include <Victor.h>
|
||||
#include <Spark.h>
|
||||
|
||||
/**
|
||||
* The Pivot subsystem contains the Van-door motor and the pot for PID control
|
||||
@@ -61,14 +61,14 @@ private:
|
||||
// Subsystem devices
|
||||
|
||||
// Sensors for measuring the position of the pivot
|
||||
frc::DigitalInput upperLimitSwitch{13};
|
||||
frc::DigitalInput lowerLimitSwitch{12};
|
||||
frc::DigitalInput m_upperLimitSwitch{13};
|
||||
frc::DigitalInput m_lowerLimitSwitch{12};
|
||||
|
||||
/* 0 degrees is vertical facing up.
|
||||
* Angle increases the more forward the pivot goes.
|
||||
*/
|
||||
frc::AnalogPotentiometer pot{1};
|
||||
frc::AnalogPotentiometer m_pot{1};
|
||||
|
||||
// Motor to move the pivot
|
||||
frc::Victor motor{5};
|
||||
frc::Spark m_motor{5};
|
||||
};
|
||||
|
||||
@@ -12,7 +12,7 @@
|
||||
Pneumatics::Pneumatics()
|
||||
: frc::Subsystem("Pneumatics") {
|
||||
frc::LiveWindow::GetInstance()->AddSensor(
|
||||
"Pneumatics", "Pressure Sensor", pressureSensor);
|
||||
"Pneumatics", "Pressure Sensor", m_pressureSensor);
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -26,7 +26,7 @@ void Pneumatics::InitDefaultCommand() {}
|
||||
*/
|
||||
void Pneumatics::Start() {
|
||||
#ifndef SIMULATION
|
||||
compressor.Start();
|
||||
m_compressor.Start();
|
||||
#endif
|
||||
}
|
||||
|
||||
@@ -35,7 +35,7 @@ void Pneumatics::Start() {
|
||||
*/
|
||||
bool Pneumatics::IsPressurized() {
|
||||
#ifndef SIMULATION
|
||||
return kMaxPressure <= pressureSensor.GetVoltage();
|
||||
return kMaxPressure <= m_pressureSensor.GetVoltage();
|
||||
#else
|
||||
return true; // NOTE: Simulation always has full pressure
|
||||
#endif
|
||||
@@ -45,5 +45,6 @@ bool Pneumatics::IsPressurized() {
|
||||
* Puts the pressure on the SmartDashboard.
|
||||
*/
|
||||
void Pneumatics::WritePressure() {
|
||||
frc::SmartDashboard::PutNumber("Pressure", pressureSensor.GetVoltage());
|
||||
frc::SmartDashboard::PutNumber(
|
||||
"Pressure", m_pressureSensor.GetVoltage());
|
||||
}
|
||||
|
||||
@@ -43,10 +43,10 @@ public:
|
||||
void WritePressure();
|
||||
|
||||
private:
|
||||
frc::AnalogInput pressureSensor{3};
|
||||
frc::AnalogInput m_pressureSensor{3};
|
||||
|
||||
#ifndef SIMULATION
|
||||
frc::Compressor compressor{1}; // TODO: (1, 14, 1, 8);
|
||||
frc::Compressor m_compressor{1}; // TODO: (1, 14, 1, 8);
|
||||
#endif
|
||||
|
||||
static constexpr double kMaxPressure = 2.55;
|
||||
|
||||
@@ -13,13 +13,14 @@ Shooter::Shooter()
|
||||
: Subsystem("Shooter") {
|
||||
// Put everything to the LiveWindow for testing.
|
||||
frc::LiveWindow::GetInstance()->AddSensor(
|
||||
"Shooter", "Hot Goal Sensor", &hotGoalSensor);
|
||||
"Shooter", "Hot Goal Sensor", &m_hotGoalSensor);
|
||||
frc::LiveWindow::GetInstance()->AddSensor("Shooter",
|
||||
"Piston1 Reed Switch Front ", &piston1ReedSwitchFront);
|
||||
"Piston1 Reed Switch Front ",
|
||||
&m_piston1ReedSwitchFront);
|
||||
frc::LiveWindow::GetInstance()->AddSensor("Shooter",
|
||||
"Piston1 Reed Switch Back ", &piston1ReedSwitchBack);
|
||||
"Piston1 Reed Switch Back ", &m_piston1ReedSwitchBack);
|
||||
frc::LiveWindow::GetInstance()->AddActuator(
|
||||
"Shooter", "Latch Piston", &latchPiston);
|
||||
"Shooter", "Latch Piston", &m_latchPiston);
|
||||
}
|
||||
|
||||
void Shooter::InitDefaultCommand() {
|
||||
@@ -28,64 +29,64 @@ void Shooter::InitDefaultCommand() {
|
||||
}
|
||||
|
||||
void Shooter::ExtendBoth() {
|
||||
piston1.Set(frc::DoubleSolenoid::kForward);
|
||||
piston2.Set(frc::DoubleSolenoid::kForward);
|
||||
m_piston1.Set(frc::DoubleSolenoid::kForward);
|
||||
m_piston2.Set(frc::DoubleSolenoid::kForward);
|
||||
}
|
||||
|
||||
void Shooter::RetractBoth() {
|
||||
piston1.Set(frc::DoubleSolenoid::kReverse);
|
||||
piston2.Set(frc::DoubleSolenoid::kReverse);
|
||||
m_piston1.Set(frc::DoubleSolenoid::kReverse);
|
||||
m_piston2.Set(frc::DoubleSolenoid::kReverse);
|
||||
}
|
||||
|
||||
void Shooter::Extend1() {
|
||||
piston1.Set(frc::DoubleSolenoid::kForward);
|
||||
m_piston1.Set(frc::DoubleSolenoid::kForward);
|
||||
}
|
||||
|
||||
void Shooter::Retract1() {
|
||||
piston1.Set(frc::DoubleSolenoid::kReverse);
|
||||
m_piston1.Set(frc::DoubleSolenoid::kReverse);
|
||||
}
|
||||
|
||||
void Shooter::Extend2() {
|
||||
piston2.Set(frc::DoubleSolenoid::kReverse);
|
||||
m_piston2.Set(frc::DoubleSolenoid::kReverse);
|
||||
}
|
||||
|
||||
void Shooter::Retract2() {
|
||||
piston2.Set(frc::DoubleSolenoid::kForward);
|
||||
m_piston2.Set(frc::DoubleSolenoid::kForward);
|
||||
}
|
||||
|
||||
void Shooter::Off1() {
|
||||
piston1.Set(frc::DoubleSolenoid::kOff);
|
||||
m_piston1.Set(frc::DoubleSolenoid::kOff);
|
||||
}
|
||||
|
||||
void Shooter::Off2() {
|
||||
piston2.Set(frc::DoubleSolenoid::kOff);
|
||||
m_piston2.Set(frc::DoubleSolenoid::kOff);
|
||||
}
|
||||
|
||||
void Shooter::Unlatch() {
|
||||
latchPiston.Set(true);
|
||||
m_latchPiston.Set(true);
|
||||
}
|
||||
|
||||
void Shooter::Latch() {
|
||||
latchPiston.Set(false);
|
||||
m_latchPiston.Set(false);
|
||||
}
|
||||
|
||||
void Shooter::ToggleLatchPosition() {
|
||||
latchPiston.Set(!latchPiston.Get());
|
||||
m_latchPiston.Set(!m_latchPiston.Get());
|
||||
}
|
||||
|
||||
bool Shooter::Piston1IsExtended() {
|
||||
return !piston1ReedSwitchFront.Get();
|
||||
return !m_piston1ReedSwitchFront.Get();
|
||||
}
|
||||
|
||||
bool Shooter::Piston1IsRetracted() {
|
||||
return !piston1ReedSwitchBack.Get();
|
||||
return !m_piston1ReedSwitchBack.Get();
|
||||
}
|
||||
|
||||
void Shooter::OffBoth() {
|
||||
piston1.Set(frc::DoubleSolenoid::kOff);
|
||||
piston2.Set(frc::DoubleSolenoid::kOff);
|
||||
m_piston1.Set(frc::DoubleSolenoid::kOff);
|
||||
m_piston2.Set(frc::DoubleSolenoid::kOff);
|
||||
}
|
||||
|
||||
bool Shooter::GoalIsHot() {
|
||||
return hotGoalSensor.Get();
|
||||
return m_hotGoalSensor.Get();
|
||||
}
|
||||
|
||||
@@ -117,11 +117,11 @@ public:
|
||||
|
||||
private:
|
||||
// Devices
|
||||
frc::DoubleSolenoid piston1{3, 4};
|
||||
frc::DoubleSolenoid piston2{5, 6};
|
||||
frc::Solenoid latchPiston{1, 2};
|
||||
frc::DigitalInput piston1ReedSwitchFront{9};
|
||||
frc::DigitalInput piston1ReedSwitchBack{11};
|
||||
frc::DigitalInput hotGoalSensor{
|
||||
frc::DoubleSolenoid m_piston1{3, 4};
|
||||
frc::DoubleSolenoid m_piston2{5, 6};
|
||||
frc::Solenoid m_latchPiston{1, 2};
|
||||
frc::DigitalInput m_piston1ReedSwitchFront{9};
|
||||
frc::DigitalInput m_piston1ReedSwitchBack{11};
|
||||
frc::DigitalInput m_hotGoalSensor{
|
||||
7}; // NOTE: Currently ignored in simulation
|
||||
};
|
||||
|
||||
@@ -9,12 +9,12 @@
|
||||
|
||||
#include <Joystick.h>
|
||||
|
||||
DoubleButton::DoubleButton(frc::Joystick* joy, int button1, int button2) {
|
||||
this->joy = joy;
|
||||
this->button1 = button1;
|
||||
this->button2 = button2;
|
||||
DoubleButton::DoubleButton(frc::Joystick* joy, int button1, int button2)
|
||||
: m_joy(*joy) {
|
||||
m_button1 = button1;
|
||||
m_button2 = button2;
|
||||
}
|
||||
|
||||
bool DoubleButton::Get() {
|
||||
return joy->GetRawButton(button1) && joy->GetRawButton(button2);
|
||||
return m_joy.GetRawButton(m_button1) && m_joy.GetRawButton(m_button2);
|
||||
}
|
||||
|
||||
@@ -20,7 +20,7 @@ public:
|
||||
bool Get();
|
||||
|
||||
private:
|
||||
frc::Joystick* joy;
|
||||
int button1;
|
||||
int button2;
|
||||
frc::Joystick& m_joy;
|
||||
int m_button1;
|
||||
int m_button2;
|
||||
};
|
||||
|
||||
Reference in New Issue
Block a user