Compare commits
11 Commits
0589463c4e
...
main
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
6c0df54b06 | ||
|
|
fa34ef00fe | ||
|
|
68da3c630c | ||
| c9316cebc3 | |||
| d312e125cd | |||
| 4386de4d4d | |||
| cca7d68766 | |||
| a8a597985f | |||
| 060b39669f | |||
|
|
4ada896603 | ||
|
|
dd26ff6de4 |
@@ -45,6 +45,25 @@
|
|||||||
"data": {
|
"data": {
|
||||||
"name": "Shoot Algae"
|
"name": "Shoot Algae"
|
||||||
}
|
}
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"type": "parallel",
|
||||||
|
"data": {
|
||||||
|
"commands": [
|
||||||
|
{
|
||||||
|
"type": "named",
|
||||||
|
"data": {
|
||||||
|
"name": "HP Pickup"
|
||||||
|
}
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"type": "path",
|
||||||
|
"data": {
|
||||||
|
"pathName": "Post-Barge Backup"
|
||||||
|
}
|
||||||
|
}
|
||||||
|
]
|
||||||
|
}
|
||||||
}
|
}
|
||||||
]
|
]
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -16,12 +16,12 @@
|
|||||||
},
|
},
|
||||||
{
|
{
|
||||||
"anchor": {
|
"anchor": {
|
||||||
"x": 1.2587090163934425,
|
"x": 1.1268442622950818,
|
||||||
"y": 7.08186475409836
|
"y": 7.201741803278688
|
||||||
},
|
},
|
||||||
"prevControl": {
|
"prevControl": {
|
||||||
"x": 2.115173057489333,
|
"x": 2.287270519874242,
|
||||||
"y": 6.135246603413428
|
"y": 6.774371912194027
|
||||||
},
|
},
|
||||||
"nextControl": null,
|
"nextControl": null,
|
||||||
"isLocked": false,
|
"isLocked": false,
|
||||||
@@ -34,7 +34,7 @@
|
|||||||
"eventMarkers": [],
|
"eventMarkers": [],
|
||||||
"globalConstraints": {
|
"globalConstraints": {
|
||||||
"maxVelocity": 5.0,
|
"maxVelocity": 5.0,
|
||||||
"maxAcceleration": 2.0,
|
"maxAcceleration": 2.5,
|
||||||
"maxAngularVelocity": 540.0,
|
"maxAngularVelocity": 540.0,
|
||||||
"maxAngularAcceleration": 400.0,
|
"maxAngularAcceleration": 400.0,
|
||||||
"nominalVoltage": 12.0,
|
"nominalVoltage": 12.0,
|
||||||
|
|||||||
@@ -46,7 +46,7 @@
|
|||||||
],
|
],
|
||||||
"globalConstraints": {
|
"globalConstraints": {
|
||||||
"maxVelocity": 5.0,
|
"maxVelocity": 5.0,
|
||||||
"maxAcceleration": 2.5,
|
"maxAcceleration": 3.5,
|
||||||
"maxAngularVelocity": 540.0,
|
"maxAngularVelocity": 540.0,
|
||||||
"maxAngularAcceleration": 400.0,
|
"maxAngularAcceleration": 400.0,
|
||||||
"nominalVoltage": 12.0,
|
"nominalVoltage": 12.0,
|
||||||
|
|||||||
@@ -3,25 +3,25 @@
|
|||||||
"waypoints": [
|
"waypoints": [
|
||||||
{
|
{
|
||||||
"anchor": {
|
"anchor": {
|
||||||
"x": 1.2587090163934425,
|
"x": 1.1268442622950818,
|
||||||
"y": 7.08186475409836
|
"y": 7.201741803278688
|
||||||
},
|
},
|
||||||
"prevControl": null,
|
"prevControl": null,
|
||||||
"nextControl": {
|
"nextControl": {
|
||||||
"x": 2.550917920503032,
|
"x": 2.0019467213114757,
|
||||||
"y": 6.856479480125757
|
"y": 6.434528688524591
|
||||||
},
|
},
|
||||||
"isLocked": false,
|
"isLocked": false,
|
||||||
"linkedName": "HP Left Position"
|
"linkedName": "HP Left Position"
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
"anchor": {
|
"anchor": {
|
||||||
"x": 3.6442622950819668,
|
"x": 3.609900518622585,
|
||||||
"y": 5.031967213114754
|
"y": 5.005924534374863
|
||||||
},
|
},
|
||||||
"prevControl": {
|
"prevControl": {
|
||||||
"x": 3.328722911520323,
|
"x": 3.2943611350609414,
|
||||||
"y": 5.557866185717494
|
"y": 5.531823506977602
|
||||||
},
|
},
|
||||||
"nextControl": null,
|
"nextControl": null,
|
||||||
"isLocked": false,
|
"isLocked": false,
|
||||||
@@ -46,7 +46,7 @@
|
|||||||
],
|
],
|
||||||
"globalConstraints": {
|
"globalConstraints": {
|
||||||
"maxVelocity": 3.5,
|
"maxVelocity": 3.5,
|
||||||
"maxAcceleration": 1.5,
|
"maxAcceleration": 1.25,
|
||||||
"maxAngularVelocity": 540.0,
|
"maxAngularVelocity": 540.0,
|
||||||
"maxAngularAcceleration": 400.0,
|
"maxAngularAcceleration": 400.0,
|
||||||
"nominalVoltage": 12.0,
|
"nominalVoltage": 12.0,
|
||||||
|
|||||||
@@ -3,13 +3,13 @@
|
|||||||
"waypoints": [
|
"waypoints": [
|
||||||
{
|
{
|
||||||
"anchor": {
|
"anchor": {
|
||||||
"x": 1.2587090163934425,
|
"x": 1.1268442622950818,
|
||||||
"y": 7.08186475409836
|
"y": 7.201741803278688
|
||||||
},
|
},
|
||||||
"prevControl": null,
|
"prevControl": null,
|
||||||
"nextControl": {
|
"nextControl": {
|
||||||
"x": 1.7741803278688524,
|
"x": 1.9266540815180775,
|
||||||
"y": 6.530430327868851
|
"y": 6.744320542331013
|
||||||
},
|
},
|
||||||
"isLocked": false,
|
"isLocked": false,
|
||||||
"linkedName": "HP Left Position"
|
"linkedName": "HP Left Position"
|
||||||
@@ -20,8 +20,8 @@
|
|||||||
"y": 5.211782786885246
|
"y": 5.211782786885246
|
||||||
},
|
},
|
||||||
"prevControl": {
|
"prevControl": {
|
||||||
"x": 3.2246926229508195,
|
"x": 2.975085616438356,
|
||||||
"y": 6.230737704918033
|
"y": 6.023416095890411
|
||||||
},
|
},
|
||||||
"nextControl": null,
|
"nextControl": null,
|
||||||
"isLocked": false,
|
"isLocked": false,
|
||||||
@@ -45,7 +45,7 @@
|
|||||||
}
|
}
|
||||||
],
|
],
|
||||||
"globalConstraints": {
|
"globalConstraints": {
|
||||||
"maxVelocity": 3.5,
|
"maxVelocity": 5.0,
|
||||||
"maxAcceleration": 1.5,
|
"maxAcceleration": 1.5,
|
||||||
"maxAngularVelocity": 540.0,
|
"maxAngularVelocity": 540.0,
|
||||||
"maxAngularAcceleration": 400.0,
|
"maxAngularAcceleration": 400.0,
|
||||||
|
|||||||
@@ -3,25 +3,25 @@
|
|||||||
"waypoints": [
|
"waypoints": [
|
||||||
{
|
{
|
||||||
"anchor": {
|
"anchor": {
|
||||||
"x": 3.6442622950819668,
|
"x": 3.609900518622585,
|
||||||
"y": 5.031967213114754
|
"y": 5.005924534374863
|
||||||
},
|
},
|
||||||
"prevControl": null,
|
"prevControl": null,
|
||||||
"nextControl": {
|
"nextControl": {
|
||||||
"x": 3.5117625600811717,
|
"x": 3.47740078362179,
|
||||||
"y": 5.243966789116026
|
"y": 5.217924110376135
|
||||||
},
|
},
|
||||||
"isLocked": false,
|
"isLocked": false,
|
||||||
"linkedName": "L"
|
"linkedName": "L"
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
"anchor": {
|
"anchor": {
|
||||||
"x": 1.2587090163934425,
|
"x": 1.1268442622950818,
|
||||||
"y": 7.08186475409836
|
"y": 7.201741803278688
|
||||||
},
|
},
|
||||||
"prevControl": {
|
"prevControl": {
|
||||||
"x": 1.4625000000000001,
|
"x": 1.3306352459016395,
|
||||||
"y": 6.8061475409836065
|
"y": 6.926024590163935
|
||||||
},
|
},
|
||||||
"nextControl": null,
|
"nextControl": null,
|
||||||
"isLocked": false,
|
"isLocked": false,
|
||||||
@@ -34,7 +34,7 @@
|
|||||||
"eventMarkers": [],
|
"eventMarkers": [],
|
||||||
"globalConstraints": {
|
"globalConstraints": {
|
||||||
"maxVelocity": 5.0,
|
"maxVelocity": 5.0,
|
||||||
"maxAcceleration": 2.5,
|
"maxAcceleration": 3.5,
|
||||||
"maxAngularVelocity": 540.0,
|
"maxAngularVelocity": 540.0,
|
||||||
"maxAngularAcceleration": 400.0,
|
"maxAngularAcceleration": 400.0,
|
||||||
"nominalVoltage": 12.0,
|
"nominalVoltage": 12.0,
|
||||||
|
|||||||
54
src/main/deploy/pathplanner/paths/New Path.path
Normal file
54
src/main/deploy/pathplanner/paths/New Path.path
Normal file
@@ -0,0 +1,54 @@
|
|||||||
|
{
|
||||||
|
"version": "2025.0",
|
||||||
|
"waypoints": [
|
||||||
|
{
|
||||||
|
"anchor": {
|
||||||
|
"x": 2.0,
|
||||||
|
"y": 7.0
|
||||||
|
},
|
||||||
|
"prevControl": null,
|
||||||
|
"nextControl": {
|
||||||
|
"x": 3.0,
|
||||||
|
"y": 7.0
|
||||||
|
},
|
||||||
|
"isLocked": false,
|
||||||
|
"linkedName": null
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"anchor": {
|
||||||
|
"x": 3.756421232876712,
|
||||||
|
"y": 5.227054794520548
|
||||||
|
},
|
||||||
|
"prevControl": {
|
||||||
|
"x": 2.756421232876712,
|
||||||
|
"y": 5.227054794520548
|
||||||
|
},
|
||||||
|
"nextControl": null,
|
||||||
|
"isLocked": false,
|
||||||
|
"linkedName": null
|
||||||
|
}
|
||||||
|
],
|
||||||
|
"rotationTargets": [],
|
||||||
|
"constraintZones": [],
|
||||||
|
"pointTowardsZones": [],
|
||||||
|
"eventMarkers": [],
|
||||||
|
"globalConstraints": {
|
||||||
|
"maxVelocity": 3.5,
|
||||||
|
"maxAcceleration": 1.75,
|
||||||
|
"maxAngularVelocity": 540.0,
|
||||||
|
"maxAngularAcceleration": 400.0,
|
||||||
|
"nominalVoltage": 12.0,
|
||||||
|
"unlimited": false
|
||||||
|
},
|
||||||
|
"goalEndState": {
|
||||||
|
"velocity": 0,
|
||||||
|
"rotation": -59.18537788806707
|
||||||
|
},
|
||||||
|
"reversed": false,
|
||||||
|
"folder": "Left Paths",
|
||||||
|
"idealStartingState": {
|
||||||
|
"velocity": 0,
|
||||||
|
"rotation": 0.0
|
||||||
|
},
|
||||||
|
"useDefaultConstraints": true
|
||||||
|
}
|
||||||
54
src/main/deploy/pathplanner/paths/Post-Barge Backup.path
Normal file
54
src/main/deploy/pathplanner/paths/Post-Barge Backup.path
Normal file
@@ -0,0 +1,54 @@
|
|||||||
|
{
|
||||||
|
"version": "2025.0",
|
||||||
|
"waypoints": [
|
||||||
|
{
|
||||||
|
"anchor": {
|
||||||
|
"x": 7.032020547945206,
|
||||||
|
"y": 4.761258561643835
|
||||||
|
},
|
||||||
|
"prevControl": null,
|
||||||
|
"nextControl": {
|
||||||
|
"x": 6.71311475409836,
|
||||||
|
"y": 4.9480532786885245
|
||||||
|
},
|
||||||
|
"isLocked": false,
|
||||||
|
"linkedName": "Pre-Barge"
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"anchor": {
|
||||||
|
"x": 5.933913934426228,
|
||||||
|
"y": 5.247745901639345
|
||||||
|
},
|
||||||
|
"prevControl": {
|
||||||
|
"x": 6.641188524590164,
|
||||||
|
"y": 5.043954918032786
|
||||||
|
},
|
||||||
|
"nextControl": null,
|
||||||
|
"isLocked": false,
|
||||||
|
"linkedName": null
|
||||||
|
}
|
||||||
|
],
|
||||||
|
"rotationTargets": [],
|
||||||
|
"constraintZones": [],
|
||||||
|
"pointTowardsZones": [],
|
||||||
|
"eventMarkers": [],
|
||||||
|
"globalConstraints": {
|
||||||
|
"maxVelocity": 3.5,
|
||||||
|
"maxAcceleration": 1.0,
|
||||||
|
"maxAngularVelocity": 540.0,
|
||||||
|
"maxAngularAcceleration": 400.0,
|
||||||
|
"nominalVoltage": 12.0,
|
||||||
|
"unlimited": false
|
||||||
|
},
|
||||||
|
"goalEndState": {
|
||||||
|
"velocity": 0,
|
||||||
|
"rotation": 0.0
|
||||||
|
},
|
||||||
|
"reversed": false,
|
||||||
|
"folder": "Center",
|
||||||
|
"idealStartingState": {
|
||||||
|
"velocity": 0,
|
||||||
|
"rotation": 0.0
|
||||||
|
},
|
||||||
|
"useDefaultConstraints": false
|
||||||
|
}
|
||||||
@@ -46,7 +46,7 @@
|
|||||||
],
|
],
|
||||||
"globalConstraints": {
|
"globalConstraints": {
|
||||||
"maxVelocity": 3.5,
|
"maxVelocity": 3.5,
|
||||||
"maxAcceleration": 1.5,
|
"maxAcceleration": 1.25,
|
||||||
"maxAngularVelocity": 540.0,
|
"maxAngularVelocity": 540.0,
|
||||||
"maxAngularAcceleration": 400.0,
|
"maxAngularAcceleration": 400.0,
|
||||||
"nominalVoltage": 12.0,
|
"nominalVoltage": 12.0,
|
||||||
|
|||||||
@@ -7,7 +7,7 @@ package frc.robot;
|
|||||||
import org.littletonrobotics.junction.LoggedRobot;
|
import org.littletonrobotics.junction.LoggedRobot;
|
||||||
import org.littletonrobotics.junction.LogFileUtil;
|
import org.littletonrobotics.junction.LogFileUtil;
|
||||||
import org.littletonrobotics.junction.Logger;
|
import org.littletonrobotics.junction.Logger;
|
||||||
//import org.littletonrobotics.junction.networktables.NT4Publisher;
|
import org.littletonrobotics.junction.networktables.NT4Publisher;
|
||||||
import org.littletonrobotics.junction.wpilog.WPILOGReader;
|
import org.littletonrobotics.junction.wpilog.WPILOGReader;
|
||||||
import org.littletonrobotics.junction.wpilog.WPILOGWriter;
|
import org.littletonrobotics.junction.wpilog.WPILOGWriter;
|
||||||
|
|
||||||
|
|||||||
@@ -111,9 +111,9 @@ public class RobotContainer {
|
|||||||
|
|
||||||
drivetrain.setDefaultCommand(
|
drivetrain.setDefaultCommand(
|
||||||
drivetrain.drive(
|
drivetrain.drive(
|
||||||
() -> driver.getLeftY() * Math.pow(Math.abs(driver.getLeftY()) + Math.abs(driver.getLeftX()), 3),
|
() -> driver.getLeftY(),
|
||||||
() -> driver.getLeftX() * Math.pow(Math.abs(driver.getLeftY()) + Math.abs(driver.getLeftX()), 3),
|
() -> driver.getLeftX(),
|
||||||
driver::getRightX, //Math.signum(driver.getRightX()) * Math.pow(driver.getRightX(), 3)
|
() -> driver.getRightX(),
|
||||||
() -> true
|
() -> true
|
||||||
)
|
)
|
||||||
);
|
);
|
||||||
@@ -339,7 +339,7 @@ public class RobotContainer {
|
|||||||
),
|
),
|
||||||
manipulatorPivot.maintainPosition()
|
manipulatorPivot.maintainPosition()
|
||||||
.withTimeout(
|
.withTimeout(
|
||||||
0.01
|
0.1
|
||||||
)
|
)
|
||||||
)
|
)
|
||||||
);
|
);
|
||||||
@@ -354,14 +354,24 @@ public class RobotContainer {
|
|||||||
|
|
||||||
NamedCommands.registerCommand(
|
NamedCommands.registerCommand(
|
||||||
"Shoot Algae",
|
"Shoot Algae",
|
||||||
shootAlgae()
|
shootAlgae().withTimeout(2)
|
||||||
);
|
);
|
||||||
|
|
||||||
NamedCommands.registerCommand(
|
NamedCommands.registerCommand(
|
||||||
"Processor Position",
|
"Processor Position",
|
||||||
moveWithAlgae(ElevatorConstants.kProcessorPosition, ManipulatorPivotConstants.kProcessorPosition)
|
moveWithAlgae(ElevatorConstants.kProcessorPosition, ManipulatorPivotConstants.kProcessorPosition)
|
||||||
.alongWith(manipulator.runManipulator(() -> 0.85, false))
|
.raceWith(manipulator.runManipulator(() -> 0.85, false))
|
||||||
.until(() -> driver.a().getAsBoolean())
|
);
|
||||||
|
|
||||||
|
NamedCommands.registerCommand(
|
||||||
|
"Pickup Algae L2",
|
||||||
|
moveWithAlgae(ElevatorConstants.kL2AlgaePosition, ManipulatorPivotConstants.kL2AlgaePosition)
|
||||||
|
.raceWith(manipulator.runManipulator(() -> 0.85, false))
|
||||||
|
.andThen(
|
||||||
|
elevator.maintainPosition()
|
||||||
|
.alongWith(manipulatorPivot.maintainPosition())).withTimeout(0.1)
|
||||||
|
|
||||||
|
//Dont you need a holdPosition call?
|
||||||
);
|
);
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -620,9 +630,9 @@ public class RobotContainer {
|
|||||||
|
|
||||||
private Command shootAlgae(){
|
private Command shootAlgae(){
|
||||||
return manipulatorPivot.goToSetpointAlgae(() -> ManipulatorPivotConstants.kBargeShotPosition)
|
return manipulatorPivot.goToSetpointAlgae(() -> ManipulatorPivotConstants.kBargeShotPosition)
|
||||||
.andThen(elevator.goToSetpoint(() -> ElevatorConstants.kL4Position), manipulatorPivot.goToSetpointAlgae(() -> ManipulatorPivotConstants.kBargeShotPosition)
|
.andThen(elevator.goToSetpointAlgae(() -> ElevatorConstants.kL4Position), manipulatorPivot.goToSetpointAlgae(() -> ManipulatorPivotConstants.kBargeShotPosition)
|
||||||
.raceWith(elevator.maintainPosition())).until(() -> elevator.getEncoderPosition()>43/* 44*/).andThen(manipulator.runManipulator(() -> -1, false),
|
.raceWith(elevator.maintainPosition())).until(() -> elevator.getEncoderPosition()>36/* 44*/).andThen(manipulator.runManipulator(() -> -1, false),
|
||||||
elevator.goToSetpoint(() -> ElevatorConstants.kL4Position), manipulatorPivot.goToSetpointAlgae(() -> ManipulatorPivotConstants.kBargeShotPosition)
|
elevator.goToSetpointAlgae(() -> ElevatorConstants.kL4Position), manipulatorPivot.goToSetpointAlgae(() -> ManipulatorPivotConstants.kBargeShotPosition)
|
||||||
.raceWith(elevator.maintainPosition()));
|
.raceWith(elevator.maintainPosition()));
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -16,6 +16,8 @@ public class AutoConstants {
|
|||||||
public static final double kMaxAngularSpeedRadiansPerSecond = Math.PI;
|
public static final double kMaxAngularSpeedRadiansPerSecond = Math.PI;
|
||||||
public static final double kMaxAngularSpeedRadiansPerSecondSquared = Math.PI;
|
public static final double kMaxAngularSpeedRadiansPerSecondSquared = Math.PI;
|
||||||
|
|
||||||
|
public static final double kMaxSpeedMetersPerSecondAutoAlign = 2.5;
|
||||||
|
|
||||||
public static final double kPXYController = 3.5;
|
public static final double kPXYController = 3.5;
|
||||||
public static final double kPThetaController = 5;
|
public static final double kPThetaController = 5;
|
||||||
|
|
||||||
|
|||||||
@@ -13,7 +13,7 @@ import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Config;
|
|||||||
public class DrivetrainConstants {
|
public class DrivetrainConstants {
|
||||||
// Driving Parameters - Note that these are not the maximum capable speeds of
|
// Driving Parameters - Note that these are not the maximum capable speeds of
|
||||||
// the robot, rather the allowed maximum speeds
|
// the robot, rather the allowed maximum speeds
|
||||||
public static final double kMaxSpeedMetersPerSecond = 5.5;
|
public static final double kMaxSpeedMetersPerSecond = 5.5 * 0.75;
|
||||||
public static final double kMaxAngularSpeed = 2 * Math.PI; // radians per second
|
public static final double kMaxAngularSpeed = 2 * Math.PI; // radians per second
|
||||||
|
|
||||||
// Chassis configuration
|
// Chassis configuration
|
||||||
|
|||||||
@@ -56,6 +56,8 @@ public class ElevatorConstants {
|
|||||||
|
|
||||||
public static final double kVoltageLimit = 7;
|
public static final double kVoltageLimit = 7;
|
||||||
|
|
||||||
|
public static final double kVoltageLimitAlgae = 9;
|
||||||
|
|
||||||
// 1, 7, 10 are the defaults for these, change as necessary
|
// 1, 7, 10 are the defaults for these, change as necessary
|
||||||
public static final double kSysIDRampRate = .25;
|
public static final double kSysIDRampRate = .25;
|
||||||
public static final double kSysIDStepVolts = 3;
|
public static final double kSysIDStepVolts = 3;
|
||||||
|
|||||||
@@ -9,4 +9,6 @@ public class OIConstants {
|
|||||||
public static final String kAutoTab = "Auto Tab";
|
public static final String kAutoTab = "Auto Tab";
|
||||||
public static final String kSensorsTab = "Sensors Tab";
|
public static final String kSensorsTab = "Sensors Tab";
|
||||||
public static final String kApriltagTab = "Apriltag Tab";
|
public static final String kApriltagTab = "Apriltag Tab";
|
||||||
|
|
||||||
|
public static final double kJoystickExponential = 3;
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -85,6 +85,6 @@ public class VisionConstants {
|
|||||||
{5.322, 2.511}//22
|
{5.322, 2.511}//22
|
||||||
};
|
};
|
||||||
|
|
||||||
public static final double latencyFudge = 0.03;
|
public static final double latencyFudge = 0.0;
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -111,8 +111,8 @@ public class Drivetrain extends SubsystemBase {
|
|||||||
m_rearRight.getPosition()
|
m_rearRight.getPosition()
|
||||||
},
|
},
|
||||||
new Pose2d(),
|
new Pose2d(),
|
||||||
VecBuilder.fill(0.07, 0.7, Units.degreesToRadians(0.5)),
|
VecBuilder.fill(0.1, 0.1, Units.degreesToRadians(5)),
|
||||||
VecBuilder.fill(1, 1, Units.degreesToRadians(4000))
|
VecBuilder.fill(1, 1, Units.degreesToRadians(360))
|
||||||
);
|
);
|
||||||
|
|
||||||
pidHeading = new ProfiledPIDController(AutoConstants.kAlignPThetaController, 0, 0, AutoConstants.kAlignThetaControllerConstraints);
|
pidHeading = new ProfiledPIDController(AutoConstants.kAlignPThetaController, 0, 0, AutoConstants.kAlignThetaControllerConstraints);
|
||||||
@@ -177,17 +177,17 @@ public class Drivetrain extends SubsystemBase {
|
|||||||
|
|
||||||
gyroBuffer.addSample(Timer.getFPGATimestamp(), m_estimator.getEstimatedPosition().getRotation().getDegrees());
|
gyroBuffer.addSample(Timer.getFPGATimestamp(), m_estimator.getEstimatedPosition().getRotation().getDegrees());
|
||||||
|
|
||||||
m_estimator.setVisionMeasurementStdDevs(VecBuilder.fill(0.40, 0.40, Units.degreesToRadians(4000)));
|
m_estimator.setVisionMeasurementStdDevs(VecBuilder.fill(0.40, 0.40, Units.degreesToRadians(360)));
|
||||||
|
|
||||||
if(vision.getOrangeTagDetected() && vision.getOrangeTagDetected()){
|
if(vision.getOrangeTagDetected() && vision.getOrangeTagDetected()){
|
||||||
if(vision.getOrangeDist() < 60 && Math.abs(getVelocity()) < 3){
|
if(vision.getOrangeDist() < 60 && Math.abs(getVelocity()) < 3){
|
||||||
m_estimator.setVisionMeasurementStdDevs(VecBuilder.fill(0.02, 0.02, Units.degreesToRadians(4000)));
|
m_estimator.setVisionMeasurementStdDevs(VecBuilder.fill(0.03, 0.03, Units.degreesToRadians(360)));
|
||||||
}else if(vision.getOrangeDist() < 100 && Math.abs(getVelocity()) < 3){
|
}else if(vision.getOrangeDist() < 100 && Math.abs(getVelocity()) < 3){
|
||||||
m_estimator.setVisionMeasurementStdDevs(VecBuilder.fill(0.05, 0.05, Units.degreesToRadians(4000)));
|
m_estimator.setVisionMeasurementStdDevs(VecBuilder.fill(0.05, 0.05, Units.degreesToRadians(360)));
|
||||||
}else if(vision.getOrangeDist() < 60 && Math.abs(getVelocity()) > 3){
|
}else if(vision.getOrangeDist() < 60 && Math.abs(getVelocity()) > 3){
|
||||||
m_estimator.setVisionMeasurementStdDevs(VecBuilder.fill(0.2, 0.2, Units.degreesToRadians(4000)));
|
m_estimator.setVisionMeasurementStdDevs(VecBuilder.fill(0.2, 0.2, Units.degreesToRadians(360)));
|
||||||
}else if(vision.getOrangeDist() < 100 && Math.abs(getVelocity()) > 3){
|
}else if(vision.getOrangeDist() < 100 && Math.abs(getVelocity()) > 3){
|
||||||
m_estimator.setVisionMeasurementStdDevs(VecBuilder.fill(0.3, 0.3, Units.degreesToRadians(4000)));
|
m_estimator.setVisionMeasurementStdDevs(VecBuilder.fill(0.3, 0.3, Units.degreesToRadians(360)));
|
||||||
}
|
}
|
||||||
|
|
||||||
// if the detected tags match your alliances reef tags use their pose estimates
|
// if the detected tags match your alliances reef tags use their pose estimates
|
||||||
@@ -204,17 +204,18 @@ public class Drivetrain extends SubsystemBase {
|
|||||||
Logger.recordOutput("orange dist", vision.getOrangeDist());
|
Logger.recordOutput("orange dist", vision.getOrangeDist());
|
||||||
Logger.recordOutput("orange detected", vision.getOrangeTagDetected());
|
Logger.recordOutput("orange detected", vision.getOrangeTagDetected());
|
||||||
Logger.recordOutput("orange tag", vision.getOrangeTagDetected());
|
Logger.recordOutput("orange tag", vision.getOrangeTagDetected());
|
||||||
|
Logger.recordOutput("orange FPS", vision.getOrangeFPS());
|
||||||
|
|
||||||
|
|
||||||
if(vision.getBlackTagDetected() && vision.getBlackTagDetected()){
|
if(vision.getBlackTagDetected() && vision.getBlackTagDetected()){
|
||||||
if(vision.getBlackDist() < 60 && Math.abs(getVelocity()) < 3){
|
if(vision.getBlackDist() < 60 && Math.abs(getVelocity()) < 3){
|
||||||
m_estimator.setVisionMeasurementStdDevs(VecBuilder.fill(0.02, 0.02, Units.degreesToRadians(4000)));
|
m_estimator.setVisionMeasurementStdDevs(VecBuilder.fill(0.03, 0.03, Units.degreesToRadians(360)));
|
||||||
}else if(vision.getBlackDist() < 100 && Math.abs(getVelocity()) < 3){
|
}else if(vision.getBlackDist() < 100 && Math.abs(getVelocity()) < 3){
|
||||||
m_estimator.setVisionMeasurementStdDevs(VecBuilder.fill(0.05, 0.05, Units.degreesToRadians(4000)));
|
m_estimator.setVisionMeasurementStdDevs(VecBuilder.fill(0.05, 0.05, Units.degreesToRadians(360)));
|
||||||
}else if(vision.getBlackDist() < 60 && Math.abs(getVelocity()) > 3){
|
}else if(vision.getBlackDist() < 60 && Math.abs(getVelocity()) > 3){
|
||||||
m_estimator.setVisionMeasurementStdDevs(VecBuilder.fill(0.2, 0.2, Units.degreesToRadians(4000)));
|
m_estimator.setVisionMeasurementStdDevs(VecBuilder.fill(0.2, 0.2, Units.degreesToRadians(360)));
|
||||||
}else if(vision.getBlackDist() < 100 && Math.abs(getVelocity()) > 3){
|
}else if(vision.getBlackDist() < 100 && Math.abs(getVelocity()) > 3){
|
||||||
m_estimator.setVisionMeasurementStdDevs(VecBuilder.fill(0.3, 0.3, Units.degreesToRadians(4000)));
|
m_estimator.setVisionMeasurementStdDevs(VecBuilder.fill(0.3, 0.3, Units.degreesToRadians(360)));
|
||||||
}
|
}
|
||||||
|
|
||||||
if(vision.getBlackClosestTag() >= 6 && vision.getBlackClosestTag() <= 11 && DriverStation.getAlliance().get().equals(Alliance.Red) && vision.getBlackTagDetected()){
|
if(vision.getBlackClosestTag() >= 6 && vision.getBlackClosestTag() <= 11 && DriverStation.getAlliance().get().equals(Alliance.Red) && vision.getBlackTagDetected()){
|
||||||
@@ -230,6 +231,7 @@ public class Drivetrain extends SubsystemBase {
|
|||||||
Logger.recordOutput("black dist", vision.getBlackDist());
|
Logger.recordOutput("black dist", vision.getBlackDist());
|
||||||
Logger.recordOutput("black detected", vision.getBlackTagDetected());
|
Logger.recordOutput("black detected", vision.getBlackTagDetected());
|
||||||
Logger.recordOutput("black tag", vision.getBlackTagDetected());
|
Logger.recordOutput("black tag", vision.getBlackTagDetected());
|
||||||
|
Logger.recordOutput("black FPS", vision.getBlackFPS());
|
||||||
|
|
||||||
Logger.recordOutput("drive velocity", getVelocity());
|
Logger.recordOutput("drive velocity", getVelocity());
|
||||||
Logger.recordOutput("closest tag", getClosestTag());
|
Logger.recordOutput("closest tag", getClosestTag());
|
||||||
@@ -321,8 +323,18 @@ public class Drivetrain extends SubsystemBase {
|
|||||||
*/
|
*/
|
||||||
public void drive(double xSpeed, double ySpeed, double rot, boolean fieldRelative) {
|
public void drive(double xSpeed, double ySpeed, double rot, boolean fieldRelative) {
|
||||||
// Convert the commanded speeds into the correct units for the drivetrain
|
// Convert the commanded speeds into the correct units for the drivetrain
|
||||||
double xSpeedDelivered = xSpeed * DrivetrainConstants.kMaxSpeedMetersPerSecond;
|
double p = Math.sqrt(Math.pow(xSpeed, 2) + Math.pow(ySpeed, 2));
|
||||||
double ySpeedDelivered = ySpeed * DrivetrainConstants.kMaxSpeedMetersPerSecond;
|
double xSpeedDelivered = 0;
|
||||||
|
double ySpeedDelivered = 0;
|
||||||
|
|
||||||
|
if(p != 0){
|
||||||
|
xSpeedDelivered = xSpeed * (Math.pow(p, OIConstants.kJoystickExponential) / p) * DrivetrainConstants.kMaxSpeedMetersPerSecond;
|
||||||
|
ySpeedDelivered = ySpeed * (Math.pow(p, OIConstants.kJoystickExponential) / p) * DrivetrainConstants.kMaxSpeedMetersPerSecond;
|
||||||
|
}else{
|
||||||
|
xSpeedDelivered = 0;
|
||||||
|
ySpeedDelivered = 0;
|
||||||
|
}
|
||||||
|
|
||||||
double rotDelivered = rot * DrivetrainConstants.kMaxAngularSpeed;
|
double rotDelivered = rot * DrivetrainConstants.kMaxAngularSpeed;
|
||||||
|
|
||||||
var swerveModuleStates = DrivetrainConstants.kDriveKinematics.toSwerveModuleStates(
|
var swerveModuleStates = DrivetrainConstants.kDriveKinematics.toSwerveModuleStates(
|
||||||
@@ -360,8 +372,8 @@ public class Drivetrain extends SubsystemBase {
|
|||||||
);
|
);
|
||||||
|
|
||||||
double speed = Math.hypot(controlEffort.vxMetersPerSecond, controlEffort.vyMetersPerSecond);
|
double speed = Math.hypot(controlEffort.vxMetersPerSecond, controlEffort.vyMetersPerSecond);
|
||||||
if (speed > AutoConstants.kMaxSpeedMetersPerSecond) {
|
if (speed > AutoConstants.kMaxSpeedMetersPerSecondAutoAlign) {
|
||||||
double mul = AutoConstants.kMaxSpeedMetersPerSecond / speed;
|
double mul = AutoConstants.kMaxSpeedMetersPerSecondAutoAlign / speed;
|
||||||
controlEffort.vxMetersPerSecond *= mul;
|
controlEffort.vxMetersPerSecond *= mul;
|
||||||
controlEffort.vyMetersPerSecond *= mul;
|
controlEffort.vyMetersPerSecond *= mul;
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -253,6 +253,64 @@ public class Elevator extends SubsystemBase {
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
public Command goToSetpointAlgae(DoubleSupplier setpoint) {
|
||||||
|
|
||||||
|
if (setpoint.getAsDouble() == 0) {
|
||||||
|
return startRun(() -> {
|
||||||
|
|
||||||
|
pidControllerUp.reset();
|
||||||
|
pidControllerDown.reset();
|
||||||
|
pidControllerUp.setSetpoint(setpoint.getAsDouble());
|
||||||
|
pidControllerDown.setSetpoint(setpoint.getAsDouble());
|
||||||
|
|
||||||
|
},
|
||||||
|
() -> {
|
||||||
|
double upOutput = pidControllerUp.calculate(getEncoderPosition());
|
||||||
|
double downOutput = pidControllerDown.calculate(getEncoderPosition());
|
||||||
|
|
||||||
|
if(setpoint.getAsDouble()>encoder.getPosition())
|
||||||
|
elevatorMotor1.setVoltage( MathUtil.clamp(
|
||||||
|
upOutput + feedForward.calculate(0), ElevatorConstants.kVoltageLimitAlgae * -1, ElevatorConstants.kVoltageLimitAlgae)
|
||||||
|
);
|
||||||
|
else{
|
||||||
|
elevatorMotor1.setVoltage(
|
||||||
|
MathUtil.clamp(
|
||||||
|
downOutput + feedForward.calculate(0), ElevatorConstants.kVoltageLimitAlgae * -1, ElevatorConstants.kVoltageLimitAlgae)
|
||||||
|
);
|
||||||
|
}
|
||||||
|
|
||||||
|
}).until(() -> pidControllerUp.atSetpoint() || pidControllerDown.atSetpoint())
|
||||||
|
.andThen(runManualElevator(() -> -.5)
|
||||||
|
.until(() -> encoder.getPosition() == 0));
|
||||||
|
|
||||||
|
} else {
|
||||||
|
return startRun(() -> {
|
||||||
|
|
||||||
|
pidControllerUp.reset();
|
||||||
|
pidControllerDown.reset();
|
||||||
|
pidControllerUp.setSetpoint(setpoint.getAsDouble());
|
||||||
|
pidControllerDown.setSetpoint(setpoint.getAsDouble());
|
||||||
|
|
||||||
|
},
|
||||||
|
() -> {
|
||||||
|
double upOutput = pidControllerUp.calculate(getEncoderPosition());
|
||||||
|
double downOutput = pidControllerDown.calculate(getEncoderPosition());
|
||||||
|
|
||||||
|
if(setpoint.getAsDouble()>encoder.getPosition())
|
||||||
|
elevatorMotor1.setVoltage( MathUtil.clamp(
|
||||||
|
upOutput + feedForward.calculate(0), ElevatorConstants.kVoltageLimitAlgae * -1, ElevatorConstants.kVoltageLimitAlgae)
|
||||||
|
);
|
||||||
|
else{
|
||||||
|
elevatorMotor1.setVoltage(
|
||||||
|
MathUtil.clamp(
|
||||||
|
downOutput + feedForward.calculate(0), ElevatorConstants.kVoltageLimitAlgae * -1, ElevatorConstants.kVoltageLimitAlgae)
|
||||||
|
);
|
||||||
|
}
|
||||||
|
|
||||||
|
}).until(() -> pidControllerUp.atSetpoint() || pidControllerDown.atSetpoint());
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Returns the current encoder position
|
* Returns the current encoder position
|
||||||
*
|
*
|
||||||
|
|||||||
Reference in New Issue
Block a user