diff --git a/frc-2020/.vscode/settings.json b/frc-2020/.vscode/settings.json index 520a141..0eae632 100644 --- a/frc-2020/.vscode/settings.json +++ b/frc-2020/.vscode/settings.json @@ -19,6 +19,64 @@ "*.inc": "cpp", "new": "cpp", "cmath": "cpp", - "complex": "cpp" + "complex": "cpp", + "array": "cpp", + "atomic": "cpp", + "hash_map": "cpp", + "hash_set": "cpp", + "*.tcc": "cpp", + "bitset": "cpp", + "cctype": "cpp", + "chrono": "cpp", + "clocale": "cpp", + "condition_variable": "cpp", + "cstdarg": "cpp", + "cstddef": "cpp", + "cstdint": "cpp", + "cstdio": "cpp", + "cstdlib": "cpp", + "cstring": "cpp", + "ctime": "cpp", + "cwchar": "cpp", + "cwctype": "cpp", + "deque": "cpp", + "list": "cpp", + "unordered_map": "cpp", + "unordered_set": "cpp", + "vector": "cpp", + "exception": "cpp", + "algorithm": "cpp", + "functional": "cpp", + "iterator": "cpp", + "map": "cpp", + "memory": "cpp", + "memory_resource": "cpp", + "numeric": "cpp", + "optional": "cpp", + "random": "cpp", + "ratio": "cpp", + "set": "cpp", + "string": "cpp", + "string_view": "cpp", + "system_error": "cpp", + "tuple": "cpp", + "type_traits": "cpp", + "utility": "cpp", + "fstream": "cpp", + "future": "cpp", + "initializer_list": "cpp", + "iomanip": "cpp", + "iosfwd": "cpp", + "iostream": "cpp", + "istream": "cpp", + "limits": "cpp", + "mutex": "cpp", + "ostream": "cpp", + "sstream": "cpp", + "stdexcept": "cpp", + "streambuf": "cpp", + "thread": "cpp", + "cinttypes": "cpp", + "typeinfo": "cpp" } } diff --git a/frc-2020/src/main/cpp/RobotContainer.cpp b/frc-2020/src/main/cpp/RobotContainer.cpp index 96c89e5..25d2e53 100644 --- a/frc-2020/src/main/cpp/RobotContainer.cpp +++ b/frc-2020/src/main/cpp/RobotContainer.cpp @@ -40,14 +40,15 @@ #include "commands/Autos/AutoLeftCommandGroup.h" -// #include "commands/Autos/AutoRightCommandGroup.h" +// #include "commands/Autos/AutoLeftCommandGroupStrafe.h" // #include "commands/Autos/AutoTestCommandGroup.h" - +#include "commands/Autos/FordAuto.h" #include #include #include -#include +#include +#include #include "Constants.h" #include @@ -80,13 +81,41 @@ +#include "Paths.h" using namespace DriveConstants; RobotContainer::RobotContainer(): m_driverController(0), m_auxController(1), m_tDpadAux(&m_auxController, XBOX_DPAD_TOP), m_bDpadAux(&m_auxController, XBOX_DPAD_BOTTOM){ - ConfigureButtonBindings(); + ConfigureButtonBindings(); + double metersToInches = 39.87; + std::vector one; + one.push_back(SwerveDrivePathGenerator::waypoint_t {RobotParameters::k_robotLength/2.0, 120 + (metersToInches*RobotParameters::k_wheelBase)/2.0, 90, 0, 0});//start + one.push_back(SwerveDrivePathGenerator::waypoint_t {56, 206, 21.57, 1000, 10000}); + one.push_back(SwerveDrivePathGenerator::waypoint_t {103.315+30.76, 246.906-8.805+6, 21.57, 0, 0});//pick up ball 4 and 5 + m_followerLeft[0].generatePath(one, "one");//247 147 + + std::vector two; + two.push_back(SwerveDrivePathGenerator::waypoint_t {103.315+30.76, 246.906-8.805+6, 21.57, 0, 0});//pick up ball 4 and 5 + two.push_back(SwerveDrivePathGenerator::waypoint_t {101.67+2.39-2.868-12, 231.5-6.577-0.877-3.5, 90, RobotParameters::k_maxSpeed*39.38, 0});//move + two.push_back(SwerveDrivePathGenerator::waypoint_t {77.2, 231.5-6.577-0.877-7.01+2.86+2.86, 180, 0, 0});//move to shoot + m_followerLeft[1].generatePath(two, "two");//92 234 + + std::vector three; + three.push_back(SwerveDrivePathGenerator::waypoint_t {77.2, 231.5-6.577-0.877-7.01+2.86+2.86, 188, 0, 0});//shoot pose + three.push_back(SwerveDrivePathGenerator::waypoint_t {36, 189, 90, (RobotParameters::k_maxSpeed)*39.38, 0}); // move + three.push_back(SwerveDrivePathGenerator::waypoint_t {32, 320, 90, 0, 0}); // pick up ball 6 - 8 + m_followerLeft[2].generatePath(three, "three"); + + + std::vector four; + four.push_back(SwerveDrivePathGenerator::waypoint_t {32, 320, 90, 0, 0}); // move + four.push_back(SwerveDrivePathGenerator::waypoint_t {54, 249, 130, (RobotParameters::k_maxSpeed)*39.38, 0}); // move + four.push_back(SwerveDrivePathGenerator::waypoint_t {77, 240, 187, 0, 0}); // move to shoot + m_followerLeft[3].generatePath(four, "four"); + + // frc::SmartDashboard::PutData("swerve drive sub", &m_drive); frc::SmartDashboard::PutData("rotate to angle", new RotateWithTrajectoryCommand(&m_drive,frc::SmartDashboard::GetNumber("angle to rotate", 0),.55)); @@ -106,8 +135,8 @@ RobotContainer::RobotContainer(): m_driverController(0), frc::SmartDashboard::PutNumber("limeLight Izone", RobotParameters::k_limeLightIZone); frc::SmartDashboard::PutNumber("Lime light X", 0); - frc::SmartDashboard::PutNumber("Lime light Y", 0); - frc::SmartDashboard::PutNumber("Lime light yaw", 0); + frc::SmartDashboard::PutNumber("Lime light Y", 0); + frc::SmartDashboard::PutNumber("Lime light yaw", 0); frc::SmartDashboard::PutData("limelight to angle", new LimeLightRotateToTargetCommand(&m_drive,.01)); frc::SmartDashboard::PutNumber("motion magic target angle", 0); frc::SmartDashboard::PutData("motion magic to angle", new RotateWithMotionMagic(&m_drive, 20,1,true)); @@ -161,8 +190,8 @@ RobotContainer::RobotContainer(): m_driverController(0), m_climber.zeroPos(); },{&m_climber})); - frc::SmartDashboard::PutNumber("climberSetPos", 0); - frc::SmartDashboard::PutData("climb to pos", new frc2::InstantCommand([this]{ + frc::SmartDashboard::PutNumber("climberSetPos", 0); + frc::SmartDashboard::PutData("climb to pos", new frc2::InstantCommand([this]{ m_climber.goToPos(frc::SmartDashboard::GetNumber("climberSetPos", 0)); },{&m_climber})); @@ -256,12 +285,14 @@ void RobotContainer::ConfigureButtonBindings(){ frc2::Command* RobotContainer::GetAutonomousCommand() { // return nullptr; - return new AutoLeftCommandGroup(&m_follower, &m_drive, &m_shooter, &m_feeder, &m_intake); + // return new FordAuto(&m_follower, &m_drive, &m_shooter, &m_feeder, &m_intake); + return new AutoLeftCommandGroup(&m_drive, &m_shooter, &m_feeder, &m_intake, m_followerLeft); + // return new AutoTestCommandGroup(&m_follower, &m_drive, &m_shooter, &m_feeder, &m_intake); // } frc2::InstantCommand* RobotContainer::GetBrakeCommand(){ return new frc2::InstantCommand([this]{m_drive.setBrake(); TurnLimeLightOff();},{&m_drive}); } - frc2::InstantCommand* RobotContainer::GetCoastCommand(){ - return new frc2::InstantCommand([this]{m_drive.setCoast();},{&m_drive}); - } +frc2::InstantCommand* RobotContainer::GetCoastCommand(){ + return new frc2::InstantCommand([this]{m_drive.setCoast();},{&m_drive}); +} diff --git a/frc-2020/src/main/cpp/Utils/SwerveDrivePathFollower.cpp b/frc-2020/src/main/cpp/Utils/SwerveDrivePathFollower.cpp index 53bab88..648f3ec 100644 --- a/frc-2020/src/main/cpp/Utils/SwerveDrivePathFollower.cpp +++ b/frc-2020/src/main/cpp/Utils/SwerveDrivePathFollower.cpp @@ -105,7 +105,6 @@ void SwerveDrivePathFollower::Update(frc::Pose2d pose){ frc::SmartDashboard::PutNumber("pathSpeed", m_path[m_pathIndex].vel); m_time += 1.0/RobotParameters::k_updateRate; - double robotYawRate = m_path[m_pathIndex].yawRate; // double robotXVel = m_path[m_pathIndex].xVel; // double robotYVel = m_path[m_pathIndex].yVel; double robotVel = m_path[m_pathIndex].vel; @@ -113,8 +112,6 @@ void SwerveDrivePathFollower::Update(frc::Pose2d pose){ double poseY = m_path[m_lookAheadIndex].yPos; double followerYaw = m_path[m_pathIndex].yaw; double followerYawRate = m_path[m_pathIndex].yawRate; - double closestX = m_path[m_pathIndex].xPos; - double closestY = m_path[m_pathIndex].yPos; //calculating new vector double distX = poseX - pose.Translation().X().to(); double distY = poseY - pose.Translation().Y().to(); @@ -130,29 +127,6 @@ void SwerveDrivePathFollower::Update(frc::Pose2d pose){ // printf("path x vel update method %f\n", m_xVel); frc::SmartDashboard::PutNumber("x follower pos", poseX); frc::SmartDashboard::PutNumber("y follower pos", poseY); - - double actualYaw = pose.Rotation().Degrees().to(); - // m_File << m_path[m_pathIndex].time << ","; - // m_File << closestX << ","; - // m_File << closestY << ","; - // m_File << robotVel << ","; - // m_File << followerYaw << ","; - // m_File << robotYawRate << ",";//6 - - - // m_File << pose.Translation().X().to() << ","; - // m_File << pose.Translation().Y().to() << ","; - // m_File << actualYaw << ","; - // m_File << skipped << ",";//4 - - - // //look ahead info - // m_File << m_path[m_lookAheadIndex].xPos << ","; - // m_File << m_path[m_lookAheadIndex].yPos << ","; - // m_File << vectorAngle*180/MATH_CONSTANTS_PI << ","; - // m_File << cos(vectorAngle)*robotVel << ","; - // m_File << sin(vectorAngle)*robotVel << ",";//5 - // m_File << m_lookAhead <<"\n"; } @@ -217,6 +191,9 @@ double SwerveDrivePathFollower::getYawRate(){ frc::Pose2d SwerveDrivePathFollower::getPointPos(int index){ return frc::Pose2d(units::meter_t(m_path[index].xPos),units::meter_t(m_path[index].yPos), frc::Rotation2d(units::degree_t(m_path[index].yaw))); } +frc::Pose2d SwerveDrivePathFollower::getFollowerPos(){ + return frc::Pose2d(units::meter_t(m_path[m_pathIndex].xPos),units::meter_t(m_path[m_pathIndex].yPos), frc::Rotation2d(units::degree_t(m_path[m_pathIndex].yaw))); +} void SwerveDrivePathFollower::stop(bool interrupted){ // m_File.close(); frc::SmartDashboard::PutBoolean("auto interrupted", interrupted); diff --git a/frc-2020/src/main/cpp/subsystems/DriveSubsystem.cpp b/frc-2020/src/main/cpp/subsystems/DriveSubsystem.cpp index 5846a6d..3682dc1 100644 --- a/frc-2020/src/main/cpp/subsystems/DriveSubsystem.cpp +++ b/frc-2020/src/main/cpp/subsystems/DriveSubsystem.cpp @@ -8,7 +8,8 @@ #include "subsystems/DriveSubsystem.h" #include -#include +#include +#include #include "Constants.h" #include diff --git a/frc-2020/src/main/cpp/subsystems/IntakeSubsystem.cpp b/frc-2020/src/main/cpp/subsystems/IntakeSubsystem.cpp index 5ceb1af..70b4c67 100644 --- a/frc-2020/src/main/cpp/subsystems/IntakeSubsystem.cpp +++ b/frc-2020/src/main/cpp/subsystems/IntakeSubsystem.cpp @@ -19,13 +19,13 @@ } void IntakeSubsystem::extend(){ - printf("----------extend----------\n"); + // printf("----------extend----------\n"); m_intakeExtended = true; m_intakeSolenoid.Set(m_intakeSolenoid.kForward);//frc::DoubleSolenoid::Value::kReverse);//TODO uncomment } void IntakeSubsystem::retract(){ m_intakeExtended = false; - printf("----------retract----------\n"); + // printf("----------retract----------\n"); m_intakeSolenoid.Set(m_intakeSolenoid.kReverse);//Set(frc::DoubleSolenoid::Value::kForward);//TODO uncomment } bool IntakeSubsystem::isIntakeExtended(){ diff --git a/frc-2020/src/main/include/Constants.h b/frc-2020/src/main/include/Constants.h index ae5b83a..af8a824 100644 --- a/frc-2020/src/main/include/Constants.h +++ b/frc-2020/src/main/include/Constants.h @@ -8,9 +8,9 @@ #include #include #include -#include +#include #include - +#include "RobotParameters.h" #pragma once /** @@ -103,9 +103,8 @@ using radians_per_second_squared_t = units::compound_unit>>; -constexpr auto kMaxSpeed = units::meters_per_second_t(3); -constexpr auto kMaxAcceleration = units::meters_per_second_squared_t(3); -constexpr auto kMaxAngularSpeed = units::radians_per_second_t(3.142); +constexpr auto kMaxSpeed = units::meters_per_second_t(RobotParameters::k_maxSpeed); +constexpr auto kMaxAngularSpeed = units::degrees_per_second_t(RobotParameters::k_maxYawRate); constexpr auto kMaxAngularAcceleration = units::unit_t(3.142); @@ -153,7 +152,7 @@ namespace IndexerConstants{ // static constexpr double test = -(1 -.059) /(1-.38) +1; namespace FeederConstants{ static constexpr double kDefaultFeederSpeed = .8; - static constexpr double kIntakeBallDistance = 30;//28 - 35 tested + static constexpr double kIntakeBallDistance = 28;//28 - 35 tested was 30 static constexpr double kLastBallDistance = 26;//28 - 35 tested static constexpr double kShootingFarFeederSpeed = .5;//28 - 35 tested static constexpr double kShootingFeederSpeed = 1;//28 - 35 tested diff --git a/frc-2020/src/main/include/RobotContainer.h b/frc-2020/src/main/include/RobotContainer.h index 2fcc17f..621d5d3 100644 --- a/frc-2020/src/main/include/RobotContainer.h +++ b/frc-2020/src/main/include/RobotContainer.h @@ -51,10 +51,15 @@ class RobotContainer { // PanelManipulatorSubsystem m_colorSensor; // PanelManipulatorSubsystem::Color_t m_color; FeederSubsystem m_feeder; - SwerveDrivePathFollower m_follower; + ClimberSubsystem m_climber; IndexerSubsystem m_indexer; + + SwerveDrivePathFollower m_followerLeft[4]; + // SwerveDrivePathFollower m_followerLeftOne; + + frc2::Button m_startDriver{[&] { return m_driverController.GetRawButton(XBOX_START_BUTTON); }};// frc2::Button m_backDriver{[&] { return m_driverController.GetRawButton(XBOX_BACK_BUTTON); }};// diff --git a/frc-2020/src/main/include/Utils/CoordinateTranslation.h b/frc-2020/src/main/include/Utils/CoordinateTranslation.h index 6b9ad5a..a5f6760 100644 --- a/frc-2020/src/main/include/Utils/CoordinateTranslation.h +++ b/frc-2020/src/main/include/Utils/CoordinateTranslation.h @@ -17,14 +17,14 @@ class CoordinateTranslation { } static void NolanToWPILib(std::vector nolanPath,std::vector &wpiPath){ - std::ofstream m_File; - std::remove("home/lvuser/NolanToWPILib.csv"); - m_File.open("home/lvuser/NolanToWPILib.csv"); - m_File <<"xPos (m), yPos (m), yaw (deg), vel (m/s), heading, accel(m/s/s), dist(m)\n"; + // std::ofstream m_File; + // std::remove("home/lvuser/NolanToWPILib.csv"); + // m_File.open("home/lvuser/NolanToWPILib.csv"); + // m_File <<"xPos (m), yPos (m), yaw (deg), vel (m/s), heading, accel(m/s/s), dist(m)\n"; wpiPath.clear(); double inchesToMeters = .0254; for(int i = 0; i < (int)nolanPath.size();i++){ - printf("NolanToWPILib cycle: %d\n", i); + // printf("NolanToWPILib cycle: %d\n", i); SwerveDrivePathGenerator::finalPathPoint_t wpiPoint = nolanPath[i]; wpiPoint.xPos = nolanPath[i].yPos*inchesToMeters; wpiPoint.yPos = -nolanPath[i].xPos*inchesToMeters; @@ -34,27 +34,27 @@ class CoordinateTranslation { wpiPoint.accel = nolanPath[i].accel*inchesToMeters; wpiPoint.dist = nolanPath[i].dist*inchesToMeters; wpiPath.push_back(wpiPoint); - m_File << wpiPoint.xPos << ", "; - m_File << wpiPoint.yPos << ", "; - m_File << wpiPoint.yaw << ", "; - m_File << wpiPoint.vel << ", "; - m_File << wpiPoint.heading << ", "; - m_File << wpiPoint.accel << ", "; - m_File << wpiPoint.dist << ", "; - m_File << "\n"; - m_File.close(); + // m_File << wpiPoint.xPos << ", "; + // m_File << wpiPoint.yPos << ", "; + // m_File << wpiPoint.yaw << ", "; + // m_File << wpiPoint.vel << ", "; + // m_File << wpiPoint.heading << ", "; + // m_File << wpiPoint.accel << ", "; + // m_File << wpiPoint.dist << ", "; + // m_File << "\n"; + // m_File.close(); } } static void WPILibToNolan(std::vector wpiPath, std::vector &nolanPath){ double metersToInches = 39.3701; // double metersToInches = 12.0;// inches to feet - std::ofstream m_File; - std::remove("home/lvuser/WPILibToNolan.csv"); - m_File.open("home/lvuser/WPILibToNolan.csv"); - m_File <<"xPos (m), yPos (m), yaw (deg), speed (m/s), radCurve\n"; - nolanPath.clear(); + // std::ofstream m_File; + // std::remove("home/lvuser/WPILibToNolan.csv"); + // m_File.open("home/lvuser/WPILibToNolan.csv"); + // m_File <<"xPos (m), yPos (m), yaw (deg), speed (m/s), radCurve\n"; + // nolanPath.clear(); for(int i = 0; i < (int)wpiPath.size();i++){ - printf("WPILibToNolan cycle: %d\n", i); + // printf("WPILibToNolan cycle: %d\n", i); SwerveDrivePathGenerator::waypoint_t nolanPoint = wpiPath[i]; nolanPoint.xPos = -wpiPath[i].yPos*metersToInches; nolanPoint.yPos = wpiPath[i].xPos*metersToInches; @@ -62,12 +62,12 @@ class CoordinateTranslation { nolanPoint.radCurve = wpiPath[i].radCurve*metersToInches; nolanPoint.yaw = normalizeToRange::NormalizeToRange(wpiPath[i].yaw+90,-180,180, true); nolanPath.push_back(nolanPoint); - m_File << nolanPoint.xPos << ", "; - m_File << nolanPoint.yPos << ", "; - m_File << nolanPoint.yaw << ", "; - m_File << nolanPoint.speed << ", "; - m_File << nolanPoint.radCurve << ", "; - m_File << "\n"; + // m_File << nolanPoint.xPos << ", "; + // m_File << nolanPoint.yPos << ", "; + // m_File << nolanPoint.yaw << ", "; + // m_File << nolanPoint.speed << ", "; + // m_File << nolanPoint.radCurve << ", "; + // m_File << "\n"; } } private: diff --git a/frc-2020/src/main/include/Utils/SwerveDrivePathFollower.h b/frc-2020/src/main/include/Utils/SwerveDrivePathFollower.h index de0e905..f6f64fe 100644 --- a/frc-2020/src/main/include/Utils/SwerveDrivePathFollower.h +++ b/frc-2020/src/main/include/Utils/SwerveDrivePathFollower.h @@ -46,6 +46,7 @@ class SwerveDrivePathFollower { int lookAheadIndex(); bool isPathFinished(); frc::Pose2d getPointPos(int index); + frc::Pose2d getFollowerPos(); // bool targetPosFound(); // void setTargetPos(); void stop(bool interrupted); diff --git a/frc-2020/src/main/include/commands/Autos/AutoLeftCommandGroup.h b/frc-2020/src/main/include/commands/Autos/AutoLeftCommandGroup.h index 8d3376e..7ddd71e 100644 --- a/frc-2020/src/main/include/commands/Autos/AutoLeftCommandGroup.h +++ b/frc-2020/src/main/include/commands/Autos/AutoLeftCommandGroup.h @@ -15,11 +15,9 @@ #include -#include "commands/pathCommands/AutoSwerveFollowPathCommand.h" -#include "commands/pathCommands/WaitForPathToFinishCommand.h" #include "commands/pathCommands/PathFollowerCommand.h" -#include "commands/pathCommands/WaitForPosCommand.h" -#include "commands/pathCommands/FollowPathToPosCommandGroup.h" +#include "commands/pathCommands/PathFollowerCommand2.h" + #include "commands/Drive/DriveOpenLoopCommand.h" @@ -30,7 +28,7 @@ #include "commands/Intake/RetractIntakeCommand.h" #include "commands/Intake/ExtendIntakeCommand.h" #include "commands/Intake/FeederDefaultCommand.h" - +#include "commands/Intake/QueFeederCommand.h" #include "commands/LimeLight/LimeLightRotateToTargetCommand.h" #include "commands/LimeLight/TurnLimeLightOff.h" #include "commands/LimeLight/TurnLimeLightOn.h" @@ -57,61 +55,49 @@ class AutoLeftCommandGroup private: public: - AutoLeftCommandGroup(SwerveDrivePathFollower* m_follower, - DriveSubsystem* m_drive, + AutoLeftCommandGroup(DriveSubsystem* m_drive, ShooterSubsystem* m_shooter, FeederSubsystem* m_feeder, - IntakeSubsystem* m_intake){ - - // double metersToInches = 39.3701; - std::vector start; - start.push_back(SwerveDrivePathGenerator::waypoint_t {RobotParameters::k_robotLength/2.0, 120 + RobotParameters::k_wheelBase/2.0, 90, 0, 0});//start - start.push_back(SwerveDrivePathGenerator::waypoint_t {56, 206, 17, 1000, 10000}); - start.push_back(SwerveDrivePathGenerator::waypoint_t {101.67+2.39-2.868-.877+3, 231.5-6.577-0.877+2.86+20, 17, 0, 0});//pick up ball 4 and 5 - - // start.push_back(SwerveDrivePathGenerator::waypoint_t {96, 210, 0, 1000, 1000}); // shoot - - - std::vector first; - first.push_back(SwerveDrivePathGenerator::waypoint_t {101.67+2.39-2.868+3, 231.5-6.577-0.877+20, 17, 0, 0});//pick up ball 4 and 5 - first.push_back(SwerveDrivePathGenerator::waypoint_t {101.67+2.39-2.868-12, 231.5-6.577-0.877-3.5, 50, RobotParameters::k_maxSpeed*39.38, 0});//pick up ball 4 and 5 - first.push_back(SwerveDrivePathGenerator::waypoint_t {77.2, 231.5-6.577-0.877-7.01+2.86+2.86, 90, 0, 0});//pick up ball 4 and 5 - - - std::vector second; - second.push_back(SwerveDrivePathGenerator::waypoint_t {77.2, 231.5-6.577-0.877-7.01, 188, 0, 0});//pick up ball 4 and 5 - second.push_back(SwerveDrivePathGenerator::waypoint_t {36, 74+115, 90, (RobotParameters::k_maxSpeed)*39.38, 0}); // move - second.push_back(SwerveDrivePathGenerator::waypoint_t {32, 201-26+115+30, 90, 0, 0}); // shoot + IntakeSubsystem* m_intake, + SwerveDrivePathFollower m_follower[]){ + + // std::vector start; + // start.push_back(SwerveDrivePathGenerator::waypoint_t {RobotParameters::k_robotLength/2.0, 120 + RobotParameters::k_wheelBase/2.0, 90, 0, 0});//start + // start.push_back(SwerveDrivePathGenerator::waypoint_t {56, 206, 21.57, 1000, 10000});//17deg + // start.push_back(SwerveDrivePathGenerator::waypoint_t {103.315+30.76, 246.906-8.805+5.5, 21.57, 0, 0});//pick up ball 4 and 5 + + // std::vector first; + // // first.push_back(SwerveDrivePathGenerator::waypoint_t {101.67+2.39-2.868+3, 231.5-6.577-0.877+20, 17, 0, 0});//pick up ball 4 and 5 + // first.push_back(SwerveDrivePathGenerator::waypoint_t {103.315+30.76, 246.906-8.805+6, 21.57, 0, 0});//pick up ball 4 and 5 + // first.push_back(SwerveDrivePathGenerator::waypoint_t {101.67+2.39-2.868-12, 231.5-6.577-0.877-3.5, 90, RobotParameters::k_maxSpeed*39.38, 0});//pick up ball 4 and 5 + // first.push_back(SwerveDrivePathGenerator::waypoint_t {77.2, 231.5-6.577-0.877-7.01+2.86+2.86, 180, 0, 0});//pick up ball 4 and 5 + + // std::vector second; + // second.push_back(SwerveDrivePathGenerator::waypoint_t {77.2, 231.5-6.577-0.877-7.01+2.86+2.86, 188, 0, 0});//pick up ball 4 and 5 77.2, 217.04 + // second.push_back(SwerveDrivePathGenerator::waypoint_t {36, 189, 90, (RobotParameters::k_maxSpeed)*39.38, 0}); // move + // second.push_back(SwerveDrivePathGenerator::waypoint_t {32, 320, 90, 0, 0}); // shoot - std::vector third; - third.push_back(SwerveDrivePathGenerator::waypoint_t {32, 201-26+115+30, 90, 0, 0}); // move - third.push_back(SwerveDrivePathGenerator::waypoint_t {54, 229, 130, (RobotParameters::k_maxSpeed)*39.38, 0}); // other end - third.push_back(SwerveDrivePathGenerator::waypoint_t {101.67+2.39-2.868-23.99-.877-.877, 231.5-6.577-0.877-7.01+2.86+2.86, 189, 0, 0}); // other end - std::vector tempWaypoints;//if meters219.916 75 + // std::vector third; + // third.push_back(SwerveDrivePathGenerator::waypoint_t {32, 320, 90, 0, 0}); // move + // third.push_back(SwerveDrivePathGenerator::waypoint_t {54, 249, 130, (RobotParameters::k_maxSpeed)*39.38, 0}); // other end + // third.push_back(SwerveDrivePathGenerator::waypoint_t {77, 240, 189, 0, 0}); // other end - // CoordinateTranslation::WPILibToNolan(waypoints, tempWaypoints); - - - // workaround of vel and accel zero at start - - - // m_follower.start(waypoints); AddCommands( frc2::ParallelRaceGroup{ FeederDefaultCommand(m_feeder), frc2::SequentialCommandGroup{ // TurnLimeLightOff(), ExtendIntakeCommand(m_intake), - PathFollowerCommand(m_drive, start, "start path" ,true),//head to end + PathFollowerCommand2(m_drive, &m_follower[0], "start path" ,true),//head to end frc2::ParallelCommandGroup{ - PathFollowerCommand(m_drive, first, "first path"), + PathFollowerCommand2(m_drive, &m_follower[1], "first path"), RetractIntakeCommand(m_intake) }, StartShooterCommand(m_shooter), frc2::ParallelCommandGroup{ SetShooterSpeedCommand(m_shooter,ShooterConstants::kDefaultShooterShortSpeed), - RotateWithMotionMagic(m_drive, 97,1, true) + RotateWithMotionMagic(m_drive, 90, .625, true) // TurnLimeLightOn(), // LimeLightRotateTillOnTarget(m_drive, 97, 2) @@ -121,7 +107,7 @@ class AutoLeftCommandGroup frc2::ParallelRaceGroup{ ShootBallCommand(m_shooter, m_feeder), - frc2::WaitCommand(1.75_s)//5 + frc2::WaitCommand(2.5_s)//2.25 }, frc2::ParallelRaceGroup{ @@ -131,21 +117,26 @@ class AutoLeftCommandGroup StopShooterCommand(m_shooter), // TurnLimeLightOff(), ExtendIntakeCommand(m_intake), - PathFollowerCommand(m_drive, second,"balls 6-8"), + PathFollowerCommand2(m_drive, &m_follower[2],"balls 6-8"), }, frc2::ParallelCommandGroup{ RetractIntakeCommand(m_intake), - PathFollowerCommand(m_drive, third,"shoot the final part"), + PathFollowerCommand2(m_drive, &m_follower[3],"shoot the final part"), }, - StartShooterCommand(m_shooter), - frc2::ParallelCommandGroup{ - SetShooterSpeedCommand(m_shooter,ShooterConstants::kDefaultShooterShortSpeed), - // TurnLimeLightOn(), - // LimeLightRotateTillOnTarget(m_drive, 97, 2) - RotateWithMotionMagic(m_drive, 97, 1, true) - } + } }, + // frc2::WaitCommand(0.5_s), + StartShooterCommand(m_shooter), + frc2::ParallelCommandGroup{ + frc2::ParallelRaceGroup{ + QueFeederCommand(m_feeder,FeederConstants::kShootingFeederSpeed), + RotateWithMotionMagic(m_drive, 97.7, .625, true)//101 //97 + }, + SetShooterSpeedCommand(m_shooter,ShooterConstants::kDefaultShooterShortSpeed) + // TurnLimeLightOn(), + // LimeLightRotateTillOnTarget(m_drive, 97, 2) + }, frc2::ParallelRaceGroup{ ShootBallCommand(m_shooter, m_feeder), frc2::WaitCommand(3_s) diff --git a/frc-2020/src/main/include/commands/Autos/AutoLeftCommandGroupStrafe.h b/frc-2020/src/main/include/commands/Autos/AutoLeftCommandGroupStrafe.h new file mode 100644 index 0000000..2d56926 --- /dev/null +++ b/frc-2020/src/main/include/commands/Autos/AutoLeftCommandGroupStrafe.h @@ -0,0 +1,154 @@ +/*----------------------------------------------------------------------------*/ +/* Copyright (c) 2019 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 +#include +#include +#include +#include +#include + + +#include "commands/pathCommands/AutoSwerveFollowPathCommand.h" +#include "commands/pathCommands/WaitForPathToFinishCommand.h" +#include "commands/pathCommands/PathFollowerCommand.h" +#include "commands/pathCommands/PathFollowerShootingCommand.h" + + +#include "commands/Drive/DriveOpenLoopCommand.h" +#include "commands/Drive/RotateToAngleCommand.h" +#include "commands/Drive/RotateWithTrajectoryCommand.h" + +#include "commands/Intake/WaitForBallCountCommand.h" +#include "commands/Intake/RetractIntakeCommand.h" +#include "commands/Intake/ExtendIntakeCommand.h" +#include "commands/Intake/FeederDefaultCommand.h" +#include "commands/Intake/QueFeederCommand.h" +#include "commands/LimeLight/LimeLightRotateToTargetCommand.h" +#include "commands/LimeLight/TurnLimeLightOff.h" +#include "commands/LimeLight/TurnLimeLightOn.h" +#include "commands/LimeLight/LimeLightRotateToTargetCommand.h" +#include "commands/Drive/RotateWithMotionMagic.h" +#include "commands/LimeLight/LimeLightRotateTillOnTarget.h" + +#include "Utils/SwerveDrivePathFollower.h" + + +#include "commands/shooter/SetShooterRangeCommand.h" +#include "commands/shooter/SetShooterSpeedCommand.h" + + +#include "subsystems/ShooterSubsystem.h" +#include "subsystems/IntakeSubsystem.h" +#include "subsystems/FeederSubsystem.h" +#include "subsystems/DriveSubsystem.h" + + +class AutoLeftCommandGroupStrafe + : public frc2::CommandHelper { + private: + + public: + AutoLeftCommandGroupStrafe(SwerveDrivePathFollower* m_follower, + DriveSubsystem* m_drive, + ShooterSubsystem* m_shooter, + FeederSubsystem* m_feeder, + IntakeSubsystem* m_intake){ + + double metersToInches = 39.3701; + std::vector one;//pick up ball 4 - 5 + one.push_back(SwerveDrivePathGenerator::waypoint_t {RobotParameters::k_robotLength/2.0, 120 + RobotParameters::k_wheelBase/2.0, 90, 0, 0});//start pos + one.push_back(SwerveDrivePathGenerator::waypoint_t {56, 206, 17, RobotParameters::k_maxSpeed*metersToInches, 10000}); + one.push_back(SwerveDrivePathGenerator::waypoint_t {103.315, 246.906, 17, 0, 0}); + + std::vector two;//Shoot ball 1 - 5 + two.push_back(SwerveDrivePathGenerator::waypoint_t {104.192, 244.046, 17, 0, 0}); + two.push_back(SwerveDrivePathGenerator::waypoint_t {89.192, 220.546, 90, RobotParameters::k_maxSpeed*metersToInches, 0}); + two.push_back(SwerveDrivePathGenerator::waypoint_t {77.2, 222.756, 180, 0, 0}); + + std::vector three;//pick up ball 6 - 8 + three.push_back(SwerveDrivePathGenerator::waypoint_t {77.2, 222.756, 188, 0, 0}); + three.push_back(SwerveDrivePathGenerator::waypoint_t {36, 189, 90, RobotParameters::k_maxSpeed*metersToInches, 0}); + three.push_back(SwerveDrivePathGenerator::waypoint_t {32, 320, 90, 0, 0}); + + std::vector four;//shoot ball 6 - 8 + four.push_back(SwerveDrivePathGenerator::waypoint_t {32, 320, 90, 0, 0}); + four.push_back(SwerveDrivePathGenerator::waypoint_t {54, 249, 130, RobotParameters::k_maxSpeed*metersToInches, 0}); + four.push_back(SwerveDrivePathGenerator::waypoint_t {77, 240, 189, 0, 0}); + + std::vector tempWaypoints; + + + AddCommands( + // frc2::ParallelRaceGroup{ + // FeederDefaultCommand(m_feeder), + // frc2::SequentialCommandGroup{ + // ExtendIntakeCommand(m_intake), + // PathFollowerCommand(m_drive, one, "one" ,true), + // frc2::ParallelCommandGroup{ + // PathFollowerShootingCommand(m_drive, two, "two"), + // RetractIntakeCommand(m_intake) + // }, + // }, + + // frc2::ParallelRaceGroup{ + // FeederDefaultCommand(m_feeder), + // frc2::SequentialCommandGroup{ + // ExtendIntakeCommand(m_intake), + // PathFollowerCommand(m_drive, one, "start path" ,true), + // frc2::ParallelCommandGroup{ + // PathFollowerCommand(m_drive, two, "first path"), + // RetractIntakeCommand(m_intake) + // }, + // StartShooterCommand(m_shooter), + // frc2::ParallelCommandGroup{ + // SetShooterSpeedCommand(m_shooter,ShooterConstants::kDefaultShooterShortSpeed), + // RotateWithMotionMagic(m_drive, 97,1, true) + // } + // } + // }, + + // frc2::ParallelRaceGroup{ + // ShootBallCommand(m_shooter, m_feeder), + // frc2::WaitCommand(2.5_s) + // }, + + // frc2::ParallelRaceGroup{ + // FeederDefaultCommand(m_feeder), + // frc2::SequentialCommandGroup{ + // frc2::ParallelCommandGroup{ + // StopShooterCommand(m_shooter), + // ExtendIntakeCommand(m_intake), + // PathFollowerCommand(m_drive, second,"balls 6-8"), + // }, + // frc2::ParallelCommandGroup{ + // RetractIntakeCommand(m_intake), + // PathFollowerCommand(m_drive, third,"shoot the final part"), + // }, + + // } + // }, + // StartShooterCommand(m_shooter), + // frc2::ParallelCommandGroup{ + // frc2::ParallelRaceGroup{ + // QueFeederCommand(m_feeder,FeederConstants::kShootingFeederSpeed), + // RotateWithMotionMagic(m_drive, 97, 1, true) + // }, + // SetShooterSpeedCommand(m_shooter,ShooterConstants::kDefaultShooterShortSpeed) + // }, + // frc2::ParallelRaceGroup{ + // ShootBallCommand(m_shooter, m_feeder), + // frc2::WaitCommand(3_s) + // }, + + // StopShooterCommand(m_shooter) + ); + } +}; diff --git a/frc-2020/src/main/include/commands/Autos/AutoTestCommandGroup.h b/frc-2020/src/main/include/commands/Autos/AutoTestCommandGroup.h index 17fc646..05eedbc 100644 --- a/frc-2020/src/main/include/commands/Autos/AutoTestCommandGroup.h +++ b/frc-2020/src/main/include/commands/Autos/AutoTestCommandGroup.h @@ -12,27 +12,44 @@ #include #include #include +#include + + #include "commands/pathCommands/AutoSwerveFollowPathCommand.h" #include "commands/pathCommands/WaitForPathToFinishCommand.h" #include "commands/pathCommands/PathFollowerCommand.h" -#include "commands/pathCommands/StartPathFollowing.h" -#include "commands/pathCommands/StopPathFollowing.h" -#include "commands/pathCommands/WaitForPosCommand.h" -#include "commands/pathCommands/FollowPathToPosCommandGroup.h" -#include "commands/DriveOpenLoopCommand.h" -#include "commands/WaitForBallCountCommand.h" -#include "subsystems/DriveSubsystem.h" +#include "commands/pathCommands/PathFollowerShootingCommand.h" + + +#include "commands/Drive/DriveOpenLoopCommand.h" +#include "commands/Drive/RotateToAngleCommand.h" +#include "commands/Drive/RotateWithTrajectoryCommand.h" + +#include "commands/Intake/WaitForBallCountCommand.h" +#include "commands/Intake/RetractIntakeCommand.h" +#include "commands/Intake/ExtendIntakeCommand.h" +#include "commands/Intake/FeederDefaultCommand.h" +#include "commands/Intake/QueFeederCommand.h" +#include "commands/LimeLight/LimeLightRotateToTargetCommand.h" +#include "commands/LimeLight/TurnLimeLightOff.h" +#include "commands/LimeLight/TurnLimeLightOn.h" +#include "commands/LimeLight/LimeLightRotateToTargetCommand.h" +#include "commands/Drive/RotateWithMotionMagic.h" +#include "commands/LimeLight/LimeLightRotateTillOnTarget.h" + #include "Utils/SwerveDrivePathFollower.h" + + +#include "commands/shooter/SetShooterRangeCommand.h" +#include "commands/shooter/SetShooterSpeedCommand.h" +#include "commands/Shooter/FarShotCommand.h" + #include "subsystems/ShooterSubsystem.h" #include "subsystems/IntakeSubsystem.h" #include "subsystems/FeederSubsystem.h" -#include "commands/LimeLight/LimeLightRotateToTargetCommand.h" -#include "commands/shooter/SetShooterRangeCommand.h" -#include "commands/shooter/SetShooterSpeedCommand.h" -#include -#include "commands/RetractIntakeCommand.h" -#include "commands/ExtendIntakeCommand.h" -#include "commands/LimeLight/LimeLightRotateToTargetCommand.h" +#include "subsystems/DriveSubsystem.h" + + class AutoTestCommandGroup : public frc2::CommandHelper { @@ -46,27 +63,15 @@ class AutoTestCommandGroup IntakeSubsystem* m_intake){ // double metersToInches = 39.3701; - std::vector waypoints; - waypoints.push_back(SwerveDrivePathGenerator::waypoint_t {0, 0, 90, 0, 0});//start - waypoints.push_back(SwerveDrivePathGenerator::waypoint_t {0, 100, 180, 100000, 0});// - waypoints.push_back(SwerveDrivePathGenerator::waypoint_t {0, 200, -90, 100000, 0});// - waypoints.push_back(SwerveDrivePathGenerator::waypoint_t {0, 300, 0, 100000, 0}); - waypoints.push_back(SwerveDrivePathGenerator::waypoint_t {0, 400, 90, 100000, 0}); - std::vector tempWaypoints; - - // CoordinateTranslation::WPILibToNolan(waypoints, tempWaypoints); - + std::vector start; + start.push_back(SwerveDrivePathGenerator::waypoint_t {0, 0, 0, 0, 0});//start + start.push_back(SwerveDrivePathGenerator::waypoint_t {-90, 0, 0, 100, 0}); + start.push_back(SwerveDrivePathGenerator::waypoint_t {-180, 0, 0, 0, 0});//pick up ball 4 and 5 + std::vector tempWaypoints;//if meters - // workaround of vel and accel zero at start - // m_follower->generatePath(Waypoints); - - // m_follower.start(waypoints); AddCommands( - PathFollowerCommand(m_drive, waypoints, "test", true) - // StartPathFollowing(m_follower, m_drive),//start - // PathFollowerCommand(m_follower,m_drive),//head to end - // StopPathFollowing(m_follower, m_drive) + PathFollowerShootingCommand(m_drive, m_shooter, m_feeder, 1, start, "start path" ,true)//head to end ); } }; diff --git a/frc-2020/src/main/include/commands/Autos/FordAuto.h b/frc-2020/src/main/include/commands/Autos/FordAuto.h new file mode 100644 index 0000000..bd6d890 --- /dev/null +++ b/frc-2020/src/main/include/commands/Autos/FordAuto.h @@ -0,0 +1,165 @@ +/*----------------------------------------------------------------------------*/ +/* Copyright (c) 2019 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 +#include +#include +#include +#include +#include + + +#include "commands/pathCommands/AutoSwerveFollowPathCommand.h" +#include "commands/pathCommands/WaitForPathToFinishCommand.h" +#include "commands/pathCommands/PathFollowerCommand.h" +#include "commands/pathCommands/PathFollowerShootingCommand.h" + + +#include "commands/Drive/DriveOpenLoopCommand.h" +#include "commands/Drive/RotateToAngleCommand.h" +#include "commands/Drive/RotateWithTrajectoryCommand.h" + +#include "commands/Intake/WaitForBallCountCommand.h" +#include "commands/Intake/RetractIntakeCommand.h" +#include "commands/Intake/ExtendIntakeCommand.h" +#include "commands/Intake/FeederDefaultCommand.h" +#include "commands/Intake/QueFeederCommand.h" +#include "commands/LimeLight/LimeLightRotateToTargetCommand.h" +#include "commands/LimeLight/TurnLimeLightOff.h" +#include "commands/LimeLight/TurnLimeLightOn.h" +#include "commands/LimeLight/LimeLightRotateToTargetCommand.h" +#include "commands/Drive/RotateWithMotionMagic.h" + +#include "Utils/SwerveDrivePathFollower.h" + + +#include "commands/shooter/SetShooterRangeCommand.h" +#include "commands/shooter/SetShooterSpeedCommand.h" + + +#include "subsystems/ShooterSubsystem.h" +#include "subsystems/IntakeSubsystem.h" +#include "subsystems/FeederSubsystem.h" +#include "subsystems/DriveSubsystem.h" + + +class FordAuto + : public frc2::CommandHelper { + private: + + public: + FordAuto(SwerveDrivePathFollower* m_follower, + DriveSubsystem* m_drive, + ShooterSubsystem* m_shooter, + FeederSubsystem* m_feeder, + IntakeSubsystem* m_intake){ + + double metersToInches = 39.3701; + std::vector one; + one.push_back(SwerveDrivePathGenerator::waypoint_t {187, 120, 140, 0, 0});//start + one.push_back(SwerveDrivePathGenerator::waypoint_t {187, 135, 151, RobotParameters::k_maxSpeed*metersToInches,0}); + one.push_back(SwerveDrivePathGenerator::waypoint_t {187, 246, 162, 0, 0});//shoot 1 - 3 + + std::vector two; + two.push_back(SwerveDrivePathGenerator::waypoint_t {187, 246, 162, 0, 0});//start + two.push_back(SwerveDrivePathGenerator::waypoint_t {167, 258.34, 180, RobotParameters::k_maxSpeed*metersToInches, 0});//grab 4 - 5 + two.push_back(SwerveDrivePathGenerator::waypoint_t {173, 258.34, 180, 0, 0});//grab 4 - 5 + + + // std::vector two; + // two.push_back(SwerveDrivePathGenerator::waypoint_t {156, 240, 180, 0, 0});//pick up ball 4 and 5 + // two.push_back(SwerveDrivePathGenerator::waypoint_t {101.67+2.39-2.868-12, 231.5-6.577-0.877-3.5, 90, RobotParameters::k_maxSpeed*39.38, 0});//pick up ball 4 and 5 + // two.push_back(SwerveDrivePathGenerator::waypoint_t {77.2, 231.5-6.577-0.877-7.01+2.86+2.86, 180, 0, 0});//pick up ball 4 and 5 + + // std::vector three; + // three.push_back(SwerveDrivePathGenerator::waypoint_t {77.2, 231.5-6.577-0.877-7.01+2.86+2.86, 188, 0, 0});//pick up ball 4 and 5 77.2, 217.04 + // three.push_back(SwerveDrivePathGenerator::waypoint_t {36, 189, 90, (RobotParameters::k_maxSpeed)*39.38, 0}); // move + // three.push_back(SwerveDrivePathGenerator::waypoint_t {32, 320, 90, 0, 0}); // shoot + + // std::vector four; + // four.push_back(SwerveDrivePathGenerator::waypoint_t {32, 320, 90, 0, 0}); // move + // four.push_back(SwerveDrivePathGenerator::waypoint_t {54, 249, 130, (RobotParameters::k_maxSpeed)*39.38, 0}); // other end + // four.push_back(SwerveDrivePathGenerator::waypoint_t {77, 240, 189, 0, 0}); // other end + //101.67+2.39-2.868-23.99-.877-.877, 222.756 + std::vector tempWaypoints;//if meters + + + AddCommands( + StartShooterCommand(m_shooter), + SetShooterSpeedCommand(m_shooter,ShooterConstants::kDefaultShooterShortSpeed), + PathFollowerShootingCommand(m_drive, m_shooter, m_feeder, .3, one, "start path" ,true, false), + frc2::ParallelRaceGroup{ + ShootBallCommand(m_shooter, m_feeder), + frc2::WaitCommand(2_s) + }, + ExtendIntakeCommand(m_intake), + PathFollowerCommand(m_drive, two, "first path") + // frc2::ParallelRaceGroup{ + // FeederDefaultCommand(m_feeder), + // frc2::SequentialCommandGroup{ + // // TurnLimeLightOff(), + // ExtendIntakeCommand(m_intake), + // PathFollowerCommand(m_drive, start, "start path" ,true),//head to end + // frc2::ParallelCommandGroup{ + // PathFollowerCommand(m_drive, first, "first path"), + // RetractIntakeCommand(m_intake) + // }, + // StartShooterCommand(m_shooter), + // frc2::ParallelCommandGroup{ + // SetShooterSpeedCommand(m_shooter,ShooterConstants::kDefaultShooterShortSpeed), + // RotateWithMotionMagic(m_drive, 97,1, true) + // // TurnLimeLightOn(), + // // LimeLightRotateTillOnTarget(m_drive, 97, 2) + + // } + // } + // }, + + // frc2::ParallelRaceGroup{ + // ShootBallCommand(m_shooter, m_feeder), + // frc2::WaitCommand(2.5_s)//5 + // }, + + // frc2::ParallelRaceGroup{ + // FeederDefaultCommand(m_feeder), + // frc2::SequentialCommandGroup{ + // frc2::ParallelCommandGroup{ + // StopShooterCommand(m_shooter), + // // TurnLimeLightOff(), + // ExtendIntakeCommand(m_intake), + // PathFollowerCommand(m_drive, second,"balls 6-8"), + // }, + // frc2::ParallelCommandGroup{ + // RetractIntakeCommand(m_intake), + // PathFollowerCommand(m_drive, third,"shoot the final part"), + // }, + + // } + // }, + // StartShooterCommand(m_shooter), + // frc2::ParallelCommandGroup{ + // frc2::ParallelRaceGroup{ + // QueFeederCommand(m_feeder,FeederConstants::kShootingFeederSpeed), + // RotateWithMotionMagic(m_drive, 97, 1, true) + // }, + // SetShooterSpeedCommand(m_shooter,ShooterConstants::kDefaultShooterShortSpeed) + // // TurnLimeLightOn(), + // // LimeLightRotateTillOnTarget(m_drive, 97, 2) + // }, + // frc2::ParallelRaceGroup{ + // ShootBallCommand(m_shooter, m_feeder), + // frc2::WaitCommand(3_s) + // }, + + // StopShooterCommand(m_shooter) + // // TurnLimeLightOff() + ); + } +}; diff --git a/frc-2020/src/main/include/commands/Drive/DriveOpenLoopCommand.h b/frc-2020/src/main/include/commands/Drive/DriveOpenLoopCommand.h index 9b3f267..6210a04 100644 --- a/frc-2020/src/main/include/commands/Drive/DriveOpenLoopCommand.h +++ b/frc-2020/src/main/include/commands/Drive/DriveOpenLoopCommand.h @@ -10,7 +10,8 @@ #include #include #include "subsystems/DriveSubsystem.h" -#include +#include +#include /** * An example command. * diff --git a/frc-2020/src/main/include/commands/Drive/DriveWithJoystickCommand.h b/frc-2020/src/main/include/commands/Drive/DriveWithJoystickCommand.h index 97fdd87..e5a3e1c 100644 --- a/frc-2020/src/main/include/commands/Drive/DriveWithJoystickCommand.h +++ b/frc-2020/src/main/include/commands/Drive/DriveWithJoystickCommand.h @@ -12,7 +12,8 @@ #include "components/Joystick2481.h" #include "subsystems/DriveSubsystem.h" #include "components/XboxController2481.h" -#include +#include +#include /** * An example command. * diff --git a/frc-2020/src/main/include/commands/Drive/RotateWithMotionMagic.h b/frc-2020/src/main/include/commands/Drive/RotateWithMotionMagic.h index 82dbfc7..f2a24b6 100644 --- a/frc-2020/src/main/include/commands/Drive/RotateWithMotionMagic.h +++ b/frc-2020/src/main/include/commands/Drive/RotateWithMotionMagic.h @@ -31,7 +31,7 @@ class RotateWithMotionMagic double m_turnInput; double m_targetZone; double m_count; - double m_targetCounter = 3; + double m_targetCounter = 5; bool m_limeLight; frc::Timer m_timer; public: @@ -64,7 +64,7 @@ class RotateWithMotionMagic m_turnInput = nt::NetworkTableInstance::GetDefault().GetTable("limelight")->GetNumber("tx",0); } - double diff = normalizeToRange::RangedDifference(target-m_turnInput, -180,180)*.7;//frc::SmartDashboard::GetNumber("scale motion error", 1) + double diff = normalizeToRange::RangedDifference(target-m_turnInput, -180,180)*.7;//.8//.7frc::SmartDashboard::GetNumber("scale motion error", 1) m_pSwerveDrive->DriveArc(RobotParameters::k_wheelLeverArm * diff * MATH_CONSTANTS_PI/180); if(fabs(diff) < m_targetZone){ m_count++; diff --git a/frc-2021_Speed/src/main/include/commands/LimeLight/LimeLightVisable.h b/frc-2020/src/main/include/commands/Intake/QueFeederCommand.h similarity index 58% rename from frc-2021_Speed/src/main/include/commands/LimeLight/LimeLightVisable.h rename to frc-2020/src/main/include/commands/Intake/QueFeederCommand.h index 68c400a..1453b4b 100644 --- a/frc-2021_Speed/src/main/include/commands/LimeLight/LimeLightVisable.h +++ b/frc-2020/src/main/include/commands/Intake/QueFeederCommand.h @@ -9,7 +9,7 @@ #include #include -#include "networktables/NetworkTableInstance.h" +#include "subsystems/FeederSubsystem.h" /** * An example command. * @@ -17,18 +17,33 @@ * directly; this is crucially important, or else the decorator functions in * Command will *not* work! */ -class LimeLightVisable - : public frc2::CommandHelper { +class QueFeederCommand + : public frc2::CommandHelper { + private: + FeederSubsystem* m_pFeeder; + double m_speed; public: - LimeLightVisable(){} + QueFeederCommand(FeederSubsystem* feeder, double speed){ + m_pFeeder = feeder; + m_speed = speed; - void Initialize() override{} + AddRequirements(m_pFeeder); + } - void Execute() override{} + void Initialize() override{ + // printf("QueFeederCommand\n"); + m_pFeeder->setFeederSpeed(m_speed); + } - void End(bool interrupted) override{} + void Execute() override{ + + } + + void End(bool interrupted) override{ + m_pFeeder->setFeederSpeed(0); + } bool IsFinished() override{ - return (bool)nt::NetworkTableInstance::GetDefault().GetTable("limelight")->GetNumber("tv",0); + return m_pFeeder->isBallInTopBeamBreak(); } }; diff --git a/frc-2020/src/main/include/commands/LimeLight/LimeLightRotateToTargetCommand.h b/frc-2020/src/main/include/commands/LimeLight/LimeLightRotateToTargetCommand.h index 7babfe5..bc73fa1 100644 --- a/frc-2020/src/main/include/commands/LimeLight/LimeLightRotateToTargetCommand.h +++ b/frc-2020/src/main/include/commands/LimeLight/LimeLightRotateToTargetCommand.h @@ -77,7 +77,7 @@ LimeLightRotateToTargetCommand m_drive->Drive(units::meters_per_second_t(0), // set the driveTrain units::meters_per_second_t(0), - units::degrees_per_second_t(yawRate), + units::degrees_per_second_t(yawRate),//*2.2 false); frc::SmartDashboard::PutNumber("YawRate", yawRate); diff --git a/frc-2020/src/main/include/commands/LimeLight/LimeLightSwerveDriveRotateToTargetCommand.h b/frc-2020/src/main/include/commands/LimeLight/LimeLightSwerveDriveRotateToTargetCommand.h index a6337ee..3ec860d 100644 --- a/frc-2020/src/main/include/commands/LimeLight/LimeLightSwerveDriveRotateToTargetCommand.h +++ b/frc-2020/src/main/include/commands/LimeLight/LimeLightSwerveDriveRotateToTargetCommand.h @@ -80,7 +80,7 @@ class LimeLightSwerveDriveRotateToTargetCommand // printf("Limelight Yaw: %.01f",yawRate); m_drive->Drive(units::meters_per_second_t(-xleftHand), // set the driveTrain units::meters_per_second_t(-yleftHand), - units::radians_per_second_t(yawRate), + units::radians_per_second_t(yawRate),//*2.2 false); frc::SmartDashboard::PutNumber("YawRate", yawRate); diff --git a/frc-2020/src/main/include/commands/LimeLight/LimelightUpdatePose.h b/frc-2020/src/main/include/commands/LimeLight/LimelightUpdatePose.h index 3e65a4f..030ee04 100644 --- a/frc-2020/src/main/include/commands/LimeLight/LimelightUpdatePose.h +++ b/frc-2020/src/main/include/commands/LimeLight/LimelightUpdatePose.h @@ -32,7 +32,6 @@ class LimelightUpdatePose void Initialize() override{ double tx = NetworkTableInstance::GetDefault().GetTable("limelight")->GetNumber("tx",0); double ty = (nt::NetworkTableInstance::GetDefault().GetTable("limelight")->GetNumber("ty",0)+LimeLightConstants::kLimeLightAngle)*MATH_CONSTANTS_PI/180; - double ta = NetworkTableInstance::GetDefault().GetTable("limelight")->GetNumber("ta",0); double height = LimeLightConstants::kTargetHeight - LimeLightConstants::kLimeLightHeight; // frc::Translation2d targetPose = Translation2d(0, 0); //target on one side of field//TODO check coordinate frame double headingToTarget = m_driveTrain->GetPose().Rotation().Radians().to()+ tx*MATH_CONSTANTS_PI/180 + MATH_CONSTANTS_PI/2; diff --git a/frc-2020/src/main/include/commands/Shooter/ShootBallCommand.h b/frc-2020/src/main/include/commands/Shooter/ShootBallCommand.h index 85c68d1..f1239d4 100644 --- a/frc-2020/src/main/include/commands/Shooter/ShootBallCommand.h +++ b/frc-2020/src/main/include/commands/Shooter/ShootBallCommand.h @@ -37,6 +37,7 @@ class ShootBallCommand // }else{//TODO work on // m_shooter->setCloseShot(false); // } + m_feeder->setSensorPos(0); if(!m_shooter->isShooterOn()){ m_finished = true; } diff --git a/frc-2020/src/main/include/commands/pathCommands/PathFollowerCommand.h b/frc-2020/src/main/include/commands/pathCommands/PathFollowerCommand.h index 247b761..2ddf67a 100644 --- a/frc-2020/src/main/include/commands/pathCommands/PathFollowerCommand.h +++ b/frc-2020/src/main/include/commands/pathCommands/PathFollowerCommand.h @@ -12,7 +12,8 @@ #include "Utils/SwerveDrivePathFollower.h" #include #include "subsystems/DriveSubsystem.h" -#include "units/units.h" + +#include #include #include #include @@ -47,7 +48,7 @@ class PathFollowerCommand : public frc2::CommandHelperResetOdometry(m_pFollower.getPointPos(0)); } - printf("initialize\n"); + // printf("initialize\n"); // m_pDrivetrain->ZeroHeading();//starting at first point in the path diff --git a/frc-2020/src/main/include/commands/pathCommands/PathFollowerCommand2.h b/frc-2020/src/main/include/commands/pathCommands/PathFollowerCommand2.h new file mode 100644 index 0000000..7c25cbb --- /dev/null +++ b/frc-2020/src/main/include/commands/pathCommands/PathFollowerCommand2.h @@ -0,0 +1,83 @@ +/*----------------------------------------------------------------------------*/ +/* Copyright (c) 2019 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 +#include +#include +#include +#include +#include +#include +#include +#include + +#include "subsystems/DriveSubsystem.h" +#include "Utils/SwerveDrivePathFollower.h" + +class PathFollowerCommand2 : public frc2::CommandHelper { + private: + SwerveDrivePathFollower* m_pFollower; + DriveSubsystem* m_pDriveSubsystem; + std::ofstream m_File; + bool m_zero; + frc2::Timer m_timer; + std::string m_name; + double metersToInches = 39.3701; + bool m_stopAtEnd; + public: + PathFollowerCommand2(DriveSubsystem* driveTrain, + SwerveDrivePathFollower* follower, const std::string &name, + bool zero = false, + bool stopAtEnd = true){ + m_pFollower = follower; + m_pDriveSubsystem = driveTrain; + m_zero = zero; + m_name = name; + m_stopAtEnd = stopAtEnd; + AddRequirements(m_pDriveSubsystem); + } + + void Initialize() override{ + m_timer.Start(); + m_pFollower->start(); + if(m_zero){ + m_pDriveSubsystem->ResetOdometry(m_pFollower->getPointPos(0)); + } + } + + void Execute() override{ + + m_pFollower->Update(m_pDriveSubsystem->GetPose()); + frc::SmartDashboard::PutNumber("follow path command x", m_pFollower->getFollowerPos().Translation().X().to()); + frc::SmartDashboard::PutNumber("follow path command y", m_pFollower->getFollowerPos().Translation().Y().to()); + frc::SmartDashboard::PutNumber("actual x vel", m_pDriveSubsystem->GetRobotVelocity().vx.to()); + frc::SmartDashboard::PutNumber("actual y vel", m_pDriveSubsystem->GetRobotVelocity().vy.to()); + frc::SmartDashboard::PutNumber("x path vel", m_pFollower->getXVel()*metersToInches); + frc::SmartDashboard::PutNumber("y path vel", m_pFollower->getYVel()*metersToInches); + m_pDriveSubsystem->Drive(units::meters_per_second_t(m_pFollower->getXVel()), + units::meters_per_second_t(m_pFollower->getYVel()), + units::degrees_per_second_t(m_pFollower->getYawRate()), + true, + false); + } + + void End(bool interrupted) override{ + if(m_stopAtEnd){ + m_pDriveSubsystem->stop(); + } + + printf("path follower time since Initialize %f\n", m_timer.Get().to()); + m_timer.Stop(); + } + + bool IsFinished() override{ + return m_pFollower->isPathFinished(); + } +}; + diff --git a/frc-2020/src/main/include/commands/pathCommands/PathFollowerShootingCommand.h b/frc-2020/src/main/include/commands/pathCommands/PathFollowerShootingCommand.h new file mode 100644 index 0000000..1c3b32d --- /dev/null +++ b/frc-2020/src/main/include/commands/pathCommands/PathFollowerShootingCommand.h @@ -0,0 +1,113 @@ +/*----------------------------------------------------------------------------*/ +/* Copyright (c) 2019 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 +#include +#include "Utils/SwerveDrivePathFollower.h" +#include + +#include "subsystems/DriveSubsystem.h" +#include "subsystems/ShooterSubsystem.h" +#include "subsystems/FeederSubsystem.h" +#include "networktables/NetworkTableInstance.h" + +#include +#include +#include +#include +#include + +class PathFollowerShootingCommand : public frc2::CommandHelper { + private: + SwerveDrivePathFollower m_pFollower; + DriveSubsystem* m_pDriveSubsystem; + ShooterSubsystem* m_pShooterSubsystem; + FeederSubsystem* m_pFeederSubsystem; + std::ofstream m_File; + bool m_zero; + double m_zone; + bool m_shoot; + frc2::Timer m_timer; + std::string m_name; + double inputConstant = 2.2; + frc::ProfiledPIDController m_turningPIDController{ + 4.5, 0, 0.2,//RobotParameters::k_limeLightDriveP, RobotParameters::k_limeLightDriveI, RobotParameters::k_limeLightDriveD,// + AutoConstants::kThetaControllerConstraints}; + public: + PathFollowerShootingCommand(DriveSubsystem* driveTrain, + ShooterSubsystem* shooter, + FeederSubsystem* feeder, + double zone, + std::vector &waypoints, const std::string &name, + bool zero = false, + bool shoot = true){ + m_pFollower.generatePath(waypoints, name); + m_pDriveSubsystem = driveTrain; + m_pShooterSubsystem = shooter; + m_pFeederSubsystem = feeder; + m_zone = zone; + m_zero = zero; + m_name = name; + m_shoot = shoot; + AddRequirements(m_pDriveSubsystem); + AddRequirements(m_pShooterSubsystem); + AddRequirements(m_pFeederSubsystem); + } + + void Initialize() override{ + m_timer.Start(); + m_pFollower.start(); + if(m_zero){ + m_pDriveSubsystem->ResetOdometry(m_pFollower.getPointPos(0)); + } + if(m_shoot){ + m_pShooterSubsystem->startShooter(); + m_pShooterSubsystem->setCloseShot(false);//false + m_pShooterSubsystem->setShooterSpeed(ShooterConstants::kDefaultShooterFarSpeed); + } + + } + + void Execute() override{ + + m_pFollower.Update(m_pDriveSubsystem->GetPose()); + + double yawRate = m_pFollower.getYawRate()*wpi::math::pi/180; + double m_turnInput = NetworkTableInstance::GetDefault().GetTable("limelight")->GetNumber("tx",0)*wpi::math::pi/180; //get target angle + bool tv = nt::NetworkTableInstance::GetDefault().GetTable("limelight")->GetNumber("tv",0); + if(tv){ + yawRate = m_turningPIDController.Calculate(units::radian_t(m_turnInput))*inputConstant; // + //m_pShooterSubsystem->autoShootSpeed(); + } + m_pDriveSubsystem->Drive(units::meters_per_second_t(m_pFollower.getXVel()), + units::meters_per_second_t(m_pFollower.getYVel()), + units::radians_per_second_t(yawRate), + true, + false); + if(m_turnInput < m_zone && tv && m_shoot){//m_pShooterSubsystem->isShooterOnTarget() && + m_pFeederSubsystem->setFeederSpeed(FeederConstants::kShootingFeederSpeed); + } + } + + void End(bool interrupted) override{ + m_pDriveSubsystem->stop(); + if (m_shoot){ + m_pShooterSubsystem->stopShooter(); + m_pFeederSubsystem->setFeederSpeed(0.0); + } + + printf("path follower time since Initialize %f\n", m_timer.Get().to()); + m_timer.Stop(); + } + + bool IsFinished() override{ + return m_pFollower.isPathFinished(); + } +}; + diff --git a/frc-2020/src/main/include/commands/pathCommands/WaitForPathToFinishCommand.h b/frc-2020/src/main/include/commands/pathCommands/WaitForPathToFinishCommand.h index e0bd591..194a724 100644 --- a/frc-2020/src/main/include/commands/pathCommands/WaitForPathToFinishCommand.h +++ b/frc-2020/src/main/include/commands/pathCommands/WaitForPathToFinishCommand.h @@ -15,7 +15,7 @@ #include "Utils/SwerveDrivePathGenerator.h" #include "subsystems/DriveSubsystem.h" #include -#include +#include /** * An example command. * diff --git a/frc-2020/src/main/include/commands/pathCommands/WaitForPosCommand.h b/frc-2020/src/main/include/commands/pathCommands/WaitForPosCommand.h index ffa5b86..e857afe 100644 --- a/frc-2020/src/main/include/commands/pathCommands/WaitForPosCommand.h +++ b/frc-2020/src/main/include/commands/pathCommands/WaitForPosCommand.h @@ -11,7 +11,7 @@ #include #include "subsystems/DriveSubsystem.h" #include -#include + /** * An example command. * diff --git a/frc-2021_Speed/.vscode/settings.json b/frc-2021_Speed/.vscode/settings.json index 243053a..4dfdff4 100644 --- a/frc-2021_Speed/.vscode/settings.json +++ b/frc-2021_Speed/.vscode/settings.json @@ -17,6 +17,67 @@ "C_Cpp.default.configurationProvider": "vscode-wpilib", "files.associations": { "new": "cpp", - "math": "cpp" + "math": "cpp", + "*.inc": "cpp", + "memory": "cpp", + "functional": "cpp", + "array": "cpp", + "atomic": "cpp", + "hash_map": "cpp", + "hash_set": "cpp", + "*.tcc": "cpp", + "bitset": "cpp", + "cctype": "cpp", + "chrono": "cpp", + "clocale": "cpp", + "cmath": "cpp", + "complex": "cpp", + "condition_variable": "cpp", + "cstdarg": "cpp", + "cstddef": "cpp", + "cstdint": "cpp", + "cstdio": "cpp", + "cstdlib": "cpp", + "cstring": "cpp", + "ctime": "cpp", + "cwchar": "cpp", + "cwctype": "cpp", + "deque": "cpp", + "list": "cpp", + "unordered_map": "cpp", + "unordered_set": "cpp", + "vector": "cpp", + "exception": "cpp", + "algorithm": "cpp", + "iterator": "cpp", + "map": "cpp", + "memory_resource": "cpp", + "numeric": "cpp", + "optional": "cpp", + "random": "cpp", + "ratio": "cpp", + "set": "cpp", + "string": "cpp", + "string_view": "cpp", + "system_error": "cpp", + "tuple": "cpp", + "type_traits": "cpp", + "utility": "cpp", + "fstream": "cpp", + "future": "cpp", + "initializer_list": "cpp", + "iomanip": "cpp", + "iosfwd": "cpp", + "iostream": "cpp", + "istream": "cpp", + "limits": "cpp", + "mutex": "cpp", + "ostream": "cpp", + "sstream": "cpp", + "stdexcept": "cpp", + "streambuf": "cpp", + "thread": "cpp", + "cinttypes": "cpp", + "typeinfo": "cpp" } } diff --git a/frc-2021_Speed/src/main/cpp/Robot.cpp b/frc-2021_Speed/src/main/cpp/Robot.cpp index 8cd7b02..0e8ad4f 100644 --- a/frc-2021_Speed/src/main/cpp/Robot.cpp +++ b/frc-2021_Speed/src/main/cpp/Robot.cpp @@ -4,7 +4,6 @@ #include "Robot.h" -#include #include void Robot::RobotInit() {} @@ -26,15 +25,20 @@ void Robot::RobotPeriodic() { * can use it to reset any subsystem information you want to clear when the * robot is disabled. */ -void Robot::DisabledInit() {} +void Robot::DisabledInit() { + m_container.GetBrakeCommand()->Schedule(); +} -void Robot::DisabledPeriodic() {} +void Robot::DisabledPeriodic() { + m_container.GetBrakeCommand()->Schedule(); +} /** * This autonomous runs the autonomous command selected by your {@link * RobotContainer} class. */ void Robot::AutonomousInit() { + m_container.GetCoastCommand()->Schedule(); m_autonomousCommand = m_container.GetAutonomousCommand(); if (m_autonomousCommand != nullptr) { @@ -45,6 +49,7 @@ void Robot::AutonomousInit() { void Robot::AutonomousPeriodic() {} void Robot::TeleopInit() { + m_container.GetBrakeCommand()->Schedule(); // 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 diff --git a/frc-2021_Speed/src/main/cpp/RobotContainer.cpp b/frc-2021_Speed/src/main/cpp/RobotContainer.cpp index 19726ee..9d6b68f 100644 --- a/frc-2021_Speed/src/main/cpp/RobotContainer.cpp +++ b/frc-2021_Speed/src/main/cpp/RobotContainer.cpp @@ -12,31 +12,37 @@ #include #include #include -#include -#include "Constants.h" +#include +#include #include - -// #include "commands/ReadColorSensorCommand.h" -// #include "commands/RotatePanelCommand.h" -// #include "commands/RotatePanelToColor.h" - - +#include "Constants.h" +//Drive #include "commands/Drive/DriveOpenLoopCommand.h" -#include "commands/Drive/RotateToAngleCommand.h" #include "commands/Drive/DriveWithJoystickCommand.h" #include "commands/Drive/RotateWithMotionMagic.h" +#include "commands/Drive/EngageBakeCommand.h" +//Intake +// #include "commands/Intake/SetBIntakeSpeed.h" +// #include "commands/Intake/SetAIntakeSpeed.h" +// #include "commands/Intake/IntakesDefaultCommand.h" +// #include "commands/Intake/ToggleIntakeCommand.h" +// #include "commands/Intake/DropBallsCommand.h" +// #include "commands/Intake/DropIntake.h" +// //Autos +#include "commands/Autos/TestSpeedsAuto.h"//T +// #include "commands/Autos/GalacticSearchPathABlue.h" +// #include "commands/Autos/GalacticSearchPathBBlue.h" +// #include "commands/Autos/GalacticSearchPathARed.h" +// #include "commands/Autos/GalacticSearchPathBRed.h" +// #include "networktables/NetworkTableInstance.h" -// #include "commands/LimeLight/LimeLightRotateToTargetCommand.h" -// #include "commands/LimeLight/LimeLightSwerveDriveRotateToTargetCommand.h" -// #include "commands/LimeLight/LimelightUpdatePose.h" - -#include "commands/Intake/CheckBeamBreak.h" -#include "commands/Intake/SetLeftIntakeSpeed.h" -#include "commands/Intake/SetRightIntakeSpeed.h" - +#include "commands/Autos/AutoNavPathA.h"//E +#include "commands/Autos/AutoNavPathB.h"//F +#include "commands/Autos/AutoNavPathC.h"//G +// #include "commands/Autos/AutoSelectorCommandPath.h" using namespace DriveConstants; RobotContainer::RobotContainer(): m_driverController(0), @@ -44,21 +50,177 @@ RobotContainer::RobotContainer(): m_driverController(0), m_tDpadAux(&m_auxController, XBOX_DPAD_TOP), m_bDpadAux(&m_auxController, XBOX_DPAD_BOTTOM){ ConfigureButtonBindings(); -frc::SmartDashboard::PutData("motion magic to angle", new RotateWithMotionMagic(&m_drive, 20,1,false)); - // frc::SmartDashboard::PutNumber("drive P", 0.1);//5 - // frc::SmartDashboard::PutNumber("drive I", 0); - // frc::SmartDashboard::PutNumber("drive D", 0);//10 - // frc::SmartDashboard::PutNumber("drive F", 1023/(RobotParameters::k_maxSpeed/RobotParameters::k_driveMotorEncoderTicksToMPS));//10 + m_drive.SetDefaultCommand(DriveWithJoystickCommand(&m_drive, &m_driverController)); + + + const double metersToInches = 39.3701; + const double curveSmall = 17;//half of robot(12) + half of cone(2.5) + buffer(2.5) + const double curveBigNavA = 32;//35// 27;//25//30 + const double radCurveA = 20; + const double slipNavAA = -27.5;//-10; + const double slipNavAB = -47.5;//-20; + const double slipNavAXB = 15;//10 + const double slipNavAC = -50;//-10; + const double angle = 180; + //Auto Nav pathABlue A waypoints + std::vector navPathA;//RobotParameters::k_maxSpeed*metersToInches + navPathA.push_back(SwerveDrivePathGenerator::waypoint_t {60 - RobotParameters::k_robotWidth/2, 80, angle, 0, 0});//start navPathB + navPathA.push_back(SwerveDrivePathGenerator::waypoint_t {150 + slipNavAA + curveBigNavA, 60 + curveBigNavA, angle, RobotParameters::k_maxSpeed*metersToInches, radCurveA});//cone 1, point 1 + navPathA.push_back(SwerveDrivePathGenerator::waypoint_t {150 + slipNavAA + curveBigNavA, 60 - curveBigNavA, angle, RobotParameters::k_maxSpeed*metersToInches, radCurveA});//cone 1, point 2 + navPathA.push_back(SwerveDrivePathGenerator::waypoint_t {150 + slipNavAA - curveBigNavA, 60 - curveBigNavA, angle, RobotParameters::k_maxSpeed*metersToInches, radCurveA});//cone 1, point 3 + navPathA.push_back(SwerveDrivePathGenerator::waypoint_t {150 + slipNavAA - curveBigNavA, 60 + curveBigNavA, angle, RobotParameters::k_maxSpeed*metersToInches, radCurveA});//cone 1, point 4 - // frc::SmartDashboard::PutData("updatDrivePID", new frc2::InstantCommand([this]{ - // m_drive.tuneDrivePID(frc::SmartDashboard::GetNumber("drive P", .1), - // frc::SmartDashboard::GetNumber("drive I", 0), - // frc::SmartDashboard::GetNumber("drive D", 0), - // frc::SmartDashboard::GetNumber("drive F", 1023/(RobotParameters::k_maxSpeed/RobotParameters::k_driveMotorEncoderTicksToMPS))); - // },{&m_drive})); + navPathA.push_back(SwerveDrivePathGenerator::waypoint_t {240 + slipNavAB + curveBigNavA, 120 + slipNavAXB - curveBigNavA, angle, RobotParameters::k_maxSpeed*metersToInches, radCurveA});//cone 2, point 1 + navPathA.push_back(SwerveDrivePathGenerator::waypoint_t {240 + slipNavAB + curveBigNavA, 120 + slipNavAXB + curveBigNavA, angle, RobotParameters::k_maxSpeed*metersToInches, radCurveA});//cone 2, point 2 + navPathA.push_back(SwerveDrivePathGenerator::waypoint_t {240 + slipNavAB - curveBigNavA, 120 + slipNavAXB + curveBigNavA, angle, RobotParameters::k_maxSpeed*metersToInches, radCurveA});//cone 2, point 3 + navPathA.push_back(SwerveDrivePathGenerator::waypoint_t {240 + slipNavAB - curveBigNavA, 120 + slipNavAXB - curveBigNavA, angle, RobotParameters::k_maxSpeed*metersToInches, radCurveA});//cone 2, point 4 + + navPathA.push_back(SwerveDrivePathGenerator::waypoint_t {300 + slipNavAC - curveBigNavA, 60 + slipNavAXB - curveBigNavA, angle, RobotParameters::k_maxSpeed*metersToInches, radCurveA});//cone 3, point 1 + navPathA.push_back(SwerveDrivePathGenerator::waypoint_t {300 + slipNavAC + curveBigNavA, 60 + slipNavAXB - curveBigNavA, angle, RobotParameters::k_maxSpeed*metersToInches, radCurveA});//cone 3, point 2 + navPathA.push_back(SwerveDrivePathGenerator::waypoint_t {300 + slipNavAC + curveBigNavA, 60 + slipNavAXB + curveBigNavA, angle, RobotParameters::k_maxSpeed*metersToInches, radCurveA});//cone 3, point 3 + navPathA.push_back(SwerveDrivePathGenerator::waypoint_t {300 + slipNavAC - curveBigNavA, 60 + slipNavAXB + curveBigNavA, angle, RobotParameters::k_maxSpeed*metersToInches, radCurveA});//cone 3, point 4 + navPathA.push_back(SwerveDrivePathGenerator::waypoint_t {20 + slipNavAC, 90 + 25 + 20, angle, RobotParameters::k_maxSpeed*metersToInches, 0});//head to end + navPathA.push_back(SwerveDrivePathGenerator::waypoint_t {20 + slipNavAC + RobotParameters::k_robotWidth/2, 90 + 25+20, angle, 0, 0});// x should be zero + m_followerNavPathA.generatePath(navPathA,"navPathA"); + + // const double curveBigNavB = 25;//22.5 25 32 + // const double radCurveB = 24;//12 + // const double curveSmallB = 20; + // //Auto Nav Path B waypoints + // const double fudge = -20;//20 + // const double x = -20; + // const double y = -5; + // const double circle = 5;//5; + // std::vector navPathB; + // navPathB.push_back(SwerveDrivePathGenerator::waypoint_t {30 + RobotParameters::k_robotWidth/2, 40, angle, 0, 0});//start + // navPathB.push_back(SwerveDrivePathGenerator::waypoint_t {60 + curveSmallB, 60 - curveSmallB, angle, RobotParameters::k_maxSpeed*metersToInches, radCurveB});//over cone 1 + // navPathB.push_back(SwerveDrivePathGenerator::waypoint_t {120 - curveBigNavB, 60 + 32, angle, RobotParameters::k_maxSpeed*metersToInches, radCurveB});//over cone 1 + // // navPathB.push_back(SwerveDrivePathGenerator::waypoint_t {110, 90, angle, RobotParameters::k_maxSpeed*metersToInches, 0});//over cone 5 + + // navPathB.push_back(SwerveDrivePathGenerator::waypoint_t {240 + fudge + curveSmallB, 60 + curveSmallB + 5, angle, RobotParameters::k_maxSpeed*metersToInches, 0});//over cone 5 + // navPathB.push_back(SwerveDrivePathGenerator::waypoint_t {300 + fudge - (curveBigNavB+circle), 60 - (curveBigNavB+circle), angle, RobotParameters::k_maxSpeed*metersToInches, radCurveB});//over cone 6 //small + // navPathB.push_back(SwerveDrivePathGenerator::waypoint_t {300 + fudge + (curveBigNavB+circle), 60 - (curveBigNavB+circle), angle, RobotParameters::k_maxSpeed*metersToInches, radCurveB});//under cone 6 + // navPathB.push_back(SwerveDrivePathGenerator::waypoint_t {300 + fudge + (curveBigNavB+circle), 60 + (curveBigNavB+circle), angle, RobotParameters::k_maxSpeed*metersToInches, radCurveB});//under cone 6 + // navPathB.push_back(SwerveDrivePathGenerator::waypoint_t {300 + fudge - (curveBigNavB+circle), 60 + (curveBigNavB+circle), angle, RobotParameters::k_maxSpeed*metersToInches, radCurveB});//over cone 6 //small + // navPathB.push_back(SwerveDrivePathGenerator::waypoint_t {240 + fudge + curveSmallB, 60 - curveSmallB + y, angle, RobotParameters::k_maxSpeed*metersToInches, 0});//under cone 5 + // navPathB.push_back(SwerveDrivePathGenerator::waypoint_t {85 + fudge + x + curveSmallB, 60 - curveSmallB + y, angle, RobotParameters::k_maxSpeed*metersToInches, 0});//under cone 1 + + // navPathB.push_back(SwerveDrivePathGenerator::waypoint_t {70 + x + fudge, 100 + y, angle, RobotParameters::k_maxSpeed*metersToInches, radCurveB});//over cone 1 + // navPathB.push_back(SwerveDrivePathGenerator::waypoint_t {60 + x + fudge, 140 + y , angle, RobotParameters::k_maxSpeed*metersToInches, 0});//head to end + // navPathB.push_back(SwerveDrivePathGenerator::waypoint_t {50 + x + fudge , 280 + y, angle, 0, 0});//head to end + // // navPathB.push_back(SwerveDrivePathGenerator::waypoint_t {15, 150, angle, 0, 0});//decelerate x should be zero + // // navPathB.push_back(SwerveDrivePathGenerator::waypoint_t {90 + fudge - 20/* 6*/, 60 - 0, angle, RobotParameters::k_maxSpeed*metersToInches, radCurveB});//over cone 1 + // // navPathB.push_back(SwerveDrivePathGenerator::waypoint_t {60 + curveBigNavB - 6, 60 + curveBigNavB, angle, RobotParameters::k_maxSpeed*metersToInches, radCurveB});//head to end + // // navPathB.push_back(SwerveDrivePathGenerator::waypoint_t {60, 90 + 4 + 2 + RobotParameters::k_robotWidth/2, angle, RobotParameters::k_maxSpeed*metersToInches, radCurveB});//head to end + // // navPathB.push_back(SwerveDrivePathGenerator::waypoint_t {30, 90 + 4 + 2 + RobotParameters::k_robotWidth/2, angle, 0, 0});//decelerate x should be zero + // m_followerNavPathB.generatePath(navPathB,"navPathB"); + + +// const double curveBigNavC = 26.0;//25 +// const double slipA = 10.0;//10//-25;//40 +// const double slipX = 8.0;//10; +// const double slipB = 18.0;//18 //15 +// const double tempSpeed = RobotParameters::k_maxSpeed*metersToInches*1.0;// +// const double fakeStopSpeed = 20.0; +// const double radCurveC = 24; +// const double tempCurve = 0;//15;//12; +// const double cone = 5; +// //Auto Nav Path C waypoints +// std::vector navPathCA; +// navPathCA.push_back(SwerveDrivePathGenerator::waypoint_t {32 + RobotParameters::k_robotWidth/2, 100, angle, 0, 0});//start +// navPathCA.push_back(SwerveDrivePathGenerator::waypoint_t {32 + RobotParameters::k_robotWidth/2 + curveBigNavC, 100, angle, tempSpeed, 0});//clear start zone +// navPathCA.push_back(SwerveDrivePathGenerator::waypoint_t {90, 150 - RobotParameters::k_robotWidth/2 - 2.5, angle, fakeStopSpeed, 0});//bounce point 1 +// m_followerNavPathC[0].generatePath(navPathCA, "pathBRed"); +// std::vector navPathCB; +// navPathCB.push_back(SwerveDrivePathGenerator::waypoint_t {90, 150 - RobotParameters::k_robotWidth/2 - 2.5, angle, fakeStopSpeed, 0});//bounce point 1 +// navPathCB.push_back(SwerveDrivePathGenerator::waypoint_t {150 - curveBigNavC - tempCurve + 1,slipA + 60 - curveBigNavC - tempCurve+3, angle, tempSpeed, radCurveC});//curve around d5 +// navPathCB.push_back(SwerveDrivePathGenerator::waypoint_t {150 + curveBigNavC, slipA + 60 - curveBigNavC, angle, tempSpeed, radCurveC});//curve around d5 +// navPathCB.push_back(SwerveDrivePathGenerator::waypoint_t {180, slipA + 10 + 150 - RobotParameters::k_robotWidth/2 - cone , angle, fakeStopSpeed, 0});//bounce point 2 +// m_followerNavPathC[1].generatePath(navPathCB, "pathBRed"); +// std::vector navPathCC; +// navPathCC.push_back(SwerveDrivePathGenerator::waypoint_t {180, 150 - RobotParameters::k_robotWidth/2- cone*2, angle, fakeStopSpeed, 0});//bounce point 2 +// navPathCC.push_back(SwerveDrivePathGenerator::waypoint_t {210 - curveBigNavC - tempCurve,slipB + 60 - curveBigNavC - 10, angle, tempSpeed, radCurveC});//curve around d7 +// navPathCC.push_back(SwerveDrivePathGenerator::waypoint_t {240 + slipX + curveBigNavC, 60 - curveBigNavC, angle, tempSpeed, radCurveC});//curve around d8 +// navPathCC.push_back(SwerveDrivePathGenerator::waypoint_t {270 + slipX, slipB + 10 + 150 + 1 - RobotParameters::k_robotWidth- cone, angle, fakeStopSpeed, 0});//bounce point 3 +// m_followerNavPathC[2].generatePath(navPathCC, "pathBRed"); +// std::vector navPathCD; +// navPathCD.push_back(SwerveDrivePathGenerator::waypoint_t {270, 150 - RobotParameters::k_robotWidth- cone*2.5, angle, fakeStopSpeed, 0});//bounce point 3 +// navPathCD.push_back(SwerveDrivePathGenerator::waypoint_t {300 - curveBigNavC, slipB - 20 + 120 - curveBigNavC- RobotParameters::k_robotWidth/2, angle, tempSpeed, 0});//head to end +// navPathCD.push_back(SwerveDrivePathGenerator::waypoint_t {300 + slipX, slipB - 45 + 100 - RobotParameters::k_robotWidth/2, angle, tempSpeed, 0});//curve into end +// navPathCD.push_back(SwerveDrivePathGenerator::waypoint_t {360 + slipX, slipB - 45 + 100 - RobotParameters::k_robotWidth/2, angle, 0, 0});//decelerate +// m_followerNavPathC[3].generatePath(navPathCD, "pathBRed"); +// std::vector navPathCE; +// navPathCE.push_back(SwerveDrivePathGenerator::waypoint_t {360, 100, angle, 0, 0});//bounce point 3 +// navPathCE.push_back(SwerveDrivePathGenerator::waypoint_t {200, 100, angle, 30, 0});//bounce point 3 +// navPathCE.push_back(SwerveDrivePathGenerator::waypoint_t {30 - RobotParameters::k_robotWidth/2, 100, angle, 0, 0});//decelerate +// m_followerNavPathC[4].generatePath(navPathCE, "pathBRed"); + + + //Galactic Search Path A Red waypoints + // const int selectOffset = 4.5; + // std::vector pathARed; + // // pathARed.push_back(SwerveDrivePathGenerator::waypoint_t {43, 90 + selectOffset, 0, 0, 0});//start pathARed + // // pathARed.push_back(SwerveDrivePathGenerator::waypoint_t {45, 90, 10, RobotParameters::k_maxSpeed*metersToInches, 0});//pick up ball 1 + // // pathARed.push_back(SwerveDrivePathGenerator::waypoint_t {90, 90, 0, RobotParameters::k_maxSpeed*metersToInches, 0});//pick up ball 1 + // // pathARed.push_back(SwerveDrivePathGenerator::waypoint_t {150, 60, -26.5, RobotParameters::k_maxSpeed*metersToInches, 0});//pick up ball 2 + // // pathARed.push_back(SwerveDrivePathGenerator::waypoint_t {177/*180*/, 150, -26.5, RobotParameters::k_maxSpeed*metersToInches, 0});//pick up ball 3 + // // pathARed.push_back(SwerveDrivePathGenerator::waypoint_t {330, 150, -26.5, RobotParameters::k_maxSpeed*metersToInches, 0});//head to end + // // pathARed.push_back(SwerveDrivePathGenerator::waypoint_t {360, 150, -26.5, 0, 0});//final 30in after endzone - m_drive.SetDefaultCommand(DriveWithJoystickCommand(&m_drive, &m_driverController)); + // pathARed.push_back(SwerveDrivePathGenerator::waypoint_t {43, 90 + selectOffset, 0, 0, 0}); + // pathARed.push_back(SwerveDrivePathGenerator::waypoint_t {43, 75, 10, 90, 0}); + // pathARed.push_back(SwerveDrivePathGenerator::waypoint_t {43, 60 + selectOffset, 0, 0, 0}); + + + // m_followerPathARed.generatePath(pathARed,"pathARed"); + + // //Galactic Search Path B Red waypoints + // std::vector pathBRed; + // // pathBRed.push_back(SwerveDrivePathGenerator::waypoint_t {43.5, 120 - selectOffset, 0, 0, 0});//start pathBRed + // // pathBRed.push_back(SwerveDrivePathGenerator::waypoint_t {90, 120, 0, RobotParameters::k_maxSpeed*metersToInches, 0});//pick up ball 1 + // // pathBRed.push_back(SwerveDrivePathGenerator::waypoint_t {150, 60, -45, RobotParameters::k_maxSpeed*metersToInches, 0});//pick up ball 2 + // // pathBRed.push_back(SwerveDrivePathGenerator::waypoint_t {210, 120, -45, RobotParameters::k_maxSpeed*metersToInches, 0});//pick up ball 3 + // // pathBRed.push_back(SwerveDrivePathGenerator::waypoint_t {330, 120, -45, RobotParameters::k_maxSpeed*metersToInches, 0});//head to end + // // pathBRed.push_back(SwerveDrivePathGenerator::waypoint_t {360, 120, -45, 0, 0});//final 30in after endzone + + // pathBRed.push_back(SwerveDrivePathGenerator::waypoint_t {43.5, 60 - selectOffset, 0, 0, 0});//start pathBRed + // pathBRed.push_back(SwerveDrivePathGenerator::waypoint_t {43.5, 75, 0, 90, 0});//pick up ball 1 + // pathBRed.push_back(SwerveDrivePathGenerator::waypoint_t {43.5, 90 - selectOffset, 0, 0, 0});//final 30in after endzone + + + // m_followerPathBRed.generatePath(pathBRed, "pathBRed"); + + // //Galactic Search Path A Blue waypoints //selectOffset + // const double slip = -10; + // std::vector pathABlue; + // pathABlue.push_back(SwerveDrivePathGenerator::waypoint_t {30, 30, 0, 0, 0});//start pathABlue + // pathABlue.push_back(SwerveDrivePathGenerator::waypoint_t {35, 30, 0, RobotParameters::k_maxSpeed*metersToInches, 0});//Drop Intakes + // pathABlue.push_back(SwerveDrivePathGenerator::waypoint_t {55, 30, 15, RobotParameters::k_maxSpeed*metersToInches, 0});//Drop Intakes + // pathABlue.push_back(SwerveDrivePathGenerator::waypoint_t {65, 30, 0, RobotParameters::k_maxSpeed*metersToInches, 0});//Drop Intakes + // pathABlue.push_back(SwerveDrivePathGenerator::waypoint_t {180, 30, 0, RobotParameters::k_maxSpeed*metersToInches, 0});//pick up ball 1 + // pathABlue.push_back(SwerveDrivePathGenerator::waypoint_t {210, 120, -26.5, RobotParameters::k_maxSpeed*metersToInches, 0});//pick up ball 2 + // pathABlue.push_back(SwerveDrivePathGenerator::waypoint_t {270, 90 + slip, -26.5, RobotParameters::k_maxSpeed*metersToInches, 0});//pick up ball 3 + // pathABlue.push_back(SwerveDrivePathGenerator::waypoint_t {330, 90 + slip, -26.5, RobotParameters::k_maxSpeed*metersToInches, 0});//head to end + // pathABlue.push_back(SwerveDrivePathGenerator::waypoint_t {360, 90 + slip, -26.5, 0, 0});//final 30in after endzone + // m_followerPathABlue.generatePath(pathABlue,"pathABlue"); + + // //Galactic Search Path B Blue waypoints + // const double yaw = 45; + // const double slipB = 0; + // std::vector pathBBlue; + // pathBBlue.push_back(SwerveDrivePathGenerator::waypoint_t {30, 60 - 5, 0, 0, 0});//start pathBBlue + // pathBBlue.push_back(SwerveDrivePathGenerator::waypoint_t {35, 60 - 5, 0, RobotParameters::k_maxSpeed*metersToInches, 0});//Drop Intake + // pathBBlue.push_back(SwerveDrivePathGenerator::waypoint_t {45, 60 - 5, 15, RobotParameters::k_maxSpeed*metersToInches, 0});//Drop Intake + // pathBBlue.push_back(SwerveDrivePathGenerator::waypoint_t {55, 60 - 5, 0, RobotParameters::k_maxSpeed*metersToInches, 0});//Drop Intake + // pathBBlue.push_back(SwerveDrivePathGenerator::waypoint_t {180, 60 - 5, 0, RobotParameters::k_maxSpeed*metersToInches, 0});//pick up ball 1 + // pathBBlue.push_back(SwerveDrivePathGenerator::waypoint_t {240, 120, -yaw + 10, RobotParameters::k_maxSpeed*metersToInches, 0});//pick up ball 2 -45 + // pathBBlue.push_back(SwerveDrivePathGenerator::waypoint_t {300, 60, -yaw, RobotParameters::k_maxSpeed*metersToInches, 0});//pick up ball 3 + // pathBBlue.push_back(SwerveDrivePathGenerator::waypoint_t {330, 60, -yaw, RobotParameters::k_maxSpeed*metersToInches, 0});//head to end + // pathBBlue.push_back(SwerveDrivePathGenerator::waypoint_t {360, 60, -yaw, 0, 0});//final 30in after endzone + // m_followerPathBBlue.generatePath(pathBBlue,"pathBBlue"); + + } @@ -75,6 +237,15 @@ class InstantDisabledCommand : public frc2::InstantCommand { void RobotContainer::ConfigureButtonBindings(){ + frc::SmartDashboard::PutData("Reset Drive Encoders", new InstantDisabledCommand([this](){ + m_drive.resetDriveEncoders(); + })); + frc::SmartDashboard::PutData("Set Coast", new InstantDisabledCommand([this](){ + m_drive.setCoast(); + })); + frc::SmartDashboard::PutData("Set Brake", new InstantDisabledCommand([this](){ + m_drive.setBrake(); + })); frc::SmartDashboard::PutData("Zero Steer Encoders", new InstantDisabledCommand([this](){ m_drive.ResetEncoders(); })); @@ -82,11 +253,6 @@ void RobotContainer::ConfigureButtonBindings(){ frc::SmartDashboard::PutData("Reset Odometry", new InstantDisabledCommand([this](){ m_drive.ResetOdometry(frc::Pose2d()); })); - frc::SmartDashboard::PutData("Reset Odometry -90", new InstantDisabledCommand([this](){ - m_drive.ResetOdometry(frc::Pose2d(m_drive.GetPose().Translation().X(), - m_drive.GetPose().Translation().Y(), - frc::Rotation2d(units::degree_t(-90)))); - })); //driver m_startDriver.WhenPressed(new frc2::InstantCommand([this]{ m_drive.ResetOdometry(frc::Pose2d( @@ -96,19 +262,77 @@ void RobotContainer::ConfigureButtonBindings(){ },{&m_drive})); m_lBumperDriver.WhenPressed(new frc2::InstantCommand([this]{m_drive.toggleFieldCentricForJoystick();},{&m_drive})); + // m_yButtonDriver.WhenPressed(new IntakesDefaultCommand(&m_intake));//ToggleIntakeCommand(&m_intake)); + // m_bButtonDriver.WhileHeld(new DropBallsCommand(&m_intake)); + // m_aButtonDriver.WhenPressed(new DropIntake(&m_intake)); + // m_rTriggerDriver.WhileHeld(new IntakesDefaultCommand(&m_intake)); //operator - } frc2::Command* RobotContainer::GetAutonomousCommand() { - - return nullptr; -// return new AutoLeftCommandGroup(&m_follower, &m_drive, &m_shooter, &m_feeder, &m_intake); + // return new EngageBakeCommand(&m_drive); + // if((bool)nt::NetworkTableInstance::GetDefault().GetTable("limelight")->GetNumber("tv",0)){ + // double targetDistance = nt::NetworkTableInstance::GetDefault().GetTable("limelight")->GetNumber("ty",0); + // double targetY = nt::NetworkTableInstance::GetDefault().GetTable("limelight")->GetNumber("tx",0); + // frc::SmartDashboard::PutNumber("target Distance", targetDistance); + // frc::SmartDashboard::PutNumber("target Y", targetY); + // if(targetDistance < 0){//RED + // if(targetY > 0){ + // frc::SmartDashboard::PutString("PATH", "A Red"); + // // printf("A Red"); + // return new GalacticSearchPathARed(&m_drive, &m_intake, &m_followerPathARed); + // }else{ + // frc::SmartDashboard::PutString("PATH", "B Red"); + // // printf("B Red"); + // return new GalacticSearchPathBRed(&m_drive, &m_intake, &m_followerPathBRed); + // } + // }else if(targetDistance > 0){//Blue + // if(targetY > 0){ + // frc::SmartDashboard::PutString("PATH", "A Blue"); + // // printf("A Blue"); + // return new GalacticSearchPathABlue(&m_drive, &m_intake, &m_followerPathABlue); + // }else{ + // frc::SmartDashboard::PutString("PATH", "B Blue"); + // // printf("B Blue"); + // return new GalacticSearchPathBBlue(&m_drive, &m_intake, &m_followerPathBBlue); + // } + // } + // } + // return new GalacticSearchPathABlue(&m_drive, &m_intake, &m_followerPathABlue); + + // return new AutoSelectorCommandPath(&m_drive, &m_intake, &m_followerPathABlue, &m_followerPathBBlue, &m_followerPathARed, &m_followerPathBRed); + // std::string gameData; + // gameData = frc::DriverStation::GetInstance().GetGameSpecificMessage(); + // if(gameData.length() > 0){ + + // switch(gameData[0]){ + // // case 'A': + // // return new GalacticSearchPathARed(&m_drive, &m_intake, &m_followerPathARed); + // // case 'B': + // // return new GalacticSearchPathBRed(&m_drive, &m_intake, &m_followerPathBRed); + // // case 'C': + // // return new GalacticSearchPathABlue(&m_drive, &m_intake, &m_followerPathABlue); + // // case 'D': + // // return new GalacticSearchPathBBlue(&m_drive, &m_intake, &m_followerPathBBlue); + // case 'A': + return new AutoNavPathA(&m_drive, &m_followerNavPathA); + // case 'B': + // return new AutoNavPathB(&m_drive, &m_followerNavPathB); + // case 'C': + // return new AutoNavPathC(&m_drive, m_followerNavPathC); + // case 'T': + // return new TestSpeedsAuto(&m_drive, &m_intake); + // default: + // return new GalacticSearchPathARed(&m_drive, &m_intake, &m_followerPathARed); + // } + // }else{ + // return new AutoNavPathC(&m_drive, m_followerNavPathC); + // } } frc2::InstantCommand* RobotContainer::GetBrakeCommand(){ - return new frc2::InstantCommand([this]{m_drive.setBrake(); },{&m_drive});//TurnLimeLightOff(); + return new frc2::InstantCommand([this]{m_drive.setBrake(); },{&m_drive}); } - frc2::InstantCommand* RobotContainer::GetCoastCommand(){ - return new frc2::InstantCommand([this]{m_drive.setCoast();},{&m_drive}); - } \ No newline at end of file +frc2::InstantCommand* RobotContainer::GetCoastCommand(){ + return new frc2::InstantCommand([this]{m_drive.setCoast();},{&m_drive}); +} \ No newline at end of file diff --git a/frc-2021_Speed/src/main/cpp/Utils/SwerveDrivePathFollower.cpp b/frc-2021_Speed/src/main/cpp/Utils/SwerveDrivePathFollower.cpp index 4f4114c..9420b96 100644 --- a/frc-2021_Speed/src/main/cpp/Utils/SwerveDrivePathFollower.cpp +++ b/frc-2021_Speed/src/main/cpp/Utils/SwerveDrivePathFollower.cpp @@ -7,15 +7,14 @@ #include "Utils/SwerveDrivePathFollower.h" #include "Utils/Interpolate.h" - +#include SwerveDrivePathFollower::SwerveDrivePathFollower(): m_lastPointReached(false), m_distToEnd(std::numeric_limits::infinity()), - m_targetZone(0.05), + m_targetZone(0.05),//.05 m_time(0){ m_xVect.push_back(0); m_xVect.push_back(RobotParameters::k_maxSpeed); - m_yVect.push_back(PathConstants::kMinLookAhead); m_yVect.push_back(PathConstants::kMaxLookAhead); } @@ -30,129 +29,112 @@ void SwerveDrivePathFollower::start(){ // This method will be called once per scheduler run void SwerveDrivePathFollower::Update(frc::Pose2d pose){ - double robotAngle = pose.Rotation().Degrees().to(); //m_pDrivetrain->GetHeading(); - - // find closest point on path - if(m_path.empty()) { - printf("empty-----------\n"); - m_lastPointReached = true; - m_distToEnd = 0; - return; - } - - frc::Translation2d vectClosestPointToRobot; - double distToClosestPoint = std::numeric_limits::infinity(); - int driftingAway = 0; - int skipped = 0; - double diffAngle = 0; - m_distToEnd = (pose.Translation() - frc::Translation2d(units::meter_t(m_path[m_path.size()-1].xPos),units::meter_t(m_path[m_path.size()-1].yPos))).Norm().to(); - // printf("size of path: %d\n", (int)m_path.size()); - for(int j = m_pathIndex; j < (int)m_path.size(); j++){ - // printf("point looking at: %d\n", j); - - frc::Translation2d vectPointToRobot = pose.Translation() - frc::Translation2d(units::meter_t(m_path[j].xPos),units::meter_t(m_path[j].yPos)); - double distToPoint = vectPointToRobot.Norm().to(); - double dirToPointRad = atan2(vectPointToRobot.Y().to(), vectPointToRobot.X().to()); - dirToPointRad = normalizeToRange::NormalizeToRange(dirToPointRad,-MATH_CONSTANTS_PI, MATH_CONSTANTS_PI,false); - double pointDirRad = m_path[j].heading*MATH_CONSTANTS_PI/180; - // printf("dirToPointRad: %f, pointDirRad: %f\n", dirToPointRad, pointDirRad); - frc::SmartDashboard::PutNumber("angleToPoint", fabs(dirToPointRad - pointDirRad)*180/MATH_CONSTANTS_PI); - //find closest point that is a specific time ahead so you dont grab points to far ahead in the path - diffAngle = fabs(normalizeToRange::RangedDifference(dirToPointRad - pointDirRad, -MATH_CONSTANTS_PI, MATH_CONSTANTS_PI)); - diffAngle = 0;//TODO check if neeeded - if(distToPoint < distToClosestPoint){ - if(MATH_CONSTANTS_PI/2 > diffAngle && fabs(m_path[j].vel) > RobotParameters::k_minRobotVelocity){ - m_pathIndex = j; - distToClosestPoint = distToPoint; - driftingAway = 0; - }else{ - skipped++; - } + double robotAngle = pose.Rotation().Degrees().to(); + + // find closest point on path + if(m_path.empty()) { + printf("empty-----------\n"); + m_lastPointReached = true; + m_distToEnd = 0; + return; + } + + frc::Translation2d vectClosestPointToRobot; + double distToClosestPoint = std::numeric_limits::infinity(); + int driftingAway = 0; + int skipped = 0; + double diffAngle = 0; + m_distToEnd = (pose.Translation() - frc::Translation2d(units::meter_t(m_path[m_path.size()-1].xPos),units::meter_t(m_path[m_path.size()-1].yPos))).Norm().to(); + for(int j = m_pathIndex; j < (int)m_path.size(); j++){ + + frc::Translation2d vectPointToRobot = pose.Translation() - frc::Translation2d(units::meter_t(m_path[j].xPos),units::meter_t(m_path[j].yPos)); + double distToPoint = vectPointToRobot.Norm().to(); + double dirToPointRad = atan2(vectPointToRobot.Y().to(), vectPointToRobot.X().to()); + dirToPointRad = normalizeToRange::NormalizeToRange(dirToPointRad,-MATH_CONSTANTS_PI, MATH_CONSTANTS_PI,false); + double pointDirRad = m_path[j].heading*MATH_CONSTANTS_PI/180; + + //find closest point that is a specific time ahead so you dont grab points to far ahead in the path + diffAngle = fabs(normalizeToRange::RangedDifference(dirToPointRad - pointDirRad, -MATH_CONSTANTS_PI, MATH_CONSTANTS_PI)); + diffAngle = 0;//TODO check if neeeded + if(distToPoint < distToClosestPoint){ + if(MATH_CONSTANTS_PI/2 > diffAngle && fabs(m_path[j].vel) > RobotParameters::k_minRobotVelocity){ + m_pathIndex = j; + distToClosestPoint = distToPoint; + driftingAway = 0; }else{ - driftingAway++; - if(driftingAway >= m_maxDrifting){ - break; - } + skipped++; } - // printf("diffAnge: %f, distToPoint: %f, distToClosestPoint %f, m_path vel: %f, driftingAway: %d\n",diffAngle, distToPoint,distToClosestPoint,m_path[j].vel, driftingAway); - } - frc::SmartDashboard::PutNumber("skipped", skipped); - frc::SmartDashboard::PutNumber("vel", m_path[m_pathIndex].vel); - // check if last point reached - if(m_pathIndex == (int)m_path.size()-1 || distToClosestPoint == std::numeric_limits::infinity() ) { - // printf("ended 120"); - frc::SmartDashboard::PutBoolean("path should stop", true); - m_lastPointReached = true; - } - frc::SmartDashboard::PutNumber("points left in the path", m_path.size() - m_pathIndex); - m_lookAhead = interpolate::interp(m_xVect, m_yVect, fabs(m_path[m_pathIndex].vel), false); - // printf("------------------lookAhead distance: %f------------------\n", m_lookAhead); - // frc::SmartDashboard::PutNumber("distToClosestPoint", distToClosestPoint); - for(int j = m_pathIndex; j < (int)m_path.size(); j++){ - frc::Translation2d vectPointToRobot = frc::Translation2d(units::meter_t(m_path[j].xPos),units::meter_t(m_path[j].yPos))- frc::Translation2d(units::meter_t(m_path[m_pathIndex].xPos),units::meter_t(m_path[m_pathIndex].yPos));//pose.Translation() - frc::Translation2d(units::meter_t(m_path[j].xPos),units::meter_t(m_path[j].yPos)); Robot centric - double distToPoint = vectPointToRobot.Norm().to(); - if(distToPoint < m_lookAhead){ - // frc::SmartDashboard::PutNumber("lookaheadPointFinding", distToPoint); - m_lookAheadIndex = j; - }else{ - + }else{ + driftingAway++; + if(driftingAway >= m_maxDrifting){ break; } } -// frc::SmartDashboard::PutNumber("look ahead point", (pose.Translation() - frc::Translation2d(units::meter_t(m_path[m_lookAheadIndex].xPos),units::meter_t(m_path[m_lookAheadIndex].yPos))).Norm().to()); - - - frc::SmartDashboard::PutNumber("pathSpeed", m_path[m_pathIndex].vel); - m_time += 1.0/RobotParameters::k_updateRate; - - double robotYawRate = m_path[m_pathIndex].yawRate; - // double robotXVel = m_path[m_pathIndex].xVel; - // double robotYVel = m_path[m_pathIndex].yVel; - double robotVel = m_path[m_pathIndex].vel; - double poseX = m_path[m_lookAheadIndex].xPos; - double poseY = m_path[m_lookAheadIndex].yPos; - double followerYaw = m_path[m_pathIndex].yaw; - double followerYawRate = m_path[m_pathIndex].yawRate; - double closestX = m_path[m_pathIndex].xPos; - double closestY = m_path[m_pathIndex].yPos; - //calculating new vector - double distX = poseX - pose.Translation().X().to(); - double distY = poseY - pose.Translation().Y().to(); - double vectorAngle = atan2(distY, distX); - // update drive - // followerYaw = 0; //temp - //field centric driving - m_yawRate = m_turningPIDController.Calculate(robotAngle,followerYaw)+followerYawRate;//add - m_xVel = cos(vectorAngle)*robotVel; - m_yVel = sin(vectorAngle)*robotVel; - - - // printf("path x vel update method %f\n", m_xVel); - frc::SmartDashboard::PutNumber("x follower pos", poseX); - frc::SmartDashboard::PutNumber("y follower pos", poseY); - - double actualYaw = pose.Rotation().Degrees().to(); - m_File << m_path[m_pathIndex].time << ","; - m_File << closestX << ","; - m_File << closestY << ","; - m_File << robotVel << ","; - m_File << followerYaw << ","; - m_File << robotYawRate << ",";//6 - - - m_File << pose.Translation().X().to() << ","; - m_File << pose.Translation().Y().to() << ","; - m_File << actualYaw << ","; - m_File << skipped << ",";//4 - - - //look ahead info - m_File << m_path[m_lookAheadIndex].xPos << ","; - m_File << m_path[m_lookAheadIndex].yPos << ","; - m_File << vectorAngle*180/MATH_CONSTANTS_PI << ","; - m_File << cos(vectorAngle)*robotVel << ","; - m_File << sin(vectorAngle)*robotVel << ",";//5 - m_File << m_lookAhead <<"\n"; + } + // check if last point reached + if(m_pathIndex == (int)m_path.size()-1 || distToClosestPoint == std::numeric_limits::infinity() ) { + // printf("ended 120"); + frc::SmartDashboard::PutBoolean("path should stop", true); + m_lastPointReached = true; + } + // frc::SmartDashboard::PutNumber("points left in the path", m_path.size() - m_pathIndex); + m_lookAhead = interpolate::interp(m_xVect, m_yVect, fabs(m_path[m_pathIndex].vel), false); + // printf("------------------lookAhead distance: %f------------------\n", m_lookAhead); + // frc::SmartDashboard::PutNumber("distToClosestPoint", distToClosestPoint); + for(int j = m_pathIndex; j < (int)m_path.size(); j++){ + frc::Translation2d vectPointToRobot = frc::Translation2d(units::meter_t(m_path[j].xPos),units::meter_t(m_path[j].yPos))- frc::Translation2d(units::meter_t(m_path[m_pathIndex].xPos),units::meter_t(m_path[m_pathIndex].yPos));//pose.Translation() - frc::Translation2d(units::meter_t(m_path[j].xPos),units::meter_t(m_path[j].yPos)); Robot centric + double distToPoint = vectPointToRobot.Norm().to(); + if(distToPoint < m_lookAhead){ + // frc::SmartDashboard::PutNumber("lookaheadPointFinding", distToPoint); + m_lookAheadIndex = j; + }else{ + + break; + } + } + + m_time += 1.0/RobotParameters::k_updateRate; + + double robotYawRate = m_path[m_pathIndex].yawRate; + double robotVel = m_path[m_pathIndex].vel; + double poseX = m_path[m_lookAheadIndex].xPos; + double poseY = m_path[m_lookAheadIndex].yPos; + double followerYaw = m_path[m_pathIndex].yaw; + double followerYawRate = m_path[m_pathIndex].yawRate; + double closestX = m_path[m_pathIndex].xPos; + double closestY = m_path[m_pathIndex].yPos; + //calculating new vector + double distX = poseX - pose.Translation().X().to(); + double distY = poseY - pose.Translation().Y().to(); + double vectorAngle = atan2(distY, distX); + //field centric driving + m_yawRate = m_turningPIDController.Calculate(robotAngle,followerYaw)+followerYawRate;//add + m_xVel = cos(vectorAngle)*robotVel; + m_yVel = sin(vectorAngle)*robotVel; + + + double actualYaw = pose.Rotation().Degrees().to(); + m_File << m_path[m_pathIndex].time << ","; + m_File << closestX * metersToInches<< ","; + m_File << closestY * metersToInches << ","; + m_File << robotVel * metersToInches << ","; + m_File << followerYaw << ","; + m_File << robotYawRate << ",";//6 + + + m_File << pose.Translation().X().to() * metersToInches << ","; + m_File << pose.Translation().Y().to() * metersToInches << ","; + m_File << actualYaw << ","; + m_File << skipped << ",";//4 + + + //look ahead info + m_File << m_path[m_lookAheadIndex].xPos * metersToInches << ","; + m_File << m_path[m_lookAheadIndex].yPos * metersToInches << ","; + m_File << vectorAngle*180/MATH_CONSTANTS_PI << ","; + m_File << cos(vectorAngle)*robotVel * metersToInches << ","; + m_File << sin(vectorAngle)*robotVel * metersToInches << ",";//5 + m_File << m_lookAhead * metersToInches <<"\n"; } @@ -166,13 +148,12 @@ bool SwerveDrivePathFollower::isPathFinished(){ frc::SmartDashboard::PutBoolean("distance", (m_distToEnd < m_targetZone)); frc::SmartDashboard::PutNumber("distance to end", m_distToEnd); frc::SmartDashboard::PutBoolean("last point reached", m_lastPointReached); - // printf("util path finished %b\n", m_pathFinished); - // printf("distance to end%f, last point reached%d\n", m_distToEnd, (int)m_lastPointReached); return (m_distToEnd < m_targetZone) || m_lastPointReached; } -void SwerveDrivePathFollower::generatePath(std::vector &waypoints, const std::string &name){ +void SwerveDrivePathFollower::generatePath(std::vector &waypoints, const std::string &name, double targetZone){ double metersToInches = 39.87; + m_targetZone = targetZone; SwerveDrivePathGenerator pathGenerator( waypoints,//tempWaypoints, RobotParameters::k_updateRate, @@ -196,9 +177,9 @@ void SwerveDrivePathFollower::generatePath(std::vector(), robotVelWheelMeas.X().to(), yawRateGyro); - // @TODO: potential improvements... - // fuse multiple observations from different sensors (IMU, lidar, etc.) } diff --git a/frc-2021_Speed/src/main/cpp/components/AnalogJoystickButton.cpp b/frc-2021_Speed/src/main/cpp/components/AnalogJoystickButton.cpp index 5a21639..62fad0e 100644 --- a/frc-2021_Speed/src/main/cpp/components/AnalogJoystickButton.cpp +++ b/frc-2021_Speed/src/main/cpp/components/AnalogJoystickButton.cpp @@ -1,5 +1,4 @@ #include "Components/AnalogJoystickButton.h" -#include AnalogJoystickButton::AnalogJoystickButton(frc::GenericHID *joystick, uint32_t axisNumber, double threshold) : m_threshold(threshold), @@ -11,7 +10,6 @@ AnalogJoystickButton::~AnalogJoystickButton() { } bool AnalogJoystickButton::Get() { - frc::SmartDashboard::PutNumber("trigger info", m_threshold); if(m_threshold < 0) { return m_pJoystick->GetRawAxis(m_axisNumber) < m_threshold; } diff --git a/frc-2021_Speed/src/main/cpp/components/ComboJoystickButton.cpp b/frc-2021_Speed/src/main/cpp/components/ComboJoystickButton.cpp deleted file mode 100644 index 6c9f916..0000000 --- a/frc-2021_Speed/src/main/cpp/components/ComboJoystickButton.cpp +++ /dev/null @@ -1,19 +0,0 @@ -// #include - -// #include -// #include "components/ComboJoystickButton.h" - -// ComboJoystickButton::ComboJoystickButton(frc2::Button *primaryButton, frc2::Button *secondaryButton, bool secondaryPressed) -// : m_pPrimaryButton(primaryButton), -// m_pSecondaryButton(secondaryButton), -// m_secondaryPressed(secondaryPressed) { -// } - -// ComboJoystickButton::~ComboJoystickButton() { -// } - -// bool ComboJoystickButton::Get() { -// return m_pPrimaryButton->Get() && -// ((m_pSecondaryButton->Get() && m_secondaryPressed) || -// (!m_pSecondaryButton->Get() && !m_secondaryPressed)); -// } diff --git a/frc-2021_Speed/src/main/cpp/components/MotorPositionController.cpp b/frc-2021_Speed/src/main/cpp/components/MotorPositionController.cpp index b9f0050..af8563e 100644 --- a/frc-2021_Speed/src/main/cpp/components/MotorPositionController.cpp +++ b/frc-2021_Speed/src/main/cpp/components/MotorPositionController.cpp @@ -1,6 +1,5 @@ #include "components/MotorPositionController.h" #include "Utils/Sign.h" -#include MotorPositionController::MotorPositionController() : m_pDriveMotor(nullptr), @@ -43,7 +42,7 @@ MotorPositionController::MotorPositionController( m_pDriveMotor->Config_kD(0, kd, 10); m_pDriveMotor->Config_IntegralZone(0, iZone, 10); m_pDriveMotor->ConfigMaxIntegralAccumulator (0, iErrorLim, 10); - m_pDriveMotor->SetNeutralMode(NeutralMode::Brake); + m_pDriveMotor->SetNeutralMode(CommonDrive::Brake); m_pDriveMotor->EnableVoltageCompensation(true); m_pDriveMotor->ConfigVoltageCompSaturation(12.0, 0); m_pDriveMotor->ConfigNeutralDeadband(0.04, 0); @@ -139,7 +138,6 @@ void MotorPositionController::updateLinear(double refP, double refV, double refA else { m_pDriveMotor->Set(CommonModes::MotionMagic, refP, DemandType::DemandType_ArbitraryFeedForward, feedforwardControl); } - // frc::SmartDashboard::PutNumber("Set Refp", refP); } double MotorPositionController::getEncoderZero() const { diff --git a/frc-2021_Speed/src/main/cpp/components/MotorVelocityController.cpp b/frc-2021_Speed/src/main/cpp/components/MotorVelocityController.cpp index da2d6ad..bf04353 100644 --- a/frc-2021_Speed/src/main/cpp/components/MotorVelocityController.cpp +++ b/frc-2021_Speed/src/main/cpp/components/MotorVelocityController.cpp @@ -42,7 +42,7 @@ MotorVelocityController::MotorVelocityController( m_pDriveMotor->Config_kF(0, 0, 10); m_pDriveMotor->Config_IntegralZone(0, iZone, 10); m_pDriveMotor->ConfigMaxIntegralAccumulator (0, iErrorLim, 10); - m_pDriveMotor->SetNeutralMode(NeutralMode::Brake); + m_pDriveMotor->SetNeutralMode(CommonDrive::Brake); m_pDriveMotor->EnableVoltageCompensation(true); m_pDriveMotor->ConfigVoltageCompSaturation(12, 10); m_pDriveMotor->ConfigNeutralDeadband(0.04, 10); diff --git a/frc-2021_Speed/src/main/cpp/components/SparkMaxMotorController.cpp b/frc-2021_Speed/src/main/cpp/components/SparkMaxMotorController.cpp index 99dd8b0..89593a2 100644 --- a/frc-2021_Speed/src/main/cpp/components/SparkMaxMotorController.cpp +++ b/frc-2021_Speed/src/main/cpp/components/SparkMaxMotorController.cpp @@ -6,7 +6,7 @@ /*----------------------------------------------------------------------------*/ #include "components/SparkMaxMotorController.h" -#include + SparkMaxMotorController::SparkMaxMotorController(int motorID, const std::string &name, rev::CANSparkMax::MotorType type): CommonMotorController(motorID, name){ m_pMotor = new rev::CANSparkMax(motorID, type); @@ -35,8 +35,6 @@ void SparkMaxMotorController::EnableVoltageCompensation(bool enable) { m_pMotor->EnableVoltageCompensation(enable); } void SparkMaxMotorController::SetInverted(bool isInverted) { - // m_pMotor-> - // frc::SmartDashboard::PutBoolean("motor inverted", isInverted); m_pMotor->SetInverted(isInverted); } void SparkMaxMotorController::Set(double speed){ @@ -45,13 +43,10 @@ void SparkMaxMotorController::Set(double speed){ void SparkMaxMotorController::Set(CommonModes mode, double value){ if(CommonModesToControlType(mode, m_pCurrentMode)){ Set(value); - frc::SmartDashboard::PutBoolean("PercentMode", true); }else{ m_setpoint = value; - frc::SmartDashboard::PutBoolean("PercentMode", false); m_pMotor->GetPIDController().SetReference(value, m_pCurrentMode); } - frc::SmartDashboard::PutNumber("SparkMaxVel", value); } void SparkMaxMotorController:: Set(CommonModes mode, double demand0, DemandType demand1Type, double demand1){ if(CommonModesToControlType(mode, m_pCurrentMode)){ @@ -84,16 +79,29 @@ double SparkMaxMotorController::GetClosedLoopError(){ } return m_setpoint - temp; } -void SparkMaxMotorController::SetNeutralMode(rev::CANSparkMax::IdleMode mode){ - m_pMotor->SetIdleMode(mode); - +void SparkMaxMotorController::SetNeutralMode(CommonDrive mode){ + if(CommonDriveToControlType(mode, m_pCurrentDriveMode)){ + m_pMotor->SetIdleMode(m_pCurrentDriveMode); + } } double SparkMaxMotorController::GetPos(){ return m_pMotor->GetEncoder().GetPosition(); } +double SparkMaxMotorController::GetCurrentOutput(){ + return m_pMotor->GetOutputCurrent(); +} // void SparkMaxMotorController::ConfigFactoryDefault(){//TODO finish // m_pMotor->RestoreFactoryDefaults(); // } + +bool SparkMaxMotorController::CommonDriveToControlType(CommonDrive mode, rev::CANSparkMax::IdleMode& retMode){ + switch(mode){ + case CommonDrive::Brake: retMode = rev::CANSparkMax::IdleMode::kBrake; break; + case CommonDrive::Coast: retMode = rev::CANSparkMax::IdleMode::kCoast; break; + default: retMode = (rev::CANSparkMax::IdleMode)(-1); return true; + } + return false; +} bool SparkMaxMotorController::CommonModesToControlType(CommonModes mode, rev::ControlType& retMode){ switch(mode) { diff --git a/frc-2021_Speed/src/main/cpp/components/TalonFXMotorController.cpp b/frc-2021_Speed/src/main/cpp/components/TalonFXMotorController.cpp index 0c06e16..071fb01 100644 --- a/frc-2021_Speed/src/main/cpp/components/TalonFXMotorController.cpp +++ b/frc-2021_Speed/src/main/cpp/components/TalonFXMotorController.cpp @@ -47,8 +47,9 @@ void TalonFXMotorController::Config_IntegralZone(int slotIdx, int izone, int ti void TalonFXMotorController::ConfigMaxIntegralAccumulator(int slotIdx, double iaccum, int timeoutMs) { m_pMotor->ConfigMaxIntegralAccumulator (slotIdx, iaccum, timeoutMs); } -void TalonFXMotorController::SetNeutralMode(NeutralMode neutralMode) { - m_pMotor->SetNeutralMode(neutralMode); +void TalonFXMotorController::SetNeutralMode(CommonDrive neutralMode) { + + m_pMotor->SetNeutralMode(CommonDriveToControlType(neutralMode)); } void TalonFXMotorController::EnableVoltageCompensation(bool enable) { m_pMotor->EnableVoltageCompensation(enable); @@ -99,7 +100,6 @@ void TalonFXMotorController::ConfigSelectedFeedbackSensor(ctre::phoenix::motorco m_pMotor->ConfigSelectedFeedbackSensor(feedbackDevice, pidIdx, timeoutMs); } int TalonFXMotorController::GetSelectedSensorPosition(int id){ - // printf("+++++++++++getting pos+++++++++++\n"); return m_pMotor->GetSelectedSensorPosition(id); } int TalonFXMotorController::isSensorConnected(){ @@ -128,6 +128,9 @@ void TalonFXMotorController::Follow(TalonFX* motor){ double TalonFXMotorController::GetPos(){ return m_pMotor->GetSelectedSensorPosition(); } +double TalonFXMotorController::GetCurrentOutput(){ + return m_pMotor->GetOutputCurrent(); +} // void TalonFXMotorController::SetNeutralMode(ctre::phoenix::motorcontrol::NeutralMode mode){ // m_pMotor->SetNeutralMode(mode); // } @@ -148,4 +151,14 @@ ControlMode TalonFXMotorController::FalconModeToCommonMode(CommonModes mode){ case CommonModes::Disabled: return ControlMode::Disabled; default: return ControlMode::PercentOutput; } +} + +NeutralMode TalonFXMotorController::CommonDriveToControlType(CommonDrive mode){ + switch(mode) + { + case CommonDrive::Brake: return NeutralMode::Brake; + case CommonDrive::Coast: return NeutralMode::Coast; + case CommonDrive::EEPROMSetting: return NeutralMode::EEPROMSetting; + default: return NeutralMode::Brake; + } } \ No newline at end of file diff --git a/frc-2021_Speed/src/main/cpp/components/TalonSRXMotorController.cpp b/frc-2021_Speed/src/main/cpp/components/TalonSRXMotorController.cpp index e8e6e19..15cf3f2 100644 --- a/frc-2021_Speed/src/main/cpp/components/TalonSRXMotorController.cpp +++ b/frc-2021_Speed/src/main/cpp/components/TalonSRXMotorController.cpp @@ -6,10 +6,10 @@ /*----------------------------------------------------------------------------*/ #include "components/TalonSRXMotorController.h" -#include TalonSRXMotorController::TalonSRXMotorController(int motorID, const std::string &name): CommonMotorController(motorID, name){ m_pMotor = new TalonSRX(motorID); + } void TalonSRXMotorController::SetStatusFramePeriod(StatusFrameEnhanced frame, uint8_t periodMs, int timeoutMs){ m_pMotor->SetStatusFramePeriod(frame, periodMs, timeoutMs); @@ -48,8 +48,8 @@ void TalonSRXMotorController::Config_IntegralZone(int slotIdx, int izone, int t void TalonSRXMotorController::ConfigMaxIntegralAccumulator(int slotIdx, double iaccum, int timeoutMs) { m_pMotor->ConfigMaxIntegralAccumulator (slotIdx, iaccum, timeoutMs); } -void TalonSRXMotorController::SetNeutralMode(NeutralMode neutralMode) { - m_pMotor->SetNeutralMode(neutralMode); +void TalonSRXMotorController::SetNeutralMode(CommonDrive neutralMode) { + m_pMotor->SetNeutralMode(CommonDriveToControlType(neutralMode)); } void TalonSRXMotorController::EnableVoltageCompensation(bool enable) { m_pMotor->EnableVoltageCompensation(enable); @@ -113,6 +113,9 @@ void TalonSRXMotorController::SetVelocityConversionFactor(double factor){ double TalonSRXMotorController::GetClosedLoopError(){ return m_pMotor->GetClosedLoopError(); } +double TalonSRXMotorController::GetCurrentOutput(){ + return m_pMotor->GetOutputCurrent(); +} ControlMode TalonSRXMotorController::CommonModeToControllMode(CommonModes mode){ switch(mode) { @@ -127,7 +130,17 @@ ControlMode TalonSRXMotorController::CommonModeToControllMode(CommonModes mode){ case CommonModes::MotionProfile: return ControlMode::MotionProfile; case CommonModes::MotionMagic: return ControlMode::MotionMagic; case CommonModes::MotionProfileArc: return ControlMode::MotionProfileArc; - case CommonModes::Disabled: return ControlMode::Disabled; + case CommonModes::Disabled: return ControlMode::Disabled; default: return ControlMode::PercentOutput; } +} + +NeutralMode TalonSRXMotorController::CommonDriveToControlType(CommonDrive mode){ + switch(mode) + { + case CommonDrive::Brake: return NeutralMode::Brake; + case CommonDrive::Coast: return NeutralMode::Coast; + case CommonDrive::EEPROMSetting: return NeutralMode::EEPROMSetting; + default: return NeutralMode::Brake; + } } \ No newline at end of file diff --git a/frc-2021_Speed/src/main/cpp/components/VictorMotorController.cpp b/frc-2021_Speed/src/main/cpp/components/VictorMotorController.cpp index a55a52d..30baed8 100644 --- a/frc-2021_Speed/src/main/cpp/components/VictorMotorController.cpp +++ b/frc-2021_Speed/src/main/cpp/components/VictorMotorController.cpp @@ -6,10 +6,10 @@ /*----------------------------------------------------------------------------*/ #include "components/VictorMotorController.h" -#include VictorMotorController::VictorMotorController(int motorID, const std::string &name): CommonMotorController(motorID, name){ m_pMotor = new VictorSPX(motorID); + } void VictorMotorController::SetStatusFramePeriod(StatusFrameEnhanced frame, uint8_t periodMs, int timeoutMs){ m_pMotor->SetStatusFramePeriod(frame, periodMs, timeoutMs); @@ -107,6 +107,7 @@ void VictorMotorController::SetVelocityConversionFactor(double factor){ double VictorMotorController::GetClosedLoopError(){ return m_pMotor->GetClosedLoopError(); } + ControlMode VictorMotorController::CommonModeToControllMode(CommonModes mode){ switch(mode) { diff --git a/frc-2021_Speed/src/main/cpp/subsystems/DriveSubsystem.cpp b/frc-2021_Speed/src/main/cpp/subsystems/DriveSubsystem.cpp index d7099c6..67d15c4 100644 --- a/frc-2021_Speed/src/main/cpp/subsystems/DriveSubsystem.cpp +++ b/frc-2021_Speed/src/main/cpp/subsystems/DriveSubsystem.cpp @@ -8,14 +8,16 @@ #include "subsystems/DriveSubsystem.h" #include -#include - +#include +#include #include "Constants.h" #include #include "Utils/NormalizeToRange.h" #include #include + + using namespace DriveConstants; DriveSubsystem::DriveSubsystem() @@ -26,12 +28,12 @@ DriveSubsystem::DriveSubsystem() kFrontLeftTurningMotorReversed, "FL_STEER_MOTOR_ENCODER"}, - m_rearLeft{ - FalconIDs::kRearLeftDriveMotorID, - TalonIDs::kRearLeftTurningMotorID, - kRearLeftDriveEncoderReversed, - kRearLeftTurningEncoderReversed, - kRearLeftTurningMotorReversed, + m_backLeft{ + FalconIDs::kBackLeftDriveMotorID, + TalonIDs::kBackLeftTurningMotorID, + kBackLeftDriveEncoderReversed, + kBackLeftTurningEncoderReversed, + kBackLeftTurningMotorReversed, "BL_STEER_MOTOR_ENCODER"}, m_frontRight{ @@ -42,44 +44,57 @@ DriveSubsystem::DriveSubsystem() kFrontRightTurningMotorReversed, "FR_STEER_MOTOR_ENCODER"}, - m_rearRight{ - FalconIDs::kRearRightDriveMotorID, - TalonIDs::kRearRightTurningMotorID, - kRearRightDriveEncoderReversed, - kRearRightTurningEncoderReversed, - kRearRightTurningMotorReversed, + m_backRight{ + FalconIDs::kBackRightDriveMotorID, + TalonIDs::kBackRightTurningMotorID, + kBackRightDriveEncoderReversed, + kBackRightTurningEncoderReversed, + kBackRightTurningMotorReversed, "BR_STEER_MOTOR_ENCODER"}, - //1097Setting m_odometry{kDriveKinematics, frc::Rotation2d(units::degree_t(0)), frc::Pose2d()}, - m_pChassisIMU{frc::SPI::kMXP}{ - // std::remove("home/lvuser/ActualPath.csv"); - // m_File.open("home/lvuser/ActualPath.csv"); + setBrake(); } void DriveSubsystem::Periodic() { // Implementation of subsystem periodic method goes here. m_odometry.Update(frc::Rotation2d(units::degree_t(GetHeading())), - m_frontLeft.GetState(), m_rearLeft.GetState(), - m_frontRight.GetState(), m_rearRight.GetState()); - // m_File << GetRobotVelocity().vx.to() <<","; - // m_File << GetRobotVelocity().vy.to() <<"\n"; - frc::SmartDashboard::PutNumber("robot speed", sqrt((GetRobotVelocity().vx *GetRobotVelocity().vx +GetRobotVelocity().vy*GetRobotVelocity().vy).to())); - frc::SmartDashboard::PutNumber("fr state angle", m_frontRight.GetState().angle.Degrees().to()); - frc::SmartDashboard::PutNumber("fr state speed", m_frontRight.GetState().speed.to()); - frc::SmartDashboard::PutNumber("fl state angle", m_frontLeft.GetState().angle.Degrees().to()); - frc::SmartDashboard::PutNumber("fl state speed", m_frontLeft.GetState().speed.to()); - frc::SmartDashboard::PutNumber("br state angle", m_rearRight.GetState().angle.Degrees().to()); - frc::SmartDashboard::PutNumber("br state speed", m_rearRight.GetState().speed.to()); - frc::SmartDashboard::PutNumber("bl state angle", m_rearLeft.GetState().angle.Degrees().to()); - frc::SmartDashboard::PutNumber("bl state speed", m_rearLeft.GetState().speed.to()); - frc::SmartDashboard::PutNumber("Odometry X", GetPose().Translation().X().to()*39.3701);// - frc::SmartDashboard::PutNumber("Odometry Y", GetPose().Translation().Y().to()*39.3701);//*39.3701 - frc::SmartDashboard::PutNumber("Odometry Yaw", GetPose().Rotation().Degrees().to()); + m_frontLeft.GetState(), m_backLeft.GetState(), + m_frontRight.GetState(), m_backRight.GetState()); + frc::Pose2d frcPose(m_odometry.GetPose().Y(), -m_odometry.GetPose().X(),m_odometry.GetPose().Rotation()); + m_pField.SetRobotPose(frcPose); + frc::SmartDashboard::PutData(&m_pField); + if(cycle == 0){ + + frc::SmartDashboard::PutNumber("fr state angle", m_frontRight.GetState().angle.Degrees().to()); + frc::SmartDashboard::PutNumber("fr state speed", m_frontRight.GetState().speed.to()); + frc::SmartDashboard::PutNumber("fr encoder ticks", fabs(m_frontRight.getDriveEncoder())); + }else if(cycle == 1){ + frc::SmartDashboard::PutNumber("fl state angle", m_frontLeft.GetState().angle.Degrees().to()); + frc::SmartDashboard::PutNumber("fl state speed", m_frontLeft.GetState().speed.to()); + frc::SmartDashboard::PutNumber("fl encoder ticks", fabs(m_frontLeft.getDriveEncoder())); + }else if(cycle == 2){ + frc::SmartDashboard::PutNumber("br state angle", m_backRight.GetState().angle.Degrees().to()); + frc::SmartDashboard::PutNumber("br state speed", m_backRight.GetState().speed.to()); + frc::SmartDashboard::PutNumber("br encoder ticks", fabs(m_backRight.getDriveEncoder())); + }else if(cycle == 3){ + frc::SmartDashboard::PutNumber("bl state angle", m_backLeft.GetState().angle.Degrees().to()); + frc::SmartDashboard::PutNumber("bl state speed", m_backLeft.GetState().speed.to()); + frc::SmartDashboard::PutNumber("bl encoder ticks", fabs(m_backLeft.getDriveEncoder())); + }else{ + frc::SmartDashboard::PutNumber("robot speed", sqrt((GetRobotVelocity().vx *GetRobotVelocity().vx +GetRobotVelocity().vy*GetRobotVelocity().vy).to())*metersToInches); + frc::SmartDashboard::PutNumber("Odometry X", GetPose().Translation().X().to()*metersToInches); + frc::SmartDashboard::PutNumber("Odometry Y", -1.0*GetPose().Translation().Y().to()*metersToInches); + frc::SmartDashboard::PutNumber("Odometry Yaw", GetPose().Rotation().Degrees().to()); + cycle = 0; + } + cycle++; + + } void DriveSubsystem::Drive(units::meters_per_second_t xSpeed, @@ -88,62 +103,43 @@ void DriveSubsystem::Drive(units::meters_per_second_t xSpeed, bool fieldRelative, bool percentMode) { // adjust to max speeds - double base = .01; + double base = .1; if(fabs(rot.to()) > base){ rot = rot * 2.2; - } - - frc::SmartDashboard::PutNumber("passed in value",ySpeed.to()); + } + // rot = rot * 0.0;//TODO Remove + // printf("there is no Yaw control"); auto states = kDriveKinematics.ToSwerveModuleStates( fieldRelative ? frc::ChassisSpeeds::FromFieldRelativeSpeeds( xSpeed, ySpeed, rot, frc::Rotation2d(GetPose().Rotation().Degrees())) : frc::ChassisSpeeds{xSpeed, ySpeed, rot}); -frc::SmartDashboard::PutNumber("driveMotorVelpreNormSpeed",states[0].speed.to()); -frc::SmartDashboard::PutNumber("driveMotorVelpreNormAngle",states[0].angle.Degrees().to()); + kDriveKinematics.NormalizeWheelSpeeds(&states, units::meters_per_second_t(RobotParameters::k_maxSpeed)); - frc::SmartDashboard::PutNumber("driveMotorVelNorm",states[0].speed.to()); auto [fl, fr, bl, br] = states; m_frontLeft.SetDesiredState(fl, percentMode); m_frontRight.SetDesiredState(fr, percentMode); - m_rearLeft.SetDesiredState(bl, percentMode); - m_rearRight.SetDesiredState(br, percentMode); - frc::SmartDashboard::PutNumber("fr", fr.speed.to()); - frc::SmartDashboard::PutNumber("fl", fl.speed.to()); - frc::SmartDashboard::PutNumber("br", br.speed.to()); - frc::SmartDashboard::PutNumber("bl", bl.speed.to()); - // frc::SmartDashboard::PutNumber("RobotVelocityX",GetRobotVelocity().vy.to()); - // frc::SmartDashboard::PutNumber("RobotVelocityY",GetRobotVelocity().vx.to()); - // printf("fr angle: %3f, fl angle: %3f, br angle: %3f, bl angle: %3f\n", - // m_frontRight.GetState().angle.Degrees().to(), - // m_frontLeft.GetState().angle.Degrees().to(), - // m_rearRight.GetState().angle.Degrees().to(), - // m_rearLeft.GetState().angle.Degrees().to()); - - + m_backLeft.SetDesiredState(bl, percentMode); + m_backRight.SetDesiredState(br, percentMode); } -void DriveSubsystem::SetModuleStates( - wpi::array desiredStates, bool percentMode) { - kDriveKinematics.NormalizeWheelSpeeds(&desiredStates, - AutoConstants::kMaxSpeed); +void DriveSubsystem::SetModuleStates(wpi::array desiredStates, bool percentMode) { + kDriveKinematics.NormalizeWheelSpeeds(&desiredStates, units::meters_per_second_t(RobotParameters::k_maxSpeed)); m_frontLeft.SetDesiredState(desiredStates[0], percentMode); - m_rearLeft.SetDesiredState(desiredStates[1],percentMode); + m_backLeft.SetDesiredState(desiredStates[1],percentMode); m_frontRight.SetDesiredState(desiredStates[2], percentMode); - m_rearRight.SetDesiredState(desiredStates[3], percentMode); + m_backRight.SetDesiredState(desiredStates[3], percentMode); } void DriveSubsystem::ResetEncoders() { m_frontLeft.ResetEncoders(); - m_rearLeft.ResetEncoders(); + m_backLeft.ResetEncoders(); m_frontRight.ResetEncoders(); - m_rearRight.ResetEncoders(); + m_backRight.ResetEncoders(); } double DriveSubsystem::GetHeading() { - // frc::SmartDashboard::PutNumber("IMU Yaw", m_pChassisIMU.GetYaw()); - // printf("Getting the robot heading"); return normalizeToRange::NormalizeToRange(m_pChassisIMU.GetYaw() , -180, 180, true) * (kGyroReversed ? -1: 1); } void DriveSubsystem::ZeroHeading() { @@ -159,26 +155,17 @@ frc::Pose2d DriveSubsystem::GetPose() { return m_odometry.GetPose(); } void DriveSubsystem::ResetOdometry(frc::Pose2d pose) { m_odometry.ResetPosition(pose, frc::Rotation2d(units::degree_t(GetHeading()))); - - // frc::SmartDashboard::PutNumber("Odometry X", GetPose().Translation().X().to()); - // frc::SmartDashboard::PutNumber("Odometry Y", GetPose().Translation().Y().to()); - // frc::SmartDashboard::PutNumber("Odometry Yaw", GetPose().Rotation().Degrees().to()); - } void DriveSubsystem::DriveArc(double arcLength){ auto [fl, fr, bl, br] = kDriveKinematics.ToSwerveModuleStates(frc::ChassisSpeeds{0_mps, 0_mps, 10000_rpm}); m_frontRight.DriveArc(arcLength, fr.angle.Degrees().to()); m_frontLeft.DriveArc(arcLength, fl.angle.Degrees().to()); - m_rearRight.DriveArc(arcLength, br.angle.Degrees().to()); - m_rearLeft.DriveArc(arcLength, bl.angle.Degrees().to()); + m_backRight.DriveArc(arcLength, br.angle.Degrees().to()); + m_backLeft.DriveArc(arcLength, bl.angle.Degrees().to()); } void DriveSubsystem::toggleFieldCentricForJoystick(){ - if(m_fieldCentricForJoystick){ - m_fieldCentricForJoystick = false; - }else{ - m_fieldCentricForJoystick = true; - } + m_fieldCentricForJoystick = !m_fieldCentricForJoystick; frc::SmartDashboard::PutBoolean("fieldCentric", m_fieldCentricForJoystick); } bool DriveSubsystem::getFiedCentricForJoystick(){ @@ -187,15 +174,15 @@ bool DriveSubsystem::getFiedCentricForJoystick(){ void DriveSubsystem::tuneDrivePID(double p, double i, double d, double f){ m_frontLeft.updateDrivePID(p, i, d, f); m_frontRight.updateDrivePID(p, i, d, f); - m_rearLeft.updateDrivePID(p, i, d, f); - m_rearRight.updateDrivePID(p, i, d, f); + m_backLeft.updateDrivePID(p, i, d, f); + m_backRight.updateDrivePID(p, i, d, f); } void DriveSubsystem::tuneSteerPID(double p, double i, double d){ m_frontLeft.updateSteerPID(p, i, d); m_frontRight.updateSteerPID(p, i, d); - m_rearLeft.updateSteerPID(p, i, d); - m_rearRight.updateSteerPID(p, i, d); + m_backLeft.updateSteerPID(p, i, d); + m_backRight.updateSteerPID(p, i, d); } void DriveSubsystem::stop(){ @@ -210,25 +197,32 @@ frc::SwerveModuleState DriveSubsystem::getFrontLeftMotor(){ return m_frontLeft.GetState(); } frc::SwerveModuleState DriveSubsystem::getBackRightMotor(){ - return m_rearRight.GetState(); + return m_backRight.GetState(); } frc::SwerveModuleState DriveSubsystem::getBackLeftMotor(){ - return m_rearLeft.GetState(); + return m_backLeft.GetState(); } frc::ChassisSpeeds DriveSubsystem::GetRobotVelocity(){ - return kDriveKinematics.ToChassisSpeeds(m_frontLeft.GetState(), m_rearLeft.GetState(), - m_frontRight.GetState(), m_rearRight.GetState()); + return kDriveKinematics.ToChassisSpeeds(m_frontLeft.GetState(), m_backLeft.GetState(), + m_frontRight.GetState(), m_backRight.GetState()); } void DriveSubsystem::setCoast(){ m_frontRight.setCoast(); m_frontLeft.setCoast(); - m_rearRight.setCoast(); - m_rearLeft.setCoast(); + m_backRight.setCoast(); + m_backLeft.setCoast(); } void DriveSubsystem::setBrake(){ m_frontRight.setBrake(); m_frontLeft.setBrake(); - m_rearRight.setBrake(); - m_rearLeft.setBrake(); -} \ No newline at end of file + m_backRight.setBrake(); + m_backLeft.setBrake(); +} + +void DriveSubsystem::resetDriveEncoders(){ + m_frontRight.resetDriveEncoder(); + m_frontLeft.resetDriveEncoder(); + m_backRight.resetDriveEncoder(); + m_backLeft.resetDriveEncoder(); +} diff --git a/frc-2021_Speed/src/main/cpp/subsystems/IntakeSubsystem.cpp b/frc-2021_Speed/src/main/cpp/subsystems/IntakeSubsystem.cpp index c61c92b..6a62171 100644 --- a/frc-2021_Speed/src/main/cpp/subsystems/IntakeSubsystem.cpp +++ b/frc-2021_Speed/src/main/cpp/subsystems/IntakeSubsystem.cpp @@ -1,37 +1,50 @@ - //TODO Copied this from 2020 because intake supposedly similar, INCOMPLETE. -Sean H. + #include "subsystems/IntakeSubsystem.h" #include "Constants.h" #include "RobotParameters.h" - - IntakeSubsystem::IntakeSubsystem() : - leftSpeed(0.0), - rightSpeed(0.0) - { - m_beamBreak = new frc::DigitalInput(BeamBreaks::kBeamBreakID); - m_rightMotor = new VictorMotorController(VictorIDs::kRightIntakeID, "Left Intake Motor"); - m_leftMotor = new VictorMotorController(VictorIDs::kLeftIntakeID,"Right Intake Motor"); +#include "Constants.h" + IntakeSubsystem::IntakeSubsystem(){ + m_servo = new frc::Servo(0); + m_aIntakeMotor = new TalonSRXMotorController(TalonIDs::kAIntakeID, "Front Intake Motor"); + m_aIntakeMotor->ConfigFactoryDefault(); + m_bIntakeMotor = new TalonSRXMotorController(TalonIDs::kBIntakeID,"Left Intake Motor"); + m_bIntakeMotor->ConfigFactoryDefault(); + m_bIntakeMotor->SetNeutralMode(CommonDrive::Brake); } void IntakeSubsystem::Periodic(){ } - void IntakeSubsystem::setLeftSpeed(double speed){ - leftSpeed = speed; - m_leftMotor->Set(speed); + void IntakeSubsystem::setBIntakeSpeed(double speed){ + m_bIntakeMotor->Set(speed); } - void IntakeSubsystem::setRightSpeed(double speed){ - rightSpeed = speed; - m_rightMotor->Set(speed); + void IntakeSubsystem::setAIntakeSpeed(double speed){ + m_aIntakeMotor->Set(speed); } - double IntakeSubsystem::getLeftSpeed(){ - return leftSpeed; + + void IntakeSubsystem::setAIntakeCurrent(double current){ + m_aIntakeMotor->Set(CommonModes::Current, current); } - double IntakeSubsystem::getRightSpeed(){ - return rightSpeed; + void IntakeSubsystem::setBIntakeCurrent(double current){ + m_bIntakeMotor->Set(CommonModes::Current, current); } - double IntakeSubsystem::getBeamBreak(){ - return m_beamBreak->Get(); + double IntakeSubsystem::getIntakeACurrent(){ + return m_aIntakeMotor->GetCurrentOutput(); + } + double IntakeSubsystem::getIntakeBCurrent(){ + return m_bIntakeMotor->GetCurrentOutput(); + } + double IntakeSubsystem::getBIntakeSpeed(){ + return m_bIntakeMotor->GetVelocity(); + } + double IntakeSubsystem::getAIntakeSpeed(){ + return m_aIntakeMotor->GetVelocity(); + } + double IntakeSubsystem::getServoAngle(){ + return m_servo->GetAngle(); + } + void IntakeSubsystem::setServoAngle(double angle){ + m_servo->SetAngle(angle); } - \ No newline at end of file diff --git a/frc-2021_Speed/src/main/cpp/subsystems/SwerveModule.cpp b/frc-2021_Speed/src/main/cpp/subsystems/SwerveModule.cpp index da6a0bd..f4858e1 100644 --- a/frc-2021_Speed/src/main/cpp/subsystems/SwerveModule.cpp +++ b/frc-2021_Speed/src/main/cpp/subsystems/SwerveModule.cpp @@ -9,7 +9,6 @@ #include "components/CTREMagEncoder.h" #include #include -#include #include "Constants.h" #include "components/MotorPositionController.h" #include "Utils/MathConstants.h" @@ -41,21 +40,9 @@ SwerveModule::SwerveModule(int driveMotorID, int turningMotorID, m_driveMotor->Config_kP(0, 0.1);//.07 m_driveMotor->Config_kI(0, 0); m_driveMotor->Config_kD(0, 0);//.035 - m_driveMotor->Config_kF(0, 1023/(RobotParameters::k_maxSpeed/RobotParameters::k_driveMotorEncoderTicksToMPS)); + m_driveMotor->Config_kF(0, 1023/(RobotParameters::k_feedForwardMaxSpeed/RobotParameters::k_driveMotorEncoderTicksToMPS)); m_driveMotor->Config_IntegralZone(0, 0); - m_driveMotor->SetNeutralMode(ctre::phoenix::motorcontrol::NeutralMode::Brake);//break - // // Set the distance per pulse for the drive encoder. We can simply use the - // // distance traveled for one rotation of the wheel divided by the encoder - // // resolution. - // m_driveEncoder.SetDistancePerPulse( - // ModuleConstants::kDriveEncoderDistancePerPulse); - - // Set the distance (in this case, angle) per pulse for the turning encoder. - // This is the the angle through an entire rotation (2 * wpi::math::pi) - // divided by the encoder resolution. - - // m_turningEncoder.SetDistancePerPulse( - // ModuleConstants::kTurningEncoderDistancePerPulse); + m_driveMotor->SetNeutralMode(CommonDrive::Brake);//break // Limit the PID Controller's input range between -pi and pi and set the input // to be continuous. @@ -68,7 +55,7 @@ SwerveModule::SwerveModule(int driveMotorID, int turningMotorID, m_turningMotor, m_turningEncoder, m_reverseTurningEncoder, - m_turningMotorReversed,//false + m_turningMotorReversed, RobotParameters::k_steerMotorControllerKp, RobotParameters::k_steerMotorControllerKi, RobotParameters::k_steerMotorControllerKd, @@ -89,53 +76,23 @@ frc::SwerveModuleState SwerveModule::GetState() { void SwerveModule::SetDesiredState(frc::SwerveModuleState& state, bool percentMode) { m_turningEncoder->update(); - // Calculate the drive output from the drive PID controller. - // const auto driveOutput = m_drivePIDController.Calculate( - // m_driveMotor->GetEncoder().GetVelocity(), state.speed.to()); - float currentAngle = units::degree_t(m_turningEncoder->getAngle()).to(); float driveMotorRPM = state.speed.to();///RobotParameters::k_driveMotorEncoderRPMToMPS; float desiredAngle = state.angle.Degrees().to(); - // // Calculate the turning motor output from the turning PID controller. - // auto turnOutput = m_turningPIDController.Calculate( - // units::radian_t(units::degree_t(m_turningEncoder->getAngle())), state.angle.Radians()); - - // frc::SmartDashboard::PutNumber("Desired", state.angle.Degrees().to()); - // frc::SmartDashboard::PutNumber("Current", units::degree_t(m_turningEncoder->getAngle()).to()); - // frc::SmartDashboard::PutNumber("Turn Output", turnOutput); //TODO: These shouldn't stay here - // frc::SmartDashboard::PutNumber("Speed", m_driveMotor->GetEncoder().GetVelocity()); - // printf("%s: current angle %f desired angle %f\n", - // m_name.c_str(), - // units::radian_t(m_turningEncoder->getAngle()).to(), - // state.angle.Radians().to()); - // printf("\nC A: %f\n", currentAngle); //TODO: Remove these printfs once turn issue fixed - // printf("\nD A: %f\n", desiredAngle); -frc::SmartDashboard::PutNumber("driveMotorVelpreLogic",driveMotorRPM); -frc::SmartDashboard::PutNumber(m_name, m_turningEncoder->getAngle()); -frc::SmartDashboard::PutNumber(m_name + " drive", m_driveMotor->GetVelocity()); if(fabs(normalizeToRange::RangedDifference(currentAngle - desiredAngle, -180, 180)) > 90){//used to be 90 desiredAngle = normalizeToRange::NormalizeToRange(desiredAngle+180, -180, 180, true); driveMotorRPM = driveMotorRPM * -1; } - if(fabs(driveMotorRPM) < 0.01){//TODO find better zone + if(fabs(driveMotorRPM) < 0.01){ desiredAngle = currentAngle; - // driveMotorRPM= 0; - // printf("\nD%f\n", driveMotorRPM); } -frc::SmartDashboard::PutNumber(m_name + " desiredAngle", desiredAngle); - // printf("\nUpdated Current Angle: %f\n", currentAngle); - // printf("\nUpdated Desired Angle: %f\n", desiredAngle); - // printf("\nUpdated Desired Speed: %f\n", driveMotorRPM); - // Set the motor outputs. if(fabs((m_driveMotor->GetVelocity()) <= RobotParameters::k_driveWheelSlotError && driveMotorRPM == 0.0) || percentMode){ m_driveMotor->Set(driveMotorRPM); }else{ m_driveMotor->Set(CommonModes::Velocity, driveMotorRPM); } - frc::SmartDashboard::PutNumber("driveMotorVelfinal",driveMotorRPM); - // m_turningMotor->Set(ctre::phoenix::motorcontrol::ControlMode::PercentOutput, turnOutput); m_turningMotorController->updateAngular(desiredAngle, 0, 0); } @@ -147,27 +104,23 @@ void SwerveModule::ResetEncoders() { } void SwerveModule::updateSteerPID(double p, double i, double d){ - // m_turningPIDController.SetPID(p, i, d); - // printf("Steer P: %0.1f, I: %0.1f, D: %0.1f", p, i, d); m_turningPIDController.SetP(p); m_turningPIDController.SetI(i); m_turningPIDController.SetD(d); } void SwerveModule::updateDrivePID(double p, double i, double d, double f){ - // printf("Drive P: %0.1f, I: %0.1f, D: %0.1f", p, i, d); - // m_drivePIDController.SetPID(p, i, d); m_driveMotor->Config_kP(0,p); m_driveMotor->Config_kI(0,i); m_driveMotor->Config_kD(0,d); m_driveMotor->Config_kF(0,f); } void SwerveModule::setCoast(){ - m_driveMotor->SetNeutralMode(ctre::phoenix::motorcontrol::NeutralMode::Coast); + m_driveMotor->SetNeutralMode(CommonDrive::Coast); } void SwerveModule::setBrake(){ - m_driveMotor->SetNeutralMode(ctre::phoenix::motorcontrol::NeutralMode::Brake); + m_driveMotor->SetNeutralMode(CommonDrive::Brake); } void SwerveModule::DriveArc(double arcLength, double wheelAngle){ @@ -176,3 +129,11 @@ void SwerveModule::DriveArc(double arcLength, double wheelAngle){ m_driveMotor->ConfigMotionAcceleration(((RobotParameters::k_maxSpeed)/RobotParameters::k_driveMotorEncoderTicksToMPS)*2); m_driveMotor->Set(CommonModes::MotionMagic, m_driveMotor->GetPos() + arcLength/RobotParameters::k_driveMotorEncoderTicksToMeters); } + +double SwerveModule::getDriveEncoder(){ + return m_driveMotor->GetPos(); +} + +void SwerveModule::resetDriveEncoder(){ + m_driveMotor->SetEncoderPosition(0.0); +} \ No newline at end of file diff --git a/frc-2021_Speed/src/main/include/Constants.h b/frc-2021_Speed/src/main/include/Constants.h index b1727b4..5cad499 100644 --- a/frc-2021_Speed/src/main/include/Constants.h +++ b/frc-2021_Speed/src/main/include/Constants.h @@ -8,9 +8,9 @@ #include #include #include -#include #include +#include "RobotParameters.h" #pragma once /** @@ -23,85 +23,45 @@ */ namespace TalonIDs{ - static constexpr int kFrontRightTurningMotorID = 3;//1 - static constexpr int kFrontLeftTurningMotorID = 1;//4 - static constexpr int kRearRightTurningMotorID = 4;//3 - static constexpr int kRearLeftTurningMotorID = 2;//2 + static constexpr int kFrontLeftTurningMotorID = 1; + static constexpr int kFrontRightTurningMotorID = 2; + static constexpr int kBackLeftTurningMotorID = 3; + static constexpr int kBackRightTurningMotorID = 4; + static constexpr int kAIntakeID = 9; + static constexpr int kBIntakeID = 10; } namespace FalconIDs{ - static constexpr int kFrontRightDriveMotorID = 7;//5 - static constexpr int kFrontLeftDriveMotorID = 5;//6 - static constexpr int kRearRightDriveMotorID = 8;//7 - static constexpr int kRearLeftDriveMotorID = 6;//8 + static constexpr int kFrontLeftDriveMotorID = 5; + static constexpr int kFrontRightDriveMotorID = 6; + static constexpr int kBackLeftDriveMotorID = 7; + static constexpr int kBackRightDriveMotorID = 8; } -namespace VictorIDs{ - static constexpr int kRightIntakeID = 11; - static constexpr int kLeftIntakeID = 12; -} -namespace BeamBreaks{ - static constexpr int kBeamBreakID = 762; -} namespace DriveConstants { -constexpr bool kFrontLeftTurningEncoderReversed = true; -constexpr bool kRearLeftTurningEncoderReversed = true; -constexpr bool kFrontRightTurningEncoderReversed = true; -constexpr bool kRearRightTurningEncoderReversed = true; + constexpr bool kFrontLeftTurningEncoderReversed = true; + constexpr bool kBackLeftTurningEncoderReversed = true; + constexpr bool kFrontRightTurningEncoderReversed = true; + constexpr bool kBackRightTurningEncoderReversed = true; -constexpr bool kFrontLeftTurningMotorReversed = false; -constexpr bool kRearLeftTurningMotorReversed = false; -constexpr bool kFrontRightTurningMotorReversed = false; -constexpr bool kRearRightTurningMotorReversed = false; + constexpr bool kFrontLeftTurningMotorReversed = false; + constexpr bool kBackLeftTurningMotorReversed = false; + constexpr bool kFrontRightTurningMotorReversed = false; + constexpr bool kBackRightTurningMotorReversed = false; -constexpr bool kFrontLeftDriveEncoderReversed = false;//true -constexpr bool kRearLeftDriveEncoderReversed = false;//true -constexpr bool kFrontRightDriveEncoderReversed = false;//true -constexpr bool kRearRightDriveEncoderReversed = false;//true + constexpr bool kFrontLeftDriveEncoderReversed = false; + constexpr bool kBackLeftDriveEncoderReversed = false; + constexpr bool kFrontRightDriveEncoderReversed = false; + constexpr bool kBackRightDriveEncoderReversed = false; -constexpr bool kGyroReversed = true; + constexpr bool kGyroReversed = true; } // namespace DriveConstants -namespace ModuleConstants { -constexpr int kEncoderCPR = 4096; -constexpr double kWheelDiameterMeters = .15; -constexpr double kDriveEncoderDistancePerPulse = - // Assumes the encoders are directly mounted on the wheel shafts - (kWheelDiameterMeters * wpi::math::pi) / static_cast(kEncoderCPR); - -constexpr double kTurningEncoderDistancePerPulse = - // Assumes the encoders are directly mounted on the wheel shafts - (wpi::math::pi * 2) / static_cast(kEncoderCPR); - -constexpr double kPModuleTurningController = 1; -constexpr double kPModuleDriveController = 1; -} // namespace ModuleConstants - -namespace AutoConstants { -using radians_per_second_squared_t = - units::compound_unit>>; - -constexpr auto kMaxSpeed = units::meters_per_second_t(3); -constexpr auto kMaxAcceleration = units::meters_per_second_squared_t(3); -constexpr auto kMaxAngularSpeed = units::radians_per_second_t(3.142); -constexpr auto kMaxAngularAcceleration = - units::unit_t(3.142); - -constexpr double kPXController = 0.5; -constexpr double kPYController = 0.5; -constexpr double kPThetaController = 0.5; - -extern const frc::TrapezoidProfile::Constraints - kThetaControllerConstraints; - -} // namespace AutoConstants - namespace OIConstants { -constexpr int kDriverControllerPort = 0; + constexpr int kDriverControllerPort = 0; } // namespace OIConstants @@ -120,16 +80,23 @@ enum class CommonModes{ MotionProfileArc = 11, Disabled = 15 }; -namespace LimeLightConstants{ - static constexpr double kLimeLightHeight = 1.09;//ft - static constexpr double kLimeLightAngle = 20;//deg - static constexpr double kLimeLightHardWarePanAngle = 12;//deg - static constexpr double kTargetHeight = 2.03;//m -} + +enum class CommonDrive{ + Brake = 0, + Coast = 1, + EEPROMSetting = 2 +}; namespace IntakeConstants{ - static constexpr double kDefaultIntakeRollerSpeed = -.7; //TODO: Improve these speeds + static constexpr double kMaxIntakeAmp = 29.0; + static constexpr double kAIntakeSpeed = 0.9; + static constexpr double kAIntakeReverse = -0.6; + static constexpr double kBIntakeSpeed = 0.8;//1; + static constexpr double kBIntakeReverse = -0.5; + + static constexpr double kAIntakeCurrent = 25.0; + static constexpr double kBIntakeCurrent = 25.0; } namespace PathConstants{ - static constexpr double kMinLookAhead = 6*.0254; - static constexpr double kMaxLookAhead = 24*.0254; + static constexpr double kMinLookAhead = 6*.0254;//6 + static constexpr double kMaxLookAhead = RobotParameters::k_maxSpeed * .16255997;//calculated constant based off of last years robot and max look ahead } diff --git a/frc-2021_Speed/src/main/include/RobotContainer.h b/frc-2021_Speed/src/main/include/RobotContainer.h index c37b516..d735590 100644 --- a/frc-2021_Speed/src/main/include/RobotContainer.h +++ b/frc-2021_Speed/src/main/include/RobotContainer.h @@ -29,6 +29,9 @@ #include "subsystems/IntakeSubsystem.h" #include "subsystems/DriveSubsystem.h" + +#include "Utils/SwerveDrivePathFollower.h" + class RobotContainer { public: RobotContainer(); @@ -42,8 +45,15 @@ class RobotContainer { DriveSubsystem m_drive; IntakeSubsystem m_intake; - - SwerveDrivePathFollower m_follower; + SwerveDrivePathFollower m_followerNavPathA; + SwerveDrivePathFollower m_followerNavPathB; +//Auto nav path C + SwerveDrivePathFollower m_followerNavPathC[5];//4 BUT ADDED A RETURN +//Auto nav path C + SwerveDrivePathFollower m_followerPathABlue; + SwerveDrivePathFollower m_followerPathARed; + SwerveDrivePathFollower m_followerPathBBlue; + SwerveDrivePathFollower m_followerPathBRed; frc2::Button m_startDriver{[&] { return m_driverController.GetRawButton(XBOX_START_BUTTON); }};// @@ -84,10 +94,8 @@ class RobotContainer { void ConfigureButtonBindings(); void TrajectoryToCSV(frc::Trajectory trajectory); -//tuning drive int cycle = 0; - double setPoint = 0; - double counting = 0; + std::vector m_path; diff --git a/frc-2021_Speed/src/main/include/RobotParameters.h b/frc-2021_Speed/src/main/include/RobotParameters.h index c6b7b9b..0e16ca1 100644 --- a/frc-2021_Speed/src/main/include/RobotParameters.h +++ b/frc-2021_Speed/src/main/include/RobotParameters.h @@ -10,30 +10,29 @@ namespace RobotParameters { // drivetrain .0625+ .11 = .41 static constexpr double k_wheelBase = 13.5*.0254; // m static constexpr double k_wheelTrack = 13.5*.0254; // m + static constexpr double k_robotWidth = 24; //in + static constexpr double k_robotLength = 24; //in static constexpr double k_wheelLeverArm = sqrt(std::pow(k_wheelBase/2,2) + std::pow(k_wheelTrack/2,2)); - static constexpr double k_wheelRad = (4.25)*.0254; // m - static constexpr double k_maxSpeed = 24*12*.0254; //1;m - static constexpr double k_maxAccel = 200*.0254; //1; // m/s^2// 200*.0254 - static constexpr double k_maxDeccel = -25*.0254;//was 50in + static constexpr double k_wheelRad = (4.25)*.0254 / 2.0* .94444; // m *constant + static constexpr double k_maxSpeed = 205*.0254; //240 + static constexpr double k_feedForwardMaxSpeed = 240*.0254;//205 + static constexpr double k_maxAccel = 700*.0254;//450 + static constexpr double k_maxDeccel = -700*.0254;//-700 //-456 static constexpr double k_steerEncoderToWheelGearRatio = 1; // gear ratio from steer encoder to wheel - static constexpr double k_driveMotorGearRatio = 16.0/26.0*(15.0/45.0); + static constexpr double k_driveMotorGearRatio = (28.0 / 14.0) * 3.0; //updated from 26.0 / 16.0 static constexpr double k_ticksPerRev = 2048.0;//ticks per 100ms - static constexpr double k_driveMotorEncoderTicksToMPS = (1/k_ticksPerRev)*(1/k_driveMotorGearRatio)*k_wheelRad*3.14159265*2;//*10 + static constexpr double k_driveMotorEncoderTicksToMPS = (1/k_ticksPerRev)*(1/k_driveMotorGearRatio)*k_wheelRad*3.14159265*2*10;// static constexpr double k_driveMotorEncoderTicksToMeters = (1/k_ticksPerRev)*(1/k_driveMotorGearRatio)*k_wheelRad*3.14159265*2; static constexpr double k_minRobotVelocity = .07;//3*.0254; static constexpr double k_minRobotYawRate = 10;//3*.0254; static constexpr double k_driveWheelSlotError = 0.002; - static constexpr double k_robotWidth = 13.5; - static constexpr double k_robotLength = 13.5; static constexpr double k_maxYawRate = k_maxSpeed / k_wheelLeverArm *180/MATH_CONSTANTS_PI; static constexpr double k_maxYawAccel = k_maxAccel / k_wheelLeverArm*180/MATH_CONSTANTS_PI; static constexpr double k_maxYawDeccel = k_maxDeccel / k_wheelLeverArm*180/MATH_CONSTANTS_PI; static constexpr double k_minYawRate = k_minRobotVelocity / k_wheelLeverArm *180 / MATH_CONSTANTS_PI; - // static constexpr double k_driveMotorEncoderMPSToRPM = (RobotParameters::k_driveMotorGearRatio/(RobotParameters::k_wheelRad*3.14159265*2))*60; - //pathfollowing - static constexpr double k_maxCentripAccel = 10.0;//10 + static constexpr double k_maxCentripAccel = 27.0;//25 //20 //15 // // steer motors static constexpr double k_steerMotorControllerKp = 3; diff --git a/frc-2021_Speed/src/main/include/Utils/CoordinateTranslation.h b/frc-2021_Speed/src/main/include/Utils/CoordinateTranslation.h index 906dc9e..a6f8c40 100644 --- a/frc-2021_Speed/src/main/include/Utils/CoordinateTranslation.h +++ b/frc-2021_Speed/src/main/include/Utils/CoordinateTranslation.h @@ -24,7 +24,7 @@ class CoordinateTranslation { wpiPath.clear(); double inchesToMeters = .0254; for(int i = 0; i < (int)nolanPath.size();i++){ - printf("NolanToWPILib cycle: %d\n", i); + // printf("NolanToWPILib cycle: %d\n", i); SwerveDrivePathGenerator::finalPathPoint_t wpiPoint = nolanPath[i]; wpiPoint.xPos = nolanPath[i].yPos*inchesToMeters; wpiPoint.yPos = -nolanPath[i].xPos*inchesToMeters; @@ -53,7 +53,7 @@ class CoordinateTranslation { m_File <<"xPos (m), yPos (m), yaw (deg), speed (m/s), radCurve\n"; nolanPath.clear(); for(int i = 0; i < (int)wpiPath.size();i++){ - printf("WPILibToNolan cycle: %d\n", i); + // printf("WPILibToNolan cycle: %d\n", i); SwerveDrivePathGenerator::waypoint_t nolanPoint = wpiPath[i]; nolanPoint.xPos = -wpiPath[i].yPos*metersToInches; nolanPoint.yPos = wpiPath[i].xPos*metersToInches; diff --git a/frc-2021_Speed/src/main/include/Utils/SwerveDrivePathFollower.h b/frc-2021_Speed/src/main/include/Utils/SwerveDrivePathFollower.h index de0e905..03ae710 100644 --- a/frc-2021_Speed/src/main/include/Utils/SwerveDrivePathFollower.h +++ b/frc-2021_Speed/src/main/include/Utils/SwerveDrivePathFollower.h @@ -18,7 +18,6 @@ #include #include #include "Utils/PoseDot2D.h" -#include #include #include #include @@ -36,8 +35,8 @@ class SwerveDrivePathFollower { /** * Will be called periodically whenever the CommandScheduler runs. */ - void generatePath(std::vector &waypoints, const std::string &name); void Update(frc::Pose2d pose); + void generatePath(std::vector &waypoints, const std::string &name, double targetZone = .05); double getXVel(); double getYVel(); double getYawRate(); @@ -46,8 +45,7 @@ class SwerveDrivePathFollower { int lookAheadIndex(); bool isPathFinished(); frc::Pose2d getPointPos(int index); - // bool targetPosFound(); - // void setTargetPos(); + frc::Pose2d getFollowerPos(); void stop(bool interrupted); private: @@ -58,11 +56,11 @@ class SwerveDrivePathFollower { bool m_pathFinished = false; - bool m_lastPointReached; - double m_distToEnd; - double m_targetZone; + bool m_lastPointReached; + double m_distToEnd; + double m_targetZone; - int m_lookAheadIndex = 0; + int m_lookAheadIndex = 0; int m_pathIndex = 0; @@ -74,8 +72,8 @@ class SwerveDrivePathFollower { double m_yawRate = 0; double m_time; - +double metersToInches = 39.87; std::ofstream m_File; frc2::PIDController m_turningPIDController{ - 8, 0, 0}; + 4, 0, 0};//1 2 4 }; diff --git a/frc-2021_Speed/src/main/include/commands/Autos/AutoNavPathA.h b/frc-2021_Speed/src/main/include/commands/Autos/AutoNavPathA.h new file mode 100644 index 0000000..27710c2 --- /dev/null +++ b/frc-2021_Speed/src/main/include/commands/Autos/AutoNavPathA.h @@ -0,0 +1,73 @@ +/*----------------------------------------------------------------------------*/ +/* Copyright (c) 2019 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 +#include +#include +#include +#include +#include + +#include "commands/pathCommands/PathFollowerCommand2.h" + + +#include "commands/Drive/DriveOpenLoopCommand.h" + +#include "commands/Drive/RotateWithMotionMagic.h" + +#include "Utils/SwerveDrivePathFollower.h" + +#include "subsystems/DriveSubsystem.h" +#include "commands/Drive/EngageBakeCommand.h" + + +class AutoNavPathA + : public frc2::CommandHelper { + private: + double metersToInches = 39.3701; + double curveSmall = 17;//half of robot(12) + half of cone(2.5) + buffer(2.5) + double curveBig = 30;//25 + public: + AutoNavPathA(DriveSubsystem* m_drive, SwerveDrivePathFollower* follower){ + + + AddCommands( + + //Break Into Multiple Commands + PathFollowerCommand2(m_drive, follower, "path path" ,true) + // EngageBakeCommand(m_drive) + ); + } +}; + + + + + + + + +// std::vector one;//RobotParameters::k_maxSpeed*metersToInches + // path.push_back(SwerveDrivePathGenerator::waypoint_t {60 + RobotParameters::k_wheelBase*metersToInches/2, 80, 0, 0, 0});//start path + // one.push_back(SwerveDrivePathGenerator::waypoint_t {150 + radCurve, 60 + radCurve, 0, 40, 0});//cone 1, point 1 + // one.push_back(SwerveDrivePathGenerator::waypoint_t {150 + radCurve, 60 - radCurve, 0, 40, 0});//cone 1, point 2 + // one.push_back(SwerveDrivePathGenerator::waypoint_t {150 - radCurve, 60 - radCurve, 0, 40, 0});//cone 1, point 3 + // path.push_back(SwerveDrivePathGenerator::waypoint_t {150 - radCurve, 60 + radCurve, 0, RobotParameters::k_maxSpeed*metersToInches, 0});//cone 1, point 4 + // path.push_back(SwerveDrivePathGenerator::waypoint_t {240 + radCurve, 120 - radCurve, 0, RobotParameters::k_maxSpeed*metersToInches, 0});//cone 2, point 1 + // path.push_back(SwerveDrivePathGenerator::waypoint_t {240 + radCurve, 120 + radCurve, 0, RobotParameters::k_maxSpeed*metersToInches, 0});//cone 2, point 2 + // path.push_back(SwerveDrivePathGenerator::waypoint_t {240 - radCurve, 120 + radCurve, 0, RobotParameters::k_maxSpeed*metersToInches, 0});//cone 2, point 3 + // path.push_back(SwerveDrivePathGenerator::waypoint_t {240 - radCurve, 120 - radCurve, 0, RobotParameters::k_maxSpeed*metersToInches, 0});//cone 2, point 4 + // path.push_back(SwerveDrivePathGenerator::waypoint_t {300 - radCurve, 60 - radCurve, 0, RobotParameters::k_maxSpeed*metersToInches, 0});//cone 3, point 1 + // path.push_back(SwerveDrivePathGenerator::waypoint_t {300 + radCurve, 60 - radCurve, 0, RobotParameters::k_maxSpeed*metersToInches, 0});//cone 3, point 2 + // path.push_back(SwerveDrivePathGenerator::waypoint_t {300 + radCurve, 60 + radCurve, 0, RobotParameters::k_maxSpeed*metersToInches, 0});//cone 3, point 3 + // path.push_back(SwerveDrivePathGenerator::waypoint_t {300 - radCurve, 60 + radCurve, 0, RobotParameters::k_maxSpeed*metersToInches, 0});//cone 3, point 4 + // path.push_back(SwerveDrivePathGenerator::waypoint_t {300, 60 + radCurve, 0, RobotParameters::k_maxSpeed*metersToInches, 0});//cone 3, point 5/1 + // path.push_back(SwerveDrivePathGenerator::waypoint_t {60, 60 + radCurve, 0, RobotParameters::k_maxSpeed*metersToInches, 0});//head to end + // path.push_back(SwerveDrivePathGenerator::waypoint_t {0, 60 + radCurve, 0, 0, 0}); \ No newline at end of file diff --git a/frc-2021_Speed/src/main/include/commands/LimeLight/LimeLightRotateTillOnTarget.h b/frc-2021_Speed/src/main/include/commands/Autos/AutoNavPathB.h similarity index 53% rename from frc-2021_Speed/src/main/include/commands/LimeLight/LimeLightRotateTillOnTarget.h rename to frc-2021_Speed/src/main/include/commands/Autos/AutoNavPathB.h index a0032e4..5100ee9 100644 --- a/frc-2021_Speed/src/main/include/commands/LimeLight/LimeLightRotateTillOnTarget.h +++ b/frc-2021_Speed/src/main/include/commands/Autos/AutoNavPathB.h @@ -9,21 +9,35 @@ #include #include -#include "subsystems/DriveSubsystem.h" -#include "commands/Drive/RotateWithMotionMagic.h" +#include +#include #include -#include "commands/LimeLight/LimeLightVisable.h" -class LimeLightRotateTillOnTarget +#include + +#include "commands/pathCommands/PathFollowerCommand.h" + + +#include "commands/Drive/DriveOpenLoopCommand.h" + +#include "commands/Drive/RotateWithMotionMagic.h" + +#include "Utils/SwerveDrivePathFollower.h" + +#include "subsystems/DriveSubsystem.h" +#include "commands/Drive/EngageBakeCommand.h" +#include "commands/Drive/EngageCoastCommand.h" +class AutoNavPathB : public frc2::CommandHelper { + AutoNavPathB> { + private: public: - LimeLightRotateTillOnTarget(DriveSubsystem* drive, double targetAngle, double range){ + AutoNavPathB(DriveSubsystem* m_drive, SwerveDrivePathFollower* m_follower){ + AddCommands( - frc2::ParallelRaceGroup{ - RotateWithMotionMagic(drive, targetAngle,range), - LimeLightVisable() - }, - RotateWithMotionMagic(drive, targetAngle,range, true) + //Break Into Multiple Commands + EngageCoastCommand(m_drive), + PathFollowerCommand2(m_drive, m_follower, "path path" ,true), + EngageBakeCommand(m_drive) ); } }; diff --git a/frc-2021_Speed/src/main/include/commands/Autos/AutoNavPathC.h b/frc-2021_Speed/src/main/include/commands/Autos/AutoNavPathC.h new file mode 100644 index 0000000..076a1d2 --- /dev/null +++ b/frc-2021_Speed/src/main/include/commands/Autos/AutoNavPathC.h @@ -0,0 +1,77 @@ +/*----------------------------------------------------------------------------*/ +/* Copyright (c) 2019 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 +#include +#include +#include +#include +#include + +#include "commands/pathCommands/PathFollowerCommand.h" + + +#include "commands/Drive/DriveOpenLoopCommand.h" + +#include "commands/Drive/RotateWithMotionMagic.h" + +#include "Utils/SwerveDrivePathFollower.h" + +#include "subsystems/DriveSubsystem.h" +#include "commands/Drive/EngageBakeCommand.h" +#include "commands/Drive/CheckInRangeCommand.h" +class AutoNavPathC + : public frc2::CommandHelper { + public: + AutoNavPathC(DriveSubsystem* m_drive, SwerveDrivePathFollower m_follower[]){ + + AddCommands( + frc2::ParallelRaceGroup{ + PathFollowerCommand2(m_drive, &m_follower[0], "path path" ,true,false), + CheckInRangeCommand(m_drive, 126.0, 1) + }, + frc2::ParallelRaceGroup{ + PathFollowerCommand2(m_drive, &m_follower[1], "path path" ,true,false), + frc2::SequentialCommandGroup{ + frc2::WaitCommand(2.2_s), + CheckInRangeCommand(m_drive, 144.0, 1)//144 + } + + }, + frc2::ParallelRaceGroup{ + PathFollowerCommand2(m_drive, &m_follower[2], "path path" ,true,false), + frc2::SequentialCommandGroup{ + frc2::WaitCommand(2_s),//2 + CheckInRangeCommand(m_drive, 140.0, 1)//146 + } + }, + PathFollowerCommand2(m_drive, &m_follower[3], "path path" ,true,false), + PathFollowerCommand2(m_drive, &m_follower[4], "path path" ,true,false), + EngageBakeCommand(m_drive) + ); + } +}; + + + + +// std::vector path; +// path.push_back(SwerveDrivePathGenerator::waypoint_t {60 + RobotParameters::k_wheelBase*metersToInches/2, 100, 0, 0, 0});//start +// path.push_back(SwerveDrivePathGenerator::waypoint_t {60 + RobotParameters::k_wheelBase*metersToInches/2 + curveBig, 100 + curveBig, 0, RobotParameters::k_maxSpeed*metersToInches, 0});//clear start zone +// path.push_back(SwerveDrivePathGenerator::waypoint_t {90, 150, 0, RobotParameters::k_maxSpeed*metersToInches, 0});//bounce point 1 +// path.push_back(SwerveDrivePathGenerator::waypoint_t {130 - radCurve, 60 - radCurve, 0, RobotParameters::k_maxSpeed*metersToInches, 0});//curve around d5 +// path.push_back(SwerveDrivePathGenerator::waypoint_t {130 + radCurve, 60 - radCurve, 0, RobotParameters::k_maxSpeed*metersToInches, 0});//curve around d5 +// path.push_back(SwerveDrivePathGenerator::waypoint_t {180, 150, 0, RobotParameters::k_maxSpeed*metersToInches, 0});//bounce point 2 +// path.push_back(SwerveDrivePathGenerator::waypoint_t {210 - radCurve, 60 - radCurve, 0, RobotParameters::k_maxSpeed*metersToInches, 0});//curve around d7 +// path.push_back(SwerveDrivePathGenerator::waypoint_t {240 + radCurve, 60 - radCurve, 0, RobotParameters::k_maxSpeed*metersToInches, 0});//curve around d8 +// path.push_back(SwerveDrivePathGenerator::waypoint_t {270, 150, 0, RobotParameters::k_maxSpeed*metersToInches, 0});//bounce point 3 +// path.push_back(SwerveDrivePathGenerator::waypoint_t {300 - radCurve, 120 - radCurve, 0, RobotParameters::k_maxSpeed*metersToInches, 0});//head to end +// path.push_back(SwerveDrivePathGenerator::waypoint_t {300, 100, 0, RobotParameters::k_maxSpeed*metersToInches, 0});//curve into end +// path.push_back(SwerveDrivePathGenerator::waypoint_t {360, 100, 0, 0, 0});//decelerate \ No newline at end of file diff --git a/frc-2021_Speed/src/main/include/commands/Autos/AutoSelectorCommandPath.h b/frc-2021_Speed/src/main/include/commands/Autos/AutoSelectorCommandPath.h new file mode 100644 index 0000000..552f000 --- /dev/null +++ b/frc-2021_Speed/src/main/include/commands/Autos/AutoSelectorCommandPath.h @@ -0,0 +1,98 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +#pragma once + +#include +#include + +#include "commands/Autos/GalacticSearchPathABlue.h" +#include "commands/Autos/GalacticSearchPathBBlue.h" +#include "commands/Autos/GalacticSearchPathARed.h" +#include "commands/Autos/GalacticSearchPathBRed.h" +#include "networktables/NetworkTableInstance.h" + +#include "subsystems/DriveSubsystem.h" +#include "subsystems/IntakeSubsystem.h" +#include "Utils/SwerveDrivePathFollower.h" +#include + +using namespace nt; +/** + * An example command. + * + *

Note that this extends CommandHelper, rather extending CommandBase + * directly; this is crucially important, or else the decorator functions in + * Command will *not* work! + */ +class AutoSelectorCommandPath + : public frc2::CommandHelper { + private: + DriveSubsystem* m_pDrive; + IntakeSubsystem* m_pIntake; + SwerveDrivePathFollower* m_followerABlue; + SwerveDrivePathFollower* m_followerBBlue; + SwerveDrivePathFollower* m_followerARed; + SwerveDrivePathFollower* m_followerBRed; + double targetDistance = 0; + double targetY = 0; + bool m_finished = false; + public: + AutoSelectorCommandPath(DriveSubsystem* drive, IntakeSubsystem* intake, SwerveDrivePathFollower* followerABlue, SwerveDrivePathFollower* followerBBlue, SwerveDrivePathFollower* followerARed, SwerveDrivePathFollower* followerBRed){ + m_pDrive = drive; + m_pIntake = intake; + m_followerABlue = followerABlue; + m_followerBBlue = followerBBlue; + m_followerARed = followerARed; + m_followerBRed = followerBRed; + AddRequirements(m_pDrive); + AddRequirements(m_pIntake); + } + + void Initialize() override{ + + } + + void Execute() override{ + if((bool)NetworkTableInstance::GetDefault().GetTable("limelight")->GetNumber("tv",0)){ + targetDistance = NetworkTableInstance::GetDefault().GetTable("limelight")->GetNumber("ty",0); + targetY = NetworkTableInstance::GetDefault().GetTable("limelight")->GetNumber("tx",0); + frc::SmartDashboard::PutNumber("target Distance", targetDistance); + frc::SmartDashboard::PutNumber("target Y", targetY); + if(targetDistance < 0){//RED + if(targetY > 0){ + frc::SmartDashboard::PutString("PATH", "A Red"); + // printf("A Red"); + GalacticSearchPathARed(m_pDrive, m_pIntake, m_followerARed); + m_finished = true; + }else{ + frc::SmartDashboard::PutString("PATH", "B Red"); + // printf("B Red"); + GalacticSearchPathBRed(m_pDrive, m_pIntake, m_followerBRed); + m_finished = true; + } + }else if(targetDistance > 0){//Blue + if(targetY > 0){ + frc::SmartDashboard::PutString("PATH", "A Blue"); + // printf("A Blue"); + GalacticSearchPathABlue(m_pDrive, m_pIntake, m_followerABlue); + m_finished = true; + }else{ + frc::SmartDashboard::PutString("PATH", "B Blue"); + // printf("B Blue"); + GalacticSearchPathBBlue(m_pDrive, m_pIntake, m_followerBBlue); + m_finished = true; + } + } + } + } + + void End(bool interrupted) override{ + + } + + bool IsFinished() override{ + return m_finished; + } +}; diff --git a/frc-2021_Speed/src/main/include/commands/Autos/GalacticSearchPathABlue.h b/frc-2021_Speed/src/main/include/commands/Autos/GalacticSearchPathABlue.h new file mode 100644 index 0000000..7b3b5f9 --- /dev/null +++ b/frc-2021_Speed/src/main/include/commands/Autos/GalacticSearchPathABlue.h @@ -0,0 +1,52 @@ +/*----------------------------------------------------------------------------*/ +/* Copyright (c) 2019 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 +#include +#include +#include +#include +#include + +#include "commands/pathCommands/PathFollowerCommand2.h" + + +#include "commands/Drive/DriveOpenLoopCommand.h" + +#include "commands/Drive/RotateWithMotionMagic.h" + +#include "Utils/SwerveDrivePathFollower.h" + +#include "subsystems/DriveSubsystem.h" +#include "subsystems/IntakeSubsystem.h" + +#include "commands/Intake/IntakesDefaultCommand.h" +#include "commands/Intake/DropIntake.h" +#include "commands/Drive/EngageBakeCommand.h" +class GalacticSearchPathABlue + : public frc2::CommandHelper { + private: + + public: + GalacticSearchPathABlue(DriveSubsystem* m_drive, + IntakeSubsystem* m_intake, + SwerveDrivePathFollower* m_follower){ + + + + AddCommands( + frc2::ParallelRaceGroup{ + IntakesDefaultCommand(m_intake), + PathFollowerCommand2(m_drive, m_follower, "path path" ,true), + }, + EngageBakeCommand(m_drive) + ); + } +}; diff --git a/frc-2021_Speed/src/main/include/commands/Autos/GalacticSearchPathARed.h b/frc-2021_Speed/src/main/include/commands/Autos/GalacticSearchPathARed.h new file mode 100644 index 0000000..a140087 --- /dev/null +++ b/frc-2021_Speed/src/main/include/commands/Autos/GalacticSearchPathARed.h @@ -0,0 +1,55 @@ +/*----------------------------------------------------------------------------*/ +/* Copyright (c) 2019 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 +#include +#include +#include +#include +#include + +#include "commands/pathCommands/PathFollowerCommand2.h" + + +#include "commands/Drive/DriveOpenLoopCommand.h" + +#include "commands/Drive/RotateWithMotionMagic.h" + +#include "Utils/SwerveDrivePathFollower.h" + +#include "subsystems/DriveSubsystem.h" +#include "subsystems/IntakeSubsystem.h" + +#include "commands/Intake/IntakesDefaultCommand.h" +#include "commands/Intake/DropIntake.h" +#include "commands/Drive/EngageBakeCommand.h" +#include "commands/Drive/EngageBakeCommand.h" +class GalacticSearchPathARed + : public frc2::CommandHelper { + private: + + public: + GalacticSearchPathARed(DriveSubsystem* m_drive, + IntakeSubsystem* m_intake, + SwerveDrivePathFollower* m_follower){ + + + AddCommands( + frc2::ParallelRaceGroup{ + // DropIntake(m_intake), + IntakesDefaultCommand(m_intake), + + PathFollowerCommand2(m_drive, m_follower, "path path" ,true), + + }, + EngageBakeCommand(m_drive) + ); + } +}; diff --git a/frc-2021_Speed/src/main/include/commands/Autos/GalacticSearchPathBBlue.h b/frc-2021_Speed/src/main/include/commands/Autos/GalacticSearchPathBBlue.h new file mode 100644 index 0000000..023757d --- /dev/null +++ b/frc-2021_Speed/src/main/include/commands/Autos/GalacticSearchPathBBlue.h @@ -0,0 +1,55 @@ + /*----------------------------------------------------------------------------*/ +/* Copyright (c) 2019 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 +#include +#include +#include +#include +#include + +#include "commands/pathCommands/PathFollowerCommand2.h" + + +#include "commands/Drive/DriveOpenLoopCommand.h" + +#include "commands/Drive/RotateWithMotionMagic.h" + +#include "Utils/SwerveDrivePathFollower.h" + +#include "subsystems/DriveSubsystem.h" +#include "subsystems/IntakeSubsystem.h" + +#include "commands/Intake/IntakesDefaultCommand.h" +#include "commands/Intake/DropIntake.h" +#include "commands/Drive/EngageBakeCommand.h" + +class GalacticSearchPathBBlue + : public frc2::CommandHelper { + private: + + public: + GalacticSearchPathBBlue(DriveSubsystem* m_drive, + IntakeSubsystem* m_intake, + SwerveDrivePathFollower* m_follower){ + + + + AddCommands( + frc2::ParallelRaceGroup{ + IntakesDefaultCommand(m_intake), + + PathFollowerCommand2(m_drive, m_follower, "path path" ,true), + + }, + EngageBakeCommand(m_drive) + ); + } +}; diff --git a/frc-2021_Speed/src/main/include/commands/Autos/GalacticSearchPathBRed.h b/frc-2021_Speed/src/main/include/commands/Autos/GalacticSearchPathBRed.h new file mode 100644 index 0000000..39c5041 --- /dev/null +++ b/frc-2021_Speed/src/main/include/commands/Autos/GalacticSearchPathBRed.h @@ -0,0 +1,51 @@ +/*----------------------------------------------------------------------------*/ +/* Copyright (c) 2019 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 +#include +#include +#include +#include +#include + +#include "commands/pathCommands/PathFollowerCommand2.h" + + +#include "commands/Drive/DriveOpenLoopCommand.h" + +#include "commands/Drive/RotateWithMotionMagic.h" + +#include "Utils/SwerveDrivePathFollower.h" + +#include "subsystems/DriveSubsystem.h" +#include "subsystems/IntakeSubsystem.h" + +#include "commands/Intake/IntakesDefaultCommand.h" +#include "commands/Intake/DropIntake.h" +#include "commands/Drive/EngageBakeCommand.h" + +class GalacticSearchPathBRed + : public frc2::CommandHelper { + private: + + public: + GalacticSearchPathBRed(DriveSubsystem* m_drive, + IntakeSubsystem* m_intake, + SwerveDrivePathFollower* m_follower){ + AddCommands( + frc2::ParallelRaceGroup{ + IntakesDefaultCommand(m_intake), + PathFollowerCommand2(m_drive, m_follower, "path path" ,true), + + }, + EngageBakeCommand(m_drive) + ); + } +}; diff --git a/frc-2021_Speed/src/main/include/commands/Autos/TestSpeedsAuto.h b/frc-2021_Speed/src/main/include/commands/Autos/TestSpeedsAuto.h new file mode 100644 index 0000000..52e44a1 --- /dev/null +++ b/frc-2021_Speed/src/main/include/commands/Autos/TestSpeedsAuto.h @@ -0,0 +1,109 @@ +/*----------------------------------------------------------------------------*/ +/* Copyright (c) 2019 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 +#include +#include +#include +#include +#include + +#include "commands/pathCommands/PathFollowerCommand.h" + + +#include "commands/Drive/DriveOpenLoopCommand.h" + +#include "commands/Drive/RotateWithMotionMagic.h" + +#include "Utils/SwerveDrivePathFollower.h" +#include "commands/Intake/IntakesDefaultCommand.h" +#include "subsystems/DriveSubsystem.h" +#include "subsystems/IntakeSubsystem.h" +#include +#include "commands/Drive/EngageBakeCommand.h" +#include "commands/Intake/IntakesDefaultCommand.h" +#include "commands/Intake/ReverseIntakesCommands.h" +#include +class TestSpeedsAuto + : public frc2::CommandHelper { + public: + TestSpeedsAuto(DriveSubsystem* m_drive, + IntakeSubsystem* m_intake){ + + const double metersToInches = 39.3701; +// double curveSmall = 17;//17; //17//half of robot(12) + half of cone(2.5) + buffer(2.5) +// double curveBig = 25; +// double testSpeed = RobotParameters::k_maxSpeed*metersToInches*1; +// double tempCurve = 12; +// const double radCurveC = 24; + // double distToAccel = (std::pow(RobotParameters::k_maxSpeed,2)/(2*RobotParameters::k_maxAccel)) * metersToInches; + // double distToDeccel = fabs((std::pow(RobotParameters::k_maxSpeed,2)/(2*RobotParameters::k_maxDeccel)) * metersToInches); + +//speeds + std::vector start; //-90 + start.push_back(SwerveDrivePathGenerator::waypoint_t {0, 0, 0, 0, 0});//start + start.push_back(SwerveDrivePathGenerator::waypoint_t {100, 0, 0, RobotParameters::k_maxSpeed * metersToInches, 0}); + start.push_back(SwerveDrivePathGenerator::waypoint_t {200, 0, 0, RobotParameters::k_maxSpeed * metersToInches, 0}); + start.push_back(SwerveDrivePathGenerator::waypoint_t {300, 0, 0, 0, 0});//pick up ball 4 and 5 +//circle + // start.push_back(SwerveDrivePathGenerator::waypoint_t {150 + curveSmall, 60 + curveSmall, 0, testSpeed, 0});//cone 1, point 1 + // start.push_back(SwerveDrivePathGenerator::waypoint_t {150 + curveBig, 60 - curveBig, 0, testSpeed, 0});//cone 1, point 2 + // start.push_back(SwerveDrivePathGenerator::waypoint_t {150 - curveBig, 60 - curveBig, 0, testSpeed, 0});//cone 1, point 3 + // start.push_back(SwerveDrivePathGenerator::waypoint_t {150 + curveSmall, 60 + curveSmall, 0, testSpeed, 0});//cone 1, point 4 +//bounce + // start.push_back(SwerveDrivePathGenerator::waypoint_t {0, 0, 0, testSpeed, 0});//cone 1, point 2 + // start.push_back(SwerveDrivePathGenerator::waypoint_t {30, 0, 0, testSpeed, 0});//cone 1, point 3 + // start.push_back(SwerveDrivePathGenerator::waypoint_t {60, 0, 0, testSpeed, 0});//cone 1, point 4 + // std::vector end; + // end.push_back(SwerveDrivePathGenerator::waypoint_t {60, 0, 0, testSpeed, 0});//cone 1, point 2 + // end.push_back(SwerveDrivePathGenerator::waypoint_t {30, 0, 0, testSpeed, 0});//cone 1, point 3 + // end.push_back(SwerveDrivePathGenerator::waypoint_t {0, 0, 0, 0, 0});//cone 1, point 4 +// const double curve = 20; +// const double radCurveC = 30; +// start.push_back(SwerveDrivePathGenerator::waypoint_t {-curve, -curve, 0, testSpeed, radCurveC});//cone 1, point 2 +// start.push_back(SwerveDrivePathGenerator::waypoint_t {-curve, curve, 0, testSpeed, radCurveC});//cone 1, point 3 +// start.push_back(SwerveDrivePathGenerator::waypoint_t {curve, curve, 0, testSpeed, radCurveC});//cone 1, point 4 +// start.push_back(SwerveDrivePathGenerator::waypoint_t {curve, -curve, 0, testSpeed, radCurveC});//cone 1, point 4 +// start.push_back(SwerveDrivePathGenerator::waypoint_t {-curve, -curve, 0, 0, radCurveC});//cone 1, point 2 +// start.push_back(SwerveDrivePathGenerator::waypoint_t {-curve, curve, 0, testSpeed, radCurveC});//cone 1, point 3 +// start.push_back(SwerveDrivePathGenerator::waypoint_t {curve, curve, 0, testSpeed, radCurveC});//cone 1, point 4 +// start.push_back(SwerveDrivePathGenerator::waypoint_t {curve, -curve, 0, testSpeed, radCurveC});//cone 1, point 4 +// start.push_back(SwerveDrivePathGenerator::waypoint_t {-curve, -curve, 0, testSpeed, radCurveC});//cone 1, point 2 +// start.push_back(SwerveDrivePathGenerator::waypoint_t {-curve, curve, 0, 30, radCurveC});//cone 1, point 3 +// start.push_back(SwerveDrivePathGenerator::waypoint_t {curve, curve, 0, 30, radCurveC});//cone 1, point 4 +// start.push_back(SwerveDrivePathGenerator::waypoint_t {curve, -curve, 0, 30, radCurveC});//cone 1, point 4 +// start.push_back(SwerveDrivePathGenerator::waypoint_t {-curve, -curve, 0, 0, radCurveC});//cone 1, point 2 + AddCommands( + // frc2::ParallelCommandGroup{ + PathFollowerCommand(m_drive, start, "path path" ,true,false), + EngageBakeCommand(m_drive) + // frc2::SequentialCommandGroup{ + // IntakesDefaultCommand(m_intake), + // frc2::WaitCommand(.1_s), + // ReverseIntakesCommands(m_intake), + // frc2::WaitCommand(.1_s), + // IntakesDefaultCommand(m_intake), + // frc2::WaitCommand(.1_s), + // ReverseIntakesCommands(m_intake), + // frc2::WaitCommand(.1_s), + // IntakesDefaultCommand(m_intake), + // frc2::WaitCommand(.1_s), + // ReverseIntakesCommands(m_intake), + // frc2::WaitCommand(.1_s), + // IntakesDefaultCommand(m_intake), + // frc2::WaitCommand(.1_s), + // ToggleIntakeCommand(m_intake) + // } + + // } + + ); + } +}; diff --git a/frc-2021_Speed/src/main/include/commands/Drive/CheckInRangeCommand.h b/frc-2021_Speed/src/main/include/commands/Drive/CheckInRangeCommand.h new file mode 100644 index 0000000..ae5c298 --- /dev/null +++ b/frc-2021_Speed/src/main/include/commands/Drive/CheckInRangeCommand.h @@ -0,0 +1,56 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +#pragma once + +#include +#include + +#include "subsystems/DriveSubsystem.h" + +/** + * An example command. + * + *

Note that this extends CommandHelper, rather extending CommandBase + * directly; this is crucially important, or else the decorator functions in + * Command will *not* work! + */ +class CheckInRangeCommand + : public frc2::CommandHelper { + private: + DriveSubsystem* m_pDriveSubsystem; + double m_xRange; + double m_xStart = 0.0; + bool m_isGreaterThanRange; + int m_greaterThanOveride; + public: + + //drive subsystem, point on x axis greaterThanOveride 0: less than, 1: greater than, 2: false + CheckInRangeCommand(DriveSubsystem* driveSubsystem, double xRange, int greaterThanOveride = 2){ + m_pDriveSubsystem = driveSubsystem; + m_xRange = xRange; + m_greaterThanOveride = greaterThanOveride; + } + + void Initialize() override{ + m_xStart = m_pDriveSubsystem->GetPose().Translation().X().to(); + if(m_greaterThanOveride == 2){ + m_isGreaterThanRange = m_xStart < m_xRange; + }else{ + m_isGreaterThanRange = (bool)m_greaterThanOveride; + } + } + + void Execute() override{ + + } + + void End(bool interrupted) override{ + printf("You are in range!"); + } + + bool IsFinished() override{ + return m_isGreaterThanRange ? m_pDriveSubsystem->GetPose().Translation().X().to() > m_xRange : m_pDriveSubsystem->GetPose().Translation().X().to() < m_xRange; + } +}; diff --git a/frc-2021_Speed/src/main/include/commands/Drive/DriveOpenLoopCommand.h b/frc-2021_Speed/src/main/include/commands/Drive/DriveOpenLoopCommand.h index 9b3f267..2503abe 100644 --- a/frc-2021_Speed/src/main/include/commands/Drive/DriveOpenLoopCommand.h +++ b/frc-2021_Speed/src/main/include/commands/Drive/DriveOpenLoopCommand.h @@ -10,7 +10,8 @@ #include #include #include "subsystems/DriveSubsystem.h" -#include +#include +#include /** * An example command. * diff --git a/frc-2021_Speed/src/main/include/commands/Drive/DriveWithJoystickCommand.h b/frc-2021_Speed/src/main/include/commands/Drive/DriveWithJoystickCommand.h index 9f44ebc..7fa0a90 100644 --- a/frc-2021_Speed/src/main/include/commands/Drive/DriveWithJoystickCommand.h +++ b/frc-2021_Speed/src/main/include/commands/Drive/DriveWithJoystickCommand.h @@ -12,7 +12,8 @@ #include "components/Joystick2481.h" #include "subsystems/DriveSubsystem.h" #include "components/XboxController2481.h" -#include +#include +#include /** * An example command. * diff --git a/frc-2021_Speed/src/main/include/commands/Drive/EngageBakeCommand.h b/frc-2021_Speed/src/main/include/commands/Drive/EngageBakeCommand.h new file mode 100644 index 0000000..090c1b6 --- /dev/null +++ b/frc-2021_Speed/src/main/include/commands/Drive/EngageBakeCommand.h @@ -0,0 +1,25 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +#pragma once + +#include +#include + +#include "subsystems/DriveSubsystem.h" + +class EngageBakeCommand + : public frc2::CommandHelper { + private: + DriveSubsystem* m_pDrive; + public: + EngageBakeCommand(DriveSubsystem* drive){ + m_pDrive = drive; + } + + void Initialize() override{ + m_pDrive->setBrake(); + } +}; diff --git a/frc-2021_Speed/src/main/include/commands/Drive/EngageCoastCommand.h b/frc-2021_Speed/src/main/include/commands/Drive/EngageCoastCommand.h new file mode 100644 index 0000000..9f6d959 --- /dev/null +++ b/frc-2021_Speed/src/main/include/commands/Drive/EngageCoastCommand.h @@ -0,0 +1,25 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +#pragma once + +#include +#include + +#include "subsystems/DriveSubsystem.h" + +class EngageCoastCommand + : public frc2::CommandHelper { + private: + DriveSubsystem* m_pDrive; + public: + EngageCoastCommand(DriveSubsystem* drive){ + m_pDrive = drive; + } + + void Initialize() override{ + m_pDrive->setCoast(); + } +}; diff --git a/frc-2021_Speed/src/main/include/commands/Drive/RotateToAngleCommand.h b/frc-2021_Speed/src/main/include/commands/Drive/RotateToAngleCommand.h deleted file mode 100644 index d4d1157..0000000 --- a/frc-2021_Speed/src/main/include/commands/Drive/RotateToAngleCommand.h +++ /dev/null @@ -1,94 +0,0 @@ - -/*----------------------------------------------------------------------------*/ -/* Copyright (c) 2019 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 -#include -#include "RobotContainer.h" -#include "subsystems/DriveSubsystem.h" -#include -#include -#include -#include "RobotParameters.h" -#include "Utils/NormalizeToRange.h" -#include -using namespace nt; - -class RotateToAngleCommand - : public frc2::CommandHelper { - - private: - - double m_turnInput; - double m_targetZone; - double m_targetYaw; - bool m_tv; - int m_loopCounter = 0; - frc2::Timer m_timer; - DriveSubsystem* m_drive; - frc2::PIDController m_turningPIDController{ - 3.5, 5, .1}; - // using radians_per_second_squared_t = - // units::compound_unit>>; - // frc::ProfiledPIDController m_turningPIDController{ - // 3, 0, 0.2, - // {units::degrees_per_second_t(RobotParameters::k_maxYawRate), units::unit_t(RobotParameters::k_maxYawAccel*MATH_CONSTANTS_PI/180)}}; - public: - RotateToAngleCommand(DriveSubsystem* driveTrain, double targetYaw, double targetZone){ - m_drive = driveTrain; - m_targetZone = targetZone; - m_targetYaw = targetYaw; - m_timer.Start(); - AddRequirements(m_drive); - // m_turningPIDController.SetP(frc::SmartDashboard::GetNumber("angle to rotate p", 35)); - // m_turningPIDController.SetI(frc::SmartDashboard::GetNumber("angle to rotate i", 35)); - // m_turningPIDController.SetD(frc::SmartDashboard::GetNumber("angle to rotate d", 35)); - m_turningPIDController.SetIntegratorRange(-5,5); - frc::SmartDashboard::PutNumber("angle to rotate p", 3.5); - frc::SmartDashboard::PutNumber("angle to rotate i", 5); - frc::SmartDashboard::PutNumber("angle to rotate d", .1); - frc::SmartDashboard::PutNumber("angle to rotate i zone", 5); - } - - void Initialize() override{ - - // m_targetYaw = frc::SmartDashboard::GetNumber("angle to rotate ", 35); - m_turningPIDController.EnableContinuousInput(-180,180); - } - - void Execute() override{ - m_turnInput = m_drive->GetPose().Rotation().Degrees().to(); - - double yawRate = m_turningPIDController.Calculate(m_turnInput, m_targetYaw); //pid tune motor controller - - m_drive->Drive(units::meters_per_second_t(0), // set the driveTrain - units::meters_per_second_t(0), - units::degrees_per_second_t(yawRate), - false); - frc::SmartDashboard::PutNumber("YawRate", yawRate); - frc::SmartDashboard::PutNumber("m_turnInput", m_turnInput); - if(fabs(normalizeToRange::RangedDifference(m_turnInput - m_targetYaw,-180, 180)) <= m_targetZone){ - m_loopCounter++; - }else{ - m_loopCounter = 0; - } - } - - void End(bool interrupted) override{ - m_drive->Drive(0_mps,0_mps,0_rpm,false);//STOP DRIVE TRAIN - printf("rotate to angle time since init %f\n", m_timer.Get().to()); - m_timer.Stop(); - } - - bool IsFinished() override{ - // printf(" - - -- - - - - rotating still- - -- - -- - --\n"); - return m_loopCounter >=5; - } -}; diff --git a/frc-2021_Speed/src/main/include/commands/Drive/RotateWithMotionMagic.h b/frc-2021_Speed/src/main/include/commands/Drive/RotateWithMotionMagic.h index 35254f5..b7629ae 100644 --- a/frc-2021_Speed/src/main/include/commands/Drive/RotateWithMotionMagic.h +++ b/frc-2021_Speed/src/main/include/commands/Drive/RotateWithMotionMagic.h @@ -41,8 +41,6 @@ class RotateWithMotionMagic m_targetZone = targetZone; m_limeLight = limeLight; AddRequirements(m_pSwerveDrive); - frc::SmartDashboard::PutNumber("scale motion error", 1); - } void Initialize() override{ @@ -61,7 +59,7 @@ class RotateWithMotionMagic m_turnInput = m_pSwerveDrive->GetPose().Rotation().Degrees().to(); } - double diff = normalizeToRange::RangedDifference(m_targetAngle-m_turnInput, -180,180)*.7;//frc::SmartDashboard::GetNumber("scale motion error", 1) + double diff = normalizeToRange::RangedDifference(m_targetAngle-m_turnInput, -180,180)*.7; m_pSwerveDrive->DriveArc(RobotParameters::k_wheelLeverArm * diff * MATH_CONSTANTS_PI/180); if(fabs(diff) < m_targetZone){ m_count++; diff --git a/frc-2021_Speed/src/main/include/commands/Drive/RotateWithTrajectoryCommand.h b/frc-2021_Speed/src/main/include/commands/Drive/RotateWithTrajectoryCommand.h deleted file mode 100644 index 387cc41..0000000 --- a/frc-2021_Speed/src/main/include/commands/Drive/RotateWithTrajectoryCommand.h +++ /dev/null @@ -1,134 +0,0 @@ -/*----------------------------------------------------------------------------*/ -/* Copyright (c) 2019 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 -#include -#include "RobotContainer.h" -#include "subsystems/DriveSubsystem.h" -#include -#include -#include -#include "RobotParameters.h" -#include "Utils/NormalizeToRange.h" -#include "Utils/TrajectoryGenerator1D.h" -#include "Utils/NormalizeToRange.h" -#include -#include "networktables/NetworkTableInstance.h" -using namespace nt; - -class RotateWithTrajectoryCommand - : public frc2::CommandHelper { - - private: - TrajectoryGenerator1D* trajectoryGenerator; - - double m_turnInput; - double m_targetZone; - double m_targetYaw; - bool m_tv; - double m_pathIndex; - double m_closestDistance; - bool m_limeLight; - frc2::Timer m_timer; - frc2::PIDController m_turningPIDController{ - 3.5, 5, .1}; - DriveSubsystem* m_drive; - std::vector path; - std::vector m_path; - std::ofstream m_File; - - public: - RotateWithTrajectoryCommand(DriveSubsystem* driveTrain, double targetYaw, double targetZone, bool limeLight = false){ - m_drive = driveTrain; - m_targetZone = targetZone; - m_targetYaw = targetYaw; - m_limeLight = limeLight; - AddRequirements(m_drive); - frc::SmartDashboard::PutNumber("angle to rotate",0); - } - - void Initialize() override{ - m_File.open("home/lvuser/ActualYawPath.csv",std::ofstream::out); - m_timer.Start(); - - m_pathIndex = 0; - m_turnInput = m_drive->GetPose().Rotation().Degrees().to(); - double currentYawRate = m_drive->GetTurnRate(); - if(m_limeLight){ - m_turnInput = nt::NetworkTableInstance::GetDefault().GetTable("limelight")->GetNumber("tx",0); - double currentAngle = m_drive->GetPose().Rotation().Degrees().to(); - if(m_turnInput < currentAngle){ - m_targetYaw = currentAngle - m_turnInput; - }else{ - m_targetYaw = m_turnInput - currentAngle; - } - } - double yawDiff = normalizeToRange::NormalizeToRange(normalizeToRange::RangedDifference(m_targetYaw - m_turnInput,-180,180)/2+m_turnInput,-180,180,true); - - path.clear(); - path.push_back(TrajectoryGenerator1D::waypoint_t{m_turnInput,currentYawRate}); - path.push_back(TrajectoryGenerator1D::waypoint_t{yawDiff,RobotParameters::k_maxYawRate}); - path.push_back(TrajectoryGenerator1D::waypoint_t{m_targetYaw,0}); - trajectoryGenerator = new TrajectoryGenerator1D(path,50,RobotParameters::k_maxYawRate,RobotParameters::k_maxYawAccel, RobotParameters::k_maxYawDeccel); - - trajectoryGenerator->setIsContinous(true, -180,180); - trajectoryGenerator->generatePath(); - trajectoryGenerator->writePathToCSV(); - // trajectoryGenerator->setPathFilename("rotating with trajectory path.csv"); - m_turningPIDController.EnableContinuousInput(-180,180); - m_path.clear(); - m_path = trajectoryGenerator->getFinalPath(); - m_File << "path yaw, path vel, robot yaw, diff in yaw\n"; - } - - void Execute() override{ - m_turnInput = m_drive->GetPose().Rotation().Degrees().to(); - m_closestDistance = std::numeric_limits::infinity(); - for(int j = m_pathIndex; j < (int)m_path.size(); j++){ - - - double diff = fabs(normalizeToRange::RangedDifference(m_path[j].pos-m_turnInput, -180,180)); - printf("point looking at: %d %f %f %f %f\n", j, m_path[j].pos, m_turnInput, m_path[j].vel, diff); - if(diff < m_closestDistance){ - if(fabs(m_path[j].vel) > RobotParameters::k_minYawRate){ - m_pathIndex = j; - m_closestDistance = diff; - } - }else{ - break; - } - } - m_File << m_path[m_pathIndex].pos <<"," - << m_path[m_pathIndex].vel << "," - << m_turnInput <<"," - << m_closestDistance <<"\n"; - double output = m_path[m_pathIndex].vel; - printf("vel %f\n", output); - m_drive->Drive(units::meters_per_second_t(0), // set the driveTrain - units::meters_per_second_t(0), - units::degrees_per_second_t(output), - true,false); - frc::SmartDashboard::PutNumber("target traject Yaw", m_path[m_pathIndex].pos); - frc::SmartDashboard::PutNumber("Actual rotate traject yaw", m_turnInput); - frc::SmartDashboard::PutNumber("traject YawRate", output); - // frc::SmartDashboard::PutNumber("m_turnInput", m_turnInput); - } - - void End(bool interrupted) override{ - printf("rotate to angle with torjecttory time since init %f\n", m_timer.Get().to()); - m_drive->Drive(0_mps,0_mps,0_rpm,false);//STOP DRIVE TRAIN - m_timer.Stop(); - m_File.close(); - } - - bool IsFinished() override{ - return m_pathIndex >= (int)m_path.size()-1 && m_closestDistance < m_targetZone ; - } -}; - diff --git a/frc-2021_Speed/src/main/include/commands/Intake/DropBallsCommand.h b/frc-2021_Speed/src/main/include/commands/Intake/DropBallsCommand.h new file mode 100644 index 0000000..f38c6c9 --- /dev/null +++ b/frc-2021_Speed/src/main/include/commands/Intake/DropBallsCommand.h @@ -0,0 +1,45 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +#pragma once + +#include +#include +#include "subsystems/IntakeSubsystem.h" +#include "Constants.h" +/** + * An example command. + * + *

Note that this extends CommandHelper, rather extending CommandBase + * directly; this is crucially important, or else the decorator functions in + * Command will *not* work! + */ +class DropBallsCommand + : public frc2::CommandHelper { + private: + IntakeSubsystem* m_pIntake; + public: + DropBallsCommand(IntakeSubsystem* intake){ + m_pIntake = intake; + AddRequirements(m_pIntake); + } + + void Initialize() override{ + m_pIntake->setAIntakeSpeed(IntakeConstants::kAIntakeReverse); + m_pIntake->setBIntakeSpeed(IntakeConstants::kBIntakeReverse); + } + + void Execute() override{ + m_pIntake->getAIntakeSpeed(); + } + + void End(bool interrupted) override{ + m_pIntake->setAIntakeSpeed(0); + m_pIntake->setBIntakeSpeed(0); + } + + bool IsFinished() override{ + return false; + } +}; diff --git a/frc-2021_Speed/src/main/include/commands/Intake/CheckBeamBreak.h b/frc-2021_Speed/src/main/include/commands/Intake/DropIntake.h similarity index 66% rename from frc-2021_Speed/src/main/include/commands/Intake/CheckBeamBreak.h rename to frc-2021_Speed/src/main/include/commands/Intake/DropIntake.h index 0e08e9e..79da3d7 100644 --- a/frc-2021_Speed/src/main/include/commands/Intake/CheckBeamBreak.h +++ b/frc-2021_Speed/src/main/include/commands/Intake/DropIntake.h @@ -6,22 +6,21 @@ #include #include + #include "subsystems/IntakeSubsystem.h" -class CheckBeamBreak +#include "Constants.h" + +class DropIntake : public frc2::CommandHelper { + DropIntake> { private: IntakeSubsystem* m_pIntake; public: - CheckBeamBreak(IntakeSubsystem* intake){ + DropIntake(IntakeSubsystem* intake){ m_pIntake = intake; - AddRequirements(m_pIntake); } void Initialize() override{ - if(m_pIntake->getBeamBreak()){ - m_pIntake->setLeftSpeed(0);//TODO check if it is right or left - } + m_pIntake->setServoAngle(0);//180 } - }; diff --git a/frc-2021_Speed/src/main/include/commands/Intake/IntakesDefaultCommand.h b/frc-2021_Speed/src/main/include/commands/Intake/IntakesDefaultCommand.h new file mode 100644 index 0000000..f864ba1 --- /dev/null +++ b/frc-2021_Speed/src/main/include/commands/Intake/IntakesDefaultCommand.h @@ -0,0 +1,71 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +#pragma once + +#include +#include +#include "subsystems/IntakeSubsystem.h" +#include +#include "Constants.h" +/** + * An example command. + * + *

Note that this extends CommandHelper, rather extending CommandBase + * directly; this is crucially important, or else the decorator functions in + * Command will *not* work! + */ + +class IntakesDefaultCommand + : public frc2::CommandHelper { + private: + IntakeSubsystem* m_pIntake; + int countB; + int countA; + public: + IntakesDefaultCommand(IntakeSubsystem* pIntake){ + m_pIntake = pIntake; + AddRequirements(m_pIntake); + } + + void Initialize() override{ + m_pIntake->setAIntakeSpeed(IntakeConstants::kAIntakeSpeed); + m_pIntake->setBIntakeSpeed(IntakeConstants::kBIntakeSpeed); + } + + void Execute() override{ + if(m_pIntake->getIntakeACurrent() >= IntakeConstants::kMaxIntakeAmp){ + countA++; + }else{ + countA = 0; + } + if(countA > 7){ + m_pIntake->setAIntakeSpeed(0); + frc::Wait(.05); + m_pIntake->setAIntakeSpeed(IntakeConstants::kBIntakeSpeed); + } + if(m_pIntake->getIntakeBCurrent() >= IntakeConstants::kMaxIntakeAmp){ + countB++; + }else{ + countB = 0; + } + if(countB > 3){ + m_pIntake->setBIntakeSpeed(0); + frc::Wait(.05); + m_pIntake->setBIntakeSpeed(IntakeConstants::kBIntakeSpeed); + } + } + + void End(bool interrupted) override{ + m_pIntake->setAIntakeSpeed(0); + m_pIntake->setBIntakeSpeed(0); + countA = 0; + countB = 0; + printf("intake was Interupted: %d", (int)interrupted); + } + + bool IsFinished() override{ + return false; + } +}; diff --git a/frc-2021_Speed/src/main/include/commands/Intake/ReverseIntakesCommands.h b/frc-2021_Speed/src/main/include/commands/Intake/ReverseIntakesCommands.h new file mode 100644 index 0000000..13ec02e --- /dev/null +++ b/frc-2021_Speed/src/main/include/commands/Intake/ReverseIntakesCommands.h @@ -0,0 +1,44 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +#pragma once + +#include +#include +#include "subsystems/IntakeSubsystem.h" +#include "Constants.h" +/** + * An example command. + * + *

Note that this extends CommandHelper, rather extending CommandBase + * directly; this is crucially important, or else the decorator functions in + * Command will *not* work! + */ +class ReverseIntakesCommands + : public frc2::CommandHelper { + private: + IntakeSubsystem* m_pIntake; + public: + ReverseIntakesCommands(IntakeSubsystem* intake){ + m_pIntake = intake; + AddRequirements(m_pIntake); + } + + void Initialize() override{ + m_pIntake->setAIntakeSpeed(-1.0); + m_pIntake->setBIntakeSpeed(-1.0); + } + + void Execute() override{ + } + + void End(bool interrupted) override{ + m_pIntake->setAIntakeSpeed(0); + m_pIntake->setBIntakeSpeed(0); + } + + bool IsFinished() override{ + return false; + } +}; diff --git a/frc-2021_Speed/src/main/include/commands/Intake/SetLeftIntakeSpeed.h b/frc-2021_Speed/src/main/include/commands/Intake/SetAIntakeSpeed.h similarity index 73% rename from frc-2021_Speed/src/main/include/commands/Intake/SetLeftIntakeSpeed.h rename to frc-2021_Speed/src/main/include/commands/Intake/SetAIntakeSpeed.h index 3a781cf..3661169 100644 --- a/frc-2021_Speed/src/main/include/commands/Intake/SetLeftIntakeSpeed.h +++ b/frc-2021_Speed/src/main/include/commands/Intake/SetAIntakeSpeed.h @@ -7,20 +7,20 @@ #include #include #include "subsystems/IntakeSubsystem.h" -class SetLeftIntakeSpeed +class SetAIntakeSpeed : public frc2::CommandHelper { + SetAIntakeSpeed> { private: IntakeSubsystem* m_pIntake; double m_speed; public: - SetLeftIntakeSpeed(IntakeSubsystem* intake, double speed){ + SetAIntakeSpeed(IntakeSubsystem* intake, double speed){ m_pIntake = intake; m_speed = speed; AddRequirements(m_pIntake); } void Initialize() override{ - m_pIntake->setLeftSpeed(m_speed);//TODO check if inverted + m_pIntake->setAIntakeSpeed(m_speed); } }; diff --git a/frc-2021_Speed/src/main/include/commands/Intake/SetRightIntakeSpeed.h b/frc-2021_Speed/src/main/include/commands/Intake/SetBIntakeSpeed.h similarity index 73% rename from frc-2021_Speed/src/main/include/commands/Intake/SetRightIntakeSpeed.h rename to frc-2021_Speed/src/main/include/commands/Intake/SetBIntakeSpeed.h index 661e3f5..242b673 100644 --- a/frc-2021_Speed/src/main/include/commands/Intake/SetRightIntakeSpeed.h +++ b/frc-2021_Speed/src/main/include/commands/Intake/SetBIntakeSpeed.h @@ -7,20 +7,20 @@ #include #include #include "subsystems/IntakeSubsystem.h" -class SetRightIntakeSpeed +class SetBIntakeIntakeSpeed : public frc2::CommandHelper { + SetBIntakeIntakeSpeed> { private: IntakeSubsystem* m_pIntake; double m_speed; public: - SetRightIntakeSpeed(IntakeSubsystem* intake, double speed){ + SetBIntakeIntakeSpeed(IntakeSubsystem* intake, double speed){ m_pIntake = intake; m_speed = speed; AddRequirements(m_pIntake); } void Initialize() override{ - m_pIntake->setLeftSpeed(m_speed);//TODO check if inverted + m_pIntake->setBIntakeSpeed(m_speed); } }; diff --git a/frc-2021_Speed/src/main/include/commands/Intake/ToggleIntakeCommand.h b/frc-2021_Speed/src/main/include/commands/Intake/ToggleIntakeCommand.h new file mode 100644 index 0000000..0f0c663 --- /dev/null +++ b/frc-2021_Speed/src/main/include/commands/Intake/ToggleIntakeCommand.h @@ -0,0 +1,39 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +#pragma once + +#include +#include +#include "subsystems/IntakeSubsystem.h" + +#include "Constants.h" + +/** + * An example command. + * + *

Note that this extends CommandHelper, rather extending CommandBase + * directly; this is crucially important, or else the decorator functions in + * Command will *not* work! + */ +class ToggleIntakeCommand + : public frc2::CommandHelper { + private: + IntakeSubsystem* m_pIntake; + public: + ToggleIntakeCommand(IntakeSubsystem* pIntake){ + m_pIntake = pIntake; + } + + void Initialize() override{ + if(m_pIntake->getAIntakeSpeed() != 0){ + m_pIntake->setAIntakeSpeed(0); + m_pIntake->setBIntakeSpeed(0); + } + else{ + m_pIntake->setAIntakeSpeed(IntakeConstants::kAIntakeSpeed); + m_pIntake->setBIntakeSpeed(IntakeConstants::kBIntakeSpeed); + } + } +}; diff --git a/frc-2021_Speed/src/main/include/commands/LimeLight/LimeLightRotateToTargetCommand.h b/frc-2021_Speed/src/main/include/commands/LimeLight/LimeLightRotateToTargetCommand.h deleted file mode 100644 index 53ca53f..0000000 --- a/frc-2021_Speed/src/main/include/commands/LimeLight/LimeLightRotateToTargetCommand.h +++ /dev/null @@ -1,116 +0,0 @@ -/*----------------------------------------------------------------------------*/ -/* Copyright (c) 2019 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 -#include -#include "networktables/NetworkTableInstance.h" -#include -#include "RobotContainer.h" -#include "subsystems/DriveSubsystem.h" -#include -#include -#include -#include -#include -#include "RobotParameters.h" -#include "components/Joystick2481.h" -#include -#include "Commands/LimeLight/TurnLimeLightOn.h" -#include "Commands/LimeLight/TurnLimeLightOff.h" -#include -using namespace nt; - -class -LimeLightRotateToTargetCommand - : public frc2::CommandHelper { - - private: - - double m_turnInput; - double m_targetZone; - int m_targetLostCounter = 0; - int m_targetZoneConter = 0; - double m_targetAngle = 0; - bool m_tv; - frc::Timer m_timer; - DriveSubsystem* m_drive; - frc2::PIDController m_turningPIDController{ - RobotParameters::k_limeLightP, RobotParameters::k_limeLightI, RobotParameters::k_limeLightD};//3.5, 0, 0}; - - // frc::ProfiledPIDController m_turningPIDController{ - // 3, 0, 0.2, - // AutoConstants::kThetaControllerConstraints}; - public: - LimeLightRotateToTargetCommand(DriveSubsystem* driveTrain, double targetZone){ - m_drive = driveTrain; - m_targetZone = targetZone; - AddRequirements(m_drive); - } - - void Initialize() override{ - TurnLimeLightOn(); - m_timer.Start(); - // m_turningPIDController. - m_turningPIDController.EnableContinuousInput(-180,180); - m_turningPIDController.SetP(frc::SmartDashboard::GetNumber("limeLight P", RobotParameters::k_limeLightP)); - m_turningPIDController.SetI(frc::SmartDashboard::GetNumber("limeLight I", RobotParameters::k_limeLightI)); - m_turningPIDController.SetD(frc::SmartDashboard::GetNumber("limeLight D", RobotParameters::k_limeLightD)); - m_turningPIDController.SetIntegratorRange(-frc::SmartDashboard::GetNumber("limeLight Izone", RobotParameters::k_limeLightIZone),frc::SmartDashboard::GetNumber("limeLight Izone", RobotParameters::k_limeLightIZone)); - m_turnInput = NetworkTableInstance::GetDefault().GetTable("limelight")->GetNumber("tx",0); - double currentAngle = m_drive->GetPose().Rotation().Degrees().to(); - if(m_turnInput < currentAngle){ - m_targetAngle = currentAngle - m_turnInput ; - }else{ - m_targetAngle = m_turnInput - currentAngle; - } - } - - void Execute() override{ - //get target angle - m_turnInput = m_drive->GetPose().Rotation().Degrees().to(); - double yawRate = m_turningPIDController.Calculate(m_turnInput, 0.0);//m_targetAngle //pid tune motor controller - m_tv = (bool)NetworkTableInstance::GetDefault().GetTable("limelight")->GetNumber("tv",0); // bool target visable - - m_drive->Drive(units::meters_per_second_t(0), // set the driveTrain - units::meters_per_second_t(0), - units::degrees_per_second_t(yawRate), - false); - frc::SmartDashboard::PutNumber("YawRate", yawRate); - frc::SmartDashboard::PutNumber("m_turnInput", m_turnInput); - if(fabs(m_turnInput)< m_targetZone){//counter for target zone - m_targetZoneConter++; - m_turnInput = NetworkTableInstance::GetDefault().GetTable("limelight")->GetNumber("tx",0); - double currentAngle = m_drive->GetPose().Rotation().Degrees().to(); - if(m_turnInput < currentAngle){ - m_targetAngle = currentAngle - m_turnInput ; - }else{ - m_targetAngle = m_turnInput - currentAngle; - } - }else{ - m_targetZoneConter = 0; - } - if(!m_tv){// counter for lost target - m_targetLostCounter++; - }else{ - m_targetLostCounter = 0; - } - } - - void End(bool interrupted) override{ - m_drive->Drive(0_mps,0_mps,0_rpm,false);//STOP DRIVE TRAIN - printf("lime light rotate command time since init%f\n",m_timer.Get()); - m_timer.Stop(); - TurnLimeLightOff(); - } - - bool IsFinished() override{ - return m_targetZoneConter >= 3||m_targetLostCounter >= 3;//||m_timer.Get() > 2; - } -}; - diff --git a/frc-2021_Speed/src/main/include/commands/LimeLight/LimeLightSwerveDriveRotateToTargetCommand.h b/frc-2021_Speed/src/main/include/commands/LimeLight/LimeLightSwerveDriveRotateToTargetCommand.h deleted file mode 100644 index 29ad0c2..0000000 --- a/frc-2021_Speed/src/main/include/commands/LimeLight/LimeLightSwerveDriveRotateToTargetCommand.h +++ /dev/null @@ -1,142 +0,0 @@ -/*----------------------------------------------------------------------------*/ -/* Copyright (c) 2019 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 -#include -#include "networktables/NetworkTableInstance.h" -#include -#include "RobotContainer.h" -#include "subsystems/DriveSubsystem.h" -#include -#include -#include -#include -#include -#include "RobotParameters.h" -#include "components/Joystick2481.h" -using namespace nt; - -class LimeLightSwerveDriveRotateToTargetCommand - : public frc2::CommandHelper { - - private: - - double m_turnInput; - double m_p = 0; - double m_i = 0; - double m_d = 0; - double m_targetZone = 1; - int m_targetLostCounter = 0; - int m_targetZoneConter = 0; - bool m_autoSkew; - bool m_tunePID; - bool m_tv; - DriveSubsystem* m_drive; - Joystick2481* m_driverController; - frc2::PIDController m_drivePIDController{ - 1, 0, 0}; - frc::ProfiledPIDController m_turningPIDController{ - 3, 0, 0.2, - AutoConstants::kThetaControllerConstraints}; - public: - LimeLightSwerveDriveRotateToTargetCommand(DriveSubsystem* driveTrain, Joystick2481* driveController, bool autoSkew, bool tunePID = false){ - m_drive = driveTrain; - m_autoSkew = autoSkew; - m_tunePID = tunePID; - m_driverController = driveController; - - AddRequirements(m_drive); - } - - void Initialize() override{ - if(m_tunePID){// tune pid - m_p = frc::SmartDashboard::GetNumber("LimelightP",1.0); //get pid - m_i = frc::SmartDashboard::GetNumber("LimelightI",0.0); - m_d = frc::SmartDashboard::GetNumber("LimelightD",0.0); - bool steer = (bool)frc::SmartDashboard::GetNumber("Steer || Translate", 1);// deciding if it si drive or steer tune - if(steer){ //check if tuning drive or steer - m_drivePIDController.SetP(m_p); - m_drivePIDController.SetI(m_i);//tuning drive - m_drivePIDCon - troller.SetD(m_d); - }else{ - m_turningPIDController.SetP(m_p);//tuning steer - m_turningPIDController.SetI(m_i); - m_turningPIDController.SetD(m_d); - } - } - m_targetZone = frc::SmartDashboard::GetNumber("Target Zone", 1)*wpi::math::pi/180; // update target zone ofset +- - } - - void Execute() override{ - double xleftHand = 0.0; //robot x and y - double yleftHand = 0.0; - if(m_autoSkew){//auto skewing - double skew = -NetworkTableInstance::GetDefault().GetTable("limelight")->GetNumber("ts",0)*wpi::math::pi/180;// get the skew limelight - frc::SmartDashboard::PutNumber("Current Skew to target",skew); //printing skew - yleftHand = 0; - xleftHand = -m_drivePIDController.Calculate(skew);//calculate skew pid - if(fabs(xleftHand) <=0.15){//dead zone - xleftHand = 0.0; - } - } - else{ - xleftHand = -m_driverController->GetRawAxis(0);//left xbox joystick - if(fabs(xleftHand) <=0.15){//dead zone - xleftHand = 0.0; - } - yleftHand = m_driverController->GetRawAxis(1);//right xbox joystick - if(fabs(yleftHand) <=0.15){//dead zone - yleftHand = 0.0; - } - } - m_turnInput = NetworkTableInstance::GetDefault().GetTable("limelight")->GetNumber("tx",0)*wpi::math::pi/180; //get target angle - auto yawRate = m_turningPIDController.Calculate(units::radian_t((m_turnInput))); //pid tune motor controller - - m_tv = (bool)NetworkTableInstance::GetDefault().GetTable("limelight")->GetNumber("tv",0); // bool target visable - - - - if(fabs(m_turnInput)< m_targetZone){// set turning to zero if in target zone - m_turnInput = 0; - } - // printf("Limelight Yaw: %.01f",yawRate); - m_drive->Drive(units::meters_per_second_t(-yleftHand), // set the driveTrain - units::meters_per_second_t(-xleftHand), - units::radians_per_second_t(yawRate), - false); - frc::SmartDashboard::PutNumber("YawRate", yawRate); - - if(fabs(m_turnInput)< m_targetZone){//counter for target zone - m_targetZoneConter++; - }else{ - m_targetZoneConter = 0; - } - if(!m_tv){// counter for lost target - m_targetLostCounter++; - }else{ - m_targetLostCounter = 0; - } - } - - void End(bool interrupted) override{ - if(m_tunePID){ - frc::SmartDashboard::PutNumber("LimelightP",m_p); - frc::SmartDashboard::PutNumber("LimelightI",m_i); //reseting the put numbers - frc::SmartDashboard::PutNumber("LimelightD",m_d); - } - frc::SmartDashboard::PutNumber("Target Zone", m_targetZone*180/wpi::math::pi); - m_drive->Drive(0_mps,0_mps,units::radians_per_second_t(0),false);//STOP DRIVE TRAIN - } - - bool IsFinished() override{ - return false; - } -}; - diff --git a/frc-2021_Speed/src/main/include/commands/LimeLight/LimelightUpdatePose.h b/frc-2021_Speed/src/main/include/commands/LimeLight/LimelightUpdatePose.h deleted file mode 100644 index 2bcf277..0000000 --- a/frc-2021_Speed/src/main/include/commands/LimeLight/LimelightUpdatePose.h +++ /dev/null @@ -1,51 +0,0 @@ -/*----------------------------------------------------------------------------*/ -/* Copyright (c) 2019 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 -#include -#include "subsystems/DriveSubsystem.h" -#include -#include -/** - * An example command. - * - *

Note that this extends CommandHelper, rather extending CommandBase - * directly; this is crucially important, or else the decorator functions in - * Command will *not* work! - */ -class LimelightUpdatePose - : public frc2::CommandHelper { - private: - DriveSubsystem* m_driveTrain; - public: - LimelightUpdatePose(DriveSubsystem* driveTrain){ - m_driveTrain = driveTrain; - AddRequirements(m_driveTrain); - } - - void Initialize() override{ - double tx = NetworkTableInstance::GetDefault().GetTable("limelight")->GetNumber("tx",0); - double ty = (nt::NetworkTableInstance::GetDefault().GetTable("limelight")->GetNumber("ty",0)-LimeLightConstants::kLimeLightAngle + LimeLightConstants::kLimeLightHardWarePanAngle)*MATH_CONSTANTS_PI/180; - double ta = NetworkTableInstance::GetDefault().GetTable("limelight")->GetNumber("ta",0); - double height = LimeLightConstants::kTargetHeight - LimeLightConstants::kLimeLightHeight; - // frc::Translation2d targetPose = Translation2d(0, 0); //target on one side of field//TODO check coordinate frame - double headingToTarget = m_driveTrain->GetPose().Rotation().Radians().to()+ tx*MATH_CONSTANTS_PI/2 + MATH_CONSTANTS_PI/2; - double distance = height/tan(ty); - double distanceX = distance*sin(headingToTarget); - double distanceY = distance*cos(headingToTarget); - frc::SmartDashboard::PutNumber("Lime light X", distanceX); - frc::SmartDashboard::PutNumber("Lime light Y", distanceY); - frc::SmartDashboard::PutNumber("Lime light yaw", headingToTarget); - frc::Translation2d newPose = frc::Translation2d(units::meter_t(15.98), units::meter_t(8.21)) - frc::Translation2d(units::meter_t(distanceX), units::meter_t - (distanceY)); - - m_driveTrain->ResetOdometry(frc::Pose2d(newPose, m_driveTrain->GetPose().Rotation())); - } - -}; diff --git a/frc-2021_Speed/src/main/include/commands/LimeLight/TurnLimeLightOff.h b/frc-2021_Speed/src/main/include/commands/LimeLight/TurnLimeLightOff.h deleted file mode 100644 index eab711f..0000000 --- a/frc-2021_Speed/src/main/include/commands/LimeLight/TurnLimeLightOff.h +++ /dev/null @@ -1,24 +0,0 @@ -/*----------------------------------------------------------------------------*/ -/* Copyright (c) 2019 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 -#include -#include "networktables/NetworkTableInstance.h" -class TurnLimeLightOff - : public frc2::CommandHelper { - public: - TurnLimeLightOff(){ - - } - - void Initialize() override{ - nt::NetworkTableInstance::GetDefault().GetTable("limelight")->PutNumber("ledMode",1); - } -}; diff --git a/frc-2021_Speed/src/main/include/commands/LimeLight/TurnLimeLightOn.h b/frc-2021_Speed/src/main/include/commands/LimeLight/TurnLimeLightOn.h deleted file mode 100644 index f2cd6ec..0000000 --- a/frc-2021_Speed/src/main/include/commands/LimeLight/TurnLimeLightOn.h +++ /dev/null @@ -1,22 +0,0 @@ -/*----------------------------------------------------------------------------*/ -/* Copyright (c) 2019 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 -#include -#include "networktables/NetworkTableInstance.h" -class TurnLimeLightOn - : public frc2::CommandHelper { - public: - TurnLimeLightOn(){} - - void Initialize() override{ - nt::NetworkTableInstance::GetDefault().GetTable("limelight")->PutNumber("ledMode",0); - } -}; diff --git a/frc-2021_Speed/src/main/include/commands/PathCommands/PathFollowerCommand.h b/frc-2021_Speed/src/main/include/commands/PathCommands/PathFollowerCommand.h new file mode 100644 index 0000000..a8ad3c6 --- /dev/null +++ b/frc-2021_Speed/src/main/include/commands/PathCommands/PathFollowerCommand.h @@ -0,0 +1,83 @@ +/*----------------------------------------------------------------------------*/ +/* Copyright (c) 2019 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 +#include +#include +#include +#include +#include +#include +#include +#include + +#include "subsystems/DriveSubsystem.h" +#include "Utils/SwerveDrivePathFollower.h" + +class PathFollowerCommand : public frc2::CommandHelper { + private: + SwerveDrivePathFollower m_pFollower; + DriveSubsystem* m_pDriveSubsystem; + std::ofstream m_File; + bool m_zero; + frc2::Timer m_timer; + std::string m_name; + double metersToInches = 39.3701; + bool m_stopAtEnd; + public: + PathFollowerCommand(DriveSubsystem* driveTrain, + std::vector &waypoints, const std::string &name, + bool zero = false, + bool stopAtEnd = true){ + m_pFollower.generatePath(waypoints, name); + m_pDriveSubsystem = driveTrain; + m_zero = zero; + m_name = name; + m_stopAtEnd = stopAtEnd; + AddRequirements(m_pDriveSubsystem); + } + + void Initialize() override{ + m_timer.Start(); + m_pFollower.start(); + if(m_zero){ + m_pDriveSubsystem->ResetOdometry(m_pFollower.getPointPos(0)); + } + } + + void Execute() override{ + + m_pFollower.Update(m_pDriveSubsystem->GetPose()); + frc::SmartDashboard::PutNumber("follow path command x", -m_pFollower.getFollowerPos().Translation().X().to()*metersToInches); + frc::SmartDashboard::PutNumber("follow path command y", -m_pFollower.getFollowerPos().Translation().Y().to()*metersToInches); + frc::SmartDashboard::PutNumber("actual x vel", m_pDriveSubsystem->GetRobotVelocity().vx.to()*metersToInches); + frc::SmartDashboard::PutNumber("actual y vel", m_pDriveSubsystem->GetRobotVelocity().vy.to()*metersToInches); + frc::SmartDashboard::PutNumber("x path vel", m_pFollower.getXVel()*metersToInches); + frc::SmartDashboard::PutNumber("y path vel", -m_pFollower.getYVel()*metersToInches); + m_pDriveSubsystem->Drive(units::meters_per_second_t(m_pFollower.getXVel()), + units::meters_per_second_t(m_pFollower.getYVel()), + units::degrees_per_second_t(m_pFollower.getYawRate()), + true, + false); + } + + void End(bool interrupted) override{ + if(m_stopAtEnd){ + m_pDriveSubsystem->stop(); + } + + printf("path follower time since Initialize %f\n", m_timer.Get().to()); + m_timer.Stop(); + } + + bool IsFinished() override{ + return m_pFollower.isPathFinished(); + } +}; + diff --git a/frc-2021_Speed/src/main/include/commands/PathCommands/PathFollowerCommand2.h b/frc-2021_Speed/src/main/include/commands/PathCommands/PathFollowerCommand2.h new file mode 100644 index 0000000..62c7681 --- /dev/null +++ b/frc-2021_Speed/src/main/include/commands/PathCommands/PathFollowerCommand2.h @@ -0,0 +1,83 @@ +/*----------------------------------------------------------------------------*/ +/* Copyright (c) 2019 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 +#include +#include +#include +#include +#include +#include +#include +#include + +#include "subsystems/DriveSubsystem.h" +#include "Utils/SwerveDrivePathFollower.h" + +class PathFollowerCommand2 : public frc2::CommandHelper { + private: + SwerveDrivePathFollower* m_pFollower; + DriveSubsystem* m_pDriveSubsystem; + std::ofstream m_File; + bool m_zero; + frc2::Timer m_timer; + std::string m_name; + double metersToInches = 39.3701; + bool m_stopAtEnd; + public: + PathFollowerCommand2(DriveSubsystem* driveTrain, + SwerveDrivePathFollower* follower, const std::string &name, + bool zero = false, + bool stopAtEnd = true){ + m_pFollower = follower; + m_pDriveSubsystem = driveTrain; + m_zero = zero; + m_name = name; + m_stopAtEnd = stopAtEnd; + AddRequirements(m_pDriveSubsystem); + } + + void Initialize() override{ + m_timer.Start(); + m_pFollower->start(); + if(m_zero){ + m_pDriveSubsystem->ResetOdometry(m_pFollower->getPointPos(0)); + } + } + + void Execute() override{ + + m_pFollower->Update(m_pDriveSubsystem->GetPose()); + frc::SmartDashboard::PutNumber("follow path command x", m_pFollower->getFollowerPos().Translation().X().to()*metersToInches); + frc::SmartDashboard::PutNumber("follow path command y", m_pFollower->getFollowerPos().Translation().Y().to()*metersToInches); + frc::SmartDashboard::PutNumber("actual x vel", m_pDriveSubsystem->GetRobotVelocity().vx.to()*metersToInches); + frc::SmartDashboard::PutNumber("actual y vel", m_pDriveSubsystem->GetRobotVelocity().vy.to()*metersToInches); + frc::SmartDashboard::PutNumber("x path vel", m_pFollower->getXVel()*metersToInches); + frc::SmartDashboard::PutNumber("y path vel", m_pFollower->getYVel()*metersToInches); + m_pDriveSubsystem->Drive(units::meters_per_second_t(m_pFollower->getXVel()), + units::meters_per_second_t(m_pFollower->getYVel()), + units::degrees_per_second_t(m_pFollower->getYawRate()), + true, + false); + } + + void End(bool interrupted) override{ + if(m_stopAtEnd){ + m_pDriveSubsystem->stop(); + } + frc::SmartDashboard::PutNumber("time since initialize", m_timer.Get().to()); + printf("path follower time since Initialize %f\n", m_timer.Get().to()); + m_timer.Stop(); + } + + bool IsFinished() override{ + return m_pFollower->isPathFinished(); + } +}; + diff --git a/frc-2021_Speed/src/main/include/components/ComboJoystickButton.h b/frc-2021_Speed/src/main/include/components/ComboJoystickButton.h deleted file mode 100644 index 15d8e5c..0000000 --- a/frc-2021_Speed/src/main/include/components/ComboJoystickButton.h +++ /dev/null @@ -1,18 +0,0 @@ -// #ifndef COMBO_JOYSTICK_BUTTON_H -// #define COMBO_JOYSTICK_BUTTON_H - -// #include -// class ComboJoystickButton : public frc2::Button { -// public: -// ComboJoystickButton(frc2::Button *primaryButton, frc2::Button *secondaryButton, bool secondaryPressed); -// virtual ~ComboJoystickButton(); - -// virtual bool Get(); - -// private: -// frc2::Button *m_pPrimaryButton; -// frc2::Button *m_pSecondaryButton; -// bool m_secondaryPressed; -// }; - -// #endif // COMBO_JOYSTICK_BUTTON_H diff --git a/frc-2021_Speed/src/main/include/components/CommonMotorController.h b/frc-2021_Speed/src/main/include/components/CommonMotorController.h index 717f0d5..6b31715 100644 --- a/frc-2021_Speed/src/main/include/components/CommonMotorController.h +++ b/frc-2021_Speed/src/main/include/components/CommonMotorController.h @@ -5,7 +5,6 @@ /* the project. */ /*----------------------------------------------------------------------------*/ #include -#include #include "Constants.h" #pragma once @@ -53,10 +52,7 @@ class CommonMotorController { virtual void ConfigMaxIntegralAccumulator(int slotIdx, double iaccum, int timeoutMs = 0){ printf("Warning: %s is calling ConfigMaxIntegralAccumulator() which is not implemented\n", m_name.c_str()); } - virtual void SetNeutralMode(NeutralMode neutralMode){ - printf("Warning: %s is calling SetNeutralMode() which is not implemented\n", m_name.c_str()); - } - virtual void SetNeutralMode(rev::CANSparkMax::IdleMode mode){ + virtual void SetNeutralMode(CommonDrive mode){ printf("Warning: %s is calling SetNeutralMode() which is not implemented\n", m_name.c_str()); } virtual void EnableVoltageCompensation(bool enable){ @@ -128,4 +124,8 @@ class CommonMotorController { printf("Warning: %s is calling GetPos() which is not implemented\n", m_name.c_str()); return 0.0; } + virtual double GetCurrentOutput(){ + printf("Warning: %s is calling GetCurrentOutput() which is not implemented\n", m_name.c_str()); + return 0.0; + } }; diff --git a/frc-2021_Speed/src/main/include/components/SparkMaxMotorController.h b/frc-2021_Speed/src/main/include/components/SparkMaxMotorController.h index fec5fbb..b85c905 100644 --- a/frc-2021_Speed/src/main/include/components/SparkMaxMotorController.h +++ b/frc-2021_Speed/src/main/include/components/SparkMaxMotorController.h @@ -5,6 +5,7 @@ /* the project. */ /*----------------------------------------------------------------------------*/ #include "components/CommonMotorController.h" +#include #pragma once @@ -13,6 +14,7 @@ class SparkMaxMotorController : public CommonMotorController{ rev::CANSparkMax* m_pMotor; double m_setpoint = 0.0; rev::ControlType m_pCurrentMode; + rev::CANSparkMax::IdleMode m_pCurrentDriveMode; public: SparkMaxMotorController(int motorID, const std::string &name, rev::CANSparkMax::MotorType type); void Config_kF(int slotIdx, double value, int timeoutMs = 0); @@ -33,7 +35,9 @@ class SparkMaxMotorController : public CommonMotorController{ void SetVelocityConversionFactor(double factor); double GetClosedLoopError(); bool CommonModesToControlType(CommonModes mode, rev::ControlType &retMode); - void SetNeutralMode(rev::CANSparkMax::IdleMode mode); + bool CommonDriveToControlType(CommonDrive mode, rev::CANSparkMax::IdleMode &retMode); + void SetNeutralMode(CommonDrive mode); double GetPos(); + double GetCurrentOutput(); }; diff --git a/frc-2021_Speed/src/main/include/components/TalonFXMotorController.h b/frc-2021_Speed/src/main/include/components/TalonFXMotorController.h index 4b50551..9eb6c71 100644 --- a/frc-2021_Speed/src/main/include/components/TalonFXMotorController.h +++ b/frc-2021_Speed/src/main/include/components/TalonFXMotorController.h @@ -22,7 +22,7 @@ class TalonFXMotorController : public CommonMotorController { void Config_kD(int slotIdx, double value, int timeoutMs = 0); void Config_IntegralZone(int slotIdx, int izone, int timeoutMs = 0); void ConfigMaxIntegralAccumulator(int slotIdx, double iaccum, int timeoutMs = 0); - void SetNeutralMode(NeutralMode neutralMode); + void SetNeutralMode(CommonDrive neutralMode); void EnableVoltageCompensation(bool enable); void ConfigVoltageCompSaturation(double voltage, int timeoutMs = 0); void ConfigNeutralDeadband(double percentDeadband, int timeoutMs = 0); @@ -44,10 +44,11 @@ class TalonFXMotorController : public CommonMotorController { void SetEncoderPosition(double pos); void SetVelocityConversionFactor(double factor); double GetClosedLoopError(); + double GetCurrentOutput(); ControlMode FalconModeToCommonMode(CommonModes mode); + NeutralMode CommonDriveToControlType(CommonDrive mode); TalonFX* GetBase(); void Follow(TalonFX* motor); - // void SetNeutralMode(ctre::phoenix::motorcontrol::NeutralMode mode); private: TalonFX* m_pMotor; double m_factor = 1; diff --git a/frc-2021_Speed/src/main/include/components/TalonSRXMotorController.h b/frc-2021_Speed/src/main/include/components/TalonSRXMotorController.h index 60415f8..0c0fa93 100644 --- a/frc-2021_Speed/src/main/include/components/TalonSRXMotorController.h +++ b/frc-2021_Speed/src/main/include/components/TalonSRXMotorController.h @@ -23,7 +23,7 @@ class TalonSRXMotorController : public CommonMotorController { void Config_kD(int slotIdx, double value, int timeoutMs = 0); void Config_IntegralZone(int slotIdx, int izone, int timeoutMs = 0); void ConfigMaxIntegralAccumulator(int slotIdx, double iaccum, int timeoutMs = 0); - void SetNeutralMode(NeutralMode neutralMode); + void SetNeutralMode(CommonDrive neutralMode); void EnableVoltageCompensation(bool enable); void ConfigVoltageCompSaturation(double voltage, int timeoutMs = 0); void ConfigNeutralDeadband(double percentDeadband, int timeoutMs = 0); @@ -44,7 +44,9 @@ class TalonSRXMotorController : public CommonMotorController { void SetEncoderPosition(double pos); void SetVelocityConversionFactor(double factor); double GetClosedLoopError(); + double GetCurrentOutput(); ControlMode CommonModeToControllMode(CommonModes mode); + NeutralMode CommonDriveToControlType(CommonDrive mode); private: TalonSRX* m_pMotor; double m_factor = 1.0; diff --git a/frc-2021_Speed/src/main/include/components/VictorMotorController.h b/frc-2021_Speed/src/main/include/components/VictorMotorController.h index 13f7275..516a92c 100644 --- a/frc-2021_Speed/src/main/include/components/VictorMotorController.h +++ b/frc-2021_Speed/src/main/include/components/VictorMotorController.h @@ -42,6 +42,7 @@ class VictorMotorController : public CommonMotorController { void SetEncoderPosition(double pos); void SetVelocityConversionFactor(double factor); double GetClosedLoopError(); + ControlMode CommonModeToControllMode(CommonModes mode); private: VictorSPX* m_pMotor; diff --git a/frc-2021_Speed/src/main/include/subsystems/DriveSubsystem.h b/frc-2021_Speed/src/main/include/subsystems/DriveSubsystem.h index 1d0b60e..80b1f9c 100644 --- a/frc-2021_Speed/src/main/include/subsystems/DriveSubsystem.h +++ b/frc-2021_Speed/src/main/include/subsystems/DriveSubsystem.h @@ -25,6 +25,7 @@ #include "Utils/PoseDot2D.h" #include #include +#include class DriveSubsystem : public frc2::SubsystemBase { public: DriveSubsystem(); @@ -99,16 +100,17 @@ class DriveSubsystem : public frc2::SubsystemBase { void toggleFieldCentricForJoystick(); bool getFiedCentricForJoystick(); -void setCoast(); -void setBrake(); -frc::SwerveModuleState getFrontRightMotor(); -frc::SwerveModuleState getFrontLeftMotor(); -frc::SwerveModuleState getBackRightMotor(); -frc::SwerveModuleState getBackLeftMotor(); -void tuneDrivePID(double p, double i, double d, double f); -void tuneSteerPID(double p, double i, double d); -void stop(); -frc::ChassisSpeeds GetRobotVelocity(); + void setCoast(); + void setBrake(); + frc::SwerveModuleState getFrontRightMotor(); + frc::SwerveModuleState getFrontLeftMotor(); + frc::SwerveModuleState getBackRightMotor(); + frc::SwerveModuleState getBackLeftMotor(); + void tuneDrivePID(double p, double i, double d, double f); + void tuneSteerPID(double p, double i, double d); + void stop(); + void resetDriveEncoders(); + frc::ChassisSpeeds GetRobotVelocity(); units::meter_t kTrackWidth = units::meter_t(RobotParameters::k_wheelTrack); // Distance between centers of right and left wheels on robot @@ -125,9 +127,9 @@ frc::ChassisSpeeds GetRobotVelocity(); // Components (e.g. motor controllers and sensors) should generally be // declared private and exposed only through public methods. SwerveModule m_frontLeft; - SwerveModule m_rearLeft; + SwerveModule m_backLeft; SwerveModule m_frontRight; - SwerveModule m_rearRight; + SwerveModule m_backRight; // The gyro sensor // frc::ADXRS450_Gyro m_gyro; @@ -137,6 +139,8 @@ frc::ChassisSpeeds GetRobotVelocity(); frc::SwerveDriveOdometry<4> m_odometry; AHRS m_pChassisIMU; bool m_fieldCentricForJoystick = false; - - std::ofstream m_File; + double metersToInches = 39.3701; + double cycle = 0; + std::ofstream m_File; + frc::Field2d m_pField; }; diff --git a/frc-2021_Speed/src/main/include/subsystems/IntakeSubsystem.h b/frc-2021_Speed/src/main/include/subsystems/IntakeSubsystem.h index 48eb591..fd6dd53 100644 --- a/frc-2021_Speed/src/main/include/subsystems/IntakeSubsystem.h +++ b/frc-2021_Speed/src/main/include/subsystems/IntakeSubsystem.h @@ -1,5 +1,4 @@ - //TODO: Pulled from 2020, still needs dual-intake compatability but CAD hasn't figured out how that needs to be done yet. -Sean H. - //TODO Copied this from 2020 because intake supposedly similar, INCOMPLETE. -Sean H. + #pragma once @@ -7,9 +6,9 @@ #include #include -#include "components/VictorMotorController.h" -#include - +#include "components/TalonSRXMotorController.h" +// #include +#include class IntakeSubsystem : public frc2::SubsystemBase { public: @@ -18,17 +17,20 @@ class IntakeSubsystem : public frc2::SubsystemBase { * Will be called periodically whenever the CommandScheduler runs. */ void Periodic() override; - void setLeftSpeed(double speed); - void setRightSpeed(double speed); - double getLeftSpeed(); - double getRightSpeed(); - double getBeamBreak(); + void setBIntakeSpeed(double speed); + void setAIntakeSpeed(double speed); + void setAIntakeCurrent(double current); + void setBIntakeCurrent(double current); + double getIntakeACurrent(); + double getIntakeBCurrent(); + + double getBIntakeSpeed(); + double getAIntakeSpeed(); + double getServoAngle(); + void setServoAngle(double angle); private: - double leftSpeed; - double rightSpeed; - frc::DigitalInput* m_beamBreak; - VictorMotorController* m_rightMotor; - VictorMotorController* m_leftMotor; - + TalonSRXMotorController* m_aIntakeMotor; + TalonSRXMotorController* m_bIntakeMotor; + frc::Servo* m_servo; }; diff --git a/frc-2021_Speed/src/main/include/subsystems/SwerveModule.h b/frc-2021_Speed/src/main/include/subsystems/SwerveModule.h index 72fa302..ba0f8fb 100644 --- a/frc-2021_Speed/src/main/include/subsystems/SwerveModule.h +++ b/frc-2021_Speed/src/main/include/subsystems/SwerveModule.h @@ -8,9 +8,8 @@ #pragma once #include -#include #include -#include +// #include #include #include #include @@ -25,7 +24,6 @@ #include "components/CommonMotorController.h" #include "components/TalonSRXMotorController.h" #include "components/TalonFXMotorController.h" -#include "components/SparkMaxMotorController.h" class SwerveModule { using radians_per_second_squared_t = @@ -46,6 +44,8 @@ class SwerveModule { void setCoast(); void setBrake(); void DriveArc(double arcLength, double wheelAngle); + double getDriveEncoder(); + void resetDriveEncoder(); private: // We have to use meters here instead of radians due to the fact that // ProfiledPIDController's constraints only take in meters per second and diff --git a/frc-2021_Speed/vendordeps/navx_frc.json b/frc-2021_Speed/vendordeps/navx_frc.json index 907bc7f..85154b3 100644 --- a/frc-2021_Speed/vendordeps/navx_frc.json +++ b/frc-2021_Speed/vendordeps/navx_frc.json @@ -1,7 +1,7 @@ { "fileName": "navx_frc.json", "name": "KauaiLabs_navX_FRC", - "version": "4.0.414", + "version": "4.0.416", "uuid": "cb311d09-36e9-4143-a032-55bb2b94443b", "mavenUrls": [ "https://repo1.maven.org/maven2/" @@ -11,7 +11,7 @@ { "groupId": "com.kauailabs.navx.frc", "artifactId": "navx-java", - "version": "4.0.414" + "version": "4.0.416" } ], "jniDependencies": [], @@ -19,7 +19,7 @@ { "groupId": "com.kauailabs.navx.frc", "artifactId": "navx-cpp", - "version": "4.0.414", + "version": "4.0.416", "headerClassifier": "headers", "sourcesClassifier": "sources", "sharedLibrary": false,