diff --git a/src/main/cpp/AutoAimer.cpp b/src/main/cpp/AutoAimer.cpp index 259af3e..1bdd917 100644 --- a/src/main/cpp/AutoAimer.cpp +++ b/src/main/cpp/AutoAimer.cpp @@ -3,11 +3,12 @@ #include AutoAimer::AutoAimer() + { m_lookup.emplace_back(VisionSetPoint{59.34, 50.0, 75.0, -51.9}); m_lookup.emplace_back(VisionSetPoint{107.4769, 30, 130.0, -89.5}); - m_lookup.emplace_back(VisionSetPoint{155.16, 22.3, 175.0, -104.5}); - m_lookup.emplace_back(VisionSetPoint{172.71, 21.2, 205.3, -104.7}); + m_lookup.emplace_back(VisionSetPoint{155.16, 21.3, 130.0, -89.5}); + m_lookup.emplace_back(VisionSetPoint{172.71, 20.25, 130.3, -89.5}); m_lookup.emplace_back(VisionSetPoint{200.58, 20.5, 250, -106.5}); diff --git a/src/main/cpp/ControllerInterface.cpp b/src/main/cpp/ControllerInterface.cpp index 07e4a5f..0b61809 100644 --- a/src/main/cpp/ControllerInterface.cpp +++ b/src/main/cpp/ControllerInterface.cpp @@ -36,6 +36,7 @@ void ControllerInterface::UpdateLauncherInput(RobotControlData &controlData) controlData.launcherInput.goToStowPos = m_copilot.GetAButton(); controlData.launcherInput.goToSubPos = m_copilot.GetYButton(); controlData.launcherInput.runIndexerBackward = m_copilot.GetLeftTriggerAxis() >= 0.2; + controlData.launcherInput.goToHoardePos = m_copilot.GetBButton(); // controlData.launcherInput.runIndexerForward = m_copilot.GetRightTriggerAxis() >= 0.2; //controlData.launcherInput.runIndexerForward = m_copilot.GetXButton(); //controlData.launcherInput.runIndexerBackward = m_copilot.GetBButton(); diff --git a/src/main/cpp/Robot.cpp b/src/main/cpp/Robot.cpp index db5f247..2aef479 100644 --- a/src/main/cpp/Robot.cpp +++ b/src/main/cpp/Robot.cpp @@ -55,6 +55,10 @@ void Robot::RobotInit() { SwerveInit(); + frc::CameraServer::StartAutomaticCapture(); + + // m_cvSink = frc::CameraServer::GetVideo(); + // m_cvSource = frc::CameraServer::PutVideo("Camera", 640, 480); } /** diff --git a/src/main/cpp/commands/SmartIntakeCommand.cpp b/src/main/cpp/commands/SmartIntakeCommand.cpp index ee0be44..c711bcb 100644 --- a/src/main/cpp/commands/SmartIntakeCommand.cpp +++ b/src/main/cpp/commands/SmartIntakeCommand.cpp @@ -8,7 +8,11 @@ SmartIntakeCommand::SmartIntakeCommand(RobotControlData &controlData) void SmartIntakeCommand::Initialize() { - m_controlData.smartIntakeInput.smartIntake = true; + if (!m_controlData.smartIntakeOutput.smartIntakeFlag) + { + m_controlData.smartIntakeInput.smartIntake = true; + } + m_state = 0; } diff --git a/src/main/cpp/subsystems/LauncherHAL.cpp b/src/main/cpp/subsystems/LauncherHAL.cpp index a9f5388..34ffc99 100644 --- a/src/main/cpp/subsystems/LauncherHAL.cpp +++ b/src/main/cpp/subsystems/LauncherHAL.cpp @@ -134,7 +134,18 @@ LauncherHAL::LauncherHAL() m_FlywheelBottom.SetControl(m_FlywheelTopFollower); m_FlywheelTop.GetConfigurator().Apply(configs); - m_FlywheelBottom.GetConfigurator().Apply(configs); + + { + bool successful = false; + int retries = 0; + + while (!successful || retries <= 10) + { + retries++; + auto status = m_FlywheelBottom.GetConfigurator().Apply(configs); + successful = status == ctre::phoenix::StatusCode::OK; + } + } m_currentAngle = -100.0; } @@ -175,6 +186,7 @@ void LauncherHAL::SetIndexerSpeed(double speed) m_IndMotor.Set(m_indexerSpeed); } + void LauncherHAL::SetAngle(double angle) { if (angle > MAX_PIVOT_ANGLE) @@ -191,19 +203,15 @@ void LauncherHAL::SetAngle(double angle) void LauncherHAL::ProfiledMoveToAngle(double angle) { - if (std::fabs(m_currentAngle - angle) >= 1e-8) - { - m_profileState = 0; - m_currentAngle = angle; - } - switch(m_profileState) { case 0: { m_ProfileStartPos = GetAngle(); - m_Timer.Restart(); + m_Timer.Stop(); + m_Timer.Reset(); + m_Timer.Start(); m_profileState++; @@ -259,5 +267,5 @@ double LauncherHAL::GetFlywheelSpeed() void LauncherHAL::ResetProfiledMoveState() { - // m_profileState = 0; + m_profileState = 0; } \ No newline at end of file diff --git a/src/main/cpp/subsystems/SmartIntake.cpp b/src/main/cpp/subsystems/SmartIntake.cpp index 2cbc9f9..de54224 100644 --- a/src/main/cpp/subsystems/SmartIntake.cpp +++ b/src/main/cpp/subsystems/SmartIntake.cpp @@ -211,7 +211,7 @@ void SmartIntake::HandleInput(RobotControlData& input){ } case 3: { - if (m_timer.Get() > units::second_t(0.035)) + if (m_timer.Get() > units::second_t(0.025)) { m_SmartOutTakeFlag = false; m_OutTakeState = 0; @@ -255,4 +255,6 @@ void SmartIntake::HandleInput(RobotControlData& input){ m_prevSmartIntake = input.smartIntakeInput.smartIntake; m_prevSmartOutTake = input.smartIntakeInput.smartOutTake; m_prevSwitchMode = input.smartIntakeInput.switchMode; + input.smartIntakeOutput.smartIntakeFlag = m_SmartIntakeFlag; + input.smartIntakeOutput.smartOuttakeFlag = m_SmartOutTakeFlag; } diff --git a/src/main/cpp/subsystems/subsystemManagers/IntakeManager.cpp b/src/main/cpp/subsystems/subsystemManagers/IntakeManager.cpp index 30e95a4..763c968 100644 --- a/src/main/cpp/subsystems/subsystemManagers/IntakeManager.cpp +++ b/src/main/cpp/subsystems/subsystemManagers/IntakeManager.cpp @@ -2,8 +2,9 @@ namespace { - const double NORMAL_INTAKE_SPEED = 0.80; - const double AMP_POS = 19.361; + const double NORMAL_INTAKE_SPEED = 0.95; + const double OUTAKE_SPEED = 0.7; + const double AMP_POS = 25.361; const double GROUND_POS = 129.000; const double STOW_POS = 68.144; const double PSEUDO_STOW_POS = 104.671; @@ -23,7 +24,7 @@ void IntakeManager::HandleInput(IntakeInput &input, IntakeOutput &output) { if (input.runIntakeOutSlow) { - m_intake.RunIntake(-0.1); + m_intake.RunIntake(-0.15); } else if (input.runIntakeIn && !input.runIntakeOut) { @@ -31,7 +32,7 @@ void IntakeManager::HandleInput(IntakeInput &input, IntakeOutput &output) } else if (input.runIntakeOut && !input.runIntakeIn) { - m_intake.RunIntake(-NORMAL_INTAKE_SPEED); + m_intake.RunIntake(-OUTAKE_SPEED); } else { diff --git a/src/main/cpp/subsystems/subsystemManagers/LauncherManager.cpp b/src/main/cpp/subsystems/subsystemManagers/LauncherManager.cpp index 121fe21..8887d7c 100644 --- a/src/main/cpp/subsystems/subsystemManagers/LauncherManager.cpp +++ b/src/main/cpp/subsystems/subsystemManagers/LauncherManager.cpp @@ -5,6 +5,7 @@ void LauncherManager::ResetLauncher() { m_goToStowPos = false; m_goToSubPos = false; + m_goToHoardePos = false; m_visionResetProfiledMoveState = false; } @@ -19,6 +20,7 @@ void LauncherManager::HandleInput(LauncherInput &launcherInput, LauncherOutput & m_visionResetProfiledMoveState = true; m_goToStowPos = false; m_goToSubPos = false; + m_goToHoardePos = false; } m_launcher.SetFlywheelSpeed(launcherInput.visionSpeedSetpoint); @@ -37,13 +39,23 @@ void LauncherManager::HandleInput(LauncherInput &launcherInput, LauncherOutput & if(launcherInput.goToStowPos){ m_goToStowPos = true; m_goToSubPos = false; + m_goToHoardePos = false; m_launcher.ResetProfiledMoveState(); } else if (launcherInput.goToSubPos) { m_goToStowPos = false; m_goToSubPos = true; + m_goToHoardePos = false; m_launcher.ResetProfiledMoveState(); + } else if (launcherInput.goToHoardePos) { + + m_goToHoardePos = true; + m_goToStowPos = false; + m_goToSubPos = false; + + m_launcher.ResetProfiledMoveState(); + } if (m_goToStowPos) @@ -64,6 +76,12 @@ void LauncherManager::HandleInput(LauncherInput &launcherInput, LauncherOutput & m_launcher.ProfiledMoveToAngle(SUB_ANGLE); m_launcher.SetFlywheelSpeed(SUB_SPEED); } + if (m_goToHoardePos) { + + m_launcher.ProfiledMoveToAngle(HOARDE_ANG); + m_launcher.SetFlywheelSpeed(HOARDE_SPD); + + } } if (launcherInput.runIndexerBackwardSlow) diff --git a/src/main/deploy/pathplanner/autos/BLUE_Top_4_Piece.auto b/src/main/deploy/pathplanner/autos/BLUE_Top_4_Piece.auto index b19e91b..18bc76a 100644 --- a/src/main/deploy/pathplanner/autos/BLUE_Top_4_Piece.auto +++ b/src/main/deploy/pathplanner/autos/BLUE_Top_4_Piece.auto @@ -36,6 +36,12 @@ "pathName": "BLUE_3_Piece_Path_1" } }, + { + "type": "wait", + "data": { + "waitTime": 0.5 + } + }, { "type": "named", "data": { diff --git a/src/main/deploy/pathplanner/autos/Red_Bottom_4_Piece.auto b/src/main/deploy/pathplanner/autos/Red_Bottom_4_Piece.auto index bb2b78c..9eaf0f7 100644 --- a/src/main/deploy/pathplanner/autos/Red_Bottom_4_Piece.auto +++ b/src/main/deploy/pathplanner/autos/Red_Bottom_4_Piece.auto @@ -11,6 +11,25 @@ "type": "sequential", "data": { "commands": [ + { + "type": "parallel", + "data": { + "commands": [ + { + "type": "named", + "data": { + "name": "IntakeDown" + } + }, + { + "type": "named", + "data": { + "name": "SubShoot" + } + } + ] + } + }, { "type": "path", "data": { @@ -23,6 +42,12 @@ "pathName": "RED_Path5" } }, + { + "type": "named", + "data": { + "name": "VisionShoot" + } + }, { "type": "path", "data": { @@ -34,6 +59,12 @@ "data": { "pathName": "RED_Path3" } + }, + { + "type": "named", + "data": { + "name": "VisionShoot" + } } ] } diff --git a/src/main/deploy/pathplanner/autos/Red_Top_4_Piece.auto b/src/main/deploy/pathplanner/autos/Red_Top_4_Piece.auto index 851ccc5..183faa3 100644 --- a/src/main/deploy/pathplanner/autos/Red_Top_4_Piece.auto +++ b/src/main/deploy/pathplanner/autos/Red_Top_4_Piece.auto @@ -11,12 +11,43 @@ "type": "sequential", "data": { "commands": [ + { + "type": "parallel", + "data": { + "commands": [ + { + "type": "named", + "data": { + "name": "IntakeDown" + } + }, + { + "type": "named", + "data": { + "name": "SubShoot" + } + } + ] + } + }, { "type": "path", "data": { "pathName": "RED_3_Piece_Path_1" } }, + { + "type": "wait", + "data": { + "waitTime": 0.5 + } + }, + { + "type": "named", + "data": { + "name": "VisionShoot" + } + }, { "type": "path", "data": { @@ -29,6 +60,12 @@ "pathName": "RED_3_Piece_Path_3" } }, + { + "type": "named", + "data": { + "name": "VisionShoot" + } + }, { "type": "path", "data": { @@ -40,6 +77,12 @@ "data": { "pathName": "RED_3_Piece_Path_5" } + }, + { + "type": "named", + "data": { + "name": "VisionShoot" + } } ] } diff --git a/src/main/deploy/pathplanner/paths/BLUE_3_Piece_Path_1.path b/src/main/deploy/pathplanner/paths/BLUE_3_Piece_Path_1.path index 634ef46..f61e3ee 100644 --- a/src/main/deploy/pathplanner/paths/BLUE_3_Piece_Path_1.path +++ b/src/main/deploy/pathplanner/paths/BLUE_3_Piece_Path_1.path @@ -33,7 +33,7 @@ "eventMarkers": [ { "name": "SmartIntakeCommand", - "waypointRelativePos": 0, + "waypointRelativePos": 0.05, "command": { "type": "parallel", "data": { @@ -58,7 +58,7 @@ "goalEndState": { "velocity": 0, "rotation": 25.0, - "rotateFast": false + "rotateFast": true }, "reversed": false, "folder": "BLUEPATH", diff --git a/src/main/deploy/pathplanner/paths/BLUE_3_Piece_Path_2.path b/src/main/deploy/pathplanner/paths/BLUE_3_Piece_Path_2.path index 87aedc7..7ed1b3e 100644 --- a/src/main/deploy/pathplanner/paths/BLUE_3_Piece_Path_2.path +++ b/src/main/deploy/pathplanner/paths/BLUE_3_Piece_Path_2.path @@ -32,8 +32,8 @@ "constraintZones": [], "eventMarkers": [ { - "name": "New Event Marker", - "waypointRelativePos": 0.45, + "name": "SmartIntake", + "waypointRelativePos": 0.05, "command": { "type": "parallel", "data": { diff --git a/src/main/deploy/pathplanner/paths/BLUE_3_Piece_Path_4.path b/src/main/deploy/pathplanner/paths/BLUE_3_Piece_Path_4.path index be06b8b..5c3f32d 100644 --- a/src/main/deploy/pathplanner/paths/BLUE_3_Piece_Path_4.path +++ b/src/main/deploy/pathplanner/paths/BLUE_3_Piece_Path_4.path @@ -48,8 +48,8 @@ "constraintZones": [], "eventMarkers": [ { - "name": "New Event Marker", - "waypointRelativePos": 0.35, + "name": "SmartIntake", + "waypointRelativePos": 0.05, "command": { "type": "parallel", "data": { @@ -57,7 +57,7 @@ { "type": "named", "data": { - "name": "VisionShoot" + "name": "SmartIntakeCommand" } } ] diff --git a/src/main/deploy/pathplanner/paths/BLUE_BottomNote_Note5.path b/src/main/deploy/pathplanner/paths/BLUE_BottomNote_Note5.path index 1b79ac3..7712452 100644 --- a/src/main/deploy/pathplanner/paths/BLUE_BottomNote_Note5.path +++ b/src/main/deploy/pathplanner/paths/BLUE_BottomNote_Note5.path @@ -33,7 +33,7 @@ "eventMarkers": [ { "name": "Intake", - "waypointRelativePos": 0.5, + "waypointRelativePos": 0.05, "command": { "type": "parallel", "data": { diff --git a/src/main/deploy/pathplanner/paths/BLUE_Note5_Shoot.path b/src/main/deploy/pathplanner/paths/BLUE_Note5_Shoot.path index 6658e4a..9be2603 100644 --- a/src/main/deploy/pathplanner/paths/BLUE_Note5_Shoot.path +++ b/src/main/deploy/pathplanner/paths/BLUE_Note5_Shoot.path @@ -16,12 +16,12 @@ }, { "anchor": { - "x": 2.8078366589303156, - "y": 3.0288752689464666 + "x": 2.1289508227871425, + "y": 3.8435382723182747 }, "prevControl": { - "x": 4.656495012735573, - "y": 1.5562152243897376 + "x": 3.9776091765924, + "y": 2.3708782277615454 }, "nextControl": null, "isLocked": false, diff --git a/src/main/deploy/pathplanner/paths/BLUE_Path1.path b/src/main/deploy/pathplanner/paths/BLUE_Path1.path index a349e5b..74af509 100644 --- a/src/main/deploy/pathplanner/paths/BLUE_Path1.path +++ b/src/main/deploy/pathplanner/paths/BLUE_Path1.path @@ -32,12 +32,12 @@ }, { "anchor": { - "x": 7.9882578085766855, - "y": 2.5170997924693057 + "x": 7.998702206055811, + "y": 2.767765331968324 }, "prevControl": { - "x": 7.1735948052048775, - "y": 2.5170997924693057 + "x": 7.184039202684003, + "y": 2.767765331968324 }, "nextControl": null, "isLocked": false, @@ -48,8 +48,8 @@ "constraintZones": [], "eventMarkers": [ { - "name": "New Event Marker", - "waypointRelativePos": 0.95, + "name": "SmartIntake", + "waypointRelativePos": 0.05, "command": { "type": "sequential", "data": { diff --git a/src/main/deploy/pathplanner/paths/BLUE_Path2.path b/src/main/deploy/pathplanner/paths/BLUE_Path2.path index 59dc8df..e03cebe 100644 --- a/src/main/deploy/pathplanner/paths/BLUE_Path2.path +++ b/src/main/deploy/pathplanner/paths/BLUE_Path2.path @@ -3,13 +3,13 @@ "waypoints": [ { "anchor": { - "x": 2.8078366589303156, - "y": 3.0288752689464666 + "x": 2.1289508227871425, + "y": 3.8435382723182747 }, "prevControl": null, "nextControl": { - "x": 4.572939832902567, - "y": 2.078435098346024 + "x": 3.894053996759394, + "y": 2.893098101717832 }, "isLocked": false, "linkedName": "BottomShootPos" @@ -32,8 +32,8 @@ "constraintZones": [], "eventMarkers": [ { - "name": "New Event Marker", - "waypointRelativePos": 0.25, + "name": "SmartIntake", + "waypointRelativePos": 0.05, "command": { "type": "parallel", "data": { diff --git a/src/main/deploy/pathplanner/paths/BLUE_Path3.path b/src/main/deploy/pathplanner/paths/BLUE_Path3.path index a118a15..251ee55 100644 --- a/src/main/deploy/pathplanner/paths/BLUE_Path3.path +++ b/src/main/deploy/pathplanner/paths/BLUE_Path3.path @@ -32,12 +32,12 @@ }, { "anchor": { - "x": 2.8078366589303156, - "y": 3.0288752689464666 + "x": 2.1289508227871425, + "y": 3.8435382723182747 }, "prevControl": { - "x": 4.499829050548687, - "y": 2.1515458806999037 + "x": 3.820943214405514, + "y": 2.966208884071712 }, "nextControl": null, "isLocked": false, diff --git a/src/main/deploy/pathplanner/paths/BLUE_Path4.path b/src/main/deploy/pathplanner/paths/BLUE_Path4.path index d1c59a7..806835a 100644 --- a/src/main/deploy/pathplanner/paths/BLUE_Path4.path +++ b/src/main/deploy/pathplanner/paths/BLUE_Path4.path @@ -32,12 +32,12 @@ }, { "anchor": { - "x": 7.9882578085766855, - "y": 2.5170997924693057 + "x": 7.998702206055811, + "y": 2.767765331968324 }, "prevControl": { - "x": 6.442486981666077, - "y": 2.5484329849066834 + "x": 6.452931379145203, + "y": 2.799098524405702 }, "nextControl": null, "isLocked": false, diff --git a/src/main/deploy/pathplanner/paths/BLUE_Path5.path b/src/main/deploy/pathplanner/paths/BLUE_Path5.path index ddadb7d..07b2cc9 100644 --- a/src/main/deploy/pathplanner/paths/BLUE_Path5.path +++ b/src/main/deploy/pathplanner/paths/BLUE_Path5.path @@ -3,13 +3,13 @@ "waypoints": [ { "anchor": { - "x": 7.9882578085766855, - "y": 2.5170997924693057 + "x": 7.998702206055811, + "y": 2.767765331968324 }, "prevControl": null, "nextControl": { - "x": 6.223154634604435, - "y": 2.454433407594551 + "x": 6.233599032083561, + "y": 2.7050989470935694 }, "isLocked": false, "linkedName": "Note4" @@ -32,12 +32,12 @@ }, { "anchor": { - "x": 2.8078366589303156, - "y": 3.0288752689464666 + "x": 2.1289508227871425, + "y": 3.8435382723182747 }, "prevControl": { - "x": 4.750494590047705, - "y": 1.4413268521193536 + "x": 4.071608753904531, + "y": 2.2559898554911615 }, "nextControl": null, "isLocked": false, diff --git a/src/main/deploy/pathplanner/paths/RED_3_Piece_Path_1.path b/src/main/deploy/pathplanner/paths/RED_3_Piece_Path_1.path index 483b8c7..5bb53a1 100644 --- a/src/main/deploy/pathplanner/paths/RED_3_Piece_Path_1.path +++ b/src/main/deploy/pathplanner/paths/RED_3_Piece_Path_1.path @@ -33,7 +33,7 @@ "eventMarkers": [ { "name": "SmartIntakeCommand", - "waypointRelativePos": 0, + "waypointRelativePos": 0.1, "command": { "type": "parallel", "data": { @@ -58,7 +58,7 @@ "goalEndState": { "velocity": 0, "rotation": 25.0, - "rotateFast": false + "rotateFast": true }, "reversed": false, "folder": "REDPATH", diff --git a/src/main/deploy/pathplanner/paths/RED_3_Piece_Path_2.path b/src/main/deploy/pathplanner/paths/RED_3_Piece_Path_2.path index 8e15b77..e4ac6e7 100644 --- a/src/main/deploy/pathplanner/paths/RED_3_Piece_Path_2.path +++ b/src/main/deploy/pathplanner/paths/RED_3_Piece_Path_2.path @@ -30,7 +30,25 @@ ], "rotationTargets": [], "constraintZones": [], - "eventMarkers": [], + "eventMarkers": [ + { + "name": "SmartIntake", + "waypointRelativePos": 0.1, + "command": { + "type": "parallel", + "data": { + "commands": [ + { + "type": "named", + "data": { + "name": "SmartIntakeCommand" + } + } + ] + } + } + } + ], "globalConstraints": { "maxVelocity": 3.0, "maxAcceleration": 3.0, diff --git a/src/main/deploy/pathplanner/paths/RED_3_Piece_Path_4.path b/src/main/deploy/pathplanner/paths/RED_3_Piece_Path_4.path index 1c700c4..b8d5a5f 100644 --- a/src/main/deploy/pathplanner/paths/RED_3_Piece_Path_4.path +++ b/src/main/deploy/pathplanner/paths/RED_3_Piece_Path_4.path @@ -46,7 +46,25 @@ ], "rotationTargets": [], "constraintZones": [], - "eventMarkers": [], + "eventMarkers": [ + { + "name": "SmartIntake", + "waypointRelativePos": 0.1, + "command": { + "type": "parallel", + "data": { + "commands": [ + { + "type": "named", + "data": { + "name": "SmartIntakeCommand" + } + } + ] + } + } + } + ], "globalConstraints": { "maxVelocity": 3.0, "maxAcceleration": 3.0, diff --git a/src/main/deploy/pathplanner/paths/RED_BottomNote_Note5.path b/src/main/deploy/pathplanner/paths/RED_BottomNote_Note5.path index e45d60b..b5f38dd 100644 --- a/src/main/deploy/pathplanner/paths/RED_BottomNote_Note5.path +++ b/src/main/deploy/pathplanner/paths/RED_BottomNote_Note5.path @@ -33,7 +33,7 @@ "eventMarkers": [ { "name": "Intake", - "waypointRelativePos": 0.5, + "waypointRelativePos": 0.1, "command": { "type": "parallel", "data": { diff --git a/src/main/deploy/pathplanner/paths/RED_Note5_Shoot.path b/src/main/deploy/pathplanner/paths/RED_Note5_Shoot.path index c424512..69a91f9 100644 --- a/src/main/deploy/pathplanner/paths/RED_Note5_Shoot.path +++ b/src/main/deploy/pathplanner/paths/RED_Note5_Shoot.path @@ -16,12 +16,12 @@ }, { "anchor": { - "x": 2.8078366589303156, - "y": 3.0288752689464666 + "x": 2.1289508227871425, + "y": 3.8435382723182747 }, "prevControl": { - "x": 4.656495012735573, - "y": 1.5562152243897376 + "x": 3.9776091765924, + "y": 2.3708782277615454 }, "nextControl": null, "isLocked": false, diff --git a/src/main/deploy/pathplanner/paths/RED_Path1.path b/src/main/deploy/pathplanner/paths/RED_Path1.path index da31120..6c4ff7f 100644 --- a/src/main/deploy/pathplanner/paths/RED_Path1.path +++ b/src/main/deploy/pathplanner/paths/RED_Path1.path @@ -46,7 +46,25 @@ ], "rotationTargets": [], "constraintZones": [], - "eventMarkers": [], + "eventMarkers": [ + { + "name": "SmartIntake", + "waypointRelativePos": 0.1, + "command": { + "type": "parallel", + "data": { + "commands": [ + { + "type": "named", + "data": { + "name": "SmartIntakeCommand" + } + } + ] + } + } + } + ], "globalConstraints": { "maxVelocity": 3.0, "maxAcceleration": 3.0, diff --git a/src/main/deploy/pathplanner/paths/RED_Path2.path b/src/main/deploy/pathplanner/paths/RED_Path2.path index 8501f42..7811a2b 100644 --- a/src/main/deploy/pathplanner/paths/RED_Path2.path +++ b/src/main/deploy/pathplanner/paths/RED_Path2.path @@ -3,25 +3,25 @@ "waypoints": [ { "anchor": { - "x": 2.8078366589303156, - "y": 3.0288752689464666 + "x": 2.1289508227871425, + "y": 3.8435382723182747 }, "prevControl": null, "nextControl": { - "x": 4.572939832902567, - "y": 2.078435098346024 + "x": 3.894053996759394, + "y": 2.893098101717832 }, "isLocked": false, "linkedName": "BottomShootPos" }, { "anchor": { - "x": 7.977907247481162, - "y": 1.2188049746469864 + "x": 8.259812143033956, + "y": 1.0966617353082035 }, "prevControl": { - "x": 6.244137265946287, - "y": 1.2188049746469864 + "x": 6.526042161499081, + "y": 1.0966617353082035 }, "nextControl": null, "isLocked": false, @@ -30,7 +30,25 @@ ], "rotationTargets": [], "constraintZones": [], - "eventMarkers": [], + "eventMarkers": [ + { + "name": "SmartIntake", + "waypointRelativePos": 0.1, + "command": { + "type": "parallel", + "data": { + "commands": [ + { + "type": "named", + "data": { + "name": "SmartIntakeCommand" + } + } + ] + } + } + } + ], "globalConstraints": { "maxVelocity": 3.0, "maxAcceleration": 3.0, diff --git a/src/main/deploy/pathplanner/paths/RED_Path3.path b/src/main/deploy/pathplanner/paths/RED_Path3.path index f04b7cc..8eb9cc8 100644 --- a/src/main/deploy/pathplanner/paths/RED_Path3.path +++ b/src/main/deploy/pathplanner/paths/RED_Path3.path @@ -3,41 +3,41 @@ "waypoints": [ { "anchor": { - "x": 7.977907247481162, - "y": 1.2188049746469864 + "x": 8.259812143033956, + "y": 1.0966617353082035 }, "prevControl": null, "nextControl": { - "x": 6.620135575194813, - "y": 1.2188049746469864 + "x": 6.9020404707476075, + "y": 1.0966617353082035 }, "isLocked": false, "linkedName": "RedNote5" }, { "anchor": { - "x": 6.024711082501046, - "y": 1.2742164924533423 + "x": 6.0038222875427945, + "y": 1.336882877328097 }, "prevControl": { - "x": 6.596541844483181, - "y": 0.9752456146133677 + "x": 6.567819751415584, + "y": 1.1071061327873286 }, "nextControl": { - "x": 5.4528803205189105, - "y": 1.573187370293317 + "x": 5.406242216137098, + "y": 1.5803414249378276 }, "isLocked": false, "linkedName": null }, { "anchor": { - "x": 2.8078366589303156, - "y": 3.0288752689464666 + "x": 2.1289508227871425, + "y": 3.8435382723182747 }, "prevControl": { - "x": 4.499829050548687, - "y": 2.1515458806999037 + "x": 3.820943214405513, + "y": 2.966208884071712 }, "nextControl": null, "isLocked": false, @@ -55,7 +55,7 @@ }, "goalEndState": { "velocity": 0, - "rotation": -40.0, + "rotation": -39.0, "rotateFast": false }, "reversed": false, diff --git a/src/main/deploy/pathplanner/paths/RED_Path4.path b/src/main/deploy/pathplanner/paths/RED_Path4.path index 05188e3..4f52486 100644 --- a/src/main/deploy/pathplanner/paths/RED_Path4.path +++ b/src/main/deploy/pathplanner/paths/RED_Path4.path @@ -32,12 +32,12 @@ }, { "anchor": { - "x": 7.9882578085766855, - "y": 2.5170997924693057 + "x": 7.998702206055811, + "y": 2.767765331968324 }, "prevControl": { - "x": 6.442486981666077, - "y": 2.5484329849066834 + "x": 6.452931379145203, + "y": 2.799098524405702 }, "nextControl": null, "isLocked": false, diff --git a/src/main/deploy/pathplanner/paths/RED_Path5.path b/src/main/deploy/pathplanner/paths/RED_Path5.path index 1aca035..9344f43 100644 --- a/src/main/deploy/pathplanner/paths/RED_Path5.path +++ b/src/main/deploy/pathplanner/paths/RED_Path5.path @@ -16,28 +16,28 @@ }, { "anchor": { - "x": 5.5429632487763705, - "y": 1.6149649602098184 + "x": 5.502491208544758, + "y": 1.691992391618371 }, "prevControl": { - "x": 5.99337789006367, - "y": 1.5979928143062396 + "x": 5.9529058498320575, + "y": 1.6750202457147922 }, "nextControl": { - "x": 5.01230600835305, - "y": 1.6349607402837398 + "x": 4.971833968121438, + "y": 1.7119881716922924 }, "isLocked": false, "linkedName": null }, { "anchor": { - "x": 2.8078366589303156, - "y": 3.0288752689464666 + "x": 2.1289508227871425, + "y": 3.8435382723182747 }, "prevControl": { - "x": 4.750494590047705, - "y": 1.4413268521193536 + "x": 3.538944482469119, + "y": 2.16199027817903 }, "nextControl": null, "isLocked": false, @@ -55,7 +55,7 @@ }, "goalEndState": { "velocity": 0, - "rotation": -40.0, + "rotation": -39.0, "rotateFast": false }, "reversed": false, diff --git a/src/main/include/Robot.h b/src/main/include/Robot.h index 6b2080e..67a01f0 100644 --- a/src/main/include/Robot.h +++ b/src/main/include/Robot.h @@ -38,6 +38,7 @@ #include "commands/SubShoot.h" #include "commands/VisionShoot.h" #include "commands/IntakeDown.h" +#include "cameraserver/CameraServer.h" class Robot : public frc::TimedRobot { public: @@ -85,4 +86,8 @@ class Robot : public frc::TimedRobot { frc::SendableChooser m_auto_chooser; AutoAimer m_autoAim = AutoAimer(); -}; + + cs::CvSink m_cvSink; + + cs::CvSource m_cvSource; +}; diff --git a/src/main/include/RobotControlData.h b/src/main/include/RobotControlData.h index aedf7d6..4049503 100644 --- a/src/main/include/RobotControlData.h +++ b/src/main/include/RobotControlData.h @@ -29,6 +29,11 @@ struct AutoAimOutput{ double robotRotSpeed; }; +struct SmartIntakeOutput{ + bool smartIntakeFlag; + bool smartOuttakeFlag; +}; + struct RobotControlData { IntakeInput intakeInput; IntakeOutput intakeOutput; @@ -36,6 +41,7 @@ struct RobotControlData { LauncherOutput launcherOutput; SwerveInput swerveInput; SmartIntakeInput smartIntakeInput; + SmartIntakeOutput smartIntakeOutput; AutoAimInput autoAimInput; AutoAimOutput autoAimOutput; }; diff --git a/src/main/include/SwerveConfig.h b/src/main/include/SwerveConfig.h index a8bf074..ca23701 100644 --- a/src/main/include/SwerveConfig.h +++ b/src/main/include/SwerveConfig.h @@ -39,7 +39,7 @@ rev::SparkPIDController fl_drive_pid = fl_drive_mtr.GetPIDController(); // --------------------Absolute Encoder----------------------- const int FR_ABS_ENC_PORT = 12; const bool FR_ABS_ENC_INVERTED = false; -const frc::Rotation2d FR_ZERO_HEADING{units::degree_t{77.9f}}; +const frc::Rotation2d FR_ZERO_HEADING{units::degree_t{92.94f}}; ctre::phoenix6::hardware::CANcoder fr_abs_enc{FR_ABS_ENC_PORT}; @@ -154,7 +154,7 @@ const double MAX_DRIVE_SPEED_FPS = 18.0; const double MAX_ANGULAR_VELOCITY_DEGPS = 540.0; const double CONTROLLER_DEADZONE = 0.1; const int TURN_MOTOR_CURRENT_LIMIT = 20; -const int DRIVE_MOTOR_CURRENT_LIMIT = 55; +const int DRIVE_MOTOR_CURRENT_LIMIT = 30; const double SWERVE_VOLTAGE_COMPENSATION = 10.5; const bool IS_DRIVE_IN_COAST = false; const bool IS_ROBOT_ORIENTED_DRIVE = false; diff --git a/src/main/include/subsystems/SubSystemConfig.h b/src/main/include/subsystems/SubSystemConfig.h index 58d2ffd..84e2c6e 100644 --- a/src/main/include/subsystems/SubSystemConfig.h +++ b/src/main/include/subsystems/SubSystemConfig.h @@ -79,7 +79,9 @@ const double DOWN_MAX_ACC = 200.0; const double MAX_JERK = 1250.0; const double SUB_ANGLE = 55.0; +const double HOARDE_ANG = 40.0; const double STOW_ANGLE = 10.0; const double SUB_SPEED = 150.0; +const double HOARDE_SPD = 70.0; const double INDEXER_SPEED = 1.0; const double INDEXER_SLOW_SPEED = 0.15; \ No newline at end of file diff --git a/src/main/include/subsystems/subsystemsManagers/LauncherManager.h b/src/main/include/subsystems/subsystemsManagers/LauncherManager.h index d2c7056..a6c55f5 100644 --- a/src/main/include/subsystems/subsystemsManagers/LauncherManager.h +++ b/src/main/include/subsystems/subsystemsManagers/LauncherManager.h @@ -14,6 +14,7 @@ struct LauncherInput bool runIndexerForward; //Indexer is the little "kick" to help the Note transfer from the Intake to the Launcher bool runIndexerBackward; bool runIndexerBackwardSlow; + bool goToHoardePos; }; struct LauncherOutput @@ -32,5 +33,6 @@ class LauncherManager LauncherHAL m_launcher; bool m_goToStowPos; bool m_goToSubPos; + bool m_goToHoardePos; bool m_visionResetProfiledMoveState = false; }; \ No newline at end of file