diff --git a/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/command-based/PIDSubsystem.cpp b/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/command-based/PIDSubsystem.cpp index d88641ff61..01dcf6a649 100644 --- a/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/command-based/PIDSubsystem.cpp +++ b/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/command-based/PIDSubsystem.cpp @@ -12,7 +12,7 @@ $classname::$classname() : // Enable() - Enables the PID controller. } -double $classname::ReturnPIDInput() const +double $classname::ReturnPIDInput() { // Return your input value for the PID loop // e.g. a sensor, like a potentiometer: diff --git a/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/command-based/PIDSubsystem.h b/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/command-based/PIDSubsystem.h index 2e72a8d560..ffb573a3de 100644 --- a/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/command-based/PIDSubsystem.h +++ b/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/command-based/PIDSubsystem.h @@ -8,7 +8,7 @@ class $classname: public PIDSubsystem { public: $classname(); - double ReturnPIDInput() const; + double ReturnPIDInput(); void UsePIDOutput(double output); void InitDefaultCommand(); }; diff --git a/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/command-based/Robot.cpp b/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/command-based/Robot.cpp index d062e4c36c..a41f36ab1e 100644 --- a/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/command-based/Robot.cpp +++ b/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/command-based/Robot.cpp @@ -25,7 +25,7 @@ private: void DisabledPeriodic() { - Scheduler::GetInstance().Run(); + Scheduler::GetInstance()->Run(); } void AutonomousInit() @@ -36,7 +36,7 @@ private: void AutonomousPeriodic() { - Scheduler::GetInstance().Run(); + Scheduler::GetInstance()->Run(); } void TeleopInit() @@ -51,12 +51,12 @@ private: void TeleopPeriodic() { - Scheduler::GetInstance().Run(); + Scheduler::GetInstance()->Run(); } void TestPeriodic() { - LiveWindow::GetInstance().Run(); + LiveWindow::GetInstance()->Run(); } }; diff --git a/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/GearsBot/src/Commands/DriveStraight.cpp b/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/GearsBot/src/Commands/DriveStraight.cpp index b2ae54e911..9945514ab6 100644 --- a/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/GearsBot/src/Commands/DriveStraight.cpp +++ b/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/GearsBot/src/Commands/DriveStraight.cpp @@ -40,7 +40,7 @@ void DriveStraight::Interrupted() { DriveStraightPIDSource::~DriveStraightPIDSource() {} -double DriveStraightPIDSource::PIDGet() const { +double DriveStraightPIDSource::PIDGet() { return Robot::drivetrain->GetDistance(); } diff --git a/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/GearsBot/src/Commands/DriveStraight.h b/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/GearsBot/src/Commands/DriveStraight.h index 69166b00ae..50cd0b8e60 100644 --- a/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/GearsBot/src/Commands/DriveStraight.h +++ b/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/GearsBot/src/Commands/DriveStraight.h @@ -25,7 +25,7 @@ private: class DriveStraightPIDSource: public PIDSource { public: virtual ~DriveStraightPIDSource(); - double PIDGet() const; + double PIDGet(); }; class DriveStraightPIDOutput: public PIDOutput { diff --git a/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/GearsBot/src/Commands/SetDistanceToBox.cpp b/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/GearsBot/src/Commands/SetDistanceToBox.cpp index 12e6588d5b..27f70f6f38 100644 --- a/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/GearsBot/src/Commands/SetDistanceToBox.cpp +++ b/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/GearsBot/src/Commands/SetDistanceToBox.cpp @@ -40,7 +40,7 @@ void SetDistanceToBox::Interrupted() { SetDistanceToBoxPIDSource::~SetDistanceToBoxPIDSource() {} -double SetDistanceToBoxPIDSource::PIDGet() const { +double SetDistanceToBoxPIDSource::PIDGet() { return Robot::drivetrain->GetDistanceToObstacle(); } diff --git a/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/GearsBot/src/Commands/SetDistanceToBox.h b/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/GearsBot/src/Commands/SetDistanceToBox.h index 3508a367a4..1c284884db 100644 --- a/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/GearsBot/src/Commands/SetDistanceToBox.h +++ b/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/GearsBot/src/Commands/SetDistanceToBox.h @@ -25,7 +25,7 @@ private: class SetDistanceToBoxPIDSource: public PIDSource { public: virtual ~SetDistanceToBoxPIDSource(); - double PIDGet() const; + double PIDGet(); }; class SetDistanceToBoxPIDOutput: public PIDOutput { diff --git a/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/GearsBot/src/Robot.cpp b/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/GearsBot/src/Robot.cpp index 866ac156f9..26a2a2076b 100644 --- a/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/GearsBot/src/Robot.cpp +++ b/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/GearsBot/src/Robot.cpp @@ -29,7 +29,7 @@ void Robot::AutonomousInit() { } void Robot::AutonomousPeriodic() { - Scheduler::GetInstance().Run(); + Scheduler::GetInstance()->Run(); } void Robot::TeleopInit() { @@ -42,11 +42,11 @@ void Robot::TeleopInit() { } void Robot::TeleopPeriodic() { - Scheduler::GetInstance().Run(); + Scheduler::GetInstance()->Run(); } void Robot::TestPeriodic() { - lw.Run(); + lw->Run(); } START_ROBOT_CLASS(Robot) diff --git a/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/GearsBot/src/Robot.h b/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/GearsBot/src/Robot.h index 45f88bea18..ee98beb2d8 100644 --- a/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/GearsBot/src/Robot.h +++ b/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/GearsBot/src/Robot.h @@ -28,7 +28,7 @@ public: private: Autonomous autonomousCommand; - LiveWindow &lw = LiveWindow::GetInstance(); + LiveWindow *lw = LiveWindow::GetInstance(); void RobotInit(); void AutonomousInit(); diff --git a/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/GearsBot/src/Subsystems/DriveTrain.cpp b/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/GearsBot/src/Subsystems/DriveTrain.cpp index d3578f7d5a..f5055be04c 100644 --- a/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/GearsBot/src/Subsystems/DriveTrain.cpp +++ b/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/GearsBot/src/Subsystems/DriveTrain.cpp @@ -23,14 +23,14 @@ DriveTrain::DriveTrain() #endif // Let's show everything on the LiveWindow - // TODO: LiveWindow::GetInstance().AddActuator("Drive Train", "Front_Left Motor", (Talon) front_left_motor); - // TODO: LiveWindow::GetInstance().AddActuator("Drive Train", "Back Left Motor", (Talon) back_left_motor); - // TODO: LiveWindow::GetInstance().AddActuator("Drive Train", "Front Right Motor", (Talon) front_right_motor); - // TODO: LiveWindow::GetInstance().AddActuator("Drive Train", "Back Right Motor", (Talon) back_right_motor); - LiveWindow::GetInstance().AddSensor("Drive Train", "Left Encoder", left_encoder); - LiveWindow::GetInstance().AddSensor("Drive Train", "Right Encoder", right_encoder); - LiveWindow::GetInstance().AddSensor("Drive Train", "Rangefinder", rangefinder); - LiveWindow::GetInstance().AddSensor("Drive Train", "Gyro", gyro); + // TODO: LiveWindow::GetInstance()->AddActuator("Drive Train", "Front_Left Motor", (Talon) front_left_motor); + // TODO: LiveWindow::GetInstance()->AddActuator("Drive Train", "Back Left Motor", (Talon) back_left_motor); + // TODO: LiveWindow::GetInstance()->AddActuator("Drive Train", "Front Right Motor", (Talon) front_right_motor); + // TODO: LiveWindow::GetInstance()->AddActuator("Drive Train", "Back Right Motor", (Talon) back_right_motor); + LiveWindow::GetInstance()->AddSensor("Drive Train", "Left Encoder", left_encoder); + LiveWindow::GetInstance()->AddSensor("Drive Train", "Right Encoder", right_encoder); + LiveWindow::GetInstance()->AddSensor("Drive Train", "Rangefinder", rangefinder); + LiveWindow::GetInstance()->AddSensor("Drive Train", "Gyro", gyro); } /** diff --git a/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/GearsBot/src/Subsystems/Elevator.cpp b/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/GearsBot/src/Subsystems/Elevator.cpp index 5e8ad83586..02c558ffa5 100644 --- a/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/GearsBot/src/Subsystems/Elevator.cpp +++ b/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/GearsBot/src/Subsystems/Elevator.cpp @@ -18,16 +18,16 @@ Elevator::Elevator() : PIDSubsystem("Elevator", kP_real, kI_real, 0.0) { #endif // Let's show everything on the LiveWindow - // TODO: LiveWindow::GetInstance().AddActuator("Elevator", "Motor", (Victor) motor); - // TODO: LiveWindow::GetInstance().AddSensor("Elevator", "Pot", (AnalogPotentiometer) pot); - LiveWindow::GetInstance().AddActuator("Elevator", "PID", GetPIDController()); + // TODO: LiveWindow::GetInstance()->AddActuator("Elevator", "Motor", (Victor) motor); + // TODO: LiveWindow::GetInstance()->AddSensor("Elevator", "Pot", (AnalogPotentiometer) pot); + LiveWindow::GetInstance()->AddActuator("Elevator", "PID", GetPIDController()); } void Elevator::Log() { // TODO: SmartDashboard::PutData("Wrist Pot", (AnalogPotentiometer) pot); } -double Elevator::ReturnPIDInput() const { +double Elevator::ReturnPIDInput() { return pot->Get(); } diff --git a/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/GearsBot/src/Subsystems/Elevator.h b/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/GearsBot/src/Subsystems/Elevator.h index a428d5510c..d079de03b5 100644 --- a/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/GearsBot/src/Subsystems/Elevator.h +++ b/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/GearsBot/src/Subsystems/Elevator.h @@ -29,7 +29,7 @@ public: * Use the potentiometer as the PID sensor. This method is automatically * called by the subsystem. */ - double ReturnPIDInput() const; + double ReturnPIDInput(); /** diff --git a/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/GearsBot/src/Subsystems/Wrist.cpp b/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/GearsBot/src/Subsystems/Wrist.cpp index 5ab9ff98bd..f09fdbb790 100644 --- a/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/GearsBot/src/Subsystems/Wrist.cpp +++ b/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/GearsBot/src/Subsystems/Wrist.cpp @@ -18,16 +18,16 @@ Wrist::Wrist() : PIDSubsystem("Wrist", kP_real, 0.0, 0.0) { #endif // Let's show everything on the LiveWindow - // TODO: LiveWindow::GetInstance().AddActuator("Wrist", "Motor", (Victor) motor); - // TODO: LiveWindow::GetInstance().AddSensor("Wrist", "Pot", (AnalogPotentiometer) pot); - LiveWindow::GetInstance().AddActuator("Wrist", "PID", GetPIDController()); + // TODO: LiveWindow::GetInstance()->AddActuator("Wrist", "Motor", (Victor) motor); + // TODO: LiveWindow::GetInstance()->AddSensor("Wrist", "Pot", (AnalogPotentiometer) pot); + LiveWindow::GetInstance()->AddActuator("Wrist", "PID", GetPIDController()); } void Wrist::Log() { // TODO: SmartDashboard::PutData("Wrist Angle", (AnalogPotentiometer) pot); } -double Wrist::ReturnPIDInput() const { +double Wrist::ReturnPIDInput() { return pot->Get(); } diff --git a/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/GearsBot/src/Subsystems/Wrist.h b/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/GearsBot/src/Subsystems/Wrist.h index f0f7593b37..e80364e7cd 100644 --- a/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/GearsBot/src/Subsystems/Wrist.h +++ b/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/GearsBot/src/Subsystems/Wrist.h @@ -28,7 +28,7 @@ public: * Use the potentiometer as the PID sensor. This method is automatically * called by the subsystem. */ - double ReturnPIDInput() const; + double ReturnPIDInput(); /** * Use the motor as the PID output. This method is automatically called by diff --git a/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/GettingStarted/src/Robot.cpp b/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/GettingStarted/src/Robot.cpp index 67303df9b9..ccf2e587f9 100644 --- a/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/GettingStarted/src/Robot.cpp +++ b/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/GettingStarted/src/Robot.cpp @@ -5,7 +5,7 @@ class Robot: public IterativeRobot RobotDrive myRobot; // robot drive system Joystick stick; // only joystick - LiveWindow &lw; + LiveWindow *lw; int autoLoopCounter; public: @@ -47,7 +47,7 @@ private: void TestPeriodic() { - lw.Run(); + lw->Run(); } }; diff --git a/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/PacGoat/src/Robot.cpp b/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/PacGoat/src/Robot.cpp index c59cbf7140..7ef891620e 100644 --- a/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/PacGoat/src/Robot.cpp +++ b/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/PacGoat/src/Robot.cpp @@ -39,7 +39,7 @@ void Robot::AutonomousInit() { } void Robot::AutonomousPeriodic() { - Scheduler::GetInstance().Run(); + Scheduler::GetInstance()->Run(); Log(); } @@ -55,12 +55,12 @@ void Robot::TeleopInit() { } void Robot::TeleopPeriodic() { - Scheduler::GetInstance().Run(); + Scheduler::GetInstance()->Run(); Log(); } void Robot::TestPeriodic() { - LiveWindow::GetInstance().Run(); + LiveWindow::GetInstance()->Run(); } void Robot::DisabledInit() { diff --git a/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/PacGoat/src/Subsystems/Collector.cpp b/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/PacGoat/src/Subsystems/Collector.cpp index 24a060f4f9..c296e0a84b 100644 --- a/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/PacGoat/src/Subsystems/Collector.cpp +++ b/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/PacGoat/src/Subsystems/Collector.cpp @@ -11,9 +11,9 @@ Collector::Collector() : // Put everything to the LiveWindow for testing. // XXX: LiveWindow::GetInstance()->AddActuator("Collector", "Roller Motor", (Victor) rollerMotor); - LiveWindow::GetInstance().AddSensor("Collector", "Ball Detector", ballDetector); - LiveWindow::GetInstance().AddSensor("Collector", "Claw Open Detector", openDetector); - LiveWindow::GetInstance().AddActuator("Collector", "Piston", piston); + LiveWindow::GetInstance()->AddSensor("Collector", "Ball Detector", ballDetector); + LiveWindow::GetInstance()->AddSensor("Collector", "Claw Open Detector", openDetector); + LiveWindow::GetInstance()->AddActuator("Collector", "Piston", piston); } bool Collector::HasBall() { diff --git a/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/PacGoat/src/Subsystems/DriveTrain.cpp b/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/PacGoat/src/Subsystems/DriveTrain.cpp index 7e1caf58f4..ae1fe2b4db 100644 --- a/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/PacGoat/src/Subsystems/DriveTrain.cpp +++ b/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/PacGoat/src/Subsystems/DriveTrain.cpp @@ -44,14 +44,14 @@ DriveTrain::DriveTrain() leftEncoder->SetDistancePerPulse((4.0/*in*/*M_PI)/(360.0*12.0/*in/ft*/)); #endif - LiveWindow::GetInstance().AddSensor("DriveTrain", "Right Encoder", rightEncoder); - LiveWindow::GetInstance().AddSensor("DriveTrain", "Left Encoder", leftEncoder); + LiveWindow::GetInstance()->AddSensor("DriveTrain", "Right Encoder", rightEncoder); + LiveWindow::GetInstance()->AddSensor("DriveTrain", "Left Encoder", leftEncoder); // Configure gyro #ifdef REAL gyro->SetSensitivity(0.007); // TODO: Handle more gracefully? #endif - LiveWindow::GetInstance().AddSensor("DriveTrain", "Gyro", gyro); + LiveWindow::GetInstance()->AddSensor("DriveTrain", "Gyro", gyro); } void DriveTrain::InitDefaultCommand() { diff --git a/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/PacGoat/src/Subsystems/Pivot.cpp b/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/PacGoat/src/Subsystems/Pivot.cpp index 6b51da5bba..d6fc1ef843 100644 --- a/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/PacGoat/src/Subsystems/Pivot.cpp +++ b/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/PacGoat/src/Subsystems/Pivot.cpp @@ -20,16 +20,16 @@ Pivot::Pivot() : #endif // Put everything to the LiveWindow for testing. - LiveWindow::GetInstance().AddSensor("Pivot", "Upper Limit Switch", upperLimitSwitch); - LiveWindow::GetInstance().AddSensor("Pivot", "Lower Limit Switch", lowerLimitSwitch); - // XXX: LiveWindow::GetInstance().AddSensor("Pivot", "Pot", (AnalogPotentiometer) pot); - // XXX: LiveWindow::GetInstance().AddActuator("Pivot", "Motor", (Victor) motor); - LiveWindow::GetInstance().AddActuator("Pivot", "PIDSubsystem Controller", GetPIDController()); + LiveWindow::GetInstance()->AddSensor("Pivot", "Upper Limit Switch", upperLimitSwitch); + LiveWindow::GetInstance()->AddSensor("Pivot", "Lower Limit Switch", lowerLimitSwitch); + // XXX: LiveWindow::GetInstance()->AddSensor("Pivot", "Pot", (AnalogPotentiometer) pot); + // XXX: LiveWindow::GetInstance()->AddActuator("Pivot", "Motor", (Victor) motor); + LiveWindow::GetInstance()->AddActuator("Pivot", "PIDSubsystem Controller", GetPIDController()); } void InitDefaultCommand() {} -double Pivot::ReturnPIDInput() const { +double Pivot::ReturnPIDInput() { return pot->Get(); } diff --git a/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/PacGoat/src/Subsystems/Pivot.h b/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/PacGoat/src/Subsystems/Pivot.h index 4c5af09755..d8f1783936 100644 --- a/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/PacGoat/src/Subsystems/Pivot.h +++ b/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/PacGoat/src/Subsystems/Pivot.h @@ -35,7 +35,7 @@ public: /** * @return The angle read in by the potentiometer */ - double ReturnPIDInput() const; + double ReturnPIDInput(); /** * Set the motor speed based off of the PID output diff --git a/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/PacGoat/src/Subsystems/Pneumatics.cpp b/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/PacGoat/src/Subsystems/Pneumatics.cpp index d224c6aee5..a2b6bec31e 100644 --- a/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/PacGoat/src/Subsystems/Pneumatics.cpp +++ b/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/PacGoat/src/Subsystems/Pneumatics.cpp @@ -8,7 +8,7 @@ Pneumatics::Pneumatics() : compressor = new Compressor(uint8_t(1)); // TODO: (1, 14, 1, 8); #endif - LiveWindow::GetInstance().AddSensor("Pneumatics", "Pressure Sensor", pressureSensor); + LiveWindow::GetInstance()->AddSensor("Pneumatics", "Pressure Sensor", pressureSensor); } /** diff --git a/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/PacGoat/src/Subsystems/Shooter.cpp b/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/PacGoat/src/Subsystems/Shooter.cpp index 703fd7263f..8f10c41ad5 100644 --- a/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/PacGoat/src/Subsystems/Shooter.cpp +++ b/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/PacGoat/src/Subsystems/Shooter.cpp @@ -12,10 +12,10 @@ Shooter::Shooter() : { // Put everything to the LiveWindow for testing. - LiveWindow::GetInstance().AddSensor("Shooter", "Hot Goal Sensor", hotGoalSensor); - LiveWindow::GetInstance().AddSensor("Shooter", "Piston1 Reed Switch Front ", piston1ReedSwitchFront); - LiveWindow::GetInstance().AddSensor("Shooter", "Piston1 Reed Switch Back ", piston1ReedSwitchBack); - LiveWindow::GetInstance().AddActuator("Shooter", "Latch Piston", latchPiston); + LiveWindow::GetInstance()->AddSensor("Shooter", "Hot Goal Sensor", hotGoalSensor); + LiveWindow::GetInstance()->AddSensor("Shooter", "Piston1 Reed Switch Front ", piston1ReedSwitchFront); + LiveWindow::GetInstance()->AddSensor("Shooter", "Piston1 Reed Switch Back ", piston1ReedSwitchBack); + LiveWindow::GetInstance()->AddActuator("Shooter", "Latch Piston", latchPiston); } void Shooter::InitDefaultCommand() diff --git a/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/iterative/Robot.cpp b/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/iterative/Robot.cpp index b409b30e34..44af60fd59 100644 --- a/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/iterative/Robot.cpp +++ b/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/iterative/Robot.cpp @@ -3,7 +3,7 @@ class Robot: public IterativeRobot { private: - LiveWindow &lw = LiveWindow::GetInstance(); + LiveWindow *lw = LiveWindow::GetInstance(); void RobotInit() { @@ -31,7 +31,7 @@ private: void TestPeriodic() { - lw.Run(); + lw->Run(); } }; diff --git a/wpilibc/wpilibC++/include/Commands/PIDCommand.h b/wpilibc/wpilibC++/include/Commands/PIDCommand.h index fd0c3c6446..a98c239550 100644 --- a/wpilibc/wpilibC++/include/Commands/PIDCommand.h +++ b/wpilibc/wpilibC++/include/Commands/PIDCommand.h @@ -32,7 +32,7 @@ class PIDCommand : public Command, public PIDOutput, public PIDSource { virtual void PIDWrite(float output); // PIDSource interface - virtual double PIDGet() const; + virtual double PIDGet(); protected: std::shared_ptr GetPIDController() const; @@ -41,9 +41,9 @@ class PIDCommand : public Command, public PIDOutput, public PIDSource { virtual void _End(); void SetSetpoint(double setpoint); double GetSetpoint() const; - double GetPosition() const; + double GetPosition(); - virtual double ReturnPIDInput() const = 0; + virtual double ReturnPIDInput() = 0; virtual void UsePIDOutput(double output) = 0; private: diff --git a/wpilibc/wpilibC++/include/Commands/PIDSubsystem.h b/wpilibc/wpilibC++/include/Commands/PIDSubsystem.h index b4cf754fd5..ff05514375 100644 --- a/wpilibc/wpilibC++/include/Commands/PIDSubsystem.h +++ b/wpilibc/wpilibC++/include/Commands/PIDSubsystem.h @@ -45,7 +45,7 @@ class PIDSubsystem : public Subsystem, public PIDOutput, public PIDSource { virtual void PIDWrite(float output); // PIDSource interface - virtual double PIDGet() const; + virtual double PIDGet(); void SetSetpoint(double setpoint); void SetSetpointRelative(double deltaSetpoint); void SetInputRange(float minimumInput, float maximumInput); @@ -61,7 +61,7 @@ class PIDSubsystem : public Subsystem, public PIDOutput, public PIDSource { protected: std::shared_ptr GetPIDController(); - virtual double ReturnPIDInput() const = 0; + virtual double ReturnPIDInput() = 0; virtual void UsePIDOutput(double output) = 0; private: diff --git a/wpilibc/wpilibC++/include/Commands/Scheduler.h b/wpilibc/wpilibC++/include/Commands/Scheduler.h index a624b5daa2..200c9517e2 100644 --- a/wpilibc/wpilibC++/include/Commands/Scheduler.h +++ b/wpilibc/wpilibC++/include/Commands/Scheduler.h @@ -27,7 +27,7 @@ class Subsystem; class Scheduler : public ErrorBase, public NamedSendable { public: - static Scheduler &GetInstance(); + static Scheduler *GetInstance(); void AddCommand(Command *command); void AddButton(ButtonScheduler *button); diff --git a/wpilibc/wpilibC++/include/LiveWindow/LiveWindow.h b/wpilibc/wpilibC++/include/LiveWindow/LiveWindow.h index 8eb5bf6ce3..5d41441423 100644 --- a/wpilibc/wpilibC++/include/LiveWindow/LiveWindow.h +++ b/wpilibc/wpilibC++/include/LiveWindow/LiveWindow.h @@ -30,7 +30,7 @@ struct LiveWindowComponent { */ class LiveWindow { public: - static LiveWindow &GetInstance(); + static LiveWindow *GetInstance(); void Run(); #if !defined(_MSC_VER) [[deprecated( @@ -90,7 +90,7 @@ class LiveWindow { std::shared_ptr m_liveWindowTable; std::shared_ptr m_statusTable; - Scheduler &m_scheduler; + Scheduler *m_scheduler; bool m_enabled = false; bool m_firstTime = true; diff --git a/wpilibc/wpilibC++/include/PIDSource.h b/wpilibc/wpilibC++/include/PIDSource.h index f0eb1cb08a..8f46ea4707 100644 --- a/wpilibc/wpilibC++/include/PIDSource.h +++ b/wpilibc/wpilibC++/include/PIDSource.h @@ -18,7 +18,7 @@ class PIDSource { public: virtual void SetPIDSourceType(PIDSourceType pidSource); PIDSourceType GetPIDSourceType() const; - virtual double PIDGet() const = 0; + virtual double PIDGet() = 0; protected: PIDSourceType m_pidSource = PIDSourceType::kDisplacement; diff --git a/wpilibc/wpilibC++/src/Buttons/ButtonScheduler.cpp b/wpilibc/wpilibC++/src/Buttons/ButtonScheduler.cpp index 43c7c148f9..ddc9025fe4 100644 --- a/wpilibc/wpilibC++/src/Buttons/ButtonScheduler.cpp +++ b/wpilibc/wpilibC++/src/Buttons/ButtonScheduler.cpp @@ -12,4 +12,4 @@ ButtonScheduler::ButtonScheduler(bool last, Trigger *button, Command *orders) : m_pressedLast(last), m_button(button), m_command(orders) {} -void ButtonScheduler::Start() { Scheduler::GetInstance().AddButton(this); } +void ButtonScheduler::Start() { Scheduler::GetInstance()->AddButton(this); } diff --git a/wpilibc/wpilibC++/src/Commands/Command.cpp b/wpilibc/wpilibC++/src/Commands/Command.cpp index 78e05f7d1c..38c2f26598 100644 --- a/wpilibc/wpilibC++/src/Commands/Command.cpp +++ b/wpilibc/wpilibC++/src/Commands/Command.cpp @@ -152,7 +152,7 @@ void Command::Start() { CommandIllegalUse, "Can not start a command that is part of a command group"); - Scheduler::GetInstance().AddCommand(this); + Scheduler::GetInstance()->AddCommand(this); } /** diff --git a/wpilibc/wpilibC++/src/Commands/PIDCommand.cpp b/wpilibc/wpilibC++/src/Commands/PIDCommand.cpp index 16b7fa6645..c6ac919669 100644 --- a/wpilibc/wpilibC++/src/Commands/PIDCommand.cpp +++ b/wpilibc/wpilibC++/src/Commands/PIDCommand.cpp @@ -50,7 +50,7 @@ void PIDCommand::SetSetpointRelative(double deltaSetpoint) { void PIDCommand::PIDWrite(float output) { UsePIDOutput(output); } -double PIDCommand::PIDGet() const { return ReturnPIDInput(); } +double PIDCommand::PIDGet() { return ReturnPIDInput(); } std::shared_ptr PIDCommand::GetPIDController() const { return m_controller; @@ -62,7 +62,7 @@ void PIDCommand::SetSetpoint(double setpoint) { double PIDCommand::GetSetpoint() const { return m_controller->GetSetpoint(); } -double PIDCommand::GetPosition() const { return ReturnPIDInput(); } +double PIDCommand::GetPosition() { return ReturnPIDInput(); } std::string PIDCommand::GetSmartDashboardType() const { return "PIDCommand"; } void PIDCommand::InitTable(std::shared_ptr table) { diff --git a/wpilibc/wpilibC++/src/Commands/PIDSubsystem.cpp b/wpilibc/wpilibC++/src/Commands/PIDSubsystem.cpp index e5fe6107d1..e48319abff 100644 --- a/wpilibc/wpilibC++/src/Commands/PIDSubsystem.cpp +++ b/wpilibc/wpilibC++/src/Commands/PIDSubsystem.cpp @@ -216,7 +216,7 @@ double PIDSubsystem::GetRate() { return ReturnPIDInput(); } void PIDSubsystem::PIDWrite(float output) { UsePIDOutput(output); } -double PIDSubsystem::PIDGet() const { return ReturnPIDInput(); } +double PIDSubsystem::PIDGet() { return ReturnPIDInput(); } std::string PIDSubsystem::GetSmartDashboardType() const { return "PIDCommand"; } void PIDSubsystem::InitTable(std::shared_ptr table) { diff --git a/wpilibc/wpilibC++/src/Commands/Scheduler.cpp b/wpilibc/wpilibC++/src/Commands/Scheduler.cpp index 525b70456a..caeeff273e 100644 --- a/wpilibc/wpilibC++/src/Commands/Scheduler.cpp +++ b/wpilibc/wpilibC++/src/Commands/Scheduler.cpp @@ -23,9 +23,9 @@ Scheduler::Scheduler() { * Returns the {@link Scheduler}, creating it if one does not exist. * @return the {@link Scheduler} */ -Scheduler &Scheduler::GetInstance() { +Scheduler *Scheduler::GetInstance() { static Scheduler instance; - return instance; + return &instance; } void Scheduler::SetEnabled(bool enabled) { m_enabled = enabled; } diff --git a/wpilibc/wpilibC++/src/Commands/Subsystem.cpp b/wpilibc/wpilibC++/src/Commands/Subsystem.cpp index 60c48ca65e..0b4b92ffd0 100644 --- a/wpilibc/wpilibC++/src/Commands/Subsystem.cpp +++ b/wpilibc/wpilibC++/src/Commands/Subsystem.cpp @@ -17,7 +17,7 @@ */ Subsystem::Subsystem(const std::string &name) { m_name = name; - Scheduler::GetInstance().RegisterSubsystem(this); + Scheduler::GetInstance()->RegisterSubsystem(this); } /** * Initialize the default command for this subsystem diff --git a/wpilibc/wpilibC++/src/LiveWindow/LiveWindow.cpp b/wpilibc/wpilibC++/src/LiveWindow/LiveWindow.cpp index 6355aa6833..0d89620551 100644 --- a/wpilibc/wpilibC++/src/LiveWindow/LiveWindow.cpp +++ b/wpilibc/wpilibC++/src/LiveWindow/LiveWindow.cpp @@ -9,9 +9,9 @@ * regardless of * how many times GetInstance is called. */ -LiveWindow &LiveWindow::GetInstance() { +LiveWindow *LiveWindow::GetInstance() { static LiveWindow instance; - return instance; + return &instance; } /** @@ -34,8 +34,8 @@ void LiveWindow::SetEnabled(bool enabled) { InitializeLiveWindowComponents(); m_firstTime = false; } - m_scheduler.SetEnabled(false); - m_scheduler.RemoveAll(); + m_scheduler->SetEnabled(false); + m_scheduler->RemoveAll(); for (auto& elem : m_components) { elem.first->StartLiveWindowMode(); } @@ -43,7 +43,7 @@ void LiveWindow::SetEnabled(bool enabled) { for (auto& elem : m_components) { elem.first->StopLiveWindowMode(); } - m_scheduler.SetEnabled(true); + m_scheduler->SetEnabled(true); } m_enabled = enabled; m_statusTable->PutBoolean("LW Enabled", m_enabled); diff --git a/wpilibc/wpilibC++Devices/include/AnalogAccelerometer.h b/wpilibc/wpilibC++Devices/include/AnalogAccelerometer.h index 9c17a8e983..aa18e6e308 100644 --- a/wpilibc/wpilibC++Devices/include/AnalogAccelerometer.h +++ b/wpilibc/wpilibC++Devices/include/AnalogAccelerometer.h @@ -38,7 +38,7 @@ class AnalogAccelerometer : public SensorBase, float GetAcceleration() const; void SetSensitivity(float sensitivity); void SetZero(float zero); - double PIDGet() const override; + double PIDGet() override; void UpdateTable() override; void StartLiveWindowMode() override; diff --git a/wpilibc/wpilibC++Devices/include/AnalogInput.h b/wpilibc/wpilibC++Devices/include/AnalogInput.h index 85314b01e1..24870dc938 100644 --- a/wpilibc/wpilibC++Devices/include/AnalogInput.h +++ b/wpilibc/wpilibC++Devices/include/AnalogInput.h @@ -67,7 +67,7 @@ class AnalogInput : public SensorBase, static void SetSampleRate(float samplesPerSecond); static float GetSampleRate(); - double PIDGet() const override; + double PIDGet() override; void UpdateTable() override; void StartLiveWindowMode() override; diff --git a/wpilibc/wpilibC++Devices/include/AnalogPotentiometer.h b/wpilibc/wpilibC++Devices/include/AnalogPotentiometer.h index 12910bd8c4..3d27ea3dd6 100644 --- a/wpilibc/wpilibC++Devices/include/AnalogPotentiometer.h +++ b/wpilibc/wpilibC++Devices/include/AnalogPotentiometer.h @@ -61,7 +61,7 @@ class AnalogPotentiometer : public Potentiometer, public LiveWindowSendable { * * @return The current reading. */ - virtual double PIDGet() const override; + virtual double PIDGet() override; /* * Live Window code, only does anything if live window is activated. diff --git a/wpilibc/wpilibC++Devices/include/CANTalon.h b/wpilibc/wpilibC++Devices/include/CANTalon.h index 9108451b71..0c7ab779ec 100644 --- a/wpilibc/wpilibC++Devices/include/CANTalon.h +++ b/wpilibc/wpilibC++Devices/include/CANTalon.h @@ -50,7 +50,7 @@ class CANTalon : public MotorSafety, virtual void PIDWrite(float output) override; // PIDSource interface - virtual double PIDGet() const override; + virtual double PIDGet() override; // MotorSafety interface virtual void SetExpiration(float timeout) override; diff --git a/wpilibc/wpilibC++Devices/include/Encoder.h b/wpilibc/wpilibC++Devices/include/Encoder.h index 7396eb0326..7fae4c9fa0 100644 --- a/wpilibc/wpilibC++Devices/include/Encoder.h +++ b/wpilibc/wpilibC++Devices/include/Encoder.h @@ -83,7 +83,7 @@ class Encoder : public SensorBase, void SetReverseDirection(bool reverseDirection); void SetSamplesToAverage(int samplesToAverage); int GetSamplesToAverage() const; - double PIDGet() const override; + double PIDGet() override; void SetIndexSource(uint32_t channel, IndexingType type = kResetOnRisingEdge); [[deprecated("Raw pointers are deprecated; use references instead.")]] diff --git a/wpilibc/wpilibC++Devices/include/Gyro.h b/wpilibc/wpilibC++Devices/include/Gyro.h index df9434066e..46eb128b68 100644 --- a/wpilibc/wpilibC++Devices/include/Gyro.h +++ b/wpilibc/wpilibC++Devices/include/Gyro.h @@ -53,7 +53,7 @@ class Gyro : public SensorBase, public PIDSource, public LiveWindowSendable { void InitGyro(); // PIDSource interface - double PIDGet() const override; + double PIDGet() override; void UpdateTable() override; void StartLiveWindowMode() override; diff --git a/wpilibc/wpilibC++Devices/include/Ultrasonic.h b/wpilibc/wpilibC++Devices/include/Ultrasonic.h index a648f1d90c..59f28fdcd0 100644 --- a/wpilibc/wpilibC++Devices/include/Ultrasonic.h +++ b/wpilibc/wpilibC++Devices/include/Ultrasonic.h @@ -69,7 +69,7 @@ class Ultrasonic : public SensorBase, bool IsEnabled() const { return m_enabled; } void SetEnabled(bool enable) { m_enabled = enable; } - double PIDGet() const override; + double PIDGet() override; void SetPIDSourceType(PIDSourceType pidSource) override; void SetDistanceUnits(DistanceUnit units); DistanceUnit GetDistanceUnits() const; diff --git a/wpilibc/wpilibC++Devices/src/ADXL345_I2C.cpp b/wpilibc/wpilibC++Devices/src/ADXL345_I2C.cpp index e1cb4467d1..000d4b8570 100644 --- a/wpilibc/wpilibC++Devices/src/ADXL345_I2C.cpp +++ b/wpilibc/wpilibC++Devices/src/ADXL345_I2C.cpp @@ -30,7 +30,7 @@ ADXL345_I2C::ADXL345_I2C(Port port, Range range) : I2C(port, kAddress) { HALReport(HALUsageReporting::kResourceType_ADXL345, HALUsageReporting::kADXL345_I2C, 0); - LiveWindow::GetInstance().AddSensor("ADXL345_I2C", port, this); + LiveWindow::GetInstance()->AddSensor("ADXL345_I2C", port, this); } /** {@inheritdoc} */ diff --git a/wpilibc/wpilibC++Devices/src/ADXL345_SPI.cpp b/wpilibc/wpilibC++Devices/src/ADXL345_SPI.cpp index 0b2f0089f7..7fb3b71528 100644 --- a/wpilibc/wpilibC++Devices/src/ADXL345_SPI.cpp +++ b/wpilibc/wpilibC++Devices/src/ADXL345_SPI.cpp @@ -39,7 +39,7 @@ ADXL345_SPI::ADXL345_SPI(SPI::Port port, ADXL345_SPI::Range range) : SPI(port) { HALReport(HALUsageReporting::kResourceType_ADXL345, HALUsageReporting::kADXL345_SPI); - LiveWindow::GetInstance().AddSensor("ADXL345_SPI", port, this); + LiveWindow::GetInstance()->AddSensor("ADXL345_SPI", port, this); } /** {@inheritdoc} */ diff --git a/wpilibc/wpilibC++Devices/src/AnalogAccelerometer.cpp b/wpilibc/wpilibC++Devices/src/AnalogAccelerometer.cpp index 8ee07bd668..d5567f3b2e 100644 --- a/wpilibc/wpilibC++Devices/src/AnalogAccelerometer.cpp +++ b/wpilibc/wpilibC++Devices/src/AnalogAccelerometer.cpp @@ -16,7 +16,7 @@ void AnalogAccelerometer::InitAccelerometer() { HALReport(HALUsageReporting::kResourceType_Accelerometer, m_analogInput->GetChannel()); - LiveWindow::GetInstance().AddSensor("Accelerometer", + LiveWindow::GetInstance()->AddSensor("Accelerometer", m_analogInput->GetChannel(), this); } @@ -110,7 +110,7 @@ void AnalogAccelerometer::SetZero(float zero) { m_zeroGVoltage = zero; } * * @return The current acceleration in Gs. */ -double AnalogAccelerometer::PIDGet() const { return GetAcceleration(); } +double AnalogAccelerometer::PIDGet() { return GetAcceleration(); } void AnalogAccelerometer::UpdateTable() { if (m_table != nullptr) { diff --git a/wpilibc/wpilibC++Devices/src/AnalogInput.cpp b/wpilibc/wpilibC++Devices/src/AnalogInput.cpp index 2239f008ad..54214a894e 100644 --- a/wpilibc/wpilibC++Devices/src/AnalogInput.cpp +++ b/wpilibc/wpilibC++Devices/src/AnalogInput.cpp @@ -47,7 +47,7 @@ AnalogInput::AnalogInput(uint32_t channel) { m_port = initializeAnalogInputPort(port, &status); wpi_setErrorWithContext(status, getHALErrorMessage(status)); - LiveWindow::GetInstance().AddSensor("AnalogInput", channel, this); + LiveWindow::GetInstance()->AddSensor("AnalogInput", channel, this); HALReport(HALUsageReporting::kResourceType_AnalogChannel, channel); } @@ -394,7 +394,7 @@ float AnalogInput::GetSampleRate() { * * @return The average voltage. */ -double AnalogInput::PIDGet() const { +double AnalogInput::PIDGet() { if (StatusIsFatal()) return 0.0; return GetAverageVoltage(); } diff --git a/wpilibc/wpilibC++Devices/src/AnalogOutput.cpp b/wpilibc/wpilibC++Devices/src/AnalogOutput.cpp index 19eee52985..8ec5ede8dc 100644 --- a/wpilibc/wpilibC++Devices/src/AnalogOutput.cpp +++ b/wpilibc/wpilibC++Devices/src/AnalogOutput.cpp @@ -42,7 +42,7 @@ AnalogOutput::AnalogOutput(uint32_t channel) { m_port = initializeAnalogOutputPort(port, &status); wpi_setErrorWithContext(status, getHALErrorMessage(status)); - LiveWindow::GetInstance().AddActuator("AnalogOutput", m_channel, this); + LiveWindow::GetInstance()->AddActuator("AnalogOutput", m_channel, this); HALReport(HALUsageReporting::kResourceType_AnalogOutput, m_channel); } diff --git a/wpilibc/wpilibC++Devices/src/AnalogPotentiometer.cpp b/wpilibc/wpilibC++Devices/src/AnalogPotentiometer.cpp index 052715dd1b..a944312ec1 100644 --- a/wpilibc/wpilibC++Devices/src/AnalogPotentiometer.cpp +++ b/wpilibc/wpilibC++Devices/src/AnalogPotentiometer.cpp @@ -66,7 +66,7 @@ double AnalogPotentiometer::Get() const { * * @return The current reading. */ -double AnalogPotentiometer::PIDGet() const { return Get(); } +double AnalogPotentiometer::PIDGet() { return Get(); } /** * @return the Smart Dashboard Type diff --git a/wpilibc/wpilibC++Devices/src/BuiltInAccelerometer.cpp b/wpilibc/wpilibC++Devices/src/BuiltInAccelerometer.cpp index d5450a850e..a504524ed0 100644 --- a/wpilibc/wpilibC++Devices/src/BuiltInAccelerometer.cpp +++ b/wpilibc/wpilibC++Devices/src/BuiltInAccelerometer.cpp @@ -18,7 +18,7 @@ BuiltInAccelerometer::BuiltInAccelerometer(Range range) { HALReport(HALUsageReporting::kResourceType_Accelerometer, 0, 0, "Built-in accelerometer"); - LiveWindow::GetInstance().AddSensor((std::string) "BuiltInAccel", 0, this); + LiveWindow::GetInstance()->AddSensor((std::string) "BuiltInAccel", 0, this); } /** {@inheritdoc} */ diff --git a/wpilibc/wpilibC++Devices/src/CANJaguar.cpp b/wpilibc/wpilibC++Devices/src/CANJaguar.cpp index 608a9663e7..ddfba620f2 100644 --- a/wpilibc/wpilibC++Devices/src/CANJaguar.cpp +++ b/wpilibc/wpilibC++Devices/src/CANJaguar.cpp @@ -147,7 +147,7 @@ void CANJaguar::InitCANJaguar() { } HALReport(HALUsageReporting::kResourceType_CANJaguar, m_deviceNumber, m_controlMode); - LiveWindow::GetInstance().AddActuator("CANJaguar", m_deviceNumber, this); + LiveWindow::GetInstance()->AddActuator("CANJaguar", m_deviceNumber, this); } /** diff --git a/wpilibc/wpilibC++Devices/src/CANTalon.cpp b/wpilibc/wpilibC++Devices/src/CANTalon.cpp index 9b267eceaa..a7bc529d59 100644 --- a/wpilibc/wpilibC++Devices/src/CANTalon.cpp +++ b/wpilibc/wpilibC++Devices/src/CANTalon.cpp @@ -70,7 +70,7 @@ void CANTalon::PIDWrite(float output) { * * @return The current sensor value of the Talon. */ -double CANTalon::PIDGet() const { return Get(); } +double CANTalon::PIDGet() { return Get(); } /** * Gets the current status of the Talon (usually a sensor value). diff --git a/wpilibc/wpilibC++Devices/src/DigitalInput.cpp b/wpilibc/wpilibC++Devices/src/DigitalInput.cpp index cdfa009f66..acbe186854 100644 --- a/wpilibc/wpilibC++Devices/src/DigitalInput.cpp +++ b/wpilibc/wpilibC++Devices/src/DigitalInput.cpp @@ -33,7 +33,7 @@ DigitalInput::DigitalInput(uint32_t channel) { allocateDIO(m_digital_ports[channel], true, &status); wpi_setErrorWithContext(status, getHALErrorMessage(status)); - LiveWindow::GetInstance().AddSensor("DigitalInput", channel, this); + LiveWindow::GetInstance()->AddSensor("DigitalInput", channel, this); HALReport(HALUsageReporting::kResourceType_DigitalInput, channel); } diff --git a/wpilibc/wpilibC++Devices/src/DoubleSolenoid.cpp b/wpilibc/wpilibC++Devices/src/DoubleSolenoid.cpp index 63ff0aa586..1ef56916db 100644 --- a/wpilibc/wpilibC++Devices/src/DoubleSolenoid.cpp +++ b/wpilibc/wpilibC++Devices/src/DoubleSolenoid.cpp @@ -79,7 +79,7 @@ DoubleSolenoid::DoubleSolenoid(uint8_t moduleNumber, uint32_t forwardChannel, m_moduleNumber); HALReport(HALUsageReporting::kResourceType_Solenoid, m_reverseChannel, m_moduleNumber); - LiveWindow::GetInstance().AddActuator("DoubleSolenoid", m_moduleNumber, + LiveWindow::GetInstance()->AddActuator("DoubleSolenoid", m_moduleNumber, m_forwardChannel, this); } diff --git a/wpilibc/wpilibC++Devices/src/Encoder.cpp b/wpilibc/wpilibC++Devices/src/Encoder.cpp index 10dcb66358..d999e19088 100644 --- a/wpilibc/wpilibC++Devices/src/Encoder.cpp +++ b/wpilibc/wpilibC++Devices/src/Encoder.cpp @@ -69,7 +69,7 @@ void Encoder::InitEncoder(bool reverseDirection, EncodingType encodingType) { } HALReport(HALUsageReporting::kResourceType_Encoder, m_index, encodingType); - LiveWindow::GetInstance().AddSensor("Encoder", + LiveWindow::GetInstance()->AddSensor("Encoder", m_aSource->GetChannelForRouting(), this); } @@ -480,7 +480,7 @@ int Encoder::GetSamplesToAverage() const { * * @return The current value of the selected source parameter. */ -double Encoder::PIDGet() const { +double Encoder::PIDGet() { if (StatusIsFatal()) return 0.0; switch (GetPIDSourceType()) { case PIDSourceType::kDisplacement: diff --git a/wpilibc/wpilibC++Devices/src/GearTooth.cpp b/wpilibc/wpilibC++Devices/src/GearTooth.cpp index b9625b2478..b659125ca4 100644 --- a/wpilibc/wpilibC++Devices/src/GearTooth.cpp +++ b/wpilibc/wpilibC++Devices/src/GearTooth.cpp @@ -30,7 +30,7 @@ void GearTooth::EnableDirectionSensing(bool directionSensitive) { GearTooth::GearTooth(uint32_t channel, bool directionSensitive) : Counter(channel) { EnableDirectionSensing(directionSensitive); - LiveWindow::GetInstance().AddSensor("GearTooth", channel, this); + LiveWindow::GetInstance()->AddSensor("GearTooth", channel, this); } /** diff --git a/wpilibc/wpilibC++Devices/src/Gyro.cpp b/wpilibc/wpilibC++Devices/src/Gyro.cpp index 89c16834c8..291a4ce8dd 100644 --- a/wpilibc/wpilibC++Devices/src/Gyro.cpp +++ b/wpilibc/wpilibC++Devices/src/Gyro.cpp @@ -65,7 +65,7 @@ void Gyro::InitGyro() { SetPIDSourceType(PIDSourceType::kDisplacement); HALReport(HALUsageReporting::kResourceType_Gyro, m_analog->GetChannel()); - LiveWindow::GetInstance().AddSensor("Gyro", m_analog->GetChannel(), this); + LiveWindow::GetInstance()->AddSensor("Gyro", m_analog->GetChannel(), this); } /** @@ -195,7 +195,7 @@ void Gyro::SetDeadband(float volts) { * * @return The PIDOutput (angle or rate, defaults to angle) */ -double Gyro::PIDGet() const { +double Gyro::PIDGet() { switch (GetPIDSourceType()) { case PIDSourceType::kRate: return GetRate(); diff --git a/wpilibc/wpilibC++Devices/src/IterativeRobot.cpp b/wpilibc/wpilibC++Devices/src/IterativeRobot.cpp index d367615369..9a2110d4d8 100644 --- a/wpilibc/wpilibC++Devices/src/IterativeRobot.cpp +++ b/wpilibc/wpilibC++Devices/src/IterativeRobot.cpp @@ -31,7 +31,7 @@ void IterativeRobot::StartCompetition() { HALReport(HALUsageReporting::kResourceType_Framework, HALUsageReporting::kFramework_Iterative); - LiveWindow &lw = LiveWindow::GetInstance(); + LiveWindow *lw = LiveWindow::GetInstance(); // first and one-time initialization SmartDashboard::init(); NetworkTable::GetTable("LiveWindow") @@ -46,14 +46,14 @@ void IterativeRobot::StartCompetition() { HALNetworkCommunicationObserveUserProgramStarting(); // loop forever, calling the appropriate mode-dependent function - lw.SetEnabled(false); + lw->SetEnabled(false); while (true) { // Call the appropriate function depending upon the current robot mode if (IsDisabled()) { // call DisabledInit() if we are now just entering disabled mode from // either a different mode or from power-on if (!m_disabledInitialized) { - lw.SetEnabled(false); + lw->SetEnabled(false); DisabledInit(); m_disabledInitialized = true; // reset the initialization flags for the other modes @@ -67,7 +67,7 @@ void IterativeRobot::StartCompetition() { // call AutonomousInit() if we are now just entering autonomous mode from // either a different mode or from power-on if (!m_autonomousInitialized) { - lw.SetEnabled(false); + lw->SetEnabled(false); AutonomousInit(); m_autonomousInitialized = true; // reset the initialization flags for the other modes @@ -81,7 +81,7 @@ void IterativeRobot::StartCompetition() { // call TestInit() if we are now just entering test mode from // either a different mode or from power-on if (!m_testInitialized) { - lw.SetEnabled(true); + lw->SetEnabled(true); TestInit(); m_testInitialized = true; // reset the initialization flags for the other modes @@ -95,14 +95,14 @@ void IterativeRobot::StartCompetition() { // call TeleopInit() if we are now just entering teleop mode from // either a different mode or from power-on if (!m_teleopInitialized) { - lw.SetEnabled(false); + lw->SetEnabled(false); TeleopInit(); m_teleopInitialized = true; // reset the initialization flags for the other modes m_disabledInitialized = false; m_autonomousInitialized = false; m_testInitialized = false; - Scheduler::GetInstance().SetEnabled(true); + Scheduler::GetInstance()->SetEnabled(true); } HALNetworkCommunicationObserveUserProgramTeleop(); TeleopPeriodic(); diff --git a/wpilibc/wpilibC++Devices/src/Jaguar.cpp b/wpilibc/wpilibC++Devices/src/Jaguar.cpp index 2351874912..9b02302eb9 100644 --- a/wpilibc/wpilibC++Devices/src/Jaguar.cpp +++ b/wpilibc/wpilibC++Devices/src/Jaguar.cpp @@ -30,7 +30,7 @@ Jaguar::Jaguar(uint32_t channel) : SafePWM(channel) { SetZeroLatch(); HALReport(HALUsageReporting::kResourceType_Jaguar, GetChannel()); - LiveWindow::GetInstance().AddActuator("Jaguar", GetChannel(), this); + LiveWindow::GetInstance()->AddActuator("Jaguar", GetChannel(), this); } /** diff --git a/wpilibc/wpilibC++Devices/src/Relay.cpp b/wpilibc/wpilibC++Devices/src/Relay.cpp index 05dc167412..8d48812755 100644 --- a/wpilibc/wpilibC++Devices/src/Relay.cpp +++ b/wpilibc/wpilibC++Devices/src/Relay.cpp @@ -62,7 +62,7 @@ Relay::Relay(uint32_t channel, Relay::Direction direction) setRelayReverse(m_relay_ports[m_channel], false, &status); wpi_setErrorWithContext(status, getHALErrorMessage(status)); - LiveWindow::GetInstance().AddActuator("Relay", 1, m_channel, this); + LiveWindow::GetInstance()->AddActuator("Relay", 1, m_channel, this); } /** diff --git a/wpilibc/wpilibC++Devices/src/SampleRobot.cpp b/wpilibc/wpilibC++Devices/src/SampleRobot.cpp index 2fa9bebc5b..eb2d0bbc85 100644 --- a/wpilibc/wpilibC++Devices/src/SampleRobot.cpp +++ b/wpilibc/wpilibC++Devices/src/SampleRobot.cpp @@ -101,7 +101,7 @@ void SampleRobot::RobotMain() { m_robotMainOverridden = false; } * robot to be enabled again. */ void SampleRobot::StartCompetition() { - LiveWindow &lw = LiveWindow::GetInstance(); + LiveWindow *lw = LiveWindow::GetInstance(); HALReport(HALUsageReporting::kResourceType_Framework, HALUsageReporting::kFramework_Simple); @@ -115,7 +115,7 @@ void SampleRobot::StartCompetition() { if (!m_robotMainOverridden) { // first and one-time initialization - lw.SetEnabled(false); + lw->SetEnabled(false); RobotInit(); while (true) { @@ -130,12 +130,12 @@ void SampleRobot::StartCompetition() { m_ds.InAutonomous(false); while (IsAutonomous() && IsEnabled()) m_ds.WaitForData(); } else if (IsTest()) { - lw.SetEnabled(true); + lw->SetEnabled(true); m_ds.InTest(true); Test(); m_ds.InTest(false); while (IsTest() && IsEnabled()) m_ds.WaitForData(); - lw.SetEnabled(false); + lw->SetEnabled(false); } else { m_ds.InOperatorControl(true); OperatorControl(); diff --git a/wpilibc/wpilibC++Devices/src/Solenoid.cpp b/wpilibc/wpilibC++Devices/src/Solenoid.cpp index b6d0669be1..fd9c6450e6 100644 --- a/wpilibc/wpilibC++Devices/src/Solenoid.cpp +++ b/wpilibc/wpilibC++Devices/src/Solenoid.cpp @@ -48,7 +48,7 @@ Solenoid::Solenoid(uint8_t moduleNumber, uint32_t channel) return; } - LiveWindow::GetInstance().AddActuator("Solenoid", m_moduleNumber, m_channel, + LiveWindow::GetInstance()->AddActuator("Solenoid", m_moduleNumber, m_channel, this); HALReport(HALUsageReporting::kResourceType_Solenoid, m_channel, m_moduleNumber); diff --git a/wpilibc/wpilibC++Devices/src/Talon.cpp b/wpilibc/wpilibC++Devices/src/Talon.cpp index b9be294a7f..1270af839b 100644 --- a/wpilibc/wpilibC++Devices/src/Talon.cpp +++ b/wpilibc/wpilibC++Devices/src/Talon.cpp @@ -35,7 +35,7 @@ Talon::Talon(uint32_t channel) : SafePWM(channel) { SetZeroLatch(); HALReport(HALUsageReporting::kResourceType_Talon, GetChannel()); - LiveWindow::GetInstance().AddActuator("Talon", GetChannel(), this); + LiveWindow::GetInstance()->AddActuator("Talon", GetChannel(), this); } /** diff --git a/wpilibc/wpilibC++Devices/src/TalonSRX.cpp b/wpilibc/wpilibC++Devices/src/TalonSRX.cpp index ea00cd440e..6e6115f872 100644 --- a/wpilibc/wpilibC++Devices/src/TalonSRX.cpp +++ b/wpilibc/wpilibC++Devices/src/TalonSRX.cpp @@ -34,7 +34,7 @@ TalonSRX::TalonSRX(uint32_t channel) : SafePWM(channel) { SetZeroLatch(); HALReport(HALUsageReporting::kResourceType_TalonSRX, GetChannel()); - LiveWindow::GetInstance().AddActuator("TalonSRX", GetChannel(), this); + LiveWindow::GetInstance()->AddActuator("TalonSRX", GetChannel(), this); } /** diff --git a/wpilibc/wpilibC++Devices/src/Ultrasonic.cpp b/wpilibc/wpilibC++Devices/src/Ultrasonic.cpp index e81b990fc1..5ddf0f645b 100644 --- a/wpilibc/wpilibC++Devices/src/Ultrasonic.cpp +++ b/wpilibc/wpilibC++Devices/src/Ultrasonic.cpp @@ -81,7 +81,7 @@ void Ultrasonic::Initialize() { static int instances = 0; instances++; HALReport(HALUsageReporting::kResourceType_Ultrasonic, instances); - LiveWindow::GetInstance().AddSensor("Ultrasonic", + LiveWindow::GetInstance()->AddSensor("Ultrasonic", m_echoChannel->GetChannel(), this); } @@ -305,7 +305,7 @@ double Ultrasonic::GetRangeMM() const { return GetRangeInches() * 25.4; } * * @return The range in DistanceUnit */ -double Ultrasonic::PIDGet() const { +double Ultrasonic::PIDGet() { switch (m_units) { case Ultrasonic::kInches: return GetRangeInches(); diff --git a/wpilibc/wpilibC++Devices/src/Victor.cpp b/wpilibc/wpilibC++Devices/src/Victor.cpp index f20e1904d9..30202db528 100644 --- a/wpilibc/wpilibC++Devices/src/Victor.cpp +++ b/wpilibc/wpilibC++Devices/src/Victor.cpp @@ -35,7 +35,7 @@ Victor::Victor(uint32_t channel) : SafePWM(channel) { SetRaw(m_centerPwm); SetZeroLatch(); - LiveWindow::GetInstance().AddActuator("Victor", GetChannel(), this); + LiveWindow::GetInstance()->AddActuator("Victor", GetChannel(), this); HALReport(HALUsageReporting::kResourceType_Victor, GetChannel()); } diff --git a/wpilibc/wpilibC++Devices/src/VictorSP.cpp b/wpilibc/wpilibC++Devices/src/VictorSP.cpp index 81af2c3d91..5341ccfb93 100644 --- a/wpilibc/wpilibC++Devices/src/VictorSP.cpp +++ b/wpilibc/wpilibC++Devices/src/VictorSP.cpp @@ -39,7 +39,7 @@ VictorSP::VictorSP(uint32_t channel) : SafePWM(channel) { SetZeroLatch(); HALReport(HALUsageReporting::kResourceType_VictorSP, GetChannel()); - LiveWindow::GetInstance().AddActuator("VictorSP", GetChannel(), this); + LiveWindow::GetInstance()->AddActuator("VictorSP", GetChannel(), this); } /** diff --git a/wpilibc/wpilibC++IntegrationTests/src/TestEnvironment.cpp b/wpilibc/wpilibC++IntegrationTests/src/TestEnvironment.cpp index b727e3f295..d65493a86a 100644 --- a/wpilibc/wpilibC++IntegrationTests/src/TestEnvironment.cpp +++ b/wpilibc/wpilibC++IntegrationTests/src/TestEnvironment.cpp @@ -30,7 +30,7 @@ class TestEnvironment : public testing::Environment { station returns that the robot is enabled, to ensure that tests will be able to run on the hardware. */ HALNetworkCommunicationObserveUserProgramStarting(); - LiveWindow::GetInstance().SetEnabled(false); + LiveWindow::GetInstance()->SetEnabled(false); std::cout << "Waiting for enable" << std::endl; diff --git a/wpilibc/wpilibC++IntegrationTests/src/command/CommandTest.cpp b/wpilibc/wpilibC++IntegrationTests/src/command/CommandTest.cpp index 15dd774e7b..3e16021fd1 100644 --- a/wpilibc/wpilibC++IntegrationTests/src/command/CommandTest.cpp +++ b/wpilibc/wpilibC++IntegrationTests/src/command/CommandTest.cpp @@ -18,7 +18,7 @@ class CommandTest : public testing::Test { protected: virtual void SetUp() override { RobotState::SetImplementation(DriverStation::GetInstance()); - Scheduler::GetInstance().SetEnabled(true); + Scheduler::GetInstance()->SetEnabled(true); } /** @@ -30,7 +30,7 @@ class CommandTest : public testing::Test { * is called outside of the * scope of the test. */ - void TeardownScheduler() { Scheduler::GetInstance().ResetAll(); } + void TeardownScheduler() { Scheduler::GetInstance()->ResetAll(); } void AssertCommandState(MockCommand &command, int initialize, int execute, int isFinished, int end, int interrupted) { @@ -72,24 +72,24 @@ TEST_F(CommandTest, ParallelCommands) { commandGroup.Start(); AssertCommandState(command1, 0, 0, 0, 0, 0); AssertCommandState(command2, 0, 0, 0, 0, 0); - Scheduler::GetInstance().Run(); + Scheduler::GetInstance()->Run(); AssertCommandState(command1, 0, 0, 0, 0, 0); AssertCommandState(command2, 0, 0, 0, 0, 0); - Scheduler::GetInstance().Run(); + Scheduler::GetInstance()->Run(); AssertCommandState(command1, 1, 1, 1, 0, 0); AssertCommandState(command2, 1, 1, 1, 0, 0); - Scheduler::GetInstance().Run(); + Scheduler::GetInstance()->Run(); AssertCommandState(command1, 1, 2, 2, 0, 0); AssertCommandState(command2, 1, 2, 2, 0, 0); command1.SetHasFinished(true); - Scheduler::GetInstance().Run(); + Scheduler::GetInstance()->Run(); AssertCommandState(command1, 1, 3, 3, 1, 0); AssertCommandState(command2, 1, 3, 3, 0, 0); - Scheduler::GetInstance().Run(); + Scheduler::GetInstance()->Run(); AssertCommandState(command1, 1, 3, 3, 1, 0); AssertCommandState(command2, 1, 4, 4, 0, 0); command2.SetHasFinished(true); - Scheduler::GetInstance().Run(); + Scheduler::GetInstance()->Run(); AssertCommandState(command1, 1, 3, 3, 1, 0); AssertCommandState(command2, 1, 5, 5, 1, 0); @@ -102,17 +102,17 @@ TEST_F(CommandTest, RunAndTerminate) { MockCommand command; command.Start(); AssertCommandState(command, 0, 0, 0, 0, 0); - Scheduler::GetInstance().Run(); + Scheduler::GetInstance()->Run(); AssertCommandState(command, 0, 0, 0, 0, 0); - Scheduler::GetInstance().Run(); + Scheduler::GetInstance()->Run(); AssertCommandState(command, 1, 1, 1, 0, 0); - Scheduler::GetInstance().Run(); + Scheduler::GetInstance()->Run(); AssertCommandState(command, 1, 2, 2, 0, 0); command.SetHasFinished(true); AssertCommandState(command, 1, 2, 2, 0, 0); - Scheduler::GetInstance().Run(); + Scheduler::GetInstance()->Run(); AssertCommandState(command, 1, 3, 3, 1, 0); - Scheduler::GetInstance().Run(); + Scheduler::GetInstance()->Run(); AssertCommandState(command, 1, 3, 3, 1, 0); TeardownScheduler(); @@ -122,19 +122,19 @@ TEST_F(CommandTest, RunAndCancel) { MockCommand command; command.Start(); AssertCommandState(command, 0, 0, 0, 0, 0); - Scheduler::GetInstance().Run(); + Scheduler::GetInstance()->Run(); AssertCommandState(command, 0, 0, 0, 0, 0); - Scheduler::GetInstance().Run(); + Scheduler::GetInstance()->Run(); AssertCommandState(command, 1, 1, 1, 0, 0); - Scheduler::GetInstance().Run(); + Scheduler::GetInstance()->Run(); AssertCommandState(command, 1, 2, 2, 0, 0); - Scheduler::GetInstance().Run(); + Scheduler::GetInstance()->Run(); AssertCommandState(command, 1, 3, 3, 0, 0); command.Cancel(); AssertCommandState(command, 1, 3, 3, 0, 0); - Scheduler::GetInstance().Run(); + Scheduler::GetInstance()->Run(); AssertCommandState(command, 1, 3, 3, 0, 1); - Scheduler::GetInstance().Run(); + Scheduler::GetInstance()->Run(); AssertCommandState(command, 1, 3, 3, 0, 1); TeardownScheduler(); @@ -165,34 +165,34 @@ TEST_F(CommandTest, ThreeCommandOnSubSystem) { AssertCommandState(command2, 0, 0, 0, 0, 0); AssertCommandState(command3, 0, 0, 0, 0, 0); - Scheduler::GetInstance().Run(); + Scheduler::GetInstance()->Run(); AssertCommandState(command1, 0, 0, 0, 0, 0); AssertCommandState(command2, 0, 0, 0, 0, 0); AssertCommandState(command3, 0, 0, 0, 0, 0); - Scheduler::GetInstance().Run(); + Scheduler::GetInstance()->Run(); AssertCommandState(command1, 1, 1, 1, 0, 0); AssertCommandState(command2, 0, 0, 0, 0, 0); AssertCommandState(command3, 0, 0, 0, 0, 0); Wait(1); // command 1 timeout - Scheduler::GetInstance().Run(); + Scheduler::GetInstance()->Run(); AssertCommandState(command1, 1, 1, 1, 0, 1); AssertCommandState(command2, 1, 1, 1, 0, 0); AssertCommandState(command3, 0, 0, 0, 0, 0); - Scheduler::GetInstance().Run(); + Scheduler::GetInstance()->Run(); AssertCommandState(command1, 1, 1, 1, 0, 1); AssertCommandState(command2, 1, 2, 2, 0, 0); AssertCommandState(command3, 0, 0, 0, 0, 0); Wait(2); // command 2 timeout - Scheduler::GetInstance().Run(); + Scheduler::GetInstance()->Run(); AssertCommandState(command1, 1, 1, 1, 0, 1); AssertCommandState(command2, 1, 2, 2, 0, 1); AssertCommandState(command3, 1, 1, 1, 0, 0); - Scheduler::GetInstance().Run(); + Scheduler::GetInstance()->Run(); AssertCommandState(command1, 1, 1, 1, 0, 1); AssertCommandState(command2, 1, 2, 2, 0, 1); AssertCommandState(command3, 1, 2, 2, 0, 0); @@ -201,12 +201,12 @@ TEST_F(CommandTest, ThreeCommandOnSubSystem) { AssertCommandState(command2, 1, 2, 2, 0, 1); AssertCommandState(command3, 1, 2, 2, 0, 0); - Scheduler::GetInstance().Run(); + Scheduler::GetInstance()->Run(); AssertCommandState(command1, 1, 1, 1, 0, 1); AssertCommandState(command2, 1, 2, 2, 0, 1); AssertCommandState(command3, 1, 3, 3, 1, 0); - Scheduler::GetInstance().Run(); + Scheduler::GetInstance()->Run(); AssertCommandState(command1, 1, 1, 1, 0, 1); AssertCommandState(command2, 1, 2, 2, 0, 1); AssertCommandState(command3, 1, 3, 3, 1, 0); @@ -230,19 +230,19 @@ TEST_F(CommandTest, OneCommandSupersedingAnotherBecauseOfDependencies) { AssertCommandState(command1, 0, 0, 0, 0, 0); AssertCommandState(command2, 0, 0, 0, 0, 0); - Scheduler::GetInstance().Run(); + Scheduler::GetInstance()->Run(); AssertCommandState(command1, 0, 0, 0, 0, 0); AssertCommandState(command2, 0, 0, 0, 0, 0); - Scheduler::GetInstance().Run(); + Scheduler::GetInstance()->Run(); AssertCommandState(command1, 1, 1, 1, 0, 0); AssertCommandState(command2, 0, 0, 0, 0, 0); - Scheduler::GetInstance().Run(); + Scheduler::GetInstance()->Run(); AssertCommandState(command1, 1, 2, 2, 0, 0); AssertCommandState(command2, 0, 0, 0, 0, 0); - Scheduler::GetInstance().Run(); + Scheduler::GetInstance()->Run(); AssertCommandState(command1, 1, 3, 3, 0, 0); AssertCommandState(command2, 0, 0, 0, 0, 0); @@ -250,19 +250,19 @@ TEST_F(CommandTest, OneCommandSupersedingAnotherBecauseOfDependencies) { AssertCommandState(command1, 1, 3, 3, 0, 0); AssertCommandState(command2, 0, 0, 0, 0, 0); - Scheduler::GetInstance().Run(); + Scheduler::GetInstance()->Run(); AssertCommandState(command1, 1, 4, 4, 0, 1); AssertCommandState(command2, 0, 0, 0, 0, 0); - Scheduler::GetInstance().Run(); + Scheduler::GetInstance()->Run(); AssertCommandState(command1, 1, 4, 4, 0, 1); AssertCommandState(command2, 1, 1, 1, 0, 0); - Scheduler::GetInstance().Run(); + Scheduler::GetInstance()->Run(); AssertCommandState(command1, 1, 4, 4, 0, 1); AssertCommandState(command2, 1, 2, 2, 0, 0); - Scheduler::GetInstance().Run(); + Scheduler::GetInstance()->Run(); AssertCommandState(command1, 1, 4, 4, 0, 1); AssertCommandState(command2, 1, 3, 3, 0, 0); @@ -287,19 +287,19 @@ TEST_F(CommandTest, AssertCommandState(command1, 0, 0, 0, 0, 0); AssertCommandState(command2, 0, 0, 0, 0, 0); - Scheduler::GetInstance().Run(); + Scheduler::GetInstance()->Run(); AssertCommandState(command1, 0, 0, 0, 0, 0); AssertCommandState(command2, 0, 0, 0, 0, 0); - Scheduler::GetInstance().Run(); + Scheduler::GetInstance()->Run(); AssertCommandState(command1, 1, 1, 1, 0, 0); AssertCommandState(command2, 0, 0, 0, 0, 0); - Scheduler::GetInstance().Run(); + Scheduler::GetInstance()->Run(); AssertCommandState(command1, 1, 2, 2, 0, 0); AssertCommandState(command2, 0, 0, 0, 0, 0); - Scheduler::GetInstance().Run(); + Scheduler::GetInstance()->Run(); AssertCommandState(command1, 1, 3, 3, 0, 0); AssertCommandState(command2, 0, 0, 0, 0, 0); @@ -307,7 +307,7 @@ TEST_F(CommandTest, AssertCommandState(command1, 1, 3, 3, 0, 0); AssertCommandState(command2, 0, 0, 0, 0, 0); - Scheduler::GetInstance().Run(); + Scheduler::GetInstance()->Run(); AssertCommandState(command1, 1, 4, 4, 0, 0); AssertCommandState(command2, 0, 0, 0, 0, 0); @@ -331,18 +331,18 @@ TEST_F(CommandTest, TwoSecondTimeout) { command.Start(); AssertCommandState(command, 0, 0, 0, 0, 0); - Scheduler::GetInstance().Run(); + Scheduler::GetInstance()->Run(); AssertCommandState(command, 0, 0, 0, 0, 0); - Scheduler::GetInstance().Run(); + Scheduler::GetInstance()->Run(); AssertCommandState(command, 1, 1, 1, 0, 0); - Scheduler::GetInstance().Run(); + Scheduler::GetInstance()->Run(); AssertCommandState(command, 1, 2, 2, 0, 0); - Scheduler::GetInstance().Run(); + Scheduler::GetInstance()->Run(); AssertCommandState(command, 1, 3, 3, 0, 0); Wait(2); - Scheduler::GetInstance().Run(); + Scheduler::GetInstance()->Run(); AssertCommandState(command, 1, 4, 4, 1, 0); - Scheduler::GetInstance().Run(); + Scheduler::GetInstance()->Run(); AssertCommandState(command, 1, 4, 4, 1, 0); TeardownScheduler(); @@ -359,35 +359,35 @@ TEST_F(CommandTest, DefaultCommandWhereTheInteruptingCommandEndsItself) { subsystem.Init(&defaultCommand); AssertCommandState(defaultCommand, 0, 0, 0, 0, 0); - Scheduler::GetInstance().Run(); + Scheduler::GetInstance()->Run(); AssertCommandState(defaultCommand, 0, 0, 0, 0, 0); - Scheduler::GetInstance().Run(); + Scheduler::GetInstance()->Run(); AssertCommandState(defaultCommand, 1, 1, 1, 0, 0); - Scheduler::GetInstance().Run(); + Scheduler::GetInstance()->Run(); AssertCommandState(defaultCommand, 1, 2, 2, 0, 0); anotherCommand.Start(); AssertCommandState(defaultCommand, 1, 2, 2, 0, 0); AssertCommandState(anotherCommand, 0, 0, 0, 0, 0); - Scheduler::GetInstance().Run(); + Scheduler::GetInstance()->Run(); AssertCommandState(defaultCommand, 1, 3, 3, 0, 1); AssertCommandState(anotherCommand, 0, 0, 0, 0, 0); - Scheduler::GetInstance().Run(); + Scheduler::GetInstance()->Run(); AssertCommandState(defaultCommand, 1, 3, 3, 0, 1); AssertCommandState(anotherCommand, 1, 1, 1, 0, 0); - Scheduler::GetInstance().Run(); + Scheduler::GetInstance()->Run(); AssertCommandState(defaultCommand, 1, 3, 3, 0, 1); AssertCommandState(anotherCommand, 1, 2, 2, 0, 0); anotherCommand.SetHasFinished(true); AssertCommandState(defaultCommand, 1, 3, 3, 0, 1); AssertCommandState(anotherCommand, 1, 2, 2, 0, 0); - Scheduler::GetInstance().Run(); + Scheduler::GetInstance()->Run(); AssertCommandState(defaultCommand, 1, 3, 3, 0, 1); AssertCommandState(anotherCommand, 1, 3, 3, 1, 0); - Scheduler::GetInstance().Run(); + Scheduler::GetInstance()->Run(); AssertCommandState(defaultCommand, 2, 4, 4, 0, 1); AssertCommandState(anotherCommand, 1, 3, 3, 1, 0); - Scheduler::GetInstance().Run(); + Scheduler::GetInstance()->Run(); AssertCommandState(defaultCommand, 2, 5, 5, 0, 1); AssertCommandState(anotherCommand, 1, 3, 3, 1, 0); @@ -405,35 +405,35 @@ TEST_F(CommandTest, DefaultCommandsInterruptingCommandCanceled) { subsystem.Init(&defaultCommand); subsystem.InitDefaultCommand(); AssertCommandState(defaultCommand, 0, 0, 0, 0, 0); - Scheduler::GetInstance().Run(); + Scheduler::GetInstance()->Run(); AssertCommandState(defaultCommand, 0, 0, 0, 0, 0); - Scheduler::GetInstance().Run(); + Scheduler::GetInstance()->Run(); AssertCommandState(defaultCommand, 1, 1, 1, 0, 0); - Scheduler::GetInstance().Run(); + Scheduler::GetInstance()->Run(); AssertCommandState(defaultCommand, 1, 2, 2, 0, 0); anotherCommand.Start(); AssertCommandState(defaultCommand, 1, 2, 2, 0, 0); AssertCommandState(anotherCommand, 0, 0, 0, 0, 0); - Scheduler::GetInstance().Run(); + Scheduler::GetInstance()->Run(); AssertCommandState(defaultCommand, 1, 3, 3, 0, 1); AssertCommandState(anotherCommand, 0, 0, 0, 0, 0); - Scheduler::GetInstance().Run(); + Scheduler::GetInstance()->Run(); AssertCommandState(defaultCommand, 1, 3, 3, 0, 1); AssertCommandState(anotherCommand, 1, 1, 1, 0, 0); - Scheduler::GetInstance().Run(); + Scheduler::GetInstance()->Run(); AssertCommandState(defaultCommand, 1, 3, 3, 0, 1); AssertCommandState(anotherCommand, 1, 2, 2, 0, 0); anotherCommand.Cancel(); AssertCommandState(defaultCommand, 1, 3, 3, 0, 1); AssertCommandState(anotherCommand, 1, 2, 2, 0, 0); - Scheduler::GetInstance().Run(); + Scheduler::GetInstance()->Run(); AssertCommandState(defaultCommand, 1, 3, 3, 0, 1); AssertCommandState(anotherCommand, 1, 2, 2, 0, 1); - Scheduler::GetInstance().Run(); + Scheduler::GetInstance()->Run(); AssertCommandState(defaultCommand, 2, 4, 4, 0, 1); AssertCommandState(anotherCommand, 1, 2, 2, 0, 1); - Scheduler::GetInstance().Run(); + Scheduler::GetInstance()->Run(); AssertCommandState(defaultCommand, 2, 5, 5, 0, 1); AssertCommandState(anotherCommand, 1, 2, 2, 0, 1); diff --git a/wpilibc/wpilibC++Sim/include/AnalogInput.h b/wpilibc/wpilibC++Sim/include/AnalogInput.h index dd85922b01..9ce15d31c2 100644 --- a/wpilibc/wpilibC++Sim/include/AnalogInput.h +++ b/wpilibc/wpilibC++Sim/include/AnalogInput.h @@ -37,7 +37,7 @@ public: uint32_t GetChannel() const; - double PIDGet() const override; + double PIDGet() override; void UpdateTable() override; void StartLiveWindowMode() override; diff --git a/wpilibc/wpilibC++Sim/include/AnalogPotentiometer.h b/wpilibc/wpilibC++Sim/include/AnalogPotentiometer.h index 90a62f7d8a..786f36f757 100644 --- a/wpilibc/wpilibC++Sim/include/AnalogPotentiometer.h +++ b/wpilibc/wpilibC++Sim/include/AnalogPotentiometer.h @@ -51,7 +51,7 @@ public: * * @return The current reading. */ - virtual double PIDGet() const override; + virtual double PIDGet() override; /* diff --git a/wpilibc/wpilibC++Sim/include/Encoder.h b/wpilibc/wpilibC++Sim/include/Encoder.h index b573522a1f..89b1b3a303 100644 --- a/wpilibc/wpilibC++Sim/include/Encoder.h +++ b/wpilibc/wpilibC++Sim/include/Encoder.h @@ -54,7 +54,7 @@ public: void SetSamplesToAverage(int samplesToAverage); int GetSamplesToAverage() const; void SetPIDSourceType(PIDSourceType pidSource); - double PIDGet() const override; + double PIDGet() override; void UpdateTable() override; void StartLiveWindowMode() override; diff --git a/wpilibc/wpilibC++Sim/include/Gyro.h b/wpilibc/wpilibC++Sim/include/Gyro.h index 3eae6e8bc6..9503738ab3 100644 --- a/wpilibc/wpilibC++Sim/include/Gyro.h +++ b/wpilibc/wpilibC++Sim/include/Gyro.h @@ -42,7 +42,7 @@ public: // PIDSource interface void SetPIDSourceType(PIDSourceType pidSource) override; - double PIDGet() const override; + double PIDGet() override; void UpdateTable() override; void StartLiveWindowMode() override; diff --git a/wpilibc/wpilibC++Sim/src/AnalogInput.cpp b/wpilibc/wpilibC++Sim/src/AnalogInput.cpp index 561a6f4c03..71c48c565a 100644 --- a/wpilibc/wpilibC++Sim/src/AnalogInput.cpp +++ b/wpilibc/wpilibC++Sim/src/AnalogInput.cpp @@ -20,7 +20,7 @@ AnalogInput::AnalogInput(uint32_t channel) int n = sprintf(buffer, "analog/%d", channel); m_impl = new SimFloatInput(buffer); - LiveWindow::GetInstance().AddSensor("AnalogInput", channel, this); + LiveWindow::GetInstance()->AddSensor("AnalogInput", channel, this); } /** @@ -59,7 +59,7 @@ uint32_t AnalogInput::GetChannel() const * * @return The average voltage. */ -double AnalogInput::PIDGet() const +double AnalogInput::PIDGet() { return GetAverageVoltage(); } diff --git a/wpilibc/wpilibC++Sim/src/AnalogPotentiometer.cpp b/wpilibc/wpilibC++Sim/src/AnalogPotentiometer.cpp index e7f6b49d36..fa312c12e0 100644 --- a/wpilibc/wpilibC++Sim/src/AnalogPotentiometer.cpp +++ b/wpilibc/wpilibC++Sim/src/AnalogPotentiometer.cpp @@ -46,7 +46,7 @@ double AnalogPotentiometer::Get() const { * * @return The current reading. */ -double AnalogPotentiometer::PIDGet() const { +double AnalogPotentiometer::PIDGet() { return Get(); } diff --git a/wpilibc/wpilibC++Sim/src/DoubleSolenoid.cpp b/wpilibc/wpilibC++Sim/src/DoubleSolenoid.cpp index c4cb6c6e96..b6e45278e4 100644 --- a/wpilibc/wpilibC++Sim/src/DoubleSolenoid.cpp +++ b/wpilibc/wpilibC++Sim/src/DoubleSolenoid.cpp @@ -39,7 +39,7 @@ DoubleSolenoid::DoubleSolenoid(uint8_t moduleNumber, uint32_t forwardChannel, ui forwardChannel, moduleNumber, reverseChannel); m_impl = new SimContinuousOutput(buffer); - LiveWindow::GetInstance().AddActuator("DoubleSolenoid", moduleNumber, + LiveWindow::GetInstance()->AddActuator("DoubleSolenoid", moduleNumber, forwardChannel, this); } diff --git a/wpilibc/wpilibC++Sim/src/Encoder.cpp b/wpilibc/wpilibC++Sim/src/Encoder.cpp index ecd658bd1c..790868e5ce 100644 --- a/wpilibc/wpilibC++Sim/src/Encoder.cpp +++ b/wpilibc/wpilibC++Sim/src/Encoder.cpp @@ -35,7 +35,7 @@ void Encoder::InitEncoder(int channelA, int channelB, bool reverseDirection, Enc int32_t index = 0; m_distancePerPulse = 1.0; - LiveWindow::GetInstance().AddSensor("Encoder", channelA, this); + LiveWindow::GetInstance()->AddSensor("Encoder", channelA, this); if (channelB < channelA) { // Swap ports int channel = channelB; @@ -318,7 +318,7 @@ void Encoder::SetPIDSourceType(PIDSourceType pidSource) * * @return The current value of the selected source parameter. */ -double Encoder::PIDGet() const +double Encoder::PIDGet() { switch (m_pidSource) { diff --git a/wpilibc/wpilibC++Sim/src/Gyro.cpp b/wpilibc/wpilibC++Sim/src/Gyro.cpp index 09571b76a6..a28bb9b523 100644 --- a/wpilibc/wpilibC++Sim/src/Gyro.cpp +++ b/wpilibc/wpilibC++Sim/src/Gyro.cpp @@ -31,7 +31,7 @@ void Gyro::InitGyro(int channel) int n = sprintf(buffer, "analog/%d", channel); impl = new SimGyro(buffer); - LiveWindow::GetInstance().AddSensor("Gyro", channel, this); + LiveWindow::GetInstance()->AddSensor("Gyro", channel, this); } /** @@ -93,7 +93,7 @@ void Gyro::SetPIDSourceType(PIDSourceType pidSource) * * @return The angle in degrees. */ -double Gyro::PIDGet() const +double Gyro::PIDGet() { switch(GetPIDSourceType()){ case PIDSourceType::kRate: diff --git a/wpilibc/wpilibC++Sim/src/IterativeRobot.cpp b/wpilibc/wpilibC++Sim/src/IterativeRobot.cpp index e18d40be15..f2511df7da 100644 --- a/wpilibc/wpilibC++Sim/src/IterativeRobot.cpp +++ b/wpilibc/wpilibC++Sim/src/IterativeRobot.cpp @@ -71,14 +71,14 @@ double IterativeRobot::GetLoopsPerSec() */ void IterativeRobot::StartCompetition() { - LiveWindow &lw = LiveWindow::GetInstance(); + LiveWindow *lw = LiveWindow::GetInstance(); // first and one-time initialization SmartDashboard::init(); NetworkTable::GetTable("LiveWindow")->GetSubTable("~STATUS~")->PutBoolean("LW Enabled", false); RobotInit(); // loop forever, calling the appropriate mode-dependent function - lw.SetEnabled(false); + lw->SetEnabled(false); while (true) { // Call the appropriate function depending upon the current robot mode @@ -88,7 +88,7 @@ void IterativeRobot::StartCompetition() // either a different mode or from power-on if(!m_disabledInitialized) { - lw.SetEnabled(false); + lw->SetEnabled(false); DisabledInit(); m_disabledInitialized = true; // reset the initialization flags for the other modes @@ -108,7 +108,7 @@ void IterativeRobot::StartCompetition() // either a different mode or from power-on if(!m_autonomousInitialized) { - lw.SetEnabled(false); + lw->SetEnabled(false); AutonomousInit(); m_autonomousInitialized = true; // reset the initialization flags for the other modes @@ -128,7 +128,7 @@ void IterativeRobot::StartCompetition() // either a different mode or from power-on if(!m_testInitialized) { - lw.SetEnabled(true); + lw->SetEnabled(true); TestInit(); m_testInitialized = true; // reset the initialization flags for the other modes @@ -148,14 +148,14 @@ void IterativeRobot::StartCompetition() // either a different mode or from power-on if(!m_teleopInitialized) { - lw.SetEnabled(false); + lw->SetEnabled(false); TeleopInit(); m_teleopInitialized = true; // reset the initialization flags for the other modes m_disabledInitialized = false; m_autonomousInitialized = false; m_testInitialized = false; - Scheduler::GetInstance().SetEnabled(true); + Scheduler::GetInstance()->SetEnabled(true); } if (NextPeriodReady()) { diff --git a/wpilibc/wpilibC++Sim/src/Jaguar.cpp b/wpilibc/wpilibC++Sim/src/Jaguar.cpp index f6fafc499e..fab109d578 100644 --- a/wpilibc/wpilibC++Sim/src/Jaguar.cpp +++ b/wpilibc/wpilibC++Sim/src/Jaguar.cpp @@ -27,7 +27,7 @@ Jaguar::Jaguar(uint32_t channel) : SafePWM(channel) SetPeriodMultiplier(kPeriodMultiplier_1X); SetRaw(m_centerPwm); - LiveWindow::GetInstance().AddActuator("Jaguar", GetChannel(), this); + LiveWindow::GetInstance()->AddActuator("Jaguar", GetChannel(), this); } /** diff --git a/wpilibc/wpilibC++Sim/src/Relay.cpp b/wpilibc/wpilibC++Sim/src/Relay.cpp index 17df05f375..a86320af6d 100644 --- a/wpilibc/wpilibC++Sim/src/Relay.cpp +++ b/wpilibc/wpilibC++Sim/src/Relay.cpp @@ -32,7 +32,7 @@ Relay::Relay(uint32_t channel, Relay::Direction direction) sprintf(buf, "relay/%d", m_channel); impl = new SimContinuousOutput(buf); // TODO: Allow two different relays (targetting the different halves of a relay) to be combined to control one motor. - LiveWindow::GetInstance().AddActuator("Relay", 1, m_channel, this); + LiveWindow::GetInstance()->AddActuator("Relay", 1, m_channel, this); go_pos = go_neg = false; } diff --git a/wpilibc/wpilibC++Sim/src/SampleRobot.cpp b/wpilibc/wpilibC++Sim/src/SampleRobot.cpp index 91a80c70b6..b8f318185e 100644 --- a/wpilibc/wpilibC++Sim/src/SampleRobot.cpp +++ b/wpilibc/wpilibC++Sim/src/SampleRobot.cpp @@ -107,7 +107,7 @@ void SampleRobot::RobotMain() */ void SampleRobot::StartCompetition() { - LiveWindow &lw = LiveWindow::GetInstance(); + LiveWindow *lw = LiveWindow::GetInstance(); SmartDashboard::init(); NetworkTable::GetTable("LiveWindow")->GetSubTable("~STATUS~")->PutBoolean("LW Enabled", false); @@ -117,7 +117,7 @@ void SampleRobot::StartCompetition() if (!m_robotMainOverridden) { // first and one-time initialization - lw.SetEnabled(false); + lw->SetEnabled(false); RobotInit(); while (true) @@ -138,12 +138,12 @@ void SampleRobot::StartCompetition() } else if (IsTest()) { - lw.SetEnabled(true); + lw->SetEnabled(true); m_ds.InTest(true); Test(); m_ds.InTest(false); - while (IsTest() && IsEnabled()) sleep(1); //m_ds.WaitForData(); - lw.SetEnabled(false); + while (IsTest() && IsEnabled()) sleep(1); //m_ds.WaitForData(); + lw->SetEnabled(false); } else { diff --git a/wpilibc/wpilibC++Sim/src/Solenoid.cpp b/wpilibc/wpilibC++Sim/src/Solenoid.cpp index 26a38a9764..682995b497 100644 --- a/wpilibc/wpilibC++Sim/src/Solenoid.cpp +++ b/wpilibc/wpilibC++Sim/src/Solenoid.cpp @@ -28,7 +28,7 @@ Solenoid::Solenoid(uint8_t moduleNumber, uint32_t channel) int n = sprintf(buffer, "pneumatic/%d/%d", moduleNumber, channel); m_impl = new SimContinuousOutput(buffer); - LiveWindow::GetInstance().AddActuator("Solenoid", moduleNumber, channel, + LiveWindow::GetInstance()->AddActuator("Solenoid", moduleNumber, channel, this); } diff --git a/wpilibc/wpilibC++Sim/src/Talon.cpp b/wpilibc/wpilibC++Sim/src/Talon.cpp index 7642d2bf9d..0e9505dbf4 100644 --- a/wpilibc/wpilibC++Sim/src/Talon.cpp +++ b/wpilibc/wpilibC++Sim/src/Talon.cpp @@ -31,7 +31,7 @@ Talon::Talon(uint32_t channel) : SafePWM(channel) SetPeriodMultiplier(kPeriodMultiplier_2X); SetRaw(m_centerPwm); - LiveWindow::GetInstance().AddActuator("Talon", GetChannel(), this); + LiveWindow::GetInstance()->AddActuator("Talon", GetChannel(), this); } /** diff --git a/wpilibc/wpilibC++Sim/src/Victor.cpp b/wpilibc/wpilibC++Sim/src/Victor.cpp index dc8050218b..54ba61fd8d 100644 --- a/wpilibc/wpilibC++Sim/src/Victor.cpp +++ b/wpilibc/wpilibC++Sim/src/Victor.cpp @@ -33,7 +33,7 @@ Victor::Victor(uint32_t channel) : SafePWM(channel) SetPeriodMultiplier(kPeriodMultiplier_2X); SetRaw(m_centerPwm); - LiveWindow::GetInstance().AddActuator("Victor", GetChannel(), this); + LiveWindow::GetInstance()->AddActuator("Victor", GetChannel(), this); } /**