Skip to content

Commit 4efa3c3

Browse files
committed
Remove m_ from all examples
1 parent b7feedf commit 4efa3c3

346 files changed

Lines changed: 3887 additions & 3989 deletions

File tree

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

robotpyExamples/DifferentialDrivePoseEstimator/robot.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -17,7 +17,7 @@ def __init__(self) -> None:
1717
super().__init__()
1818

1919
self.inst = ntcore.NetworkTableInstance.getDefault()
20-
self.doubleArrayTopic = self.inst.getDoubleArrayTopic("m_doubleArrayTopic")
20+
self.doubleArrayTopic = self.inst.getDoubleArrayTopic("doubleArrayTopic")
2121

2222
self.controller = wpilib.NiDsXboxController(0)
2323
self.drive = Drivetrain(self.doubleArrayTopic)

robotpyExamples/SwerveDrivePoseEstimator/swervemodule.py

Lines changed: 6 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -112,21 +112,17 @@ def setDesiredVelocity(self, desiredVelocity: wpimath.SwerveModuleVelocity) -> N
112112
encoderRotation
113113
)
114114

115-
# Calculate the drive output from the drive PID controller.
115+
# Calculate the drive output from the drive PID controller and feedforward.
116116
driveOutput = self.drivePIDController.calculate(
117117
self.driveEncoder.getRate(), velocity.velocity
118-
)
119-
120-
driveFeedforward = self.driveFeedforward.calculate(velocity.velocity)
118+
) + self.driveFeedforward.calculate(velocity.velocity)
121119

122-
# Calculate the turning motor output from the turning PID controller.
120+
# Calculate the turning motor output from the turning PID controller and feedforward.
123121
turnOutput = self.turningPIDController.calculate(
124122
self.turningEncoder.getDistance(), velocity.angle.radians()
125-
)
126-
127-
turnFeedforward = self.turnFeedforward.calculate(
123+
) + self.turnFeedforward.calculate(
128124
self.turningPIDController.getSetpoint().velocity
129125
)
130126

131-
self.driveMotor.setVoltage(driveOutput + driveFeedforward)
132-
self.turningMotor.setVoltage(turnOutput + turnFeedforward)
127+
self.driveMotor.setVoltage(driveOutput)
128+
self.turningMotor.setVoltage(turnOutput)

shared/java/javastyle.gradle

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -89,4 +89,4 @@ task javaFormat {
8989
javaFormat.dependsOn 'spotlessApply'
9090
tasks.withType(Checkstyle) {
9191
it.mustRunAfter 'spotlessApply'
92-
}
92+
}

styleguide/pmd-ruleset.xml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -12,7 +12,7 @@
1212
<exclude-pattern>.*/Timestamped.*\.java</exclude-pattern>
1313
<exclude-pattern>.*/units/measure/.*\.java</exclude-pattern>
1414

15-
<exclude-pattern>.*/*IntegrationTests.*</exclude-pattern>
15+
<exclude-pattern>.*/*Examples.*</exclude-pattern>
1616
<exclude-pattern>.*/*JNI.*</exclude-pattern>
1717
<exclude-pattern>.*/math/proto.*</exclude-pattern>
1818
<exclude-pattern>.*/command3/proto.*</exclude-pattern>

wpilibcExamples/src/main/cpp/examples/ArcadeDriveGamepad/cpp/Robot.cpp

Lines changed: 11 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -12,30 +12,30 @@
1212
* Runs the motors with split arcade steering and a Gamepad.
1313
*/
1414
class Robot : public wpi::TimedRobot {
15-
wpi::PWMSparkMax m_leftMotor{0};
16-
wpi::PWMSparkMax m_rightMotor{1};
17-
wpi::DifferentialDrive m_robotDrive{
18-
[&](double output) { m_leftMotor.SetThrottle(output); },
19-
[&](double output) { m_rightMotor.SetThrottle(output); }};
20-
wpi::Gamepad m_driverController{0};
15+
wpi::PWMSparkMax leftMotor{0};
16+
wpi::PWMSparkMax rightMotor{1};
17+
wpi::DifferentialDrive robotDrive{
18+
[&](double output) { leftMotor.SetThrottle(output); },
19+
[&](double output) { rightMotor.SetThrottle(output); }};
20+
wpi::Gamepad driverController{0};
2121

2222
public:
2323
Robot() {
24-
wpi::util::SendableRegistry::AddChild(&m_robotDrive, &m_leftMotor);
25-
wpi::util::SendableRegistry::AddChild(&m_robotDrive, &m_rightMotor);
24+
wpi::util::SendableRegistry::AddChild(&robotDrive, &leftMotor);
25+
wpi::util::SendableRegistry::AddChild(&robotDrive, &rightMotor);
2626

2727
// We need to invert one side of the drivetrain so that positive voltages
2828
// result in both sides moving forward. Depending on how your robot's
2929
// gearbox is constructed, you might have to invert the left side instead.
30-
m_rightMotor.SetInverted(true);
30+
rightMotor.SetInverted(true);
3131
}
3232

3333
void TeleopPeriodic() override {
3434
// Drive with split arcade style
3535
// That means that the Y axis of the left stick moves forward
3636
// and backward, and the X of the right stick turns left and right.
37-
m_robotDrive.ArcadeDrive(-m_driverController.GetLeftY(),
38-
-m_driverController.GetRightX());
37+
robotDrive.ArcadeDrive(-driverController.GetLeftY(),
38+
-driverController.GetRightX());
3939
}
4040
};
4141

wpilibcExamples/src/main/cpp/examples/ArmSimulation/cpp/Robot.cpp

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -5,26 +5,26 @@
55
#include "Robot.hpp"
66

77
void Robot::SimulationPeriodic() {
8-
m_arm.SimulationPeriodic();
8+
arm.SimulationPeriodic();
99
}
1010

1111
void Robot::TeleopInit() {
12-
m_arm.LoadPreferences();
12+
arm.LoadPreferences();
1313
}
1414

1515
void Robot::TeleopPeriodic() {
16-
if (m_joystick.GetTrigger()) {
16+
if (joystick.GetTrigger()) {
1717
// Here, we run PID control like normal.
18-
m_arm.ReachSetpoint();
18+
arm.ReachSetpoint();
1919
} else {
2020
// Otherwise, we disable the motor.
21-
m_arm.Stop();
21+
arm.Stop();
2222
}
2323
}
2424

2525
void Robot::DisabledInit() {
2626
// This just makes sure that our simulation code knows that the motor's off.
27-
m_arm.Stop();
27+
arm.Stop();
2828
}
2929

3030
#ifndef RUNNING_WPILIB_TESTS

wpilibcExamples/src/main/cpp/examples/ArmSimulation/cpp/subsystems/Arm.cpp

Lines changed: 19 additions & 19 deletions
Original file line numberDiff line numberDiff line change
@@ -9,55 +9,55 @@
99
#include "wpi/util/Preferences.hpp"
1010

1111
Arm::Arm() {
12-
m_encoder.SetDistancePerPulse(kArmEncoderDistPerPulse);
12+
encoder.SetDistancePerPulse(kArmEncoderDistPerPulse);
1313

1414
// Put Mechanism 2d to SmartDashboard
15-
wpi::SmartDashboard::PutData("Arm Sim", &m_mech2d);
15+
wpi::SmartDashboard::PutData("Arm Sim", &mech2d);
1616

1717
// Set the Arm position setpoint and P constant to Preferences if the keys
1818
// don't already exist
19-
wpi::Preferences::InitDouble(kArmPositionKey, m_armSetpoint.value());
20-
wpi::Preferences::InitDouble(kArmPKey, m_armKp);
19+
wpi::Preferences::InitDouble(kArmPositionKey, armSetpoint.value());
20+
wpi::Preferences::InitDouble(kArmPKey, armKp);
2121
}
2222

2323
void Arm::SimulationPeriodic() {
2424
// In this method, we update our simulation of what our arm is doing
2525
// First, we set our "inputs" (voltages)
26-
m_armSim.SetInput(wpi::math::Vectord<1>{
27-
m_motor.GetThrottle() * wpi::RobotController::GetInputVoltage()});
26+
armSim.SetInput(wpi::math::Vectord<1>{
27+
motor.GetThrottle() * wpi::RobotController::GetInputVoltage()});
2828

2929
// Next, we update it. The standard loop time is 20ms.
30-
m_armSim.Update(20_ms);
30+
armSim.Update(20_ms);
3131

3232
// Finally, we set our simulated encoder's readings and simulated battery
3333
// voltage
34-
m_encoderSim.SetDistance(m_armSim.GetAngle().value());
34+
encoderSim.SetDistance(armSim.GetAngle().value());
3535
// SimBattery estimates loaded battery voltages
3636
wpi::sim::RoboRioSim::SetVInVoltage(
37-
wpi::sim::BatterySim::Calculate({m_armSim.GetCurrentDraw()}));
37+
wpi::sim::BatterySim::Calculate({armSim.GetCurrentDraw()}));
3838

3939
// Update the Mechanism Arm angle based on the simulated arm angle
40-
m_arm->SetAngle(m_armSim.GetAngle());
40+
arm->SetAngle(armSim.GetAngle());
4141
}
4242

4343
void Arm::LoadPreferences() {
4444
// Read Preferences for Arm setpoint and kP on entering Teleop
45-
m_armSetpoint = wpi::units::degree_t{
46-
wpi::Preferences::GetDouble(kArmPositionKey, m_armSetpoint.value())};
47-
if (m_armKp != wpi::Preferences::GetDouble(kArmPKey, m_armKp)) {
48-
m_armKp = wpi::Preferences::GetDouble(kArmPKey, m_armKp);
49-
m_controller.SetP(m_armKp);
45+
armSetpoint = wpi::units::degree_t{
46+
wpi::Preferences::GetDouble(kArmPositionKey, armSetpoint.value())};
47+
if (armKp != wpi::Preferences::GetDouble(kArmPKey, armKp)) {
48+
armKp = wpi::Preferences::GetDouble(kArmPKey, armKp);
49+
controller.SetP(armKp);
5050
}
5151
}
5252

5353
void Arm::ReachSetpoint() {
5454
// Here, we run PID control like normal, with a setpoint read from
5555
// preferences in degrees.
56-
double pidOutput = m_controller.Calculate(
57-
m_encoder.GetDistance(), (wpi::units::radian_t{m_armSetpoint}.value()));
58-
m_motor.SetVoltage(wpi::units::volt_t{pidOutput});
56+
double pidOutput = controller.Calculate(
57+
encoder.GetDistance(), (wpi::units::radian_t{armSetpoint}.value()));
58+
motor.SetVoltage(wpi::units::volt_t{pidOutput});
5959
}
6060

6161
void Arm::Stop() {
62-
m_motor.SetThrottle(0.0);
62+
motor.SetThrottle(0.0);
6363
}

wpilibcExamples/src/main/cpp/examples/ArmSimulation/include/Robot.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -20,6 +20,6 @@ class Robot : public wpi::TimedRobot {
2020
void DisabledInit() override;
2121

2222
private:
23-
wpi::Joystick m_joystick{kJoystickPort};
24-
Arm m_arm;
23+
wpi::Joystick joystick{kJoystickPort};
24+
Arm arm;
2525
};

wpilibcExamples/src/main/cpp/examples/ArmSimulation/include/subsystems/Arm.hpp

Lines changed: 15 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -29,23 +29,23 @@ class Arm {
2929

3030
private:
3131
// The P gain for the PID controller that drives this arm.
32-
double m_armKp = kDefaultArmKp;
33-
wpi::units::degree_t m_armSetpoint = kDefaultArmSetpoint;
32+
double armKp = kDefaultArmKp;
33+
wpi::units::degree_t armSetpoint = kDefaultArmSetpoint;
3434

3535
// The arm gearbox represents a gearbox containing two Vex 775pro motors.
36-
wpi::math::DCMotor m_armGearbox = wpi::math::DCMotor::Vex775Pro(2);
36+
wpi::math::DCMotor armGearbox = wpi::math::DCMotor::Vex775Pro(2);
3737

3838
// Standard classes for controlling our arm
39-
wpi::math::PIDController m_controller{m_armKp, 0, 0};
40-
wpi::Encoder m_encoder{kEncoderAChannel, kEncoderBChannel};
41-
wpi::PWMSparkMax m_motor{kMotorPort};
39+
wpi::math::PIDController controller{armKp, 0, 0};
40+
wpi::Encoder encoder{kEncoderAChannel, kEncoderBChannel};
41+
wpi::PWMSparkMax motor{kMotorPort};
4242

4343
// Simulation classes help us simulate what's going on, including gravity.
4444
// This sim represents an arm with 2 775s, a 600:1 reduction, a mass of 5kg,
4545
// 30in overall arm length, range of motion in [-75, 255] degrees, and noise
4646
// with a standard deviation of 1 encoder tick.
47-
wpi::sim::SingleJointedArmSim m_armSim{
48-
m_armGearbox,
47+
wpi::sim::SingleJointedArmSim armSim{
48+
armGearbox,
4949
kArmReduction,
5050
wpi::sim::SingleJointedArmSim::EstimateMOI(kArmLength, kArmMass),
5151
kArmLength,
@@ -54,16 +54,16 @@ class Arm {
5454
true,
5555
0_deg,
5656
{kArmEncoderDistPerPulse}};
57-
wpi::sim::EncoderSim m_encoderSim{m_encoder};
57+
wpi::sim::EncoderSim encoderSim{encoder};
5858

5959
// Create a Mechanism2d display of an Arm
60-
wpi::Mechanism2d m_mech2d{60, 60};
61-
wpi::MechanismRoot2d* m_armBase = m_mech2d.GetRoot("ArmBase", 30, 30);
62-
wpi::MechanismLigament2d* m_armTower =
63-
m_armBase->Append<wpi::MechanismLigament2d>(
60+
wpi::Mechanism2d mech2d{60, 60};
61+
wpi::MechanismRoot2d* armBase = mech2d.GetRoot("ArmBase", 30, 30);
62+
wpi::MechanismLigament2d* armTower =
63+
armBase->Append<wpi::MechanismLigament2d>(
6464
"Arm Tower", 30, -90_deg, 6,
6565
wpi::util::Color8Bit{wpi::util::Color::BLUE});
66-
wpi::MechanismLigament2d* m_arm = m_armBase->Append<wpi::MechanismLigament2d>(
67-
"Arm", 30, m_armSim.GetAngle(), 6,
66+
wpi::MechanismLigament2d* arm = armBase->Append<wpi::MechanismLigament2d>(
67+
"Arm", 30, armSim.GetAngle(), 6,
6868
wpi::util::Color8Bit{wpi::util::Color::YELLOW});
6969
};

wpilibcExamples/src/main/cpp/examples/DifferentialDriveBot/cpp/Drivetrain.cpp

Lines changed: 12 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -6,24 +6,24 @@
66

77
void Drivetrain::SetVelocities(
88
const wpi::math::DifferentialDriveWheelVelocities& velocities) {
9-
const auto leftFeedforward = m_feedforward.Calculate(velocities.left);
10-
const auto rightFeedforward = m_feedforward.Calculate(velocities.right);
11-
const double leftOutput = m_leftPIDController.Calculate(
12-
m_leftEncoder.GetRate(), velocities.left.value());
13-
const double rightOutput = m_rightPIDController.Calculate(
14-
m_rightEncoder.GetRate(), velocities.right.value());
9+
const auto leftFeedforward = feedforward.Calculate(velocities.left);
10+
const auto rightFeedforward = feedforward.Calculate(velocities.right);
11+
const double leftOutput = leftPIDController.Calculate(
12+
leftEncoder.GetRate(), velocities.left.value());
13+
const double rightOutput = rightPIDController.Calculate(
14+
rightEncoder.GetRate(), velocities.right.value());
1515

16-
m_leftLeader.SetVoltage(wpi::units::volt_t{leftOutput} + leftFeedforward);
17-
m_rightLeader.SetVoltage(wpi::units::volt_t{rightOutput} + rightFeedforward);
16+
leftLeader.SetVoltage(wpi::units::volt_t{leftOutput} + leftFeedforward);
17+
rightLeader.SetVoltage(wpi::units::volt_t{rightOutput} + rightFeedforward);
1818
}
1919

2020
void Drivetrain::Drive(wpi::units::meters_per_second_t xVelocity,
2121
wpi::units::radians_per_second_t rot) {
22-
SetVelocities(m_kinematics.ToWheelVelocities({xVelocity, 0_mps, rot}));
22+
SetVelocities(kinematics.ToWheelVelocities({xVelocity, 0_mps, rot}));
2323
}
2424

2525
void Drivetrain::UpdateOdometry() {
26-
m_odometry.Update(m_imu.GetRotation2d(),
27-
wpi::units::meter_t{m_leftEncoder.GetDistance()},
28-
wpi::units::meter_t{m_rightEncoder.GetDistance()});
26+
odometry.Update(imu.GetRotation2d(),
27+
wpi::units::meter_t{leftEncoder.GetDistance()},
28+
wpi::units::meter_t{rightEncoder.GetDistance()});
2929
}

0 commit comments

Comments
 (0)