From 3d1ca856b28c8d8f015896fb9e9fcfe5dd30bf87 Mon Sep 17 00:00:00 2001 From: Oblarg Date: Thu, 21 Nov 2019 00:46:33 -0500 Subject: [PATCH] Fix missing typename and return type (#2115) --- .../src/main/native/include/frc2/command/ProfiledPIDCommand.h | 4 ++-- .../main/native/include/frc2/command/ProfiledPIDSubsystem.h | 4 ++-- .../native/include/frc2/command/TrapezoidProfileCommand.h | 2 +- .../native/include/frc2/command/TrapezoidProfileSubsystem.h | 4 ++-- 4 files changed, 7 insertions(+), 7 deletions(-) diff --git a/wpilibNewCommands/src/main/native/include/frc2/command/ProfiledPIDCommand.h b/wpilibNewCommands/src/main/native/include/frc2/command/ProfiledPIDCommand.h index 226fa01bc3..3955ba9c6c 100644 --- a/wpilibNewCommands/src/main/native/include/frc2/command/ProfiledPIDCommand.h +++ b/wpilibNewCommands/src/main/native/include/frc2/command/ProfiledPIDCommand.h @@ -32,7 +32,7 @@ class ProfiledPIDCommand using Velocity = units::compound_unit>; using Velocity_t = units::unit_t; - using State = frc::TrapezoidProfile::State; + using State = typename frc::TrapezoidProfile::State; public: /** @@ -139,7 +139,7 @@ class ProfiledPIDCommand protected: frc::ProfiledPIDController m_controller; - std::function> m_measurement; + std::function m_measurement; std::function m_goal; std::function m_useOutput; }; diff --git a/wpilibNewCommands/src/main/native/include/frc2/command/ProfiledPIDSubsystem.h b/wpilibNewCommands/src/main/native/include/frc2/command/ProfiledPIDSubsystem.h index 41815c6162..757668bedf 100644 --- a/wpilibNewCommands/src/main/native/include/frc2/command/ProfiledPIDSubsystem.h +++ b/wpilibNewCommands/src/main/native/include/frc2/command/ProfiledPIDSubsystem.h @@ -25,7 +25,7 @@ class ProfiledPIDSubsystem : public SubsystemBase { using Velocity = units::compound_unit>; using Velocity_t = units::unit_t; - using State = frc::TrapezoidProfile::State; + using State = typename frc::TrapezoidProfile::State; public: /** @@ -65,7 +65,7 @@ class ProfiledPIDSubsystem : public SubsystemBase { * * @return the measurement of the process variable */ - virtual units::meter_t GetMeasurement() = 0; + virtual Distance_t GetMeasurement() = 0; /** * Enables the PID control. Resets the controller. diff --git a/wpilibNewCommands/src/main/native/include/frc2/command/TrapezoidProfileCommand.h b/wpilibNewCommands/src/main/native/include/frc2/command/TrapezoidProfileCommand.h index afa46b1d4f..38b904d88e 100644 --- a/wpilibNewCommands/src/main/native/include/frc2/command/TrapezoidProfileCommand.h +++ b/wpilibNewCommands/src/main/native/include/frc2/command/TrapezoidProfileCommand.h @@ -30,7 +30,7 @@ class TrapezoidProfileCommand using Velocity = units::compound_unit>; using Velocity_t = units::unit_t; - using State = frc::TrapezoidProfile::State; + using State = typename frc::TrapezoidProfile::State; public: /** * Creates a new TrapezoidProfileCommand that will execute the given diff --git a/wpilibNewCommands/src/main/native/include/frc2/command/TrapezoidProfileSubsystem.h b/wpilibNewCommands/src/main/native/include/frc2/command/TrapezoidProfileSubsystem.h index 66c6bc3a87..92837b6fa7 100644 --- a/wpilibNewCommands/src/main/native/include/frc2/command/TrapezoidProfileSubsystem.h +++ b/wpilibNewCommands/src/main/native/include/frc2/command/TrapezoidProfileSubsystem.h @@ -23,8 +23,8 @@ class TrapezoidProfileSubsystem : public SubsystemBase { using Velocity = units::compound_unit>; using Velocity_t = units::unit_t; - using State = frc::TrapezoidProfile::State; - using Constraints = frc::TrapezoidProfile::Constraints; + using State = typename frc::TrapezoidProfile::State; + using Constraints = typename frc::TrapezoidProfile::Constraints; public: /** * Creates a new TrapezoidProfileSubsystem.