Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
8 changes: 4 additions & 4 deletions src/main/java/frc/robot/subsystems/Arm.java
Original file line number Diff line number Diff line change
Expand Up @@ -6,14 +6,13 @@

import com.ctre.phoenix6.CANBus;
import com.ctre.phoenix6.configs.TalonFXConfiguration;
import com.ctre.phoenix6.controls.PositionVoltage;
import com.ctre.phoenix6.controls.MotionMagicVoltage;
import com.ctre.phoenix6.hardware.CANcoder;
import com.ctre.phoenix6.hardware.TalonFX;
import com.ctre.phoenix6.signals.FeedbackSensorSourceValue;
import com.ctre.phoenix6.signals.GravityTypeValue;
import com.ctre.phoenix6.signals.InvertedValue;
import com.ctre.phoenix6.signals.NeutralModeValue;
import com.ctre.phoenix6.signals.StaticFeedforwardSignValue;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.SubsystemBase;

Expand All @@ -27,7 +26,7 @@ public class Arm extends SubsystemBase {
private final CANcoder encoder = new CANcoder(32, canivore);

// Position output control for the arm
private final PositionVoltage positionOut = new PositionVoltage(0);
private final MotionMagicVoltage positionOut = new MotionMagicVoltage(0);

public Arm() {
// Create and apply the configuration for the leader motor
Expand All @@ -41,7 +40,8 @@ public Arm() {
config.Slot0.kS = 0.0; // Static gain
config.Slot0.kP = 0.0; // Proportional gain
config.Slot0.kD = 0.0; // Derivative gain
config.Slot0.StaticFeedforwardSign = StaticFeedforwardSignValue.UseClosedLoopSign;
config.MotionMagic.MotionMagicCruiseVelocity = 0.0; // Max velocity
config.MotionMagic.MotionMagicAcceleration = 0.0; // Max acceleration allowed
// Configure the leader motor to use the CANcoder for position feedback
config.Feedback.FeedbackSensorSource = FeedbackSensorSourceValue.RemoteCANcoder;
config.Feedback.FeedbackRemoteSensorID = encoder.getDeviceID();
Expand Down
6 changes: 4 additions & 2 deletions src/main/java/frc/robot/subsystems/Flywheel.java
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@
import com.ctre.phoenix6.CANBus;
import com.ctre.phoenix6.configs.TalonFXConfiguration;
import com.ctre.phoenix6.controls.Follower;
import com.ctre.phoenix6.controls.VelocityVoltage;
import com.ctre.phoenix6.controls.MotionMagicVelocityVoltage;
import com.ctre.phoenix6.hardware.TalonFX;
import com.ctre.phoenix6.signals.InvertedValue;
import com.ctre.phoenix6.signals.NeutralModeValue;
Expand All @@ -24,7 +24,7 @@ public class Flywheel extends SubsystemBase {
private final TalonFX follower = new TalonFX(22, canivore);

// Velocity output control for the flywheel
private final VelocityVoltage velocityOut = new VelocityVoltage(0);
private final MotionMagicVelocityVoltage velocityOut = new MotionMagicVelocityVoltage(0);

public Flywheel() {
// Set the follower to follow the leader motor
Expand All @@ -38,6 +38,8 @@ public Flywheel() {
config.Slot0.kS = 0.0; // Static gain
config.Slot0.kV = 0.0; // Velocity gain
config.Slot0.kP = 0.0; // Proportional gain
config.MotionMagic.MotionMagicCruiseVelocity = 0.0; // Max velocity
config.MotionMagic.MotionMagicAcceleration = 0.0; // Max acceleration allowed
// Try to apply config multiple time. Break after successfully applying
for (int i = 0; i < 2; ++i) {
var status = leader.getConfigurator().apply(config);
Expand Down