Skip to content
Merged
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: 2 additions & 0 deletions lib/cpp/subzero/motor/PidMotorController.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -182,6 +182,8 @@ void PidMotorController<TMotor, TController, TRelativeEncoder, TAbsoluteEncoder,
rev::spark::SparkBase::ResetMode::kNoResetSafeParameters,
rev::spark::SparkBase::PersistMode::kPersistParameters);
m_isInitialized = true;

std::cout << "Updated PID settings." << std::endl;
}

m_settings = settings;
Expand Down
13 changes: 10 additions & 3 deletions lib/include/subzero/motor/PidMotorController.h
Original file line number Diff line number Diff line change
Expand Up @@ -185,6 +185,7 @@ class PidMotorControllerTuner {
PidMotorController<TMotor, TController, TRelativeEncoder,
TAbsoluteEncoder, TPidConfig> &controller)
: m_controller{controller} {

frc::SmartDashboard::PutNumber(m_controller.m_name + " P Gain",
m_controller.GetPidSettings().p);
frc::SmartDashboard::PutNumber(m_controller.m_name + " I Gain",
Expand All @@ -199,8 +200,9 @@ class PidMotorControllerTuner {

/**
* @brief Call this within the Periodic method of the encapsulating subsystem
*
* Note: You must enable submit button to work in Elastic
*/

void UpdateFromShuffleboard() {
double tP = frc::SmartDashboard::GetNumber(m_controller.m_name + " P Gain",
m_controller.GetPidSettings().p);
Expand All @@ -215,12 +217,17 @@ class PidMotorControllerTuner {
m_controller.GetPidSettings().ff);

m_controller.UpdatePidSettings(
{.p = tP, .i = tI, .d = tD, .iZone = tIZone, .ff = tFeedForward});
{.p = tP,
.i = tI,
.d = tD,
.iZone = tIZone,
.ff = tFeedForward,
.isIdleModeBrake = m_controller.GetPidSettings().isIdleModeBrake});
}

private:
PidMotorController<TMotor, TController, TRelativeEncoder, TAbsoluteEncoder,
rev::spark::SparkFlexConfig> &m_controller;
TPidConfig> &m_controller;
};

class RevPidMotorController
Expand Down