Skip to content

Commit f601b36

Browse files
rohitalamgariAntarcticaByToto
authored andcommitted
fixed lift and auto tuning
1 parent 8535de8 commit f601b36

File tree

6 files changed

+18
-19
lines changed

6 files changed

+18
-19
lines changed

Competition/src/main/cpp/Robot.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -37,11 +37,11 @@ void Robot::DisabledInit() {
3737
m_container.m_drivetrain.robotMode = ValorSubsystem::RobotMode::DISABLED;
3838
m_container.m_shooter.robotMode = ValorSubsystem::RobotMode::DISABLED;
3939
m_container.m_turretTracker.robotMode = ValorSubsystem::RobotMode::DISABLED;
40-
//m_container.m_lift.robotMode = ValorSubsystem::RobotMode::DISABLED; //just added, not tested
40+
m_container.m_lift.robotMode = ValorSubsystem::RobotMode::DISABLED; //just added, not tested
4141

4242
m_container.m_shooter.resetState();
4343
m_container.m_drivetrain.resetState();
44-
// m_container.m_lift.resetState();
44+
m_container.m_lift.resetState();
4545
m_container.m_turretTracker.resetState();
4646
//m_container.m_feeder.resetState(); //just added, not tested
4747

@@ -70,7 +70,7 @@ void Robot::AutonomousInit() {
7070
m_container.m_feeder.robotMode = ValorSubsystem::RobotMode::AUTO;
7171
m_container.m_drivetrain.robotMode = ValorSubsystem::RobotMode::AUTO;
7272
m_container.m_shooter.robotMode = ValorSubsystem::RobotMode::AUTO;
73-
// m_container.m_lift.robotMode = ValorSubsystem::RobotMode::AUTO;
73+
m_container.m_lift.robotMode = ValorSubsystem::RobotMode::AUTO;
7474
m_container.m_turretTracker.robotMode = ValorSubsystem::RobotMode::AUTO;
7575

7676
m_container.m_drivetrain.pullSwerveModuleZeroReference();
@@ -95,7 +95,7 @@ void Robot::TeleopInit() {
9595
m_container.m_drivetrain.robotMode = ValorSubsystem::RobotMode::TELEOP;
9696
m_container.m_shooter.robotMode = ValorSubsystem::RobotMode::TELEOP;
9797
m_container.m_shooter.state.turretState = m_container.m_shooter.TURRET_TRACK;
98-
// m_container.m_lift.robotMode = ValorSubsystem::RobotMode::TELEOP;
98+
m_container.m_lift.robotMode = ValorSubsystem::RobotMode::TELEOP;
9999
m_container.m_turretTracker.robotMode = ValorSubsystem::RobotMode::TELEOP;
100100

101101
}

Competition/src/main/cpp/RobotContainer.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -19,7 +19,7 @@ void RobotContainer::ConfigureButtonBindings() {
1919
m_feeder.setControllers(&m_GamepadOperator, &m_GamepadDriver);
2020
m_drivetrain.setController(&m_GamepadDriver);
2121
m_shooter.setControllers(&m_GamepadOperator, &m_GamepadDriver);
22-
// m_lift.setController(&m_GamepadOperator);
22+
m_lift.setController(&m_GamepadOperator);
2323
}
2424

2525
frc2::Command* RobotContainer::GetAutonomousCommand() {

Competition/src/main/cpp/ValorAuto.cpp

Lines changed: 4 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -78,8 +78,8 @@ ValorAuto::ValorAuto(Drivetrain *_drivetrain, Shooter *_shooter, Feeder *_feeder
7878
frc::Pose2d hangarSpotRed = frc::Pose2d(units::meter_t(4), units::meter_t(7.5), frc::Rotation2d(170_deg));
7979
frc::Pose2d hangarSpotBlue = frc::Pose2d(units::meter_t(4), units::meter_t(7.5), frc::Rotation2d(170_deg));
8080

81-
frc::Pose2d trenchSpotRed = frc::Pose2d(units::meter_t(4.5), units::meter_t(6.4), frc::Rotation2d(-43_deg));
82-
frc::Pose2d trenchSpotBlue = frc::Pose2d(units::meter_t(4.5), units::meter_t(6.4), frc::Rotation2d(-43_deg));
81+
frc::Pose2d trenchSpotRed = frc::Pose2d(units::meter_t(4.5), units::meter_t(5.4), frc::Rotation2d(-43_deg));
82+
frc::Pose2d trenchSpotBlue = frc::Pose2d(units::meter_t(4.5), units::meter_t(5.4), frc::Rotation2d(-43_deg));
8383

8484
frc::Pose2d speedyRed = frc::Pose2d(3.35_m, 3.2_m, frc::Rotation2d(-60_deg)); //originally 0
8585
frc::Pose2d speedyBlue = frc::Pose2d(3.35_m, 3.2_m, frc::Rotation2d(-60_deg)); //originally 0
@@ -301,12 +301,12 @@ ValorAuto::ValorAuto(Drivetrain *_drivetrain, Shooter *_shooter, Feeder *_feeder
301301
reverseConfig);
302302

303303
auto moveTrenchRed = frc::TrajectoryGenerator::GenerateTrajectory(
304-
hangarSpotRed,
304+
tasRed,
305305
{},
306306
trenchSpotRed,
307307
reverseConfig);
308308
auto moveTrenchBlue = frc::TrajectoryGenerator::GenerateTrajectory(
309-
hangarSpotBlue,
309+
tasBlue,
310310
{},
311311
trenchSpotBlue,
312312
reverseConfig);
@@ -1006,7 +1006,6 @@ ValorAuto::ValorAuto(Drivetrain *_drivetrain, Shooter *_shooter, Feeder *_feeder
10061006
frc2::WaitCommand((units::second_t).5),
10071007
cmd_intakeOne,
10081008
cmd_move_moveTasRed,
1009-
cmd_move_moveHangarRed,
10101009
cmd_move_moveTrenchRed,
10111010
cmd_intakeReverse,
10121011
frc2::WaitCommand((units::second_t)1),

Competition/src/main/cpp/subsystems/TurretTracker.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -82,11 +82,11 @@ void TurretTracker::assignOutputs() {
8282
state.target -= 360;
8383
}
8484

85-
if (state.target < -16) {
86-
state.target = -16;
85+
if (state.target < -12) {
86+
state.target = -12;
8787
}
88-
else if (state.target > 196) {
89-
state.target = 196;
88+
else if (state.target > 192) {
89+
state.target = 192;
9090
}
9191

9292
shooter->assignTurret(state.target);

Competition/src/main/include/Constants.h

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -214,8 +214,8 @@ namespace ShooterConstants{
214214
constexpr static double homePositionMid = 90;
215215
constexpr static double homePositionLeft = 180;
216216
constexpr static double homePositionRight = 0;
217-
constexpr static double turretLimitLeft = 180 + 16;
218-
constexpr static double turretLimitRight = 0 - 16;
217+
constexpr static double turretLimitLeft = 180 + 12;
218+
constexpr static double turretLimitRight = 0 - 12;
219219

220220
constexpr static double turretRotateLiftThreshold = 20000; // lowered from 64500
221221
constexpr static double hubX = 0;
@@ -259,7 +259,7 @@ namespace LiftConstants{
259259

260260
constexpr static int MAIN_FIRST_POSITION = 62000;
261261
constexpr static int MAIN_SECOND_POSITION = 78500;
262-
constexpr static int MAIN_THIRD_POSITION = 103000;
262+
constexpr static int MAIN_THIRD_POSITION = 98000;
263263
constexpr static int MAIN_DOWN_POSITION = 125;
264264
constexpr static int MAIN_BOTTOM_POSITION = 0;
265265
constexpr static int MAIN_SLOW_UP_POSITION = 5500;
@@ -270,7 +270,7 @@ namespace LiftConstants{
270270
constexpr static double rotateForwardLimit = 40;
271271
constexpr static double rotateReverseLimit = 0;
272272

273-
constexpr static double extendForwardLimit = 103000;
273+
constexpr static double extendForwardLimit = 98000;
274274
constexpr static double extendReverseLimit = 125;
275275

276276
constexpr static double pivotGearRatio = 1 / 95.67;

Competition/src/main/include/RobotContainer.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -33,7 +33,7 @@ class RobotContainer {
3333
Drivetrain m_drivetrain;
3434
Shooter m_shooter;
3535
Feeder m_feeder;
36-
// Lift m_lift;
36+
Lift m_lift;
3737
TurretTracker m_turretTracker;
3838

3939
private:

0 commit comments

Comments
 (0)