mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-20 00:51:42 +00:00
Replace deprecated API usage in C++ examples
Since there is a new version of GearsBot using the new command-based API, the old GearsBot is just removed. PR #1842 is being included to verify this PR is correct.
This commit is contained in:
committed by
Peter Johnson
parent
d6b9c7e148
commit
c9f9feff1f
@@ -1,36 +0,0 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2017-2018 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#include "OI.h"
|
||||
|
||||
#include <frc/smartdashboard/SmartDashboard.h>
|
||||
|
||||
#include "commands/Autonomous.h"
|
||||
#include "commands/CloseClaw.h"
|
||||
#include "commands/OpenClaw.h"
|
||||
#include "commands/Pickup.h"
|
||||
#include "commands/Place.h"
|
||||
#include "commands/PrepareToPickup.h"
|
||||
#include "commands/SetElevatorSetpoint.h"
|
||||
|
||||
OI::OI() {
|
||||
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());
|
||||
|
||||
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; }
|
||||
@@ -1,47 +0,0 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2017-2018 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#include "Robot.h"
|
||||
|
||||
#include <iostream>
|
||||
|
||||
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);
|
||||
frc::SmartDashboard::PutData(&elevator);
|
||||
frc::SmartDashboard::PutData(&wrist);
|
||||
frc::SmartDashboard::PutData(&claw);
|
||||
}
|
||||
|
||||
void Robot::AutonomousInit() {
|
||||
m_autonomousCommand.Start();
|
||||
std::cout << "Starting Auto" << std::endl;
|
||||
}
|
||||
|
||||
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;
|
||||
}
|
||||
|
||||
void Robot::TeleopPeriodic() { frc::Scheduler::GetInstance()->Run(); }
|
||||
|
||||
void Robot::TestPeriodic() {}
|
||||
|
||||
#ifndef RUNNING_FRC_TESTS
|
||||
int main() { return frc::StartRobot<Robot>(); }
|
||||
#endif
|
||||
@@ -1,30 +0,0 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2017-2018 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#include "commands/Autonomous.h"
|
||||
|
||||
#include "commands/CloseClaw.h"
|
||||
#include "commands/DriveStraight.h"
|
||||
#include "commands/Pickup.h"
|
||||
#include "commands/Place.h"
|
||||
#include "commands/PrepareToPickup.h"
|
||||
#include "commands/SetDistanceToBox.h"
|
||||
#include "commands/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());
|
||||
}
|
||||
@@ -1,28 +0,0 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2017-2018 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#include "commands/CloseClaw.h"
|
||||
|
||||
#include "Robot.h"
|
||||
|
||||
CloseClaw::CloseClaw() : frc::Command("CloseClaw") { Requires(&Robot::claw); }
|
||||
|
||||
// Called just before this Command runs the first time
|
||||
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(); }
|
||||
|
||||
// Called once after isFinished returns true
|
||||
void CloseClaw::End() {
|
||||
// NOTE: Doesn't stop in simulation due to lower friction causing the can to
|
||||
// fall out
|
||||
// + there is no need to worry about stalling the motor or crushing the can.
|
||||
#ifndef SIMULATION
|
||||
Robot::claw.Stop();
|
||||
#endif
|
||||
}
|
||||
@@ -1,42 +0,0 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2017-2018 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#include "commands/DriveStraight.h"
|
||||
|
||||
#include "Robot.h"
|
||||
|
||||
DriveStraight::DriveStraight(double 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();
|
||||
}
|
||||
|
||||
// Make this return true when this Command no longer needs to run execute()
|
||||
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);
|
||||
}
|
||||
|
||||
double DriveStraight::DriveStraightPIDSource::PIDGet() {
|
||||
return Robot::drivetrain.GetDistance();
|
||||
}
|
||||
|
||||
void DriveStraight::DriveStraightPIDOutput::PIDWrite(double d) {
|
||||
Robot::drivetrain.Drive(d, d);
|
||||
}
|
||||
@@ -1,24 +0,0 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2017-2018 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#include "commands/OpenClaw.h"
|
||||
|
||||
#include "Robot.h"
|
||||
|
||||
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(); }
|
||||
|
||||
// Make this return true when this Command no longer needs to run execute()
|
||||
bool OpenClaw::IsFinished() { return IsTimedOut(); }
|
||||
|
||||
// Called once after isFinished returns true
|
||||
void OpenClaw::End() { Robot::claw.Stop(); }
|
||||
@@ -1,18 +0,0 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2017-2018 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#include "commands/Pickup.h"
|
||||
|
||||
#include "commands/CloseClaw.h"
|
||||
#include "commands/SetElevatorSetpoint.h"
|
||||
#include "commands/SetWristSetpoint.h"
|
||||
|
||||
Pickup::Pickup() : frc::CommandGroup("Pickup") {
|
||||
AddSequential(new CloseClaw());
|
||||
AddParallel(new SetWristSetpoint(-45));
|
||||
AddSequential(new SetElevatorSetpoint(0.25));
|
||||
}
|
||||
@@ -1,18 +0,0 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2017-2018 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#include "commands/Place.h"
|
||||
|
||||
#include "commands/OpenClaw.h"
|
||||
#include "commands/SetElevatorSetpoint.h"
|
||||
#include "commands/SetWristSetpoint.h"
|
||||
|
||||
Place::Place() : frc::CommandGroup("Place") {
|
||||
AddSequential(new SetElevatorSetpoint(0.25));
|
||||
AddSequential(new SetWristSetpoint(0));
|
||||
AddSequential(new OpenClaw());
|
||||
}
|
||||
@@ -1,18 +0,0 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2017-2018 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#include "commands/PrepareToPickup.h"
|
||||
|
||||
#include "commands/OpenClaw.h"
|
||||
#include "commands/SetElevatorSetpoint.h"
|
||||
#include "commands/SetWristSetpoint.h"
|
||||
|
||||
PrepareToPickup::PrepareToPickup() : frc::CommandGroup("PrepareToPickup") {
|
||||
AddParallel(new OpenClaw());
|
||||
AddParallel(new SetWristSetpoint(0));
|
||||
AddSequential(new SetElevatorSetpoint(0));
|
||||
}
|
||||
@@ -1,44 +0,0 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2017-2018 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#include "commands/SetDistanceToBox.h"
|
||||
|
||||
#include <frc/PIDController.h>
|
||||
|
||||
#include "Robot.h"
|
||||
|
||||
SetDistanceToBox::SetDistanceToBox(double 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();
|
||||
}
|
||||
|
||||
// Make this return true when this Command no longer needs to run execute()
|
||||
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);
|
||||
}
|
||||
|
||||
double SetDistanceToBox::SetDistanceToBoxPIDSource::PIDGet() {
|
||||
return Robot::drivetrain.GetDistanceToObstacle();
|
||||
}
|
||||
|
||||
void SetDistanceToBox::SetDistanceToBoxPIDOutput::PIDWrite(double d) {
|
||||
Robot::drivetrain.Drive(d, d);
|
||||
}
|
||||
@@ -1,27 +0,0 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2017-2018 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#include "commands/SetElevatorSetpoint.h"
|
||||
|
||||
#include <cmath>
|
||||
|
||||
#include "Robot.h"
|
||||
|
||||
SetElevatorSetpoint::SetElevatorSetpoint(double setpoint)
|
||||
: frc::Command("SetElevatorSetpoint") {
|
||||
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();
|
||||
}
|
||||
|
||||
// Make this return true when this Command no longer needs to run execute()
|
||||
bool SetElevatorSetpoint::IsFinished() { return Robot::elevator.OnTarget(); }
|
||||
@@ -1,25 +0,0 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2017-2018 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#include "commands/SetWristSetpoint.h"
|
||||
|
||||
#include "Robot.h"
|
||||
|
||||
SetWristSetpoint::SetWristSetpoint(double setpoint)
|
||||
: frc::Command("SetWristSetpoint") {
|
||||
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();
|
||||
}
|
||||
|
||||
// Make this return true when this Command no longer needs to run execute()
|
||||
bool SetWristSetpoint::IsFinished() { return Robot::wrist.OnTarget(); }
|
||||
@@ -1,27 +0,0 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2017-2018 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#include "commands/TankDriveWithJoystick.h"
|
||||
|
||||
#include "Robot.h"
|
||||
|
||||
TankDriveWithJoystick::TankDriveWithJoystick()
|
||||
: frc::Command("TankDriveWithJoystick") {
|
||||
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));
|
||||
}
|
||||
|
||||
// Make this return true when this Command no longer needs to run execute()
|
||||
bool TankDriveWithJoystick::IsFinished() { return false; }
|
||||
|
||||
// Called once after isFinished returns true
|
||||
void TankDriveWithJoystick::End() { Robot::drivetrain.Drive(0, 0); }
|
||||
@@ -1,25 +0,0 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2017-2018 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#include "subsystems/Claw.h"
|
||||
|
||||
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::Close() { m_motor.Set(1); }
|
||||
|
||||
void Claw::Stop() { m_motor.Set(0); }
|
||||
|
||||
bool Claw::IsGripping() { return m_contact.Get(); }
|
||||
|
||||
void Claw::Log() {}
|
||||
@@ -1,75 +0,0 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2017-2018 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#include "subsystems/DriveTrain.h"
|
||||
|
||||
#include <frc/Joystick.h>
|
||||
#include <frc/smartdashboard/SmartDashboard.h>
|
||||
|
||||
#include "commands/TankDriveWithJoystick.h"
|
||||
|
||||
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);
|
||||
#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);
|
||||
#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);
|
||||
}
|
||||
|
||||
void DriveTrain::InitDefaultCommand() {
|
||||
SetDefaultCommand(new TankDriveWithJoystick());
|
||||
}
|
||||
|
||||
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());
|
||||
}
|
||||
|
||||
void DriveTrain::Drive(double left, double right) {
|
||||
m_robotDrive.TankDrive(left, right);
|
||||
}
|
||||
|
||||
double DriveTrain::GetHeading() { return m_gyro.GetAngle(); }
|
||||
|
||||
void DriveTrain::Reset() {
|
||||
m_gyro.Reset();
|
||||
m_leftEncoder.Reset();
|
||||
m_rightEncoder.Reset();
|
||||
}
|
||||
|
||||
double DriveTrain::GetDistance() {
|
||||
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();
|
||||
}
|
||||
@@ -1,32 +0,0 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2017-2018 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#include "subsystems/Elevator.h"
|
||||
|
||||
#include <frc/livewindow/LiveWindow.h>
|
||||
#include <frc/smartdashboard/SmartDashboard.h>
|
||||
|
||||
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);
|
||||
#endif
|
||||
SetAbsoluteTolerance(0.005);
|
||||
|
||||
// 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);
|
||||
}
|
||||
|
||||
double Elevator::ReturnPIDInput() { return m_pot.Get(); }
|
||||
|
||||
void Elevator::UsePIDOutput(double d) { m_motor.Set(d); }
|
||||
@@ -1,31 +0,0 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2017-2018 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#include "subsystems/Wrist.h"
|
||||
|
||||
#include <frc/smartdashboard/SmartDashboard.h>
|
||||
|
||||
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);
|
||||
#endif
|
||||
SetAbsoluteTolerance(2.5);
|
||||
|
||||
// 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);
|
||||
}
|
||||
|
||||
double Wrist::ReturnPIDInput() { return m_pot.Get(); }
|
||||
|
||||
void Wrist::UsePIDOutput(double d) { m_motor.Set(d); }
|
||||
@@ -1,30 +0,0 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2017-2018 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <frc/Joystick.h>
|
||||
#include <frc/buttons/JoystickButton.h>
|
||||
|
||||
class OI {
|
||||
public:
|
||||
OI();
|
||||
frc::Joystick& GetJoystick();
|
||||
|
||||
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};
|
||||
};
|
||||
@@ -1,41 +0,0 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2017-2018 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <frc/TimedRobot.h>
|
||||
#include <frc/commands/Command.h>
|
||||
#include <frc/commands/Scheduler.h>
|
||||
#include <frc/livewindow/LiveWindow.h>
|
||||
#include <frc/smartdashboard/SmartDashboard.h>
|
||||
|
||||
#include "OI.h"
|
||||
#include "commands/Autonomous.h"
|
||||
#include "subsystems/Claw.h"
|
||||
#include "subsystems/DriveTrain.h"
|
||||
#include "subsystems/Elevator.h"
|
||||
#include "subsystems/Wrist.h"
|
||||
|
||||
class Robot : public frc::TimedRobot {
|
||||
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();
|
||||
|
||||
void RobotInit() override;
|
||||
void AutonomousInit() override;
|
||||
void AutonomousPeriodic() override;
|
||||
void TeleopInit() override;
|
||||
void TeleopPeriodic() override;
|
||||
void TestPeriodic() override;
|
||||
};
|
||||
@@ -1,18 +0,0 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2017-2018 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <frc/commands/CommandGroup.h>
|
||||
|
||||
/**
|
||||
* The main autonomous command to pickup and deliver the soda to the box.
|
||||
*/
|
||||
class Autonomous : public frc::CommandGroup {
|
||||
public:
|
||||
Autonomous();
|
||||
};
|
||||
@@ -1,22 +0,0 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2017-2018 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <frc/commands/Command.h>
|
||||
|
||||
/**
|
||||
* Opens the claw for one second. Real robots should use sensors, stalling
|
||||
* motors is BAD!
|
||||
*/
|
||||
class CloseClaw : public frc::Command {
|
||||
public:
|
||||
CloseClaw();
|
||||
void Initialize() override;
|
||||
bool IsFinished() override;
|
||||
void End() override;
|
||||
};
|
||||
@@ -1,44 +0,0 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2017-2018 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <frc/PIDController.h>
|
||||
#include <frc/PIDOutput.h>
|
||||
#include <frc/PIDSource.h>
|
||||
#include <frc/commands/Command.h>
|
||||
|
||||
/**
|
||||
* Drive the given distance straight (negative values go backwards).
|
||||
* Uses a local PID controller to run a simple PID loop that is only
|
||||
* enabled while this command is running. The input is the averaged
|
||||
* 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;
|
||||
|
||||
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:
|
||||
DriveStraightPIDSource m_source;
|
||||
DriveStraightPIDOutput m_output;
|
||||
frc::PIDController m_pid{4, 0, 0, &m_source, &m_output};
|
||||
};
|
||||
@@ -1,22 +0,0 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2017-2018 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <frc/commands/Command.h>
|
||||
|
||||
/**
|
||||
* Opens the claw for one second. Real robots should use sensors, stalling
|
||||
* motors is BAD!
|
||||
*/
|
||||
class OpenClaw : public frc::Command {
|
||||
public:
|
||||
OpenClaw();
|
||||
void Initialize() override;
|
||||
bool IsFinished() override;
|
||||
void End() override;
|
||||
};
|
||||
@@ -1,19 +0,0 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2017-2018 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <frc/commands/CommandGroup.h>
|
||||
|
||||
/**
|
||||
* Pickup a soda can (if one is between the open claws) and
|
||||
* get it in a safe state to drive around.
|
||||
*/
|
||||
class Pickup : public frc::CommandGroup {
|
||||
public:
|
||||
Pickup();
|
||||
};
|
||||
@@ -1,18 +0,0 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2017-2018 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <frc/commands/CommandGroup.h>
|
||||
|
||||
/**
|
||||
* Place a held soda can onto the platform.
|
||||
*/
|
||||
class Place : public frc::CommandGroup {
|
||||
public:
|
||||
Place();
|
||||
};
|
||||
@@ -1,18 +0,0 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2017-2018 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <frc/commands/CommandGroup.h>
|
||||
|
||||
/**
|
||||
* Make sure the robot is in a state to pickup soda cans.
|
||||
*/
|
||||
class PrepareToPickup : public frc::CommandGroup {
|
||||
public:
|
||||
PrepareToPickup();
|
||||
};
|
||||
@@ -1,44 +0,0 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2017-2018 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <frc/PIDController.h>
|
||||
#include <frc/PIDOutput.h>
|
||||
#include <frc/PIDSource.h>
|
||||
#include <frc/commands/Command.h>
|
||||
|
||||
/**
|
||||
* 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
|
||||
* command is running. The input is the averaged values of the left and right
|
||||
* encoders.
|
||||
*/
|
||||
class SetDistanceToBox : public frc::Command {
|
||||
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 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};
|
||||
};
|
||||
@@ -1,27 +0,0 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2017-2018 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <frc/commands/Command.h>
|
||||
|
||||
/**
|
||||
* Move the elevator to a given location. This command finishes when it is
|
||||
* within
|
||||
* the tolerance, but leaves the PID loop running to maintain the position.
|
||||
* Other
|
||||
* 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;
|
||||
|
||||
private:
|
||||
double m_setpoint;
|
||||
};
|
||||
@@ -1,25 +0,0 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2017-2018 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <frc/commands/Command.h>
|
||||
|
||||
/**
|
||||
* Move the wrist to a given angle. This command finishes when it is within
|
||||
* the tolerance, but leaves the PID loop running to maintain the position.
|
||||
* 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;
|
||||
|
||||
private:
|
||||
double m_setpoint;
|
||||
};
|
||||
@@ -1,21 +0,0 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2017-2018 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <frc/commands/Command.h>
|
||||
|
||||
/**
|
||||
* 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;
|
||||
};
|
||||
@@ -1,51 +0,0 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2017-2018 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <frc/DigitalInput.h>
|
||||
#include <frc/PWMVictorSPX.h>
|
||||
#include <frc/commands/Subsystem.h>
|
||||
|
||||
/**
|
||||
* The claw subsystem is a simple system with a motor for opening and closing.
|
||||
* If using stronger motors, you should probably use a sensor so that the
|
||||
* motors don't stall.
|
||||
*/
|
||||
class Claw : public frc::Subsystem {
|
||||
public:
|
||||
Claw();
|
||||
|
||||
void InitDefaultCommand() override;
|
||||
|
||||
/**
|
||||
* Set the claw motor to move in the open direction.
|
||||
*/
|
||||
void Open();
|
||||
|
||||
/**
|
||||
* Set the claw motor to move in the close direction.
|
||||
*/
|
||||
void Close();
|
||||
|
||||
/**
|
||||
* 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();
|
||||
|
||||
void Log();
|
||||
|
||||
private:
|
||||
frc::PWMVictorSPX m_motor{7};
|
||||
frc::DigitalInput m_contact{5};
|
||||
};
|
||||
@@ -1,84 +0,0 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2017-2018 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <frc/AnalogGyro.h>
|
||||
#include <frc/AnalogInput.h>
|
||||
#include <frc/Encoder.h>
|
||||
#include <frc/PWMVictorSPX.h>
|
||||
#include <frc/SpeedControllerGroup.h>
|
||||
#include <frc/commands/Subsystem.h>
|
||||
#include <frc/drive/DifferentialDrive.h>
|
||||
|
||||
namespace frc {
|
||||
class Joystick;
|
||||
} // namespace frc
|
||||
|
||||
/**
|
||||
* 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 frc::Subsystem {
|
||||
public:
|
||||
DriveTrain();
|
||||
|
||||
/**
|
||||
* 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();
|
||||
|
||||
/**
|
||||
* 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();
|
||||
|
||||
/**
|
||||
* 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 to the obstacle detected by the rangefinder.
|
||||
*/
|
||||
double GetDistanceToObstacle();
|
||||
|
||||
private:
|
||||
frc::PWMVictorSPX m_frontLeft{1};
|
||||
frc::PWMVictorSPX m_rearLeft{2};
|
||||
frc::SpeedControllerGroup m_left{m_frontLeft, m_rearLeft};
|
||||
|
||||
frc::PWMVictorSPX m_frontRight{3};
|
||||
frc::PWMVictorSPX 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};
|
||||
};
|
||||
@@ -1,59 +0,0 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2017-2018 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <frc/AnalogPotentiometer.h>
|
||||
#include <frc/PWMVictorSPX.h>
|
||||
#include <frc/commands/PIDSubsystem.h>
|
||||
|
||||
/**
|
||||
* The elevator subsystem uses PID to go to a given height. Unfortunately, in
|
||||
* it's current
|
||||
* state PID values for simulation are different than in the real world do to
|
||||
* minor differences.
|
||||
*/
|
||||
class Elevator : public frc::PIDSubsystem {
|
||||
public:
|
||||
Elevator();
|
||||
|
||||
void InitDefaultCommand() override;
|
||||
|
||||
/**
|
||||
* 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 motor as the PID output. This method is automatically called
|
||||
* by
|
||||
* the subsystem.
|
||||
*/
|
||||
void UsePIDOutput(double d) override;
|
||||
|
||||
private:
|
||||
frc::PWMVictorSPX m_motor{5};
|
||||
|
||||
// Conversion value of potentiometer varies between the real world and
|
||||
// simulation
|
||||
#ifndef SIMULATION
|
||||
frc::AnalogPotentiometer m_pot{2, -2.0 / 5};
|
||||
#else
|
||||
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;
|
||||
};
|
||||
@@ -1,55 +0,0 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2017-2018 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <frc/AnalogPotentiometer.h>
|
||||
#include <frc/PWMVictorSPX.h>
|
||||
#include <frc/commands/PIDSubsystem.h>
|
||||
|
||||
/**
|
||||
* The wrist subsystem is like the elevator, but with a rotational joint instead
|
||||
* of a linear joint.
|
||||
*/
|
||||
class Wrist : public frc::PIDSubsystem {
|
||||
public:
|
||||
Wrist();
|
||||
|
||||
void InitDefaultCommand() override;
|
||||
|
||||
/**
|
||||
* 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 motor as the PID output. This method is automatically called
|
||||
* by
|
||||
* the subsystem.
|
||||
*/
|
||||
void UsePIDOutput(double d) override;
|
||||
|
||||
private:
|
||||
frc::PWMVictorSPX m_motor{6};
|
||||
|
||||
// Conversion value of potentiometer varies between the real world and
|
||||
// simulation
|
||||
#ifndef SIMULATION
|
||||
frc::AnalogPotentiometer m_pot{3, -270.0 / 5};
|
||||
#else
|
||||
frc::AnalogPotentiometer m_pot{3}; // Defaults to degrees
|
||||
#endif
|
||||
|
||||
static constexpr double kP_real = 1;
|
||||
static constexpr double kP_simulation = 0.05;
|
||||
};
|
||||
Reference in New Issue
Block a user