mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-20 00:51:42 +00:00
Fix missing typename and return type (#2115)
This commit is contained in:
@@ -32,7 +32,7 @@ class ProfiledPIDCommand
|
||||
using Velocity =
|
||||
units::compound_unit<Distance, units::inverse<units::seconds>>;
|
||||
using Velocity_t = units::unit_t<Velocity>;
|
||||
using State = frc::TrapezoidProfile<Distance>::State;
|
||||
using State = typename frc::TrapezoidProfile<Distance>::State;
|
||||
|
||||
public:
|
||||
/**
|
||||
@@ -139,7 +139,7 @@ class ProfiledPIDCommand
|
||||
|
||||
protected:
|
||||
frc::ProfiledPIDController<Distance> m_controller;
|
||||
std::function<units::unit_t<Distance>> m_measurement;
|
||||
std::function<Distance_t> m_measurement;
|
||||
std::function<State()> m_goal;
|
||||
std::function<void(double, State)> m_useOutput;
|
||||
};
|
||||
|
||||
@@ -25,7 +25,7 @@ class ProfiledPIDSubsystem : public SubsystemBase {
|
||||
using Velocity =
|
||||
units::compound_unit<Distance, units::inverse<units::seconds>>;
|
||||
using Velocity_t = units::unit_t<Velocity>;
|
||||
using State = frc::TrapezoidProfile<Distance>::State;
|
||||
using State = typename frc::TrapezoidProfile<Distance>::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.
|
||||
|
||||
@@ -30,7 +30,7 @@ class TrapezoidProfileCommand
|
||||
using Velocity =
|
||||
units::compound_unit<Distance, units::inverse<units::seconds>>;
|
||||
using Velocity_t = units::unit_t<Velocity>;
|
||||
using State = frc::TrapezoidProfile<Distance>::State;
|
||||
using State = typename frc::TrapezoidProfile<Distance>::State;
|
||||
public:
|
||||
/**
|
||||
* Creates a new TrapezoidProfileCommand that will execute the given
|
||||
|
||||
@@ -23,8 +23,8 @@ class TrapezoidProfileSubsystem : public SubsystemBase {
|
||||
using Velocity =
|
||||
units::compound_unit<Distance, units::inverse<units::seconds>>;
|
||||
using Velocity_t = units::unit_t<Velocity>;
|
||||
using State = frc::TrapezoidProfile<Distance>::State;
|
||||
using Constraints = frc::TrapezoidProfile<Distance>::Constraints;
|
||||
using State = typename frc::TrapezoidProfile<Distance>::State;
|
||||
using Constraints = typename frc::TrapezoidProfile<Distance>::Constraints;
|
||||
public:
|
||||
/**
|
||||
* Creates a new TrapezoidProfileSubsystem.
|
||||
|
||||
Reference in New Issue
Block a user