Skip to content

Commit

Permalink
Rename m_applyRobotSpeeds and m_applyFieldSpeeds to mention path foll…
Browse files Browse the repository at this point in the history
…owing
  • Loading branch information
bhall-ctre committed Oct 31, 2024
1 parent c3385ff commit 53fa17b
Show file tree
Hide file tree
Showing 6 changed files with 12 additions and 12 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@ void CommandSwerveDrivetrain::FollowPath(frc::Pose2d const &pose, choreo::Swerve
std::vector moduleForcesY(sample.moduleForcesY.begin(), sample.moduleForcesY.end());

SetControl(
m_applyFieldSpeeds.WithSpeeds(targetSpeeds)
m_pathApplyFieldSpeeds.WithSpeeds(targetSpeeds)
.WithWheelForceFeedforwardsX(std::move(moduleForcesX))
.WithWheelForceFeedforwardsY(std::move(moduleForcesY))
);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -31,8 +31,8 @@ class CommandSwerveDrivetrain : public frc2::SubsystemBase, public swerve::Swerv
/* Keep track if we've ever applied the operator perspective before or not */
bool m_hasAppliedOperatorPerspective = false;

/* Swerve request to apply during path following */
swerve::requests::ApplyFieldSpeeds m_applyFieldSpeeds;
/** Swerve request to apply during field-centric path following */
swerve::requests::ApplyFieldSpeeds m_pathApplyFieldSpeeds;
frc::PIDController m_pathXController{10, 0, 0};
frc::PIDController m_pathYController{10, 0, 0};
frc::PIDController m_pathThetaController{7, 0, 0};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@ void CommandSwerveDrivetrain::ConfigureAutoBuilder()
// Consumer of ChassisSpeeds and feedforwards to drive the robot
[this](frc::ChassisSpeeds const &speeds, pathplanner::DriveFeedforwards const &feedforwards) {
return SetControl(
m_applyRobotSpeeds.WithSpeeds(speeds)
m_pathApplyRobotSpeeds.WithSpeeds(speeds)
.WithWheelForceFeedforwardsX(feedforwards.robotRelativeForcesX)
.WithWheelForceFeedforwardsY(feedforwards.robotRelativeForcesY)
);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -29,8 +29,8 @@ class CommandSwerveDrivetrain : public frc2::SubsystemBase, public swerve::Swerv
/* Keep track if we've ever applied the operator perspective before or not */
bool m_hasAppliedOperatorPerspective = false;

/* Swerve request to apply during path following */
swerve::requests::ApplyRobotSpeeds m_applyRobotSpeeds;
/** Swerve request to apply during robot-centric path following */
swerve::requests::ApplyRobotSpeeds m_pathApplyRobotSpeeds;

/* Swerve requests to apply during SysId characterization */
swerve::requests::SysIdSwerveTranslation m_translationCharacterization;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -42,8 +42,8 @@ public class CommandSwerveDrivetrain extends SwerveDrivetrain implements Subsyst
/* Keep track if we've ever applied the operator perspective before or not */
private boolean m_hasAppliedOperatorPerspective = false;

/* Swerve request to apply during path following */
private final SwerveRequest.ApplyFieldSpeeds m_applyFieldSpeeds = new SwerveRequest.ApplyFieldSpeeds();
/** Swerve request to apply during field-centric path following */
private final SwerveRequest.ApplyFieldSpeeds m_pathApplyFieldSpeeds = new SwerveRequest.ApplyFieldSpeeds();
private final PIDController m_pathXController = new PIDController(10, 0, 0);
private final PIDController m_pathYController = new PIDController(10, 0, 0);
private final PIDController m_pathThetaController = new PIDController(7, 0, 0);
Expand Down Expand Up @@ -208,7 +208,7 @@ public void followPath(Pose2d pose, SwerveSample sample) {
);

setControl(
m_applyFieldSpeeds.withSpeeds(targetSpeeds)
m_pathApplyFieldSpeeds.withSpeeds(targetSpeeds)
.withWheelForceFeedforwardsX(sample.moduleForcesX())
.withWheelForceFeedforwardsY(sample.moduleForcesY())
);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -44,8 +44,8 @@ public class CommandSwerveDrivetrain extends SwerveDrivetrain implements Subsyst
/* Keep track if we've ever applied the operator perspective before or not */
private boolean m_hasAppliedOperatorPerspective = false;

/* Swerve request to apply during path following */
private final SwerveRequest.ApplyRobotSpeeds m_applyRobotSpeeds = new SwerveRequest.ApplyRobotSpeeds();
/** Swerve request to apply during robot-centric path following */
private final SwerveRequest.ApplyRobotSpeeds m_pathApplyRobotSpeeds = new SwerveRequest.ApplyRobotSpeeds();

/* Swerve requests to apply during SysId characterization */
private final SwerveRequest.SysIdSwerveTranslation m_translationCharacterization = new SwerveRequest.SysIdSwerveTranslation();
Expand Down Expand Up @@ -188,7 +188,7 @@ private void configureAutoBuilder() {
() -> getState().Speeds, // Supplier of current robot speeds
// Consumer of ChassisSpeeds and feedforwards to drive the robot
(speeds, feedforwards) -> setControl(
m_applyRobotSpeeds.withSpeeds(speeds)
m_pathApplyRobotSpeeds.withSpeeds(speeds)
.withWheelForceFeedforwardsX(feedforwards.robotRelativeForcesXNewtons())
.withWheelForceFeedforwardsY(feedforwards.robotRelativeForcesYNewtons())
),
Expand Down

0 comments on commit 53fa17b

Please sign in to comment.