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
2 changes: 1 addition & 1 deletion Java General/MotionMagic/.wpilib/wpilib_preferences.json
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
{
"enableCppIntellisense": false,
"currentLanguage": "java",
"projectYear": "Beta2020-2",
"projectYear": "2020",
"teamNumber": 1718
}
2 changes: 1 addition & 1 deletion Java General/MotionMagic/build.gradle
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
plugins {
id "java"
id "edu.wpi.first.GradleRIO" version "2020.1.2"
id "edu.wpi.first.GradleRIO" version "2020.3.2"
}

sourceCompatibility = JavaVersion.VERSION_11
Expand Down
34 changes: 26 additions & 8 deletions Java General/MotionMagic/src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -67,6 +67,7 @@
import com.ctre.phoenix.motorcontrol.can.*;
import com.ctre.phoenix.motorcontrol.ControlMode;
import com.ctre.phoenix.motorcontrol.FeedbackDevice;
import com.ctre.phoenix.motorcontrol.NeutralMode;
import com.ctre.phoenix.motorcontrol.StatusFrameEnhanced;

public class Robot extends TimedRobot {
Expand Down Expand Up @@ -113,8 +114,8 @@ public void robotInit() {
* have green LEDs when driving Talon Forward / Requesting Postiive Output Phase
* sensor to have positive increment when driving Talon Forward (Green LED)
*/
_talon.setSensorPhase(false);
_talon.setInverted(false);
_talon.setSensorPhase( false );
_talon.setInverted( false );

/* Set relevant frame periods to be at least as fast as periodic rate */
_talon.setStatusFramePeriod(StatusFrameEnhanced.Status_13_Base_PIDF0, 10, Constants.kTimeoutMs);
Expand All @@ -134,11 +135,26 @@ public void robotInit() {
_talon.config_kD(Constants.kSlotIdx, Constants.kGains.kD, Constants.kTimeoutMs);

/* Set acceleration and vcruise velocity - see documentation */
_talon.configMotionCruiseVelocity(15000, Constants.kTimeoutMs);
_talon.configMotionAcceleration(6000, Constants.kTimeoutMs);
_talon.configMotionCruiseVelocity( 15000, Constants.kTimeoutMs);
_talon.configMotionAcceleration( 6000, Constants.kTimeoutMs);

/* Zero the sensor once on robot boot up */
_talon.setSelectedSensorPosition(0, Constants.kPIDLoopIdx, Constants.kTimeoutMs);

/* Use for sensors that don't role over back to Zero similar to a Potentiometer */
//_talon.configFeedbackNotContinuous(true, Constants.kTimeoutMs);

/* Zero Encoder on Reverce Limit switch or Forward Limit switch*/
//_talon.configClearPositionOnLimitR(true, Constants.kTimeoutMs);
//_talon.configClearPositionOnLimitF(true, Constants.kTimeoutMs);

/* Configure Current Limits */
//_talon.configPeakCurrentLimit(30);
//_talon.configPeakCurrentDuration(150);
// _talon.configContinuousCurrentLimit(20);

// put all Talon SRX into brake mode
//_talon.setNeutralMode(NeutralMode.Brake);
}

/**
Expand All @@ -155,10 +171,12 @@ public void teleopPeriodic() {
double motorOutput = _talon.getMotorOutputPercent();

/* Prepare line to print */
_sb.append("\tOut%:");
_sb.append("\t Out%:");
_sb.append(motorOutput);
_sb.append("\tVel:");
_sb.append("\t Vel:");
_sb.append(_talon.getSelectedSensorVelocity(Constants.kPIDLoopIdx));
_sb.append("\t Current Pos:");
_sb.append(_talon.getSelectedSensorPosition());

/**
* Peform Motion Magic when Button 1 is held, else run Percent Output, which can
Expand All @@ -172,9 +190,9 @@ public void teleopPeriodic() {
_talon.set(ControlMode.MotionMagic, targetPos);

/* Append more signals to print when in speed mode */
_sb.append("\terr:");
_sb.append("\t err:");
_sb.append(_talon.getClosedLoopError(Constants.kPIDLoopIdx));
_sb.append("\ttrg:");
_sb.append("\t trg:");
_sb.append(targetPos);
} else {
/* Percent Output */
Expand Down