Skip to content

Commit

Permalink
Merge branch 'anaorakthegreat-main'
Browse files Browse the repository at this point in the history
  • Loading branch information
truher committed Nov 23, 2024
2 parents b5f7220 + 142d119 commit 2a109b2
Show file tree
Hide file tree
Showing 3 changed files with 9 additions and 16 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -479,12 +479,6 @@ public RobotContainer(TimedRobot100 robot) throws IOException {
feeder.setDefaultCommand(feeder.run(feeder::stop));
intake.setDefaultCommand(intake.run(intake::stop));
// climber.setDefaultCommand(new ClimberDefault(
// // comLog,
// climber,
// operatorControl::leftClimb,
// operatorControl::rightClimb));
// m_ampFeeder.setDefaultCommand(m_ampFeeder.run(m_ampFeeder::stop));

// if far from the goal, go fast. if near, go slow.
// m_ampPivot.setDefaultCommand(new AmpFastThenSlow(m_ampPivot, 0.1, 0));

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,7 @@ public static SwerveKinodynamics get() {
0.3); // vcg m
case SWERVE_ONE:
return new SwerveKinodynamics(
4, // vel m/s
5, // vel m/s
10, // stall m/s/s
10, // max accel m/s/s
20, // max decel m/s/s
Expand Down
Original file line number Diff line number Diff line change
@@ -1,7 +1,6 @@
package org.team100.lib.motion.drivetrain.module;

import org.team100.lib.config.Identity;
import org.team100.lib.encoder.AnalogTurningEncoder;
import org.team100.lib.encoder.DutyCycleRotaryPositionSensor;
import org.team100.lib.encoder.EncoderDrive;
import org.team100.lib.logging.LoggerFactory;
Expand Down Expand Up @@ -104,8 +103,8 @@ public static SwerveModuleCollection get(
32,
DriveRatio.FAST, DutyCycleRotaryPositionSensor.class,
12,
7,
0.151,
2,
0.34,
kinodynamics,
EncoderDrive.DIRECT, MotorPhase.REVERSE),
WCPSwerveModule100.getFalconDrive(frontRightLogger,
Expand All @@ -114,8 +113,8 @@ public static SwerveModuleCollection get(
30,
DriveRatio.FAST, DutyCycleRotaryPositionSensor.class,
11,
8,
0.88,
1,
0.62,
kinodynamics,
EncoderDrive.DIRECT, MotorPhase.REVERSE),
WCPSwerveModule100.getFalconDrive(rearLeftLogger,
Expand All @@ -124,8 +123,8 @@ public static SwerveModuleCollection get(
31,
DriveRatio.FAST, DutyCycleRotaryPositionSensor.class,
21,
6,
0.91,
3,
0.59,
kinodynamics,
EncoderDrive.DIRECT, MotorPhase.REVERSE),
WCPSwerveModule100.getFalconDrive(rearRightLogger,
Expand All @@ -134,8 +133,8 @@ public static SwerveModuleCollection get(
22,
DriveRatio.FAST, DutyCycleRotaryPositionSensor.class,
33,
9,
0.888,
0,
0.59,
kinodynamics,
EncoderDrive.DIRECT, MotorPhase.REVERSE));
case BETA_BOT:
Expand Down

0 comments on commit 2a109b2

Please sign in to comment.