Skip to content

Commit

Permalink
deleted follower motor's bounds
Browse files Browse the repository at this point in the history
  • Loading branch information
stwiggy committed Mar 3, 2024
1 parent a0e46b3 commit ff6a115
Showing 1 changed file with 3 additions and 3 deletions.
6 changes: 3 additions & 3 deletions src/main/java/org/carlmontrobotics/subsystems/Arm.java
Original file line number Diff line number Diff line change
Expand Up @@ -104,9 +104,9 @@ public Arm() {
armPIDMaster.setPositionPIDWrappingMaxInput(UPPER_ANGLE_LIMIT);
//two PIDs?
armPIDFollower.setFeedbackDevice(armMotorFollower.getEncoder());
armPIDFollower.setPositionPIDWrappingEnabled(true);
armPIDFollower.setPositionPIDWrappingMinInput(LOWER_ANGLE_LIMIT - Math.PI); //Wierd math, im not sure it this works but basically
armPIDFollower.setPositionPIDWrappingMaxInput(UPPER_ANGLE_LIMIT - Math.PI);// since absolute is between -180 and 180 and relative is between 0 and 360(correct me if im wrong) so if we subract 180, then its the same
// armPIDFollower.setPositionPIDWrappingEnabled(true);
// armPIDFollower.setPositionPIDWrappingMinInput(LOWER_ANGLE_LIMIT - Math.PI); //Wierd math, im not sure it this works but basically
// armPIDFollower.setPositionPIDWrappingMaxInput(UPPER_ANGLE_LIMIT - Math.PI);// since absolute is between -180 and 180 and relative is between 0 and 360(correct me if im wrong) so if we subract 180, then its the same

SmartDashboard.putData("Arm", this);

Expand Down

0 comments on commit ff6a115

Please sign in to comment.