diff --git a/hal/include/HAL/cpp/Resource.hpp b/hal/include/HAL/cpp/Resource.hpp index f624f62774..ae31996692 100644 --- a/hal/include/HAL/cpp/Resource.hpp +++ b/hal/include/HAL/cpp/Resource.hpp @@ -37,7 +37,7 @@ public: void Free(uint32_t index); private: - ::std::vector m_isAllocated; + std::vector m_isAllocated; priority_recursive_mutex m_allocateLock; static priority_recursive_mutex m_createLock; diff --git a/hal/include/HAL/cpp/priority_mutex.h b/hal/include/HAL/cpp/priority_mutex.h index b4b84c3d79..719c4df4f7 100644 --- a/hal/include/HAL/cpp/priority_mutex.h +++ b/hal/include/HAL/cpp/priority_mutex.h @@ -6,8 +6,8 @@ #ifdef FRC_SIMULATOR // We do not want to use pthreads if in the simulator; however, in the // simulator, we do not care about priority inversion. -typedef ::std::mutex priority_mutex; -typedef ::std::recursive_mutex priority_recursive_mutex; +typedef std::mutex priority_mutex; +typedef std::recursive_mutex priority_recursive_mutex; #else // Covers rest of file. #include diff --git a/networktables/cpp/include/networktables/NetworkTableKeyListenerAdapter.h b/networktables/cpp/include/networktables/NetworkTableKeyListenerAdapter.h index 46f24c6e6b..edbc764bc3 100644 --- a/networktables/cpp/include/networktables/NetworkTableKeyListenerAdapter.h +++ b/networktables/cpp/include/networktables/NetworkTableKeyListenerAdapter.h @@ -28,7 +28,7 @@ public: NetworkTableKeyListenerAdapter(std::string relativeKey, std::string fullKey, NetworkTable* targetSource, ITableListener* targetListener); virtual ~NetworkTableKeyListenerAdapter(); void ValueChanged(ITable* source, const std::string& key, EntryValue value, bool isNew); - void ValueChanged(::std::shared_ptr source, const std::string& key, + void ValueChanged(std::shared_ptr source, const std::string& key, EntryValue value, bool isNew) { ValueChanged(source.get(), key, value, isNew); } diff --git a/networktables/cpp/include/networktables/NetworkTableListenerAdapter.h b/networktables/cpp/include/networktables/NetworkTableListenerAdapter.h index c4da9eb939..d1bed8f9b6 100644 --- a/networktables/cpp/include/networktables/NetworkTableListenerAdapter.h +++ b/networktables/cpp/include/networktables/NetworkTableListenerAdapter.h @@ -26,7 +26,7 @@ class NetworkTableListenerAdapter : public ITableListener { virtual ~NetworkTableListenerAdapter(); void ValueChanged(ITable* source, const std::string& key, EntryValue value, bool isNew); - void ValueChanged(::std::shared_ptr source, const std::string& key, + void ValueChanged(std::shared_ptr source, const std::string& key, EntryValue value, bool isNew) { ValueChanged(source.get(), key, value, isNew); } diff --git a/networktables/cpp/include/networktables/NetworkTableSubListenerAdapter.h b/networktables/cpp/include/networktables/NetworkTableSubListenerAdapter.h index bdad00af66..c0a62bb417 100644 --- a/networktables/cpp/include/networktables/NetworkTableSubListenerAdapter.h +++ b/networktables/cpp/include/networktables/NetworkTableSubListenerAdapter.h @@ -29,7 +29,7 @@ public: NetworkTableSubListenerAdapter(std::string& prefix, NetworkTable* targetSource, ITableListener* targetListener); virtual ~NetworkTableSubListenerAdapter(); void ValueChanged(ITable* source, const std::string& key, EntryValue value, bool isNew); - void ValueChanged(::std::shared_ptr source, const std::string& key, + void ValueChanged(std::shared_ptr source, const std::string& key, EntryValue value, bool isNew) { ValueChanged(source.get(), key, value, isNew); } diff --git a/networktables/cpp/include/tables/ITableListener.h b/networktables/cpp/include/tables/ITableListener.h index 239b508dd7..582a79313e 100644 --- a/networktables/cpp/include/tables/ITableListener.h +++ b/networktables/cpp/include/tables/ITableListener.h @@ -33,11 +33,11 @@ class ITableListener { * @param value the new value * @param isNew true if the key did not previously exist in the table, otherwise it is false */ - virtual void ValueChanged(::std::shared_ptr source, const std::string& key, EntryValue value, bool isNew) = 0; + virtual void ValueChanged(std::shared_ptr source, const std::string& key, EntryValue value, bool isNew) = 0; virtual void ValueChanged(ITable* source, const std::string& key, EntryValue value, bool isNew) { - ValueChanged(::std::shared_ptr(source, NullDeleter()), key, value, isNew); + ValueChanged(std::shared_ptr(source, NullDeleter()), key, value, isNew); } private: diff --git a/wpilibc/wpilibC++/include/Buttons/NetworkButton.h b/wpilibc/wpilibC++/include/Buttons/NetworkButton.h index 4a37e9d5b6..9dcba58db2 100644 --- a/wpilibc/wpilibC++/include/Buttons/NetworkButton.h +++ b/wpilibc/wpilibC++/include/Buttons/NetworkButton.h @@ -15,13 +15,13 @@ class NetworkButton : public Button { public: NetworkButton(const std::string &tableName, const std::string &field); - NetworkButton(::std::shared_ptr table, const std::string &field); + NetworkButton(std::shared_ptr table, const std::string &field); virtual ~NetworkButton() = default; virtual bool Get(); private: - ::std::shared_ptr m_netTable; + std::shared_ptr m_netTable; std::string m_field; }; diff --git a/wpilibc/wpilibC++/include/Buttons/Trigger.h b/wpilibc/wpilibC++/include/Buttons/Trigger.h index d78ad7e141..34aa6334e9 100644 --- a/wpilibc/wpilibC++/include/Buttons/Trigger.h +++ b/wpilibc/wpilibC++/include/Buttons/Trigger.h @@ -42,12 +42,12 @@ class Trigger : public Sendable { void CancelWhenActive(Command *command); void ToggleWhenActive(Command *command); - virtual void InitTable(::std::shared_ptr table); - virtual ::std::shared_ptr GetTable() const; + virtual void InitTable(std::shared_ptr table); + virtual std::shared_ptr GetTable() const; virtual std::string GetSmartDashboardType() const; protected: - ::std::shared_ptr m_table = nullptr; + std::shared_ptr m_table = nullptr; }; #endif diff --git a/wpilibc/wpilibC++/include/Commands/Command.h b/wpilibc/wpilibC++/include/Commands/Command.h index c9f99d1745..815399d711 100644 --- a/wpilibc/wpilibC++/include/Commands/Command.h +++ b/wpilibc/wpilibC++/include/Commands/Command.h @@ -176,14 +176,14 @@ class Command : public ErrorBase, public NamedSendable, public ITableListener { public: virtual std::string GetName() const; - virtual void InitTable(::std::shared_ptr table); - virtual ::std::shared_ptr GetTable() const; + virtual void InitTable(std::shared_ptr table); + virtual std::shared_ptr GetTable() const; virtual std::string GetSmartDashboardType() const; - virtual void ValueChanged(::std::shared_ptr source, const std::string &key, + virtual void ValueChanged(std::shared_ptr source, const std::string &key, EntryValue value, bool isNew); protected: - ::std::shared_ptr m_table = nullptr; + std::shared_ptr m_table = nullptr; }; #endif diff --git a/wpilibc/wpilibC++/include/Commands/PIDCommand.h b/wpilibc/wpilibC++/include/Commands/PIDCommand.h index 20443f49a5..60266a9eaf 100644 --- a/wpilibc/wpilibC++/include/Commands/PIDCommand.h +++ b/wpilibc/wpilibC++/include/Commands/PIDCommand.h @@ -51,7 +51,7 @@ class PIDCommand : public Command, public PIDOutput, public PIDSource { std::unique_ptr m_controller; public: - virtual void InitTable(::std::shared_ptr table); + virtual void InitTable(std::shared_ptr table); virtual std::string GetSmartDashboardType() const; }; diff --git a/wpilibc/wpilibC++/include/Commands/PIDSubsystem.h b/wpilibc/wpilibC++/include/Commands/PIDSubsystem.h index 4c32c489b5..065fa8e561 100644 --- a/wpilibc/wpilibC++/include/Commands/PIDSubsystem.h +++ b/wpilibc/wpilibC++/include/Commands/PIDSubsystem.h @@ -68,7 +68,7 @@ class PIDSubsystem : public Subsystem, public PIDOutput, public PIDSource { std::unique_ptr m_controller; public: - virtual void InitTable(::std::shared_ptr table); + virtual void InitTable(std::shared_ptr table); virtual std::string GetSmartDashboardType() const; }; diff --git a/wpilibc/wpilibC++/include/Commands/Scheduler.h b/wpilibc/wpilibC++/include/Commands/Scheduler.h index 5060868c66..a624b5daa2 100644 --- a/wpilibc/wpilibC++/include/Commands/Scheduler.h +++ b/wpilibc/wpilibC++/include/Commands/Scheduler.h @@ -40,8 +40,8 @@ class Scheduler : public ErrorBase, public NamedSendable { void UpdateTable(); std::string GetSmartDashboardType() const; - void InitTable(::std::shared_ptr subTable); - ::std::shared_ptr GetTable() const; + void InitTable(std::shared_ptr subTable); + std::shared_ptr GetTable() const; std::string GetName() const; std::string GetType() const; @@ -65,7 +65,7 @@ class Scheduler : public ErrorBase, public NamedSendable { StringArray *commands = nullptr; NumberArray *ids = nullptr; NumberArray *toCancel = nullptr; - ::std::shared_ptr m_table = nullptr; + std::shared_ptr m_table = nullptr; bool m_runningCommandsChanged = false; }; #endif diff --git a/wpilibc/wpilibC++/include/Commands/Subsystem.h b/wpilibc/wpilibC++/include/Commands/Subsystem.h index 5858a10d2c..b4a5604050 100644 --- a/wpilibc/wpilibC++/include/Commands/Subsystem.h +++ b/wpilibc/wpilibC++/include/Commands/Subsystem.h @@ -39,12 +39,12 @@ class Subsystem : public ErrorBase, public NamedSendable { public: virtual std::string GetName() const; - virtual void InitTable(::std::shared_ptr table); - virtual ::std::shared_ptr GetTable() const; + virtual void InitTable(std::shared_ptr table); + virtual std::shared_ptr GetTable() const; virtual std::string GetSmartDashboardType() const; protected: - ::std::shared_ptr m_table = nullptr; + std::shared_ptr m_table = nullptr; }; #endif diff --git a/wpilibc/wpilibC++/include/LiveWindow/LiveWindow.h b/wpilibc/wpilibC++/include/LiveWindow/LiveWindow.h index 037a6a242e..4f7c84882e 100644 --- a/wpilibc/wpilibC++/include/LiveWindow/LiveWindow.h +++ b/wpilibc/wpilibC++/include/LiveWindow/LiveWindow.h @@ -38,14 +38,14 @@ class LiveWindow { void AddSensor(const std::string &subsystem, const std::string &name, LiveWindowSendable *component); void AddSensor(const std::string &subsystem, const std::string &name, - ::std::shared_ptr component); + std::shared_ptr component); [[deprecated( "Raw pointers are deprecated; pass the component using shared_ptr " "instead.")]] void AddActuator(const std::string &subsystem, const std::string &name, LiveWindowSendable *component); void AddActuator(const std::string &subsystem, const std::string &name, - ::std::shared_ptr component); + std::shared_ptr component); void AddSensor(std::string type, int channel, LiveWindowSendable *component); void AddActuator(std::string type, int channel, LiveWindowSendable *component); @@ -64,11 +64,11 @@ class LiveWindow { void Initialize(); void InitializeLiveWindowComponents(); - std::vector<::std::shared_ptr> m_sensors; - std::map<::std::shared_ptr, LiveWindowComponent> m_components; + std::vector> m_sensors; + std::map, LiveWindowComponent> m_components; - ::std::shared_ptr m_liveWindowTable; - ::std::shared_ptr m_statusTable; + std::shared_ptr m_liveWindowTable; + std::shared_ptr m_statusTable; Scheduler &m_scheduler; diff --git a/wpilibc/wpilibC++/include/LiveWindow/LiveWindowStatusListener.h b/wpilibc/wpilibC++/include/LiveWindow/LiveWindowStatusListener.h index a1d4d6aa13..6f06c0e220 100644 --- a/wpilibc/wpilibC++/include/LiveWindow/LiveWindowStatusListener.h +++ b/wpilibc/wpilibC++/include/LiveWindow/LiveWindowStatusListener.h @@ -6,7 +6,7 @@ class LiveWindowStatusListener : public ITableListener { public: - virtual void ValueChanged(::std::shared_ptr source, const std::string& key, + virtual void ValueChanged(std::shared_ptr source, const std::string& key, EntryValue value, bool isNew); }; diff --git a/wpilibc/wpilibC++/include/Notifier.h b/wpilibc/wpilibC++/include/Notifier.h index eb9687c532..de3f377554 100644 --- a/wpilibc/wpilibC++/include/Notifier.h +++ b/wpilibc/wpilibC++/include/Notifier.h @@ -49,8 +49,8 @@ class Notifier : public ErrorBase { // handler call is in progress #ifdef FRC_SIMULATOR - static ::std::thread m_task; - static ::std::atomic m_stopped; + static std::thread m_task; + static std::atomic m_stopped; #endif static void Run(); }; diff --git a/wpilibc/wpilibC++/include/PIDController.h b/wpilibc/wpilibC++/include/PIDController.h index 1c37334265..7ff0b5c63f 100644 --- a/wpilibc/wpilibC++/include/PIDController.h +++ b/wpilibc/wpilibC++/include/PIDController.h @@ -65,7 +65,7 @@ class PIDController : public LiveWindowSendable, virtual void Reset() override; - virtual void InitTable(::std::shared_ptr table) override; + virtual void InitTable(std::shared_ptr table) override; private: float m_P; // factor for "proportional" control @@ -104,15 +104,15 @@ class PIDController : public LiveWindowSendable, PIDOutput *output, float period = 0.05); static void CallCalculate(void *controller); - virtual ::std::shared_ptr GetTable() const override; + virtual std::shared_ptr GetTable() const override; virtual std::string GetSmartDashboardType() const override; - virtual void ValueChanged(::std::shared_ptr source, const std::string &key, + virtual void ValueChanged(std::shared_ptr source, const std::string &key, EntryValue value, bool isNew) override; virtual void UpdateTable() override; virtual void StartLiveWindowMode() override; virtual void StopLiveWindowMode() override; protected: - ::std::shared_ptr m_table = nullptr; + std::shared_ptr m_table = nullptr; virtual void Calculate(); }; diff --git a/wpilibc/wpilibC++/include/Resource.h b/wpilibc/wpilibC++/include/Resource.h index 17ee79f5f6..f7061c8e92 100644 --- a/wpilibc/wpilibC++/include/Resource.h +++ b/wpilibc/wpilibC++/include/Resource.h @@ -29,7 +29,7 @@ class Resource : public ErrorBase { Resource(const Resource&) = delete; Resource& operator=(const Resource&) = delete; - static void CreateResourceObject(::std::unique_ptr& r, uint32_t elements); + static void CreateResourceObject(std::unique_ptr& r, uint32_t elements); explicit Resource(uint32_t size); uint32_t Allocate(const std::string &resourceDesc); uint32_t Allocate(uint32_t index, const std::string &resourceDesc); diff --git a/wpilibc/wpilibC++/include/RobotState.h b/wpilibc/wpilibC++/include/RobotState.h index 252c1a197b..53bf32ae81 100644 --- a/wpilibc/wpilibC++/include/RobotState.h +++ b/wpilibc/wpilibC++/include/RobotState.h @@ -19,11 +19,11 @@ class RobotStateInterface { class RobotState { private: - static ::std::shared_ptr impl; + static std::shared_ptr impl; public: static void SetImplementation(RobotStateInterface& i); - static void SetImplementation(::std::shared_ptr i); + static void SetImplementation(std::shared_ptr i); static bool IsDisabled(); static bool IsEnabled(); static bool IsOperatorControl(); diff --git a/wpilibc/wpilibC++/include/SmartDashboard/Sendable.h b/wpilibc/wpilibC++/include/SmartDashboard/Sendable.h index 6b8ffd6a0e..613c7f84b0 100644 --- a/wpilibc/wpilibC++/include/SmartDashboard/Sendable.h +++ b/wpilibc/wpilibC++/include/SmartDashboard/Sendable.h @@ -18,12 +18,12 @@ class Sendable { * Initializes a table for this sendable object. * @param subtable The table to put the values in. */ - virtual void InitTable(::std::shared_ptr subtable) = 0; + virtual void InitTable(std::shared_ptr subtable) = 0; /** * @return the table that is currently associated with the sendable */ - virtual ::std::shared_ptr GetTable() const = 0; + virtual std::shared_ptr GetTable() const = 0; /** * @return the string representation of the named data type that will be used diff --git a/wpilibc/wpilibC++/include/SmartDashboard/SendableChooser.h b/wpilibc/wpilibC++/include/SmartDashboard/SendableChooser.h index b3f92e5372..bfdf87757c 100644 --- a/wpilibc/wpilibC++/include/SmartDashboard/SendableChooser.h +++ b/wpilibc/wpilibC++/include/SmartDashboard/SendableChooser.h @@ -39,14 +39,14 @@ class SendableChooser : public Sendable { void AddDefault(const std::string &name, void *object); void *GetSelected(); - virtual void InitTable(::std::shared_ptr subtable); - virtual ::std::shared_ptr GetTable() const; + virtual void InitTable(std::shared_ptr subtable); + virtual std::shared_ptr GetTable() const; virtual std::string GetSmartDashboardType() const; private: std::string m_defaultChoice; std::map m_choices; - ::std::shared_ptr m_table; + std::shared_ptr m_table; }; #endif diff --git a/wpilibc/wpilibC++/include/SmartDashboard/SmartDashboard.h b/wpilibc/wpilibC++/include/SmartDashboard/SmartDashboard.h index ecf7364891..1b7e6840ec 100644 --- a/wpilibc/wpilibC++/include/SmartDashboard/SmartDashboard.h +++ b/wpilibc/wpilibC++/include/SmartDashboard/SmartDashboard.h @@ -43,14 +43,14 @@ class SmartDashboard : public SensorBase { virtual ~SmartDashboard() = default; /** The {@link NetworkTable} used by {@link SmartDashboard} */ - static ::std::shared_ptr m_table; + static std::shared_ptr m_table; /** * A map linking tables in the SmartDashboard to the {@link * SmartDashboardData} objects * they came from. */ - static std::map<::std::shared_ptr , Sendable *> m_tablesToData; + static std::map , Sendable *> m_tablesToData; }; #endif diff --git a/wpilibc/wpilibC++/src/Buttons/NetworkButton.cpp b/wpilibc/wpilibC++/src/Buttons/NetworkButton.cpp index dd54269344..1e90ced31b 100644 --- a/wpilibc/wpilibC++/src/Buttons/NetworkButton.cpp +++ b/wpilibc/wpilibC++/src/Buttons/NetworkButton.cpp @@ -13,7 +13,7 @@ NetworkButton::NetworkButton(const std::string &tableName, const std::string &fi m_netTable(NetworkTable::GetTable(tableName)), m_field(field) {} -NetworkButton::NetworkButton(::std::shared_ptr table, const std::string &field) +NetworkButton::NetworkButton(std::shared_ptr table, const std::string &field) : m_netTable(table), m_field(field) {} bool NetworkButton::Get() { diff --git a/wpilibc/wpilibC++/src/Buttons/Trigger.cpp b/wpilibc/wpilibC++/src/Buttons/Trigger.cpp index 51a65ac846..5a17645af5 100644 --- a/wpilibc/wpilibC++/src/Buttons/Trigger.cpp +++ b/wpilibc/wpilibC++/src/Buttons/Trigger.cpp @@ -52,11 +52,11 @@ void Trigger::ToggleWhenActive(Command *command) { std::string Trigger::GetSmartDashboardType() const { return "Button"; } -void Trigger::InitTable(::std::shared_ptr table) { +void Trigger::InitTable(std::shared_ptr table) { m_table = table; if (m_table != nullptr) { m_table->PutBoolean("pressed", Get()); } } -::std::shared_ptr Trigger::GetTable() const { return m_table; } +std::shared_ptr Trigger::GetTable() const { return m_table; } diff --git a/wpilibc/wpilibC++/src/Commands/Command.cpp b/wpilibc/wpilibC++/src/Commands/Command.cpp index a81620a667..df25ba41aa 100644 --- a/wpilibc/wpilibC++/src/Commands/Command.cpp +++ b/wpilibc/wpilibC++/src/Commands/Command.cpp @@ -370,7 +370,7 @@ std::string Command::GetName() const { std::string Command::GetSmartDashboardType() const { return "Command"; } -void Command::InitTable(::std::shared_ptr table) { +void Command::InitTable(std::shared_ptr table) { if (m_table != nullptr) m_table->RemoveTableListener(this); m_table = table; if (m_table != nullptr) { @@ -381,9 +381,9 @@ void Command::InitTable(::std::shared_ptr table) { } } -::std::shared_ptr Command::GetTable() const { return m_table; } +std::shared_ptr Command::GetTable() const { return m_table; } -void Command::ValueChanged(::std::shared_ptr source, const std::string &key, +void Command::ValueChanged(std::shared_ptr source, const std::string &key, EntryValue value, bool isNew) { if (value.b) { if (!IsRunning()) Start(); diff --git a/wpilibc/wpilibC++/src/Commands/PIDCommand.cpp b/wpilibc/wpilibC++/src/Commands/PIDCommand.cpp index 52a568a518..d2953ef44f 100644 --- a/wpilibc/wpilibC++/src/Commands/PIDCommand.cpp +++ b/wpilibc/wpilibC++/src/Commands/PIDCommand.cpp @@ -63,7 +63,7 @@ double PIDCommand::GetSetpoint() const { return m_controller->GetSetpoint(); } double PIDCommand::GetPosition() const { return ReturnPIDInput(); } std::string PIDCommand::GetSmartDashboardType() const { return "PIDCommand"; } -void PIDCommand::InitTable(::std::shared_ptr table) { +void PIDCommand::InitTable(std::shared_ptr table) { m_controller->InitTable(table); Command::InitTable(table); } diff --git a/wpilibc/wpilibC++/src/Commands/PIDSubsystem.cpp b/wpilibc/wpilibC++/src/Commands/PIDSubsystem.cpp index 94fa7962e0..7943b44140 100644 --- a/wpilibc/wpilibC++/src/Commands/PIDSubsystem.cpp +++ b/wpilibc/wpilibC++/src/Commands/PIDSubsystem.cpp @@ -211,7 +211,7 @@ void PIDSubsystem::PIDWrite(float output) { UsePIDOutput(output); } double PIDSubsystem::PIDGet() const { return ReturnPIDInput(); } std::string PIDSubsystem::GetSmartDashboardType() const { return "PIDCommand"; } -void PIDSubsystem::InitTable(::std::shared_ptr table) { +void PIDSubsystem::InitTable(std::shared_ptr table) { m_controller->InitTable(table); Subsystem::InitTable(table); } diff --git a/wpilibc/wpilibC++/src/Commands/Scheduler.cpp b/wpilibc/wpilibC++/src/Commands/Scheduler.cpp index af23728265..525b70456a 100644 --- a/wpilibc/wpilibC++/src/Commands/Scheduler.cpp +++ b/wpilibc/wpilibC++/src/Commands/Scheduler.cpp @@ -258,7 +258,7 @@ std::string Scheduler::GetType() const { return "Scheduler"; } std::string Scheduler::GetSmartDashboardType() const { return "Scheduler"; } -void Scheduler::InitTable(::std::shared_ptr subTable) { +void Scheduler::InitTable(std::shared_ptr subTable) { m_table = subTable; commands = new StringArray(); ids = new NumberArray(); @@ -269,4 +269,4 @@ void Scheduler::InitTable(::std::shared_ptr subTable) { m_table->PutValue("Cancel", *toCancel); } -::std::shared_ptr Scheduler::GetTable() const { return m_table; } +std::shared_ptr Scheduler::GetTable() const { return m_table; } diff --git a/wpilibc/wpilibC++/src/Commands/Subsystem.cpp b/wpilibc/wpilibC++/src/Commands/Subsystem.cpp index bd75de3a4c..60c48ca65e 100644 --- a/wpilibc/wpilibC++/src/Commands/Subsystem.cpp +++ b/wpilibc/wpilibC++/src/Commands/Subsystem.cpp @@ -126,7 +126,7 @@ std::string Subsystem::GetName() const { return m_name; } std::string Subsystem::GetSmartDashboardType() const { return "Subsystem"; } -void Subsystem::InitTable(::std::shared_ptr table) { +void Subsystem::InitTable(std::shared_ptr table) { m_table = table; if (m_table != nullptr) { if (m_defaultCommand != nullptr) { @@ -144,4 +144,4 @@ void Subsystem::InitTable(::std::shared_ptr table) { } } -::std::shared_ptr Subsystem::GetTable() const { return m_table; } +std::shared_ptr Subsystem::GetTable() const { return m_table; } diff --git a/wpilibc/wpilibC++/src/LiveWindow/LiveWindow.cpp b/wpilibc/wpilibC++/src/LiveWindow/LiveWindow.cpp index 5839ae24d8..c9633a8d0a 100644 --- a/wpilibc/wpilibC++/src/LiveWindow/LiveWindow.cpp +++ b/wpilibc/wpilibC++/src/LiveWindow/LiveWindow.cpp @@ -57,7 +57,7 @@ void LiveWindow::SetEnabled(bool enabled) { * @param component A LiveWindowSendable component that represents a sensor. */ void LiveWindow::AddSensor(const std::string &subsystem, const std::string &name, - ::std::shared_ptr component) { + std::shared_ptr component) { m_components[component].subsystem = subsystem; m_components[component].name = name; m_components[component].isSensor = true; @@ -67,7 +67,7 @@ void LiveWindow::AddSensor(const std::string &subsystem, const std::string &name "Raw pointers are deprecated; pass the component using shared_ptr " "instead.")]] void LiveWindow::AddSensor(const std::string &subsystem, const std::string &name, LiveWindowSendable *component) { - AddSensor(subsystem, name, ::std::shared_ptr( + AddSensor(subsystem, name, std::shared_ptr( component, NullDeleter())); } @@ -79,7 +79,7 @@ void LiveWindow::AddSensor(const std::string &subsystem, const std::string &name * @param component A LiveWindowSendable component that represents a actuator. */ void LiveWindow::AddActuator(const std::string &subsystem, const std::string &name, - ::std::shared_ptr component) { + std::shared_ptr component) { m_components[component].subsystem = subsystem; m_components[component].name = name; m_components[component].isSensor = false; @@ -91,7 +91,7 @@ void LiveWindow::AddActuator(const std::string &subsystem, const std::string &na void LiveWindow::AddActuator(const std::string &subsystem, const std::string &name, LiveWindowSendable *component) { AddActuator(subsystem, name, - ::std::shared_ptr( + std::shared_ptr( component, NullDeleter())); } @@ -108,7 +108,7 @@ void LiveWindow::AddSensor(std::string type, int channel, types.copy(cc, types.size()); cc[types.size()] = '\0'; AddSensor("Ungrouped", cc, component); - ::std::shared_ptr component_stl( + std::shared_ptr component_stl( component, NullDeleter()); if (std::find(m_sensors.begin(), m_sensors.end(), component_stl) == m_sensors.end()) @@ -126,7 +126,7 @@ void LiveWindow::AddActuator(std::string type, int channel, auto cc = new char[types.size() + 1]; types.copy(cc, types.size()); cc[types.size()] = '\0'; - AddActuator("Ungrouped", cc, ::std::shared_ptr( + AddActuator("Ungrouped", cc, std::shared_ptr( component, [](LiveWindowSendable *) {})); } @@ -141,7 +141,7 @@ void LiveWindow::AddActuator(std::string type, int module, int channel, auto cc = new char[types.size() + 1]; types.copy(cc, types.size()); cc[types.size()] = '\0'; - AddActuator("Ungrouped", cc, ::std::shared_ptr( + AddActuator("Ungrouped", cc, std::shared_ptr( component, [](LiveWindowSendable *) {})); } @@ -175,13 +175,13 @@ void LiveWindow::Run() { */ void LiveWindow::InitializeLiveWindowComponents() { for (auto& elem : m_components) { - ::std::shared_ptr component = elem.first; + std::shared_ptr component = elem.first; LiveWindowComponent c = elem.second; std::string subsystem = c.subsystem; std::string name = c.name; m_liveWindowTable->GetSubTable(subsystem) ->PutString("~TYPE~", "LW Subsystem"); - ::std::shared_ptr table( + std::shared_ptr table( m_liveWindowTable->GetSubTable(subsystem)->GetSubTable(name)); table->PutString("~TYPE~", component->GetSmartDashboardType()); table->PutString("Name", name); diff --git a/wpilibc/wpilibC++/src/LiveWindow/LiveWindowStatusListener.cpp b/wpilibc/wpilibC++/src/LiveWindow/LiveWindowStatusListener.cpp index 9e9fa0f92e..1d49ad909e 100644 --- a/wpilibc/wpilibC++/src/LiveWindow/LiveWindowStatusListener.cpp +++ b/wpilibc/wpilibC++/src/LiveWindow/LiveWindowStatusListener.cpp @@ -1,6 +1,6 @@ #include "LiveWindow/LiveWindowStatusListener.h" #include "Commands/Scheduler.h" -void LiveWindowStatusListener::ValueChanged(::std::shared_ptr source, +void LiveWindowStatusListener::ValueChanged(std::shared_ptr source, const std::string& key, EntryValue value, bool isNew) {} diff --git a/wpilibc/wpilibC++/src/Resource.cpp b/wpilibc/wpilibC++/src/Resource.cpp index a259bd39b4..d3df09c723 100644 --- a/wpilibc/wpilibC++/src/Resource.cpp +++ b/wpilibc/wpilibC++/src/Resource.cpp @@ -20,7 +20,7 @@ priority_recursive_mutex Resource::m_createLock; */ Resource::Resource(uint32_t elements) { std::unique_lock sync(m_createLock); - m_isAllocated = ::std::vector(elements, false); + m_isAllocated = std::vector(elements, false); } /** @@ -33,7 +33,7 @@ Resource::Resource(uint32_t elements) { * track, that is, it will allocate resource numbers in the range * [0 .. elements - 1]. */ -/*static*/ void Resource::CreateResourceObject(::std::unique_ptr& r, +/*static*/ void Resource::CreateResourceObject(std::unique_ptr& r, uint32_t elements) { std::unique_lock sync(m_createLock); if (!r) { diff --git a/wpilibc/wpilibC++/src/RobotState.cpp b/wpilibc/wpilibC++/src/RobotState.cpp index 805bdc9e9d..127c50ca4f 100644 --- a/wpilibc/wpilibC++/src/RobotState.cpp +++ b/wpilibc/wpilibC++/src/RobotState.cpp @@ -2,15 +2,15 @@ #include "Base.h" -::std::shared_ptr RobotState::impl = nullptr; +std::shared_ptr RobotState::impl = nullptr; void RobotState::SetImplementation(RobotStateInterface& i) { - impl = ::std::shared_ptr( + impl = std::shared_ptr( &i, NullDeleter()); } void RobotState::SetImplementation( - ::std::shared_ptr i) { + std::shared_ptr i) { impl = i; } diff --git a/wpilibc/wpilibC++/src/SmartDashboard/SendableChooser.cpp b/wpilibc/wpilibC++/src/SmartDashboard/SendableChooser.cpp index 1cda6b2c39..49cb3e0c3d 100644 --- a/wpilibc/wpilibC++/src/SmartDashboard/SendableChooser.cpp +++ b/wpilibc/wpilibC++/src/SmartDashboard/SendableChooser.cpp @@ -53,7 +53,7 @@ void *SendableChooser::GetSelected() { return m_choices[selected]; } -void SendableChooser::InitTable(::std::shared_ptr subtable) { +void SendableChooser::InitTable(std::shared_ptr subtable) { StringArray keys; m_table = subtable; if (m_table != nullptr) { @@ -66,7 +66,7 @@ void SendableChooser::InitTable(::std::shared_ptr subtable) { } } -::std::shared_ptr SendableChooser::GetTable() const { return m_table; } +std::shared_ptr SendableChooser::GetTable() const { return m_table; } std::string SendableChooser::GetSmartDashboardType() const { return "String Chooser"; diff --git a/wpilibc/wpilibC++/src/SmartDashboard/SmartDashboard.cpp b/wpilibc/wpilibC++/src/SmartDashboard/SmartDashboard.cpp index b2dfc02fec..af4ed5f2dd 100644 --- a/wpilibc/wpilibC++/src/SmartDashboard/SmartDashboard.cpp +++ b/wpilibc/wpilibC++/src/SmartDashboard/SmartDashboard.cpp @@ -13,8 +13,8 @@ #include "networktables/NetworkTable.h" #include "HLUsageReporting.h" -::std::shared_ptr SmartDashboard::m_table = nullptr; -std::map<::std::shared_ptr , Sendable *> SmartDashboard::m_tablesToData; +std::shared_ptr SmartDashboard::m_table = nullptr; +std::map , Sendable *> SmartDashboard::m_tablesToData; void SmartDashboard::init() { m_table.reset(NetworkTable::GetTable("SmartDashboard")); @@ -35,7 +35,7 @@ void SmartDashboard::PutData(std::string key, Sendable *data) { wpi_setGlobalWPIErrorWithContext(NullParameter, "value"); return; } - ::std::shared_ptr dataTable(m_table->GetSubTable(key)); + std::shared_ptr dataTable(m_table->GetSubTable(key)); dataTable->PutString("~TYPE~", data->GetSmartDashboardType()); data->InitTable(dataTable); m_tablesToData[dataTable] = data; @@ -63,7 +63,7 @@ void SmartDashboard::PutData(NamedSendable *value) { * @return the value */ Sendable *SmartDashboard::GetData(std::string key) { - ::std::shared_ptr subtable(m_table->GetSubTable(key)); + std::shared_ptr subtable(m_table->GetSubTable(key)); Sendable *data = m_tablesToData[subtable]; if (data == nullptr) { wpi_setGlobalWPIErrorWithContext(SmartDashboardMissingKey, key.c_str()); diff --git a/wpilibc/wpilibC++Devices/include/ADXL345_I2C.h b/wpilibc/wpilibC++Devices/include/ADXL345_I2C.h index cb241ba96b..e55e00724e 100644 --- a/wpilibc/wpilibC++Devices/include/ADXL345_I2C.h +++ b/wpilibc/wpilibC++Devices/include/ADXL345_I2C.h @@ -67,12 +67,12 @@ class ADXL345_I2C : public Accelerometer, virtual AllAxes GetAccelerations(); virtual std::string GetSmartDashboardType() const override; - virtual void InitTable(::std::shared_ptr subtable) override; + virtual void InitTable(std::shared_ptr subtable) override; virtual void UpdateTable() override; - virtual ::std::shared_ptr GetTable() const override; + virtual std::shared_ptr GetTable() const override; virtual void StartLiveWindowMode() override {} virtual void StopLiveWindowMode() override {} private: - ::std::shared_ptr m_table; + std::shared_ptr m_table; }; diff --git a/wpilibc/wpilibC++Devices/include/ADXL345_SPI.h b/wpilibc/wpilibC++Devices/include/ADXL345_SPI.h index 76f1f99764..8e480a0d6b 100644 --- a/wpilibc/wpilibC++Devices/include/ADXL345_SPI.h +++ b/wpilibc/wpilibC++Devices/include/ADXL345_SPI.h @@ -71,9 +71,9 @@ class ADXL345_SPI : public Accelerometer, virtual AllAxes GetAccelerations(); virtual std::string GetSmartDashboardType() const override; - virtual void InitTable(::std::shared_ptr subtable) override; + virtual void InitTable(std::shared_ptr subtable) override; virtual void UpdateTable() override; - virtual ::std::shared_ptr GetTable() const override; + virtual std::shared_ptr GetTable() const override; virtual void StartLiveWindowMode() override {} virtual void StopLiveWindowMode() override {} @@ -84,5 +84,5 @@ class ADXL345_SPI : public Accelerometer, SPI::Port m_port; private: - ::std::shared_ptr m_table; + std::shared_ptr m_table; }; diff --git a/wpilibc/wpilibC++Devices/include/AnalogAccelerometer.h b/wpilibc/wpilibC++Devices/include/AnalogAccelerometer.h index 8bd77e8586..9c17a8e983 100644 --- a/wpilibc/wpilibC++Devices/include/AnalogAccelerometer.h +++ b/wpilibc/wpilibC++Devices/include/AnalogAccelerometer.h @@ -32,7 +32,7 @@ class AnalogAccelerometer : public SensorBase, "AnalogAccelerometer(int channel). If you want to keep your own copy of " "the AnalogInput, use std::shared_ptr.")]] explicit AnalogAccelerometer(AnalogInput *channel); - explicit AnalogAccelerometer(::std::shared_ptr channel); + explicit AnalogAccelerometer(std::shared_ptr channel); virtual ~AnalogAccelerometer() = default; float GetAcceleration() const; @@ -44,16 +44,16 @@ class AnalogAccelerometer : public SensorBase, void StartLiveWindowMode() override; void StopLiveWindowMode() override; std::string GetSmartDashboardType() const override; - void InitTable(::std::shared_ptr subTable) override; - ::std::shared_ptr GetTable() const override; + void InitTable(std::shared_ptr subTable) override; + std::shared_ptr GetTable() const override; private: void InitAccelerometer(); - ::std::shared_ptr m_analogInput; + std::shared_ptr m_analogInput; float m_voltsPerG = 1.0; float m_zeroGVoltage = 2.5; bool m_allocatedChannel; - ::std::shared_ptr m_table = nullptr; + std::shared_ptr m_table = nullptr; }; diff --git a/wpilibc/wpilibC++Devices/include/AnalogInput.h b/wpilibc/wpilibC++Devices/include/AnalogInput.h index 6caf6a6c48..85314b01e1 100644 --- a/wpilibc/wpilibC++Devices/include/AnalogInput.h +++ b/wpilibc/wpilibC++Devices/include/AnalogInput.h @@ -73,8 +73,8 @@ class AnalogInput : public SensorBase, void StartLiveWindowMode() override; void StopLiveWindowMode() override; std::string GetSmartDashboardType() const override; - void InitTable(::std::shared_ptr subTable) override; - ::std::shared_ptr GetTable() const override; + void InitTable(std::shared_ptr subTable) override; + std::shared_ptr GetTable() const override; private: uint32_t m_channel; @@ -82,5 +82,5 @@ class AnalogInput : public SensorBase, void *m_port; int64_t m_accumulatorOffset; - ::std::shared_ptr m_table = nullptr; + std::shared_ptr m_table = nullptr; }; diff --git a/wpilibc/wpilibC++Devices/include/AnalogOutput.h b/wpilibc/wpilibC++Devices/include/AnalogOutput.h index ef55816af9..9db5333777 100644 --- a/wpilibc/wpilibC++Devices/include/AnalogOutput.h +++ b/wpilibc/wpilibC++Devices/include/AnalogOutput.h @@ -27,12 +27,12 @@ class AnalogOutput : public SensorBase, public LiveWindowSendable { void StartLiveWindowMode() override; void StopLiveWindowMode() override; std::string GetSmartDashboardType() const override; - void InitTable(::std::shared_ptr subTable) override; - ::std::shared_ptr GetTable() const override; + void InitTable(std::shared_ptr subTable) override; + std::shared_ptr GetTable() const override; protected: uint32_t m_channel; void *m_port; - ::std::shared_ptr m_table = nullptr; + std::shared_ptr m_table = nullptr; }; diff --git a/wpilibc/wpilibC++Devices/include/AnalogPotentiometer.h b/wpilibc/wpilibC++Devices/include/AnalogPotentiometer.h index 5c3412fc19..12910bd8c4 100644 --- a/wpilibc/wpilibC++Devices/include/AnalogPotentiometer.h +++ b/wpilibc/wpilibC++Devices/include/AnalogPotentiometer.h @@ -44,7 +44,7 @@ class AnalogPotentiometer : public Potentiometer, public LiveWindowSendable { explicit AnalogPotentiometer(AnalogInput *input, double fullRange = 1.0, double offset = 0.0); - explicit AnalogPotentiometer(::std::shared_ptr input, + explicit AnalogPotentiometer(std::shared_ptr input, double fullRange = 1.0, double offset = 0.0); virtual ~AnalogPotentiometer() = default; @@ -67,9 +67,9 @@ class AnalogPotentiometer : public Potentiometer, public LiveWindowSendable { * Live Window code, only does anything if live window is activated. */ virtual std::string GetSmartDashboardType() const override; - virtual void InitTable(::std::shared_ptr subtable) override; + virtual void InitTable(std::shared_ptr subtable) override; virtual void UpdateTable() override; - virtual ::std::shared_ptr GetTable() const override; + virtual std::shared_ptr GetTable() const override; /** * AnalogPotentiometers don't have to do anything special when entering the @@ -84,8 +84,8 @@ class AnalogPotentiometer : public Potentiometer, public LiveWindowSendable { virtual void StopLiveWindowMode() override {} private: - ::std::shared_ptr m_analog_input; + std::shared_ptr m_analog_input; double m_fullRange, m_offset; - ::std::shared_ptr m_table; + std::shared_ptr m_table; bool m_init_analog_input; }; diff --git a/wpilibc/wpilibC++Devices/include/AnalogTrigger.h b/wpilibc/wpilibC++Devices/include/AnalogTrigger.h index b25d84c023..7fdd2028d5 100644 --- a/wpilibc/wpilibC++Devices/include/AnalogTrigger.h +++ b/wpilibc/wpilibC++Devices/include/AnalogTrigger.h @@ -27,7 +27,7 @@ class AnalogTrigger : public SensorBase { uint32_t GetIndex() const; bool GetInWindow(); bool GetTriggerState(); - ::std::shared_ptr CreateOutput(AnalogTriggerType type) const; + std::shared_ptr CreateOutput(AnalogTriggerType type) const; private: uint8_t m_index; diff --git a/wpilibc/wpilibC++Devices/include/BuiltInAccelerometer.h b/wpilibc/wpilibC++Devices/include/BuiltInAccelerometer.h index a8112519cf..82ba029ce7 100644 --- a/wpilibc/wpilibC++Devices/include/BuiltInAccelerometer.h +++ b/wpilibc/wpilibC++Devices/include/BuiltInAccelerometer.h @@ -30,12 +30,12 @@ class BuiltInAccelerometer : public Accelerometer, virtual double GetZ() override; virtual std::string GetSmartDashboardType() const override; - virtual void InitTable(::std::shared_ptr subtable) override; + virtual void InitTable(std::shared_ptr subtable) override; virtual void UpdateTable() override; - virtual ::std::shared_ptr GetTable() const override; + virtual std::shared_ptr GetTable() const override; virtual void StartLiveWindowMode() override {} virtual void StopLiveWindowMode() override {} private: - ::std::shared_ptr m_table = nullptr; + std::shared_ptr m_table = nullptr; }; diff --git a/wpilibc/wpilibC++Devices/include/CANJaguar.h b/wpilibc/wpilibC++Devices/include/CANJaguar.h index 873f698d75..6678933c2a 100644 --- a/wpilibc/wpilibC++Devices/include/CANJaguar.h +++ b/wpilibc/wpilibC++Devices/include/CANJaguar.h @@ -232,16 +232,16 @@ class CANJaguar : public MotorSafety, std::unique_ptr m_safetyHelper; - void ValueChanged(::std::shared_ptr source, const std::string &key, EntryValue value, + void ValueChanged(std::shared_ptr source, const std::string &key, EntryValue value, bool isNew) override; void UpdateTable() override; void StartLiveWindowMode() override; void StopLiveWindowMode() override; std::string GetSmartDashboardType() const override; - void InitTable(::std::shared_ptr subTable) override; - ::std::shared_ptr GetTable() const override; + void InitTable(std::shared_ptr subTable) override; + std::shared_ptr GetTable() const override; - ::std::shared_ptr m_table = nullptr; + std::shared_ptr m_table = nullptr; private: void InitCANJaguar(); diff --git a/wpilibc/wpilibC++Devices/include/CANTalon.h b/wpilibc/wpilibC++Devices/include/CANTalon.h index 9de185a57f..21c812444a 100644 --- a/wpilibc/wpilibC++Devices/include/CANTalon.h +++ b/wpilibc/wpilibC++Devices/include/CANTalon.h @@ -156,14 +156,14 @@ class CANTalon : public MotorSafety, double GetSetpoint() const override; // LiveWindow stuff. - void ValueChanged(::std::shared_ptr source, const std::string &key, EntryValue value, + void ValueChanged(std::shared_ptr source, const std::string &key, EntryValue value, bool isNew) override; void UpdateTable() override; void StartLiveWindowMode() override; void StopLiveWindowMode() override; std::string GetSmartDashboardType() const override; - void InitTable(::std::shared_ptr subTable) override; - ::std::shared_ptr GetTable() const override; + void InitTable(std::shared_ptr subTable) override; + std::shared_ptr GetTable() const override; // SpeedController overrides virtual void SetInverted(bool isInverted) override; @@ -202,6 +202,6 @@ class CANTalon : public MotorSafety, void ApplyControlMode(CANSpeedController::ControlMode mode); // LiveWindow stuff. - ::std::shared_ptr m_table; + std::shared_ptr m_table; bool m_isInverted; }; diff --git a/wpilibc/wpilibC++Devices/include/Compressor.h b/wpilibc/wpilibC++Devices/include/Compressor.h index e8cf2c113f..4afce9db84 100644 --- a/wpilibc/wpilibC++Devices/include/Compressor.h +++ b/wpilibc/wpilibC++Devices/include/Compressor.h @@ -48,9 +48,9 @@ class Compressor : public SensorBase, void StartLiveWindowMode() override; void StopLiveWindowMode() override; std::string GetSmartDashboardType() const override; - void InitTable(::std::shared_ptr subTable) override; - ::std::shared_ptr GetTable() const override; - void ValueChanged(::std::shared_ptr source, const std::string &key, EntryValue value, + void InitTable(std::shared_ptr subTable) override; + std::shared_ptr GetTable() const override; + void ValueChanged(std::shared_ptr source, const std::string &key, EntryValue value, bool isNew) override; protected: @@ -59,7 +59,7 @@ class Compressor : public SensorBase, private: void SetCompressor(bool on); - ::std::shared_ptr m_table = nullptr; + std::shared_ptr m_table = nullptr; }; #endif /* Compressor_H_ */ diff --git a/wpilibc/wpilibC++Devices/include/Counter.h b/wpilibc/wpilibC++Devices/include/Counter.h index 5faf3292db..2001ffa0b6 100644 --- a/wpilibc/wpilibC++Devices/include/Counter.h +++ b/wpilibc/wpilibC++Devices/include/Counter.h @@ -37,7 +37,7 @@ class Counter : public SensorBase, "want to keep your own copy of the DigitalSource, use " "std::shared_ptr.")]] explicit Counter(DigitalSource *source); - explicit Counter(::std::shared_ptr source); + explicit Counter(std::shared_ptr source); [[deprecated( "Raw pointers are deprecated. Use pass-by-reference instead.")]] explicit Counter(AnalogTrigger *trigger); @@ -46,8 +46,8 @@ class Counter : public SensorBase, "Raw pointers are deprecated; prefer to use shared_ptr instead.")]] Counter(EncodingType encodingType, DigitalSource *upSource, DigitalSource *downSource, bool inverted); - Counter(EncodingType encodingType, ::std::shared_ptr upSource, - ::std::shared_ptr downSource, bool inverted); + Counter(EncodingType encodingType, std::shared_ptr upSource, + std::shared_ptr downSource, bool inverted); virtual ~Counter(); void SetUpSource(int32_t channel); @@ -55,11 +55,11 @@ class Counter : public SensorBase, "Raw pointers are deprecated; prefer to call either SetUpSource(int) or " "SetUpSource(shared_ptr).")]] void SetUpSource(AnalogTrigger *analogTrigger, AnalogTriggerType triggerType); - void SetUpSource(::std::shared_ptr analogTrigger, + void SetUpSource(std::shared_ptr analogTrigger, AnalogTriggerType triggerType); [[deprecated("Raw pointers are deprecated. Use std::shared_ptr instead.")]] void SetUpSource(DigitalSource *source); - void SetUpSource(::std::shared_ptr source); + void SetUpSource(std::shared_ptr source); [[deprecated("References are deprecated. Use std::shared_ptr instead.")]] void SetUpSource(DigitalSource &source); void SetUpSourceEdge(bool risingEdge, bool fallingEdge); @@ -71,11 +71,11 @@ class Counter : public SensorBase, "or SetDownSource(shared_ptr).")]] void SetDownSource(AnalogTrigger *analogTrigger, AnalogTriggerType triggerType); - void SetDownSource(::std::shared_ptr analogTrigger, + void SetDownSource(std::shared_ptr analogTrigger, AnalogTriggerType triggerType); [[deprecated("Raw pointers are deprecated. Use std::shared_ptr instead.")]] void SetDownSource(DigitalSource *source); - void SetDownSource(::std::shared_ptr source); + void SetDownSource(std::shared_ptr source); [[deprecated("References are deprecated. Use std::shared_ptr instead.")]] void SetDownSource(DigitalSource &source); void SetDownSourceEdge(bool risingEdge, bool fallingEdge); @@ -105,18 +105,18 @@ class Counter : public SensorBase, void StartLiveWindowMode() override; void StopLiveWindowMode() override; virtual std::string GetSmartDashboardType() const override; - void InitTable(::std::shared_ptr subTable) override; - ::std::shared_ptr GetTable() const override; + void InitTable(std::shared_ptr subTable) override; + std::shared_ptr GetTable() const override; protected: // Makes the counter count up. - ::std::shared_ptr m_upSource; + std::shared_ptr m_upSource; // Makes the counter count down. - ::std::shared_ptr m_downSource; + std::shared_ptr m_downSource; // The FPGA counter object void *m_counter = nullptr; ///< The FPGA counter object. private: uint32_t m_index = 0; ///< The index of this counter. - ::std::shared_ptr m_table = nullptr; + std::shared_ptr m_table = nullptr; }; diff --git a/wpilibc/wpilibC++Devices/include/DigitalInput.h b/wpilibc/wpilibC++Devices/include/DigitalInput.h index a4bce19f77..cf6e927c44 100644 --- a/wpilibc/wpilibC++Devices/include/DigitalInput.h +++ b/wpilibc/wpilibC++Devices/include/DigitalInput.h @@ -37,11 +37,11 @@ class DigitalInput : public DigitalSource, public LiveWindowSendable { void StartLiveWindowMode(); void StopLiveWindowMode(); std::string GetSmartDashboardType() const; - void InitTable(::std::shared_ptr subTable); - ::std::shared_ptr GetTable() const; + void InitTable(std::shared_ptr subTable); + std::shared_ptr GetTable() const; private: uint32_t m_channel; - ::std::shared_ptr m_table = nullptr; + std::shared_ptr m_table = nullptr; }; diff --git a/wpilibc/wpilibC++Devices/include/DigitalOutput.h b/wpilibc/wpilibC++Devices/include/DigitalOutput.h index ce72fed76f..6236cd1631 100644 --- a/wpilibc/wpilibC++Devices/include/DigitalOutput.h +++ b/wpilibc/wpilibC++Devices/include/DigitalOutput.h @@ -38,18 +38,18 @@ class DigitalOutput : public DigitalSource, virtual uint32_t GetModuleForRouting() const; virtual bool GetAnalogTriggerForRouting() const; - virtual void ValueChanged(::std::shared_ptr source, const std::string &key, + virtual void ValueChanged(std::shared_ptr source, const std::string &key, EntryValue value, bool isNew); void UpdateTable(); void StartLiveWindowMode(); void StopLiveWindowMode(); std::string GetSmartDashboardType() const; - void InitTable(::std::shared_ptr subTable); - ::std::shared_ptr GetTable() const; + void InitTable(std::shared_ptr subTable); + std::shared_ptr GetTable() const; private: uint32_t m_channel; void *m_pwmGenerator; - ::std::shared_ptr m_table = nullptr; + std::shared_ptr m_table = nullptr; }; diff --git a/wpilibc/wpilibC++Devices/include/DoubleSolenoid.h b/wpilibc/wpilibC++Devices/include/DoubleSolenoid.h index 0e883bea4b..885880759e 100644 --- a/wpilibc/wpilibC++Devices/include/DoubleSolenoid.h +++ b/wpilibc/wpilibC++Devices/include/DoubleSolenoid.h @@ -34,14 +34,14 @@ class DoubleSolenoid : public SolenoidBase, bool IsFwdSolenoidBlackListed() const; bool IsRevSolenoidBlackListed() const; - void ValueChanged(::std::shared_ptr source, const std::string& key, EntryValue value, + void ValueChanged(std::shared_ptr source, const std::string& key, EntryValue value, bool isNew); void UpdateTable(); void StartLiveWindowMode(); void StopLiveWindowMode(); std::string GetSmartDashboardType() const; - void InitTable(::std::shared_ptr subTable); - ::std::shared_ptr GetTable() const; + void InitTable(std::shared_ptr subTable); + std::shared_ptr GetTable() const; private: uint32_t m_forwardChannel; ///< The forward channel on the module to control. @@ -49,5 +49,5 @@ class DoubleSolenoid : public SolenoidBase, uint8_t m_forwardMask; ///< The mask for the forward channel. uint8_t m_reverseMask; ///< The mask for the reverse channel. - ::std::shared_ptr m_table = nullptr; + std::shared_ptr m_table = nullptr; }; diff --git a/wpilibc/wpilibC++Devices/include/Encoder.h b/wpilibc/wpilibC++Devices/include/Encoder.h index 9e4ed839cd..77ab300626 100644 --- a/wpilibc/wpilibC++Devices/include/Encoder.h +++ b/wpilibc/wpilibC++Devices/include/Encoder.h @@ -49,8 +49,8 @@ class Encoder : public SensorBase, Encoder(uint32_t aChannel, uint32_t bChannel, bool reverseDirection = false, EncodingType encodingType = k4X); - Encoder(::std::shared_ptr aSource, - ::std::shared_ptr bSource, + Encoder(std::shared_ptr aSource, + std::shared_ptr bSource, bool reverseDirection = false, EncodingType encodingType = k4X); [[deprecated( "Raw pointers are deprecated; if you wish to construct your own copy of " @@ -97,8 +97,8 @@ class Encoder : public SensorBase, void StartLiveWindowMode() override; void StopLiveWindowMode() override; std::string GetSmartDashboardType() const override; - void InitTable(::std::shared_ptr subTable) override; - ::std::shared_ptr GetTable() const override; + void InitTable(std::shared_ptr subTable) override; + std::shared_ptr GetTable() const override; int32_t GetFPGAIndex() const { return m_index; } @@ -106,17 +106,17 @@ class Encoder : public SensorBase, void InitEncoder(bool _reverseDirection, EncodingType encodingType); double DecodingScaleFactor() const; - ::std::shared_ptr m_aSource; // the A phase of the quad encoder - ::std::shared_ptr m_bSource; // the B phase of the quad encoder + std::shared_ptr m_aSource; // the A phase of the quad encoder + std::shared_ptr m_bSource; // the B phase of the quad encoder void *m_encoder = nullptr; int32_t m_index = 0; // The encoder's FPGA index. double m_distancePerPulse = 1.0; // distance of travel for each encoder tick - ::std::unique_ptr m_counter = + std::unique_ptr m_counter = nullptr; // Counter object for 1x and 2x encoding EncodingType m_encodingType; // Encoding type int32_t m_encodingScale; // 1x, 2x, or 4x, per the encodingType PIDSourceParameter m_pidSource = kDistance; // Encoder parameter that sources a PID controller - ::std::shared_ptr m_table = nullptr; + std::shared_ptr m_table = nullptr; }; diff --git a/wpilibc/wpilibC++Devices/include/GearTooth.h b/wpilibc/wpilibC++Devices/include/GearTooth.h index 7b28fa4f32..3889f9c5a9 100644 --- a/wpilibc/wpilibC++Devices/include/GearTooth.h +++ b/wpilibc/wpilibC++Devices/include/GearTooth.h @@ -23,7 +23,7 @@ class GearTooth : public Counter { static constexpr double kGearToothThreshold = 55e-6; GearTooth(uint32_t channel, bool directionSensitive = false); GearTooth(DigitalSource *source, bool directionSensitive = false); - GearTooth(::std::shared_ptr source, + GearTooth(std::shared_ptr source, bool directionSensitive = false); virtual ~GearTooth() = default; void EnableDirectionSensing(bool directionSensitive); diff --git a/wpilibc/wpilibC++Devices/include/Gyro.h b/wpilibc/wpilibC++Devices/include/Gyro.h index f89c31f941..ea20bc4dfa 100644 --- a/wpilibc/wpilibC++Devices/include/Gyro.h +++ b/wpilibc/wpilibC++Devices/include/Gyro.h @@ -43,7 +43,7 @@ class Gyro : public SensorBase, public PIDSource, public LiveWindowSendable { "Raw pointers are deprecated; consider calling the Gyro constructor with " "a channel number or passing a shared_ptr instead.")]] explicit Gyro(AnalogInput *channel); - explicit Gyro(::std::shared_ptr channel); + explicit Gyro(std::shared_ptr channel); virtual ~Gyro() = default; virtual float GetAngle() const; virtual double GetRate() const; @@ -60,11 +60,11 @@ class Gyro : public SensorBase, public PIDSource, public LiveWindowSendable { void StartLiveWindowMode() override; void StopLiveWindowMode() override; std::string GetSmartDashboardType() const override; - void InitTable(::std::shared_ptr subTable) override; - ::std::shared_ptr GetTable() const override; + void InitTable(std::shared_ptr subTable) override; + std::shared_ptr GetTable() const override; protected: - ::std::shared_ptr m_analog; + std::shared_ptr m_analog; private: float m_voltsPerDegreePerSecond; @@ -72,5 +72,5 @@ class Gyro : public SensorBase, public PIDSource, public LiveWindowSendable { uint32_t m_center; PIDSourceParameter m_pidSource; - ::std::shared_ptr m_table = nullptr; + std::shared_ptr m_table = nullptr; }; diff --git a/wpilibc/wpilibC++Devices/include/InterruptableSensorBase.h b/wpilibc/wpilibC++Devices/include/InterruptableSensorBase.h index b64f148672..b595c8d46a 100644 --- a/wpilibc/wpilibC++Devices/include/InterruptableSensorBase.h +++ b/wpilibc/wpilibC++Devices/include/InterruptableSensorBase.h @@ -48,5 +48,5 @@ class InterruptableSensorBase : public SensorBase { uint32_t m_interruptIndex; void AllocateInterrupts(bool watcher); - static ::std::unique_ptr m_interrupts; + static std::unique_ptr m_interrupts; }; diff --git a/wpilibc/wpilibC++Devices/include/Joystick.h b/wpilibc/wpilibC++Devices/include/Joystick.h index 0922359bf3..b8ea292e37 100644 --- a/wpilibc/wpilibC++Devices/include/Joystick.h +++ b/wpilibc/wpilibC++Devices/include/Joystick.h @@ -108,8 +108,8 @@ class Joystick : public GenericHID, public ErrorBase { private: DriverStation &m_ds; uint32_t m_port; - ::std::vector m_axes; - ::std::vector m_buttons; + std::vector m_axes; + std::vector m_buttons; uint32_t m_outputs = 0; uint16_t m_leftRumble = 0; uint16_t m_rightRumble = 0; diff --git a/wpilibc/wpilibC++Devices/include/MotorSafetyHelper.h b/wpilibc/wpilibC++Devices/include/MotorSafetyHelper.h index 3e2f97e1dd..bbe76580a4 100644 --- a/wpilibc/wpilibC++Devices/include/MotorSafetyHelper.h +++ b/wpilibc/wpilibC++Devices/include/MotorSafetyHelper.h @@ -34,7 +34,7 @@ class MotorSafetyHelper : public ErrorBase { m_syncMutex; // protect accesses to the state for this object MotorSafety *m_safeObject; // the object that is using the helper // List of all existing MotorSafetyHelper objects. - static ::std::set m_helperList; + static std::set m_helperList; static priority_recursive_mutex m_listMutex; // protect accesses to the list of helpers }; diff --git a/wpilibc/wpilibC++Devices/include/PWM.h b/wpilibc/wpilibC++Devices/include/PWM.h index 425ce2a338..578ed4013b 100644 --- a/wpilibc/wpilibC++Devices/include/PWM.h +++ b/wpilibc/wpilibC++Devices/include/PWM.h @@ -99,16 +99,16 @@ class PWM : public SensorBase, int32_t m_deadbandMinPwm; int32_t m_minPwm; - void ValueChanged(::std::shared_ptr source, const std::string& key, EntryValue value, + void ValueChanged(std::shared_ptr source, const std::string& key, EntryValue value, bool isNew) override; void UpdateTable() override; void StartLiveWindowMode() override; void StopLiveWindowMode() override; std::string GetSmartDashboardType() const override; - void InitTable(::std::shared_ptr subTable) override; - ::std::shared_ptr GetTable() const override; + void InitTable(std::shared_ptr subTable) override; + std::shared_ptr GetTable() const override; - ::std::shared_ptr m_table = nullptr; + std::shared_ptr m_table = nullptr; private: uint32_t m_channel; diff --git a/wpilibc/wpilibC++Devices/include/PowerDistributionPanel.h b/wpilibc/wpilibC++Devices/include/PowerDistributionPanel.h index 0c87c63cf0..3f17725b16 100644 --- a/wpilibc/wpilibC++Devices/include/PowerDistributionPanel.h +++ b/wpilibc/wpilibC++Devices/include/PowerDistributionPanel.h @@ -38,11 +38,11 @@ class PowerDistributionPanel : public SensorBase, public LiveWindowSendable { void StartLiveWindowMode() override; void StopLiveWindowMode() override; std::string GetSmartDashboardType() const override; - void InitTable(::std::shared_ptr subTable) override; - ::std::shared_ptr GetTable() const override; + void InitTable(std::shared_ptr subTable) override; + std::shared_ptr GetTable() const override; private: - ::std::shared_ptr m_table = nullptr; + std::shared_ptr m_table = nullptr; uint8_t m_module; }; diff --git a/wpilibc/wpilibC++Devices/include/Preferences.h b/wpilibc/wpilibC++Devices/include/Preferences.h index c6b5a12a6a..118a968d38 100644 --- a/wpilibc/wpilibC++Devices/include/Preferences.h +++ b/wpilibc/wpilibC++Devices/include/Preferences.h @@ -59,7 +59,7 @@ class Preferences : public ErrorBase, public ITableListener { bool ContainsKey(const char *key); void Remove(const char *key); - void ValueChanged(::std::shared_ptr source, const std::string &key, EntryValue value, + void ValueChanged(std::shared_ptr source, const std::string &key, EntryValue value, bool isNew) override; protected: diff --git a/wpilibc/wpilibC++Devices/include/Relay.h b/wpilibc/wpilibC++Devices/include/Relay.h index 186ab68d59..edf8eb3f6a 100644 --- a/wpilibc/wpilibC++Devices/include/Relay.h +++ b/wpilibc/wpilibC++Devices/include/Relay.h @@ -40,16 +40,16 @@ class Relay : public SensorBase, void Set(Value value); Value Get() const; - void ValueChanged(::std::shared_ptr source, const std::string& key, EntryValue value, + void ValueChanged(std::shared_ptr source, const std::string& key, EntryValue value, bool isNew) override; void UpdateTable() override; void StartLiveWindowMode() override; void StopLiveWindowMode() override; std::string GetSmartDashboardType() const override; - void InitTable(::std::shared_ptr subTable) override; - ::std::shared_ptr GetTable() const override; + void InitTable(std::shared_ptr subTable) override; + std::shared_ptr GetTable() const override; - ::std::shared_ptr m_table = nullptr; + std::shared_ptr m_table = nullptr; private: uint32_t m_channel; diff --git a/wpilibc/wpilibC++Devices/include/RobotDrive.h b/wpilibc/wpilibC++Devices/include/RobotDrive.h index fa7841af83..697269c537 100644 --- a/wpilibc/wpilibC++Devices/include/RobotDrive.h +++ b/wpilibc/wpilibC++Devices/include/RobotDrive.h @@ -48,18 +48,18 @@ class RobotDrive : public MotorSafety, public ErrorBase { RobotDrive(SpeedController *leftMotor, SpeedController *rightMotor); [[deprecated("References are deprecated; use shared_ptr instead.")]] RobotDrive(SpeedController &leftMotor, SpeedController &rightMotor); - RobotDrive(::std::shared_ptr leftMotor, - ::std::shared_ptr rightMotor); + RobotDrive(std::shared_ptr leftMotor, + std::shared_ptr rightMotor); [[deprecated("Raw pointers are deprecated; use shared_ptr instead.")]] RobotDrive(SpeedController *frontLeftMotor, SpeedController *rearLeftMotor, SpeedController *frontRightMotor, SpeedController *rearRightMotor); [[deprecated("References are deprecated; use shared_ptr instead.")]] RobotDrive(SpeedController &frontLeftMotor, SpeedController &rearLeftMotor, SpeedController &frontRightMotor, SpeedController &rearRightMotor); - RobotDrive(::std::shared_ptr frontLeftMotor, - ::std::shared_ptr rearLeftMotor, - ::std::shared_ptr frontRightMotor, - ::std::shared_ptr rearRightMotor); + RobotDrive(std::shared_ptr frontLeftMotor, + std::shared_ptr rearLeftMotor, + std::shared_ptr frontRightMotor, + std::shared_ptr rearRightMotor); virtual ~RobotDrive() = default; RobotDrive(const RobotDrive&) = delete; @@ -114,10 +114,10 @@ class RobotDrive : public MotorSafety, public ErrorBase { static const int32_t kMaxNumberOfMotors = 4; float m_sensitivity = 0.5; double m_maxOutput = 1.0; - ::std::shared_ptr m_frontLeftMotor = nullptr; - ::std::shared_ptr m_frontRightMotor = nullptr; - ::std::shared_ptr m_rearLeftMotor = nullptr; - ::std::shared_ptr m_rearRightMotor = nullptr; + std::shared_ptr m_frontLeftMotor = nullptr; + std::shared_ptr m_frontRightMotor = nullptr; + std::shared_ptr m_rearLeftMotor = nullptr; + std::shared_ptr m_rearRightMotor = nullptr; std::unique_ptr m_safetyHelper; uint8_t m_syncGroup = 0; diff --git a/wpilibc/wpilibC++Devices/include/Servo.h b/wpilibc/wpilibC++Devices/include/Servo.h index bc9d10ee59..821a0caa4e 100644 --- a/wpilibc/wpilibC++Devices/include/Servo.h +++ b/wpilibc/wpilibC++Devices/include/Servo.h @@ -30,16 +30,16 @@ class Servo : public SafePWM { static float GetMaxAngle() { return kMaxServoAngle; } static float GetMinAngle() { return kMinServoAngle; } - void ValueChanged(::std::shared_ptr source, const std::string& key, + void ValueChanged(std::shared_ptr source, const std::string& key, EntryValue value, bool isNew) override; void UpdateTable() override; void StartLiveWindowMode() override; void StopLiveWindowMode() override; std::string GetSmartDashboardType() const override; - void InitTable(::std::shared_ptr subTable) override; - ::std::shared_ptr GetTable() const override; + void InitTable(std::shared_ptr subTable) override; + std::shared_ptr GetTable() const override; - ::std::shared_ptr m_table = nullptr; + std::shared_ptr m_table = nullptr; private: float GetServoAngleRange() const { return kMaxServoAngle - kMinServoAngle; } diff --git a/wpilibc/wpilibC++Devices/include/Solenoid.h b/wpilibc/wpilibC++Devices/include/Solenoid.h index ab0aff6d91..897bc67355 100644 --- a/wpilibc/wpilibC++Devices/include/Solenoid.h +++ b/wpilibc/wpilibC++Devices/include/Solenoid.h @@ -30,16 +30,16 @@ class Solenoid : public SolenoidBase, virtual bool Get() const; bool IsBlackListed() const; - void ValueChanged(::std::shared_ptr source, const std::string& key, EntryValue value, + void ValueChanged(std::shared_ptr source, const std::string& key, EntryValue value, bool isNew); void UpdateTable(); void StartLiveWindowMode(); void StopLiveWindowMode(); std::string GetSmartDashboardType() const; - void InitTable(::std::shared_ptr subTable); - ::std::shared_ptr GetTable() const; + void InitTable(std::shared_ptr subTable); + std::shared_ptr GetTable() const; private: uint32_t m_channel; ///< The channel on the module to control. - ::std::shared_ptr m_table = nullptr; + std::shared_ptr m_table = nullptr; }; diff --git a/wpilibc/wpilibC++Devices/include/SolenoidBase.h b/wpilibc/wpilibC++Devices/include/SolenoidBase.h index 2732e86219..637ad92dc5 100644 --- a/wpilibc/wpilibC++Devices/include/SolenoidBase.h +++ b/wpilibc/wpilibC++Devices/include/SolenoidBase.h @@ -35,5 +35,5 @@ class SolenoidBase : public SensorBase { static void* m_ports[m_maxModules][m_maxPorts]; uint32_t m_moduleNumber; ///< Slot number where the module is plugged into ///the chassis. - static ::std::unique_ptr m_allocated; + static std::unique_ptr m_allocated; }; diff --git a/wpilibc/wpilibC++Devices/include/Ultrasonic.h b/wpilibc/wpilibC++Devices/include/Ultrasonic.h index 6ac4d18ead..eb58690031 100644 --- a/wpilibc/wpilibC++Devices/include/Ultrasonic.h +++ b/wpilibc/wpilibC++Devices/include/Ultrasonic.h @@ -54,8 +54,8 @@ class Ultrasonic : public SensorBase, Ultrasonic(DigitalOutput &pingChannel, DigitalInput &echoChannel, DistanceUnit units = kInches); - Ultrasonic(::std::shared_ptr pingChannel, - ::std::shared_ptr echoChannel, + Ultrasonic(std::shared_ptr pingChannel, + std::shared_ptr echoChannel, DistanceUnit units = kInches); Ultrasonic(uint32_t pingChannel, uint32_t echoChannel, DistanceUnit units = kInches); @@ -77,8 +77,8 @@ class Ultrasonic : public SensorBase, void StartLiveWindowMode() override; void StopLiveWindowMode() override; std::string GetSmartDashboardType() const override; - void InitTable(::std::shared_ptr subTable) override; - ::std::shared_ptr GetTable() const override; + void InitTable(std::shared_ptr subTable) override; + std::shared_ptr GetTable() const override; private: void Initialize(); @@ -98,13 +98,13 @@ class Ultrasonic : public SensorBase, static std::atomic m_automaticEnabled; // automatic round robin mode static priority_mutex m_mutex; // synchronize access to the list of sensors - ::std::shared_ptr m_pingChannel; - ::std::shared_ptr m_echoChannel; + std::shared_ptr m_pingChannel; + std::shared_ptr m_echoChannel; bool m_allocatedChannels; bool m_enabled; Counter m_counter; Ultrasonic *m_nextSensor; DistanceUnit m_units; - ::std::shared_ptr m_table = nullptr; + std::shared_ptr m_table = nullptr; }; diff --git a/wpilibc/wpilibC++Devices/src/ADXL345_I2C.cpp b/wpilibc/wpilibC++Devices/src/ADXL345_I2C.cpp index 5287e58459..27e27be1bd 100644 --- a/wpilibc/wpilibC++Devices/src/ADXL345_I2C.cpp +++ b/wpilibc/wpilibC++Devices/src/ADXL345_I2C.cpp @@ -88,7 +88,7 @@ std::string ADXL345_I2C::GetSmartDashboardType() const { return "3AxisAccelerometer"; } -void ADXL345_I2C::InitTable(::std::shared_ptr subtable) { +void ADXL345_I2C::InitTable(std::shared_ptr subtable) { m_table = subtable; UpdateTable(); } @@ -99,4 +99,4 @@ void ADXL345_I2C::UpdateTable() { m_table->PutNumber("Z", GetZ()); } -::std::shared_ptr ADXL345_I2C::GetTable() const { return m_table; } +std::shared_ptr ADXL345_I2C::GetTable() const { return m_table; } diff --git a/wpilibc/wpilibC++Devices/src/ADXL345_SPI.cpp b/wpilibc/wpilibC++Devices/src/ADXL345_SPI.cpp index ef742a6ea8..c2f6de1991 100644 --- a/wpilibc/wpilibC++Devices/src/ADXL345_SPI.cpp +++ b/wpilibc/wpilibC++Devices/src/ADXL345_SPI.cpp @@ -122,7 +122,7 @@ std::string ADXL345_SPI::GetSmartDashboardType() const { return "3AxisAccelerometer"; } -void ADXL345_SPI::InitTable(::std::shared_ptr subtable) { +void ADXL345_SPI::InitTable(std::shared_ptr subtable) { m_table = subtable; UpdateTable(); } @@ -135,4 +135,4 @@ void ADXL345_SPI::UpdateTable() { } } -::std::shared_ptr ADXL345_SPI::GetTable() const { return m_table; } +std::shared_ptr ADXL345_SPI::GetTable() const { return m_table; } diff --git a/wpilibc/wpilibC++Devices/src/AnalogAccelerometer.cpp b/wpilibc/wpilibC++Devices/src/AnalogAccelerometer.cpp index 2ebec024d3..8ee07bd668 100644 --- a/wpilibc/wpilibC++Devices/src/AnalogAccelerometer.cpp +++ b/wpilibc/wpilibC++Devices/src/AnalogAccelerometer.cpp @@ -27,7 +27,7 @@ void AnalogAccelerometer::InitAccelerometer() { * connected to */ AnalogAccelerometer::AnalogAccelerometer(int32_t channel) { - m_analogInput = ::std::make_shared(channel); + m_analogInput = std::make_shared(channel); InitAccelerometer(); } @@ -61,7 +61,7 @@ AnalogAccelerometer::AnalogAccelerometer(AnalogInput *channel) * @param channel The existing AnalogInput object for the analog input the * accelerometer is connected to */ -AnalogAccelerometer::AnalogAccelerometer(::std::shared_ptr channel) +AnalogAccelerometer::AnalogAccelerometer(std::shared_ptr channel) : m_analogInput(channel) { if (channel == nullptr) { wpi_setWPIError(NullParameter); @@ -126,9 +126,9 @@ std::string AnalogAccelerometer::GetSmartDashboardType() const { return "Accelerometer"; } -void AnalogAccelerometer::InitTable(::std::shared_ptr subTable) { +void AnalogAccelerometer::InitTable(std::shared_ptr subTable) { m_table = subTable; UpdateTable(); } -::std::shared_ptr AnalogAccelerometer::GetTable() const { return m_table; } +std::shared_ptr AnalogAccelerometer::GetTable() const { return m_table; } diff --git a/wpilibc/wpilibC++Devices/src/AnalogInput.cpp b/wpilibc/wpilibC++Devices/src/AnalogInput.cpp index 31dec18340..2239f008ad 100644 --- a/wpilibc/wpilibC++Devices/src/AnalogInput.cpp +++ b/wpilibc/wpilibC++Devices/src/AnalogInput.cpp @@ -13,7 +13,7 @@ #include -static ::std::unique_ptr inputs; +static std::unique_ptr inputs; const uint8_t AnalogInput::kAccumulatorModuleNumber; const uint32_t AnalogInput::kAccumulatorNumChannels; @@ -413,9 +413,9 @@ std::string AnalogInput::GetSmartDashboardType() const { return "Analog Input"; } -void AnalogInput::InitTable(::std::shared_ptr subTable) { +void AnalogInput::InitTable(std::shared_ptr subTable) { m_table = subTable; UpdateTable(); } -::std::shared_ptr AnalogInput::GetTable() const { return m_table; } +std::shared_ptr AnalogInput::GetTable() const { return m_table; } diff --git a/wpilibc/wpilibC++Devices/src/AnalogOutput.cpp b/wpilibc/wpilibC++Devices/src/AnalogOutput.cpp index 4c3246e93c..19eee52985 100644 --- a/wpilibc/wpilibC++Devices/src/AnalogOutput.cpp +++ b/wpilibc/wpilibC++Devices/src/AnalogOutput.cpp @@ -12,7 +12,7 @@ #include -static ::std::unique_ptr outputs; +static std::unique_ptr outputs; /** * Construct an analog output on the given channel. @@ -91,9 +91,9 @@ std::string AnalogOutput::GetSmartDashboardType() const { return "Analog Output"; } -void AnalogOutput::InitTable(::std::shared_ptr subTable) { +void AnalogOutput::InitTable(std::shared_ptr subTable) { m_table = subTable; UpdateTable(); } -::std::shared_ptr AnalogOutput::GetTable() const { return m_table; } +std::shared_ptr AnalogOutput::GetTable() const { return m_table; } diff --git a/wpilibc/wpilibC++Devices/src/AnalogPotentiometer.cpp b/wpilibc/wpilibC++Devices/src/AnalogPotentiometer.cpp index 74ac6bd8f4..052715dd1b 100644 --- a/wpilibc/wpilibC++Devices/src/AnalogPotentiometer.cpp +++ b/wpilibc/wpilibC++Devices/src/AnalogPotentiometer.cpp @@ -12,7 +12,7 @@ */ AnalogPotentiometer::AnalogPotentiometer(int channel, double fullRange, double offset) - : m_analog_input(::std::make_unique(channel)), + : m_analog_input(std::make_unique(channel)), m_fullRange(fullRange), m_offset(offset) {} @@ -45,7 +45,7 @@ AnalogPotentiometer::AnalogPotentiometer(AnalogInput *input, double fullRange, * @param offset The angular value (in desired units) representing the angular * output at 0V. */ -AnalogPotentiometer::AnalogPotentiometer(::std::shared_ptr input, +AnalogPotentiometer::AnalogPotentiometer(std::shared_ptr input, double fullRange, double offset) : m_analog_input(input), m_fullRange(fullRange), m_offset(offset) {} @@ -78,7 +78,7 @@ std::string AnalogPotentiometer::GetSmartDashboardType() const { /** * Live Window code, only does anything if live window is activated. */ -void AnalogPotentiometer::InitTable(::std::shared_ptr subtable) { +void AnalogPotentiometer::InitTable(std::shared_ptr subtable) { m_table = subtable; UpdateTable(); } @@ -89,4 +89,4 @@ void AnalogPotentiometer::UpdateTable() { } } -::std::shared_ptr AnalogPotentiometer::GetTable() const { return m_table; } +std::shared_ptr AnalogPotentiometer::GetTable() const { return m_table; } diff --git a/wpilibc/wpilibC++Devices/src/AnalogTrigger.cpp b/wpilibc/wpilibC++Devices/src/AnalogTrigger.cpp index de9b92f6cc..61ba0353ee 100644 --- a/wpilibc/wpilibC++Devices/src/AnalogTrigger.cpp +++ b/wpilibc/wpilibC++Devices/src/AnalogTrigger.cpp @@ -151,9 +151,9 @@ bool AnalogTrigger::GetTriggerState() { * @param type An enum of the type of output object to create. * @return A pointer to a new AnalogTriggerOutput object. */ -::std::shared_ptr AnalogTrigger::CreateOutput( +std::shared_ptr AnalogTrigger::CreateOutput( AnalogTriggerType type) const { if (StatusIsFatal()) return nullptr; - return ::std::shared_ptr( + return std::shared_ptr( new AnalogTriggerOutput(*this, type), NullDeleter()); } diff --git a/wpilibc/wpilibC++Devices/src/BuiltInAccelerometer.cpp b/wpilibc/wpilibC++Devices/src/BuiltInAccelerometer.cpp index 46ed7f7ab0..d5450a850e 100644 --- a/wpilibc/wpilibC++Devices/src/BuiltInAccelerometer.cpp +++ b/wpilibc/wpilibC++Devices/src/BuiltInAccelerometer.cpp @@ -52,7 +52,7 @@ std::string BuiltInAccelerometer::GetSmartDashboardType() const { return "3AxisAccelerometer"; } -void BuiltInAccelerometer::InitTable(::std::shared_ptr subtable) { +void BuiltInAccelerometer::InitTable(std::shared_ptr subtable) { m_table = subtable; UpdateTable(); } @@ -65,4 +65,4 @@ void BuiltInAccelerometer::UpdateTable() { } } -::std::shared_ptr BuiltInAccelerometer::GetTable() const { return m_table; } +std::shared_ptr BuiltInAccelerometer::GetTable() const { return m_table; } diff --git a/wpilibc/wpilibC++Devices/src/CANJaguar.cpp b/wpilibc/wpilibC++Devices/src/CANJaguar.cpp index 5d3a2ca18d..608a9663e7 100644 --- a/wpilibc/wpilibC++Devices/src/CANJaguar.cpp +++ b/wpilibc/wpilibC++Devices/src/CANJaguar.cpp @@ -31,7 +31,7 @@ static const uint32_t kFullMessageIDMask = static const int32_t kReceiveStatusAttempts = 50; -static ::std::unique_ptr allocated; +static std::unique_ptr allocated; static int32_t sendMessageHelper(uint32_t messageID, const uint8_t *data, uint8_t dataSize, int32_t period) { @@ -1935,7 +1935,7 @@ uint8_t CANJaguar::GetDeviceID() const { return m_deviceNumber; } */ void CANJaguar::StopMotor() { DisableControl(); } -void CANJaguar::ValueChanged(::std::shared_ptr source, const std::string &key, +void CANJaguar::ValueChanged(std::shared_ptr source, const std::string &key, EntryValue value, bool isNew) { Set(value.f); } @@ -1977,9 +1977,9 @@ std::string CANJaguar::GetSmartDashboardType() const { return "Speed Controller"; } -void CANJaguar::InitTable(::std::shared_ptr subTable) { +void CANJaguar::InitTable(std::shared_ptr subTable) { m_table = subTable; UpdateTable(); } -::std::shared_ptr CANJaguar::GetTable() const { return m_table; } +std::shared_ptr CANJaguar::GetTable() const { return m_table; } diff --git a/wpilibc/wpilibC++Devices/src/CANTalon.cpp b/wpilibc/wpilibC++Devices/src/CANTalon.cpp index 8d3eff599d..2b303e86ce 100644 --- a/wpilibc/wpilibC++Devices/src/CANTalon.cpp +++ b/wpilibc/wpilibC++Devices/src/CANTalon.cpp @@ -1270,7 +1270,7 @@ bool CANTalon::GetInverted() const { return m_isInverted; } */ void CANTalon::StopMotor() { Disable(); } -void CANTalon::ValueChanged(::std::shared_ptr source, const std::string& key, +void CANTalon::ValueChanged(std::shared_ptr source, const std::string& key, EntryValue value, bool isNew) { Set(value.f); } @@ -1297,9 +1297,9 @@ std::string CANTalon::GetSmartDashboardType() const { return "Speed Controller"; } -void CANTalon::InitTable(::std::shared_ptr subTable) { +void CANTalon::InitTable(std::shared_ptr subTable) { m_table = subTable; UpdateTable(); } -::std::shared_ptr CANTalon::GetTable() const { return m_table; } +std::shared_ptr CANTalon::GetTable() const { return m_table; } diff --git a/wpilibc/wpilibC++Devices/src/Compressor.cpp b/wpilibc/wpilibC++Devices/src/Compressor.cpp index 50a07ec2ed..5435b32b20 100644 --- a/wpilibc/wpilibC++Devices/src/Compressor.cpp +++ b/wpilibc/wpilibC++Devices/src/Compressor.cpp @@ -260,14 +260,14 @@ void Compressor::StopLiveWindowMode() {} std::string Compressor::GetSmartDashboardType() const { return "Compressor"; } -void Compressor::InitTable(::std::shared_ptr subTable) { +void Compressor::InitTable(std::shared_ptr subTable) { m_table = subTable; UpdateTable(); } -::std::shared_ptr Compressor::GetTable() const { return m_table; } +std::shared_ptr Compressor::GetTable() const { return m_table; } -void Compressor::ValueChanged(::std::shared_ptr source, const std::string& key, +void Compressor::ValueChanged(std::shared_ptr source, const std::string& key, EntryValue value, bool isNew) { if (value.b) Start(); diff --git a/wpilibc/wpilibC++Devices/src/Counter.cpp b/wpilibc/wpilibC++Devices/src/Counter.cpp index a2e306d8b8..cfbacb93e8 100644 --- a/wpilibc/wpilibC++Devices/src/Counter.cpp +++ b/wpilibc/wpilibC++Devices/src/Counter.cpp @@ -67,7 +67,7 @@ Counter::Counter(DigitalSource *source) : Counter() { * @param source A pointer to the existing DigitalSource object. It will be * set as the Up Source. */ -Counter::Counter(::std::shared_ptr source) : Counter() { +Counter::Counter(std::shared_ptr source) : Counter() { SetUpSource(source); ClearDownSource(); } @@ -126,9 +126,9 @@ Counter::Counter(const AnalogTrigger &trigger) : Counter() { Counter::Counter(EncodingType encodingType, DigitalSource *upSource, DigitalSource *downSource, bool inverted) : Counter(encodingType, - ::std::shared_ptr(upSource, + std::shared_ptr(upSource, NullDeleter()), - ::std::shared_ptr(downSource, + std::shared_ptr(downSource, NullDeleter()), inverted) {} @@ -141,8 +141,8 @@ Counter::Counter(EncodingType encodingType, DigitalSource *upSource, * @param inverted True to invert the output (reverse the direction) */ Counter::Counter(EncodingType encodingType, - ::std::shared_ptr upSource, - ::std::shared_ptr downSource, bool inverted) + std::shared_ptr upSource, + std::shared_ptr downSource, bool inverted) : Counter(kExternalDirection) { if (encodingType != k1X && encodingType != k2X) { wpi_setWPIErrorWithContext( @@ -185,7 +185,7 @@ Counter::~Counter() { */ void Counter::SetUpSource(int32_t channel) { if (StatusIsFatal()) return; - SetUpSource(::std::make_shared(channel)); + SetUpSource(std::make_shared(channel)); } /** @@ -198,7 +198,7 @@ void Counter::SetUpSource(int32_t channel) { "SetUpSource(shared_ptr).")]] void Counter::SetUpSource(AnalogTrigger *analogTrigger, AnalogTriggerType triggerType) { - SetUpSource(::std::shared_ptr(analogTrigger, + SetUpSource(std::shared_ptr(analogTrigger, NullDeleter()), triggerType); } @@ -208,7 +208,7 @@ void Counter::SetUpSource(AnalogTrigger *analogTrigger, * @param analogTrigger The analog trigger object that is used for the Up Source * @param triggerType The analog trigger output that will trigger the counter. */ -void Counter::SetUpSource(::std::shared_ptr analogTrigger, +void Counter::SetUpSource(std::shared_ptr analogTrigger, AnalogTriggerType triggerType) { if (StatusIsFatal()) return; SetUpSource(analogTrigger->CreateOutput(triggerType)); @@ -219,7 +219,7 @@ void Counter::SetUpSource(::std::shared_ptr analogTrigger, * Set the up counting DigitalSource. * @param source Pointer to the DigitalSource object to set as the up source */ -void Counter::SetUpSource(::std::shared_ptr source) { +void Counter::SetUpSource(std::shared_ptr source) { if (StatusIsFatal()) return; m_upSource = source; if (m_upSource->StatusIsFatal()) { @@ -235,7 +235,7 @@ void Counter::SetUpSource(::std::shared_ptr source) { [[deprecated("Raw pointers are deprecated. Use std::shared_ptr instead.")]] void Counter::SetUpSource(DigitalSource *source) { SetUpSource( - ::std::shared_ptr(source, NullDeleter())); + std::shared_ptr(source, NullDeleter())); } /** @@ -246,7 +246,7 @@ void Counter::SetUpSource(DigitalSource *source) { [[deprecated("References are deprecated. Use std::shared_ptr instead.")]] void Counter::SetUpSource(DigitalSource &source) { SetUpSource( - ::std::shared_ptr(&source, NullDeleter())); + std::shared_ptr(&source, NullDeleter())); } /** @@ -285,7 +285,7 @@ void Counter::ClearUpSource() { */ void Counter::SetDownSource(int32_t channel) { if (StatusIsFatal()) return; - SetDownSource(::std::make_shared(channel)); + SetDownSource(std::make_shared(channel)); } /** @@ -299,7 +299,7 @@ void Counter::SetDownSource(int32_t channel) { "SetUpSource(shared_ptr).")]] void Counter::SetDownSource(AnalogTrigger *analogTrigger, AnalogTriggerType triggerType) { - SetDownSource(::std::shared_ptr(analogTrigger, NullDeleter()), triggerType); + SetDownSource(std::shared_ptr(analogTrigger, NullDeleter()), triggerType); } /** @@ -308,7 +308,7 @@ void Counter::SetDownSource(AnalogTrigger *analogTrigger, * Source * @param triggerType The analog trigger output that will trigger the counter. */ -void Counter::SetDownSource(::std::shared_ptr analogTrigger, +void Counter::SetDownSource(std::shared_ptr analogTrigger, AnalogTriggerType triggerType) { if (StatusIsFatal()) return; SetDownSource(analogTrigger->CreateOutput(triggerType)); @@ -319,7 +319,7 @@ void Counter::SetDownSource(::std::shared_ptr analogTrigger, * Set the down counting DigitalSource. * @param source Pointer to the DigitalSource object to set as the down source */ -void Counter::SetDownSource(::std::shared_ptr source) { +void Counter::SetDownSource(std::shared_ptr source) { if (StatusIsFatal()) return; m_downSource = source; if (m_downSource->StatusIsFatal()) { @@ -334,7 +334,7 @@ void Counter::SetDownSource(::std::shared_ptr source) { [[deprecated("Raw pointers are deprecated. Use std::shared_ptr instead.")]] void Counter::SetDownSource(DigitalSource *source) { - SetDownSource(::std::shared_ptr(source, NullDeleter())); + SetDownSource(std::shared_ptr(source, NullDeleter())); } /** @@ -344,7 +344,7 @@ void Counter::SetDownSource(DigitalSource *source) { */ [[deprecated("References are deprecated. Use std::shared_ptr instead.")]] void Counter::SetDownSource(DigitalSource &source) { - SetDownSource(::std::shared_ptr(&source, NullDeleter())); + SetDownSource(std::shared_ptr(&source, NullDeleter())); } /** @@ -600,9 +600,9 @@ void Counter::StopLiveWindowMode() {} std::string Counter::GetSmartDashboardType() const { return "Counter"; } -void Counter::InitTable(::std::shared_ptr subTable) { +void Counter::InitTable(std::shared_ptr subTable) { m_table = subTable; UpdateTable(); } -::std::shared_ptr Counter::GetTable() const { return m_table; } +std::shared_ptr Counter::GetTable() const { return m_table; } diff --git a/wpilibc/wpilibC++Devices/src/DigitalInput.cpp b/wpilibc/wpilibC++Devices/src/DigitalInput.cpp index b5db0939f5..cdfa009f66 100644 --- a/wpilibc/wpilibC++Devices/src/DigitalInput.cpp +++ b/wpilibc/wpilibC++Devices/src/DigitalInput.cpp @@ -100,9 +100,9 @@ std::string DigitalInput::GetSmartDashboardType() const { return "DigitalInput"; } -void DigitalInput::InitTable(::std::shared_ptr subTable) { +void DigitalInput::InitTable(std::shared_ptr subTable) { m_table = subTable; UpdateTable(); } -::std::shared_ptr DigitalInput::GetTable() const { return m_table; } +std::shared_ptr DigitalInput::GetTable() const { return m_table; } diff --git a/wpilibc/wpilibC++Devices/src/DigitalOutput.cpp b/wpilibc/wpilibC++Devices/src/DigitalOutput.cpp index c0b4b799f3..b1692b8074 100644 --- a/wpilibc/wpilibC++Devices/src/DigitalOutput.cpp +++ b/wpilibc/wpilibC++Devices/src/DigitalOutput.cpp @@ -196,7 +196,7 @@ uint32_t DigitalOutput::GetModuleForRouting() const { return 0; } */ bool DigitalOutput::GetAnalogTriggerForRouting() const { return false; } -void DigitalOutput::ValueChanged(::std::shared_ptr source, const std::string &key, +void DigitalOutput::ValueChanged(std::shared_ptr source, const std::string &key, EntryValue value, bool isNew) { Set(value.b); } @@ -219,9 +219,9 @@ std::string DigitalOutput::GetSmartDashboardType() const { return "Digital Output"; } -void DigitalOutput::InitTable(::std::shared_ptr subTable) { +void DigitalOutput::InitTable(std::shared_ptr subTable) { m_table = subTable; UpdateTable(); } -::std::shared_ptr DigitalOutput::GetTable() const { return m_table; } +std::shared_ptr DigitalOutput::GetTable() const { return m_table; } diff --git a/wpilibc/wpilibC++Devices/src/DoubleSolenoid.cpp b/wpilibc/wpilibC++Devices/src/DoubleSolenoid.cpp index 1cb6aa70cb..63ff0aa586 100644 --- a/wpilibc/wpilibC++Devices/src/DoubleSolenoid.cpp +++ b/wpilibc/wpilibC++Devices/src/DoubleSolenoid.cpp @@ -11,8 +11,8 @@ #include -::std::unique_ptr SolenoidBase::m_allocated = - ::std::make_unique(solenoid_kNumDO7_0Elements * +std::unique_ptr SolenoidBase::m_allocated = + std::make_unique(solenoid_kNumDO7_0Elements * kSolenoidChannels); /** @@ -155,7 +155,7 @@ bool DoubleSolenoid::IsRevSolenoidBlackListed() const { return (blackList & m_reverseMask) ? 1 : 0; } -void DoubleSolenoid::ValueChanged(::std::shared_ptr source, const std::string &key, +void DoubleSolenoid::ValueChanged(std::shared_ptr source, const std::string &key, EntryValue value, bool isNew) { Value lvalue = kOff; std::string *val = (std::string *)value.ptr; @@ -192,9 +192,9 @@ std::string DoubleSolenoid::GetSmartDashboardType() const { return "Double Solenoid"; } -void DoubleSolenoid::InitTable(::std::shared_ptr subTable) { +void DoubleSolenoid::InitTable(std::shared_ptr subTable) { m_table = subTable; UpdateTable(); } -::std::shared_ptr DoubleSolenoid::GetTable() const { return m_table; } +std::shared_ptr DoubleSolenoid::GetTable() const { return m_table; } diff --git a/wpilibc/wpilibC++Devices/src/Encoder.cpp b/wpilibc/wpilibC++Devices/src/Encoder.cpp index 9df94f2600..9a4b2a7f32 100644 --- a/wpilibc/wpilibC++Devices/src/Encoder.cpp +++ b/wpilibc/wpilibC++Devices/src/Encoder.cpp @@ -58,7 +58,7 @@ void Encoder::InitEncoder(bool reverseDirection, EncodingType encodingType) { case k1X: case k2X: { m_encodingScale = encodingType == k1X ? 1 : 2; - m_counter = ::std::make_unique(m_encodingType, m_aSource, + m_counter = std::make_unique(m_encodingType, m_aSource, m_bSource, reverseDirection); m_index = m_counter->GetFPGAIndex(); break; @@ -98,8 +98,8 @@ void Encoder::InitEncoder(bool reverseDirection, EncodingType encodingType) { */ Encoder::Encoder(uint32_t aChannel, uint32_t bChannel, bool reverseDirection, EncodingType encodingType) { - m_aSource = ::std::make_shared(aChannel); - m_bSource = ::std::make_shared(bChannel); + m_aSource = std::make_shared(aChannel); + m_bSource = std::make_shared(bChannel); InitEncoder(reverseDirection, encodingType); } @@ -139,8 +139,8 @@ Encoder::Encoder(DigitalSource *aSource, DigitalSource *bSource, InitEncoder(reverseDirection, encodingType); } -Encoder::Encoder(::std::shared_ptr aSource, - ::std::shared_ptr bSource, +Encoder::Encoder(std::shared_ptr aSource, + std::shared_ptr bSource, bool reverseDirection, EncodingType encodingType) : m_aSource(aSource), m_bSource(bSource) { if (m_aSource == nullptr || m_bSource == nullptr) @@ -573,9 +573,9 @@ std::string Encoder::GetSmartDashboardType() const { return "Encoder"; } -void Encoder::InitTable(::std::shared_ptr subTable) { +void Encoder::InitTable(std::shared_ptr subTable) { m_table = subTable; UpdateTable(); } -::std::shared_ptr Encoder::GetTable() const { return m_table; } +std::shared_ptr Encoder::GetTable() const { return m_table; } diff --git a/wpilibc/wpilibC++Devices/src/GearTooth.cpp b/wpilibc/wpilibC++Devices/src/GearTooth.cpp index 294e94b787..b9625b2478 100644 --- a/wpilibc/wpilibC++Devices/src/GearTooth.cpp +++ b/wpilibc/wpilibC++Devices/src/GearTooth.cpp @@ -56,7 +56,7 @@ GearTooth::GearTooth(DigitalSource *source, bool directionSensitive) * @param directionSensitive True to enable the pulse length decoding in * hardware to specify count direction. */ -GearTooth::GearTooth(::std::shared_ptr source, bool directionSensitive) +GearTooth::GearTooth(std::shared_ptr source, bool directionSensitive) : Counter(source) { EnableDirectionSensing(directionSensitive); } diff --git a/wpilibc/wpilibC++Devices/src/Gyro.cpp b/wpilibc/wpilibC++Devices/src/Gyro.cpp index ee87ce3871..504127b138 100644 --- a/wpilibc/wpilibC++Devices/src/Gyro.cpp +++ b/wpilibc/wpilibC++Devices/src/Gyro.cpp @@ -75,7 +75,7 @@ void Gyro::InitGyro() { can only be used on on-board Analog Inputs 0-1. */ Gyro::Gyro(int32_t channel) { - m_analog = ::std::make_shared(channel); + m_analog = std::make_shared(channel); InitGyro(); } @@ -92,7 +92,7 @@ Gyro::Gyro(int32_t channel) { "Raw pointers are deprecated; consider calling the Gyro constructor with " "a channel number or passing a shared_ptr instead.")]] Gyro::Gyro(AnalogInput *channel) - : Gyro(::std::shared_ptr(channel, + : Gyro(std::shared_ptr(channel, NullDeleter())) {} /** @@ -103,7 +103,7 @@ Gyro::Gyro(AnalogInput *channel) * @param channel A pointer to the AnalogInput object that the gyro is * connected to. */ -Gyro::Gyro(::std::shared_ptr channel) : m_analog(channel) { +Gyro::Gyro(std::shared_ptr channel) : m_analog(channel) { if (channel == nullptr) { wpi_setWPIError(NullParameter); } else { @@ -228,9 +228,9 @@ void Gyro::StopLiveWindowMode() {} std::string Gyro::GetSmartDashboardType() const { return "Gyro"; } -void Gyro::InitTable(::std::shared_ptr subTable) { +void Gyro::InitTable(std::shared_ptr subTable) { m_table = subTable; UpdateTable(); } -::std::shared_ptr Gyro::GetTable() const { return m_table; } +std::shared_ptr Gyro::GetTable() const { return m_table; } diff --git a/wpilibc/wpilibC++Devices/src/InterruptableSensorBase.cpp b/wpilibc/wpilibC++Devices/src/InterruptableSensorBase.cpp index 4262adac5a..9c113502f0 100644 --- a/wpilibc/wpilibC++Devices/src/InterruptableSensorBase.cpp +++ b/wpilibc/wpilibC++Devices/src/InterruptableSensorBase.cpp @@ -9,8 +9,8 @@ #include "Utility.h" #include "WPIErrors.h" -::std::unique_ptr InterruptableSensorBase::m_interrupts = - ::std::make_unique(interrupt_kNumSystems); +std::unique_ptr InterruptableSensorBase::m_interrupts = + std::make_unique(interrupt_kNumSystems); InterruptableSensorBase::InterruptableSensorBase() { } diff --git a/wpilibc/wpilibC++Devices/src/MotorSafetyHelper.cpp b/wpilibc/wpilibC++Devices/src/MotorSafetyHelper.cpp index e276fe2a82..e4fb035fd3 100644 --- a/wpilibc/wpilibC++Devices/src/MotorSafetyHelper.cpp +++ b/wpilibc/wpilibC++Devices/src/MotorSafetyHelper.cpp @@ -15,7 +15,7 @@ #include #include -::std::set MotorSafetyHelper::m_helperList; +std::set MotorSafetyHelper::m_helperList; priority_recursive_mutex MotorSafetyHelper::m_listMutex; /** diff --git a/wpilibc/wpilibC++Devices/src/PIDController.cpp b/wpilibc/wpilibC++Devices/src/PIDController.cpp index c25ad4a401..434a8e22a6 100644 --- a/wpilibc/wpilibC++Devices/src/PIDController.cpp +++ b/wpilibc/wpilibC++Devices/src/PIDController.cpp @@ -456,7 +456,7 @@ std::string PIDController::GetSmartDashboardType() const { return "PIDController"; } -void PIDController::InitTable(::std::shared_ptr table) { +void PIDController::InitTable(std::shared_ptr table) { if (m_table != nullptr) m_table->RemoveTableListener(this); m_table = table; if (m_table != nullptr) { @@ -470,9 +470,9 @@ void PIDController::InitTable(::std::shared_ptr table) { } } -::std::shared_ptr PIDController::GetTable() const { return m_table; } +std::shared_ptr PIDController::GetTable() const { return m_table; } -void PIDController::ValueChanged(::std::shared_ptr source, const std::string &key, +void PIDController::ValueChanged(std::shared_ptr source, const std::string &key, EntryValue value, bool isNew) { if (key == kP || key == kI || key == kD || key == kF) { if (m_P != m_table->GetNumber(kP) || m_I != m_table->GetNumber(kI) || diff --git a/wpilibc/wpilibC++Devices/src/PWM.cpp b/wpilibc/wpilibC++Devices/src/PWM.cpp index 1dabd1c7a8..b0c8c8cb31 100644 --- a/wpilibc/wpilibC++Devices/src/PWM.cpp +++ b/wpilibc/wpilibC++Devices/src/PWM.cpp @@ -337,7 +337,7 @@ void PWM::SetZeroLatch() { wpi_setErrorWithContext(status, getHALErrorMessage(status)); } -void PWM::ValueChanged(::std::shared_ptr source, const std::string& key, EntryValue value, +void PWM::ValueChanged(std::shared_ptr source, const std::string& key, EntryValue value, bool isNew) { SetSpeed(value.f); } @@ -364,9 +364,9 @@ void PWM::StopLiveWindowMode() { std::string PWM::GetSmartDashboardType() const { return "Speed Controller"; } -void PWM::InitTable(::std::shared_ptr subTable) { +void PWM::InitTable(std::shared_ptr subTable) { m_table = subTable; UpdateTable(); } -::std::shared_ptr PWM::GetTable() const { return m_table; } +std::shared_ptr PWM::GetTable() const { return m_table; } diff --git a/wpilibc/wpilibC++Devices/src/PowerDistributionPanel.cpp b/wpilibc/wpilibC++Devices/src/PowerDistributionPanel.cpp index cab445d60a..c2d8ed561c 100644 --- a/wpilibc/wpilibC++Devices/src/PowerDistributionPanel.cpp +++ b/wpilibc/wpilibC++Devices/src/PowerDistributionPanel.cpp @@ -182,9 +182,9 @@ std::string PowerDistributionPanel::GetSmartDashboardType() const { return "PowerDistributionPanel"; } -void PowerDistributionPanel::InitTable(::std::shared_ptr subTable) { +void PowerDistributionPanel::InitTable(std::shared_ptr subTable) { m_table = subTable; UpdateTable(); } -::std::shared_ptr PowerDistributionPanel::GetTable() const { return m_table; } +std::shared_ptr PowerDistributionPanel::GetTable() const { return m_table; } diff --git a/wpilibc/wpilibC++Devices/src/Preferences.cpp b/wpilibc/wpilibC++Devices/src/Preferences.cpp index cdf48cc557..840aa2ef88 100644 --- a/wpilibc/wpilibC++Devices/src/Preferences.cpp +++ b/wpilibc/wpilibC++Devices/src/Preferences.cpp @@ -513,7 +513,7 @@ static bool isKeyAcceptable(const std::string &value) { return true; } -void Preferences::ValueChanged(::std::shared_ptr table, const std::string &key, +void Preferences::ValueChanged(std::shared_ptr table, const std::string &key, EntryValue value, bool isNew) { if (key == kSaveField) { if (table->GetBoolean(kSaveField, false)) Save(); diff --git a/wpilibc/wpilibC++Devices/src/Relay.cpp b/wpilibc/wpilibC++Devices/src/Relay.cpp index c4fa81bd11..05dc167412 100644 --- a/wpilibc/wpilibC++Devices/src/Relay.cpp +++ b/wpilibc/wpilibC++Devices/src/Relay.cpp @@ -17,7 +17,7 @@ #include // Allocate each direction separately. -static ::std::unique_ptr relayChannels; +static std::unique_ptr relayChannels; /** * Relay constructor given a channel. @@ -189,7 +189,7 @@ Relay::Value Relay::Get() const { wpi_setErrorWithContext(status, getHALErrorMessage(status)); } -void Relay::ValueChanged(::std::shared_ptr source, const std::string &key, +void Relay::ValueChanged(std::shared_ptr source, const std::string &key, EntryValue value, bool isNew) { std::string *val = (std::string *)value.ptr; if (*val == "Off") @@ -230,9 +230,9 @@ void Relay::StopLiveWindowMode() { std::string Relay::GetSmartDashboardType() const { return "Relay"; } -void Relay::InitTable(::std::shared_ptr subTable) { +void Relay::InitTable(std::shared_ptr subTable) { m_table = subTable; UpdateTable(); } -::std::shared_ptr Relay::GetTable() const { return m_table; } +std::shared_ptr Relay::GetTable() const { return m_table; } diff --git a/wpilibc/wpilibC++Devices/src/RobotDrive.cpp b/wpilibc/wpilibC++Devices/src/RobotDrive.cpp index 8061b046fe..98cffc1045 100644 --- a/wpilibc/wpilibC++Devices/src/RobotDrive.cpp +++ b/wpilibc/wpilibC++Devices/src/RobotDrive.cpp @@ -23,7 +23,7 @@ const int32_t RobotDrive::kMaxNumberOfMotors; [[deprecated]] static auto make_shared_nodelete(SpeedController *ptr) { - return ::std::shared_ptr(ptr, NullDeleter()); + return std::shared_ptr(ptr, NullDeleter()); } /* @@ -58,8 +58,8 @@ void RobotDrive::InitRobotDrive() { */ RobotDrive::RobotDrive(uint32_t leftMotorChannel, uint32_t rightMotorChannel) { InitRobotDrive(); - m_rearLeftMotor = ::std::make_shared(leftMotorChannel); - m_rearRightMotor = ::std::make_shared(rightMotorChannel); + m_rearLeftMotor = std::make_shared(leftMotorChannel); + m_rearRightMotor = std::make_shared(rightMotorChannel); SetLeftRightMotorOutputs(0.0, 0.0); } @@ -80,10 +80,10 @@ RobotDrive::RobotDrive(uint32_t leftMotorChannel, uint32_t rightMotorChannel) { RobotDrive::RobotDrive(uint32_t frontLeftMotor, uint32_t rearLeftMotor, uint32_t frontRightMotor, uint32_t rearRightMotor) { InitRobotDrive(); - m_rearLeftMotor = ::std::make_shared(rearLeftMotor); - m_rearRightMotor = ::std::make_shared(rearRightMotor); - m_frontLeftMotor = ::std::make_shared(frontLeftMotor); - m_frontRightMotor = ::std::make_shared(frontRightMotor); + m_rearLeftMotor = std::make_shared(rearLeftMotor); + m_rearRightMotor = std::make_shared(rearRightMotor); + m_frontLeftMotor = std::make_shared(frontLeftMotor); + m_frontRightMotor = std::make_shared(frontRightMotor); SetLeftRightMotorOutputs(0.0, 0.0); } @@ -120,8 +120,8 @@ RobotDrive::RobotDrive(SpeedController &leftMotor, m_rearRightMotor = make_shared_nodelete(&rightMotor); } -RobotDrive::RobotDrive(::std::shared_ptr leftMotor, - ::std::shared_ptr rightMotor) { +RobotDrive::RobotDrive(std::shared_ptr leftMotor, + std::shared_ptr rightMotor) { InitRobotDrive(); if (leftMotor == nullptr || rightMotor == nullptr) { wpi_setWPIError(NullParameter); @@ -174,10 +174,10 @@ RobotDrive::RobotDrive(SpeedController &frontLeftMotor, m_rearRightMotor = make_shared_nodelete(&rearRightMotor); } -RobotDrive::RobotDrive(::std::shared_ptr frontLeftMotor, - ::std::shared_ptr rearLeftMotor, - ::std::shared_ptr frontRightMotor, - ::std::shared_ptr rearRightMotor) { +RobotDrive::RobotDrive(std::shared_ptr frontLeftMotor, + std::shared_ptr rearLeftMotor, + std::shared_ptr frontRightMotor, + std::shared_ptr rearRightMotor) { InitRobotDrive(); if (frontLeftMotor == nullptr || rearLeftMotor == nullptr || frontRightMotor == nullptr || rearRightMotor == nullptr) { diff --git a/wpilibc/wpilibC++Devices/src/Servo.cpp b/wpilibc/wpilibC++Devices/src/Servo.cpp index e5a3cc31ba..e2ff60e854 100644 --- a/wpilibc/wpilibC++Devices/src/Servo.cpp +++ b/wpilibc/wpilibC++Devices/src/Servo.cpp @@ -95,7 +95,7 @@ float Servo::GetAngle() const { return (float)GetPosition() * GetServoAngleRange() + kMinServoAngle; } -void Servo::ValueChanged(::std::shared_ptr source, const std::string& key, +void Servo::ValueChanged(std::shared_ptr source, const std::string& key, EntryValue value, bool isNew) { Set(value.f); } @@ -120,9 +120,9 @@ void Servo::StopLiveWindowMode() { std::string Servo::GetSmartDashboardType() const { return "Servo"; } -void Servo::InitTable(::std::shared_ptr subTable) { +void Servo::InitTable(std::shared_ptr subTable) { m_table = subTable; UpdateTable(); } -::std::shared_ptr Servo::GetTable() const { return m_table; } +std::shared_ptr Servo::GetTable() const { return m_table; } diff --git a/wpilibc/wpilibC++Devices/src/Solenoid.cpp b/wpilibc/wpilibC++Devices/src/Solenoid.cpp index f5e2304c79..b6d0669be1 100644 --- a/wpilibc/wpilibC++Devices/src/Solenoid.cpp +++ b/wpilibc/wpilibC++Devices/src/Solenoid.cpp @@ -99,7 +99,7 @@ bool Solenoid::IsBlackListed() const { return (value != 0); } -void Solenoid::ValueChanged(::std::shared_ptr source, const std::string& key, +void Solenoid::ValueChanged(std::shared_ptr source, const std::string& key, EntryValue value, bool isNew) { Set(value.b); } @@ -126,9 +126,9 @@ void Solenoid::StopLiveWindowMode() { std::string Solenoid::GetSmartDashboardType() const { return "Solenoid"; } -void Solenoid::InitTable(::std::shared_ptr subTable) { +void Solenoid::InitTable(std::shared_ptr subTable) { m_table = subTable; UpdateTable(); } -::std::shared_ptr Solenoid::GetTable() const { return m_table; } +std::shared_ptr Solenoid::GetTable() const { return m_table; } diff --git a/wpilibc/wpilibC++Devices/src/Ultrasonic.cpp b/wpilibc/wpilibC++Devices/src/Ultrasonic.cpp index 08cdd0b9a7..37d4afe0fe 100644 --- a/wpilibc/wpilibC++Devices/src/Ultrasonic.cpp +++ b/wpilibc/wpilibC++Devices/src/Ultrasonic.cpp @@ -99,8 +99,8 @@ void Ultrasonic::Initialize() { */ Ultrasonic::Ultrasonic(uint32_t pingChannel, uint32_t echoChannel, DistanceUnit units) - : m_pingChannel(::std::make_shared(pingChannel)), - m_echoChannel(::std::make_shared(echoChannel)), + : m_pingChannel(std::make_shared(pingChannel)), + m_echoChannel(std::make_shared(echoChannel)), m_counter(m_echoChannel) { m_units = units; Initialize(); @@ -164,8 +164,8 @@ Ultrasonic::Ultrasonic(DigitalOutput &pingChannel, DigitalInput &echoChannel, * determine the range. * @param units The units returned in either kInches or kMilliMeters */ -Ultrasonic::Ultrasonic(::std::shared_ptr pingChannel, - ::std::shared_ptr echoChannel, +Ultrasonic::Ultrasonic(std::shared_ptr pingChannel, + std::shared_ptr echoChannel, DistanceUnit units) : m_pingChannel(pingChannel), m_echoChannel(echoChannel), @@ -345,9 +345,9 @@ void Ultrasonic::StopLiveWindowMode() {} std::string Ultrasonic::GetSmartDashboardType() const { return "Ultrasonic"; } -void Ultrasonic::InitTable(::std::shared_ptr subTable) { +void Ultrasonic::InitTable(std::shared_ptr subTable) { m_table = subTable; UpdateTable(); } -::std::shared_ptr Ultrasonic::GetTable() const { return m_table; } +std::shared_ptr Ultrasonic::GetTable() const { return m_table; } diff --git a/wpilibc/wpilibC++IntegrationTests/src/AnalogLoopTest.cpp b/wpilibc/wpilibC++IntegrationTests/src/AnalogLoopTest.cpp index 190caeea70..4302b3829c 100644 --- a/wpilibc/wpilibC++IntegrationTests/src/AnalogLoopTest.cpp +++ b/wpilibc/wpilibC++IntegrationTests/src/AnalogLoopTest.cpp @@ -108,7 +108,7 @@ TEST_F(AnalogLoopTest, AsynchronusInterruptWorks) { trigger.SetLimitsVoltage(2.0f, 3.0f); // Given an interrupt handler that sets an int to 12345 - ::std::shared_ptr triggerOutput = trigger.CreateOutput(kState); + std::shared_ptr triggerOutput = trigger.CreateOutput(kState); triggerOutput->RequestInterrupts(InterruptHandler, ¶m); triggerOutput->EnableInterrupts(); diff --git a/wpilibc/wpilibC++IntegrationTests/src/FakeEncoderTest.cpp b/wpilibc/wpilibC++IntegrationTests/src/FakeEncoderTest.cpp index 2f408b6da5..fab83643c1 100644 --- a/wpilibc/wpilibC++IntegrationTests/src/FakeEncoderTest.cpp +++ b/wpilibc/wpilibC++IntegrationTests/src/FakeEncoderTest.cpp @@ -20,7 +20,7 @@ class FakeEncoderTest : public testing::Test { Encoder *m_encoder; AnalogTrigger *m_indexAnalogTrigger; - ::std::shared_ptr m_indexAnalogTriggerOutput; + std::shared_ptr m_indexAnalogTriggerOutput; virtual void SetUp() override { m_outputA = new DigitalOutput(TestBench::kLoop2OutputChannel); diff --git a/wpilibc/wpilibC++Sim/include/AnalogInput.h b/wpilibc/wpilibC++Sim/include/AnalogInput.h index 0ca327c4d0..dd85922b01 100644 --- a/wpilibc/wpilibC++Sim/include/AnalogInput.h +++ b/wpilibc/wpilibC++Sim/include/AnalogInput.h @@ -43,13 +43,13 @@ public: void StartLiveWindowMode() override; void StopLiveWindowMode() override; std::string GetSmartDashboardType() const override; - void InitTable(::std::shared_ptr subTable) override; - ::std::shared_ptr GetTable() const override; + void InitTable(std::shared_ptr subTable) override; + std::shared_ptr GetTable() const override; private: uint32_t m_channel; SimFloatInput* m_impl; int64_t m_accumulatorOffset; - ::std::shared_ptr m_table = nullptr; + std::shared_ptr m_table = nullptr; }; diff --git a/wpilibc/wpilibC++Sim/include/AnalogPotentiometer.h b/wpilibc/wpilibC++Sim/include/AnalogPotentiometer.h index 716f9aed92..90a62f7d8a 100644 --- a/wpilibc/wpilibC++Sim/include/AnalogPotentiometer.h +++ b/wpilibc/wpilibC++Sim/include/AnalogPotentiometer.h @@ -58,9 +58,9 @@ public: * Live Window code, only does anything if live window is activated. */ virtual std::string GetSmartDashboardType() const override; - virtual void InitTable(::std::shared_ptr subtable) override; + virtual void InitTable(std::shared_ptr subtable) override; virtual void UpdateTable() override; - virtual ::std::shared_ptr GetTable() const override; + virtual std::shared_ptr GetTable() const override; /** * AnalogPotentiometers don't have to do anything special when entering the LiveWindow. @@ -75,7 +75,7 @@ public: private: double m_scale, m_offset; AnalogInput* m_analog_input; - ::std::shared_ptr m_table; + std::shared_ptr m_table; bool m_init_analog_input; /** diff --git a/wpilibc/wpilibC++Sim/include/Counter.h b/wpilibc/wpilibC++Sim/include/Counter.h index f34d3845ec..338efc0fe6 100644 --- a/wpilibc/wpilibC++Sim/include/Counter.h +++ b/wpilibc/wpilibC++Sim/include/Counter.h @@ -77,8 +77,8 @@ public: void StartLiveWindowMode() override; void StopLiveWindowMode() override; virtual std::string GetSmartDashboardType() const override; - void InitTable(::std::shared_ptr subTable) override; - ::std::shared_ptr GetTable() const override; + void InitTable(std::shared_ptr subTable) override; + std::shared_ptr GetTable() const override; protected: // TODO: [Not Supported] DigitalSource *m_upSource; ///< What makes the counter count up. // TODO: [Not Supported] DigitalSource *m_downSource; ///< What makes the counter count down. @@ -89,5 +89,5 @@ private: bool m_allocatedDownSource; ///< Was the downSource allocated locally? uint32_t m_index; ///< The index of this counter. - ::std::shared_ptr m_table; + std::shared_ptr m_table; }; diff --git a/wpilibc/wpilibC++Sim/include/DigitalInput.h b/wpilibc/wpilibC++Sim/include/DigitalInput.h index 40ead6ebec..632da8b0b7 100644 --- a/wpilibc/wpilibC++Sim/include/DigitalInput.h +++ b/wpilibc/wpilibC++Sim/include/DigitalInput.h @@ -28,13 +28,13 @@ public: void StartLiveWindowMode() override; void StopLiveWindowMode() override; std::string GetSmartDashboardType() const override; - void InitTable(::std::shared_ptr subTable) override; - ::std::shared_ptr GetTable() const override; + void InitTable(std::shared_ptr subTable) override; + std::shared_ptr GetTable() const override; private: uint32_t m_channel; bool m_lastValue; SimDigitalInput *m_impl; - ::std::shared_ptr m_table = nullptr; + std::shared_ptr m_table = nullptr; }; diff --git a/wpilibc/wpilibC++Sim/include/DoubleSolenoid.h b/wpilibc/wpilibC++Sim/include/DoubleSolenoid.h index b363b68167..87858a845a 100644 --- a/wpilibc/wpilibC++Sim/include/DoubleSolenoid.h +++ b/wpilibc/wpilibC++Sim/include/DoubleSolenoid.h @@ -34,18 +34,18 @@ public: virtual void Set(Value value); virtual Value Get() const; - void ValueChanged(::std::shared_ptr source, const std::string& key, EntryValue value, bool isNew) override; + void ValueChanged(std::shared_ptr source, const std::string& key, EntryValue value, bool isNew) override; void UpdateTable() override; void StartLiveWindowMode() override; void StopLiveWindowMode() override; std::string GetSmartDashboardType() const override; - void InitTable(::std::shared_ptr subTable) override; - ::std::shared_ptr GetTable() const override; + void InitTable(std::shared_ptr subTable) override; + std::shared_ptr GetTable() const override; private: SimContinuousOutput* m_impl; Value m_value; bool m_reversed; - ::std::shared_ptr m_table; + std::shared_ptr m_table; }; diff --git a/wpilibc/wpilibC++Sim/include/DriverStation.h b/wpilibc/wpilibC++Sim/include/DriverStation.h index 3edc389f53..4055ed7fda 100644 --- a/wpilibc/wpilibC++Sim/include/DriverStation.h +++ b/wpilibc/wpilibC++Sim/include/DriverStation.h @@ -118,10 +118,10 @@ private: void joystickCallback5(const msgs::ConstJoystickPtr &msg); uint8_t m_digitalOut = 0; - ::std::condition_variable m_waitForDataCond; - ::std::mutex m_waitForDataMutex; - mutable ::std::recursive_mutex m_stateMutex; - ::std::recursive_mutex m_joystickMutex; + std::condition_variable m_waitForDataCond; + std::mutex m_waitForDataMutex; + mutable std::recursive_mutex m_stateMutex; + std::recursive_mutex m_joystickMutex; double m_approxMatchTimeOffset = 0; bool m_userInDisabled = false; bool m_userInAutonomous = false; diff --git a/wpilibc/wpilibC++Sim/include/Encoder.h b/wpilibc/wpilibC++Sim/include/Encoder.h index c3cd457a9f..d024a4a18f 100644 --- a/wpilibc/wpilibC++Sim/include/Encoder.h +++ b/wpilibc/wpilibC++Sim/include/Encoder.h @@ -60,8 +60,8 @@ public: void StartLiveWindowMode() override; void StopLiveWindowMode() override; std::string GetSmartDashboardType() const override; - void InitTable(::std::shared_ptr subTable) override; - ::std::shared_ptr GetTable() const override; + void InitTable(std::shared_ptr subTable) override; + std::shared_ptr GetTable() const override; int32_t FPGAEncoderIndex() const { @@ -84,5 +84,5 @@ private: bool m_reverseDirection; SimEncoder* impl; - ::std::shared_ptr m_table; + std::shared_ptr m_table; }; diff --git a/wpilibc/wpilibC++Sim/include/Gyro.h b/wpilibc/wpilibC++Sim/include/Gyro.h index ee2e560907..1204a809c1 100644 --- a/wpilibc/wpilibC++Sim/include/Gyro.h +++ b/wpilibc/wpilibC++Sim/include/Gyro.h @@ -48,8 +48,8 @@ public: void StartLiveWindowMode() override; void StopLiveWindowMode() override; std::string GetSmartDashboardType() const override; - void InitTable(::std::shared_ptr subTable) override; - ::std::shared_ptr GetTable() const override; + void InitTable(std::shared_ptr subTable) override; + std::shared_ptr GetTable() const override; private: void InitGyro(int channel); @@ -57,5 +57,5 @@ private: SimGyro* impl; PIDSourceParameter m_pidSource; - ::std::shared_ptr m_table = nullptr; + std::shared_ptr m_table = nullptr; }; diff --git a/wpilibc/wpilibC++Sim/include/PWM.h b/wpilibc/wpilibC++Sim/include/PWM.h index ab5f2d0cd4..4a35bc9650 100644 --- a/wpilibc/wpilibC++Sim/include/PWM.h +++ b/wpilibc/wpilibC++Sim/include/PWM.h @@ -87,15 +87,15 @@ protected: bool m_eliminateDeadband; int32_t m_centerPwm; - void ValueChanged(::std::shared_ptr source, const std::string& key, EntryValue value, bool isNew) override; + void ValueChanged(std::shared_ptr source, const std::string& key, EntryValue value, bool isNew) override; void UpdateTable() override; void StartLiveWindowMode() override; void StopLiveWindowMode() override; std::string GetSmartDashboardType() const override; - void InitTable(::std::shared_ptr subTable) override; - ::std::shared_ptr GetTable() const override; + void InitTable(std::shared_ptr subTable) override; + std::shared_ptr GetTable() const override; - ::std::shared_ptr m_table = nullptr; + std::shared_ptr m_table = nullptr; private: uint32_t m_channel; diff --git a/wpilibc/wpilibC++Sim/include/Relay.h b/wpilibc/wpilibC++Sim/include/Relay.h index b7808441d6..c8076ab1be 100644 --- a/wpilibc/wpilibC++Sim/include/Relay.h +++ b/wpilibc/wpilibC++Sim/include/Relay.h @@ -47,15 +47,15 @@ public: void Set(Value value); Value Get() const; - void ValueChanged(::std::shared_ptr source, const std::string& key, EntryValue value, bool isNew) override; + void ValueChanged(std::shared_ptr source, const std::string& key, EntryValue value, bool isNew) override; void UpdateTable() override; void StartLiveWindowMode() override; void StopLiveWindowMode() override; std::string GetSmartDashboardType() const override; - void InitTable(::std::shared_ptr subTable) override; - ::std::shared_ptr GetTable() const override; + void InitTable(std::shared_ptr subTable) override; + std::shared_ptr GetTable() const override; - ::std::shared_ptr m_table = nullptr; + std::shared_ptr m_table = nullptr; private: uint32_t m_channel; diff --git a/wpilibc/wpilibC++Sim/include/Solenoid.h b/wpilibc/wpilibC++Sim/include/Solenoid.h index eab08d91db..eac30deb6f 100644 --- a/wpilibc/wpilibC++Sim/include/Solenoid.h +++ b/wpilibc/wpilibC++Sim/include/Solenoid.h @@ -26,17 +26,17 @@ public: virtual void Set(bool on); virtual bool Get() const; - void ValueChanged(::std::shared_ptr source, const std::string& key, EntryValue value, bool isNew) override; + void ValueChanged(std::shared_ptr source, const std::string& key, EntryValue value, bool isNew) override; void UpdateTable() override; void StartLiveWindowMode() override; void StopLiveWindowMode() override; std::string GetSmartDashboardType() const override; - void InitTable(::std::shared_ptr subTable) override; - ::std::shared_ptr GetTable() const override; + void InitTable(std::shared_ptr subTable) override; + std::shared_ptr GetTable() const override; private: SimContinuousOutput* m_impl; bool m_on; - ::std::shared_ptr m_table; + std::shared_ptr m_table; }; diff --git a/wpilibc/wpilibC++Sim/include/simulation/msgs/driver-station.pb.h b/wpilibc/wpilibC++Sim/include/simulation/msgs/driver-station.pb.h index ce3709810a..e268ceba82 100644 --- a/wpilibc/wpilibC++Sim/include/simulation/msgs/driver-station.pb.h +++ b/wpilibc/wpilibC++Sim/include/simulation/msgs/driver-station.pb.h @@ -48,12 +48,12 @@ const DriverStation_State DriverStation_State_State_MAX = DriverStation_State_TE const int DriverStation_State_State_ARRAYSIZE = DriverStation_State_State_MAX + 1; const ::google::protobuf::EnumDescriptor* DriverStation_State_descriptor(); -inline const ::std::string& DriverStation_State_Name(DriverStation_State value) { +inline const std::string& DriverStation_State_Name(DriverStation_State value) { return ::google::protobuf::internal::NameOfEnum( DriverStation_State_descriptor(), value); } inline bool DriverStation_State_Parse( - const ::std::string& name, DriverStation_State* value) { + const std::string& name, DriverStation_State* value) { return ::google::protobuf::internal::ParseNamedEnum( DriverStation_State_descriptor(), name, value); } @@ -128,10 +128,10 @@ class DriverStation : public ::google::protobuf::Message { State_descriptor() { return DriverStation_State_descriptor(); } - static inline const ::std::string& State_Name(State value) { + static inline const std::string& State_Name(State value) { return DriverStation_State_Name(value); } - static inline bool State_Parse(const ::std::string& name, + static inline bool State_Parse(const std::string& name, State* value) { return DriverStation_State_Parse(name, value); } diff --git a/wpilibc/wpilibC++Sim/include/simulation/simTime.h b/wpilibc/wpilibC++Sim/include/simulation/simTime.h index b0dee13d54..b92d3011b6 100644 --- a/wpilibc/wpilibC++Sim/include/simulation/simTime.h +++ b/wpilibc/wpilibC++Sim/include/simulation/simTime.h @@ -5,7 +5,7 @@ namespace wpilib { namespace internal { extern double simTime; - extern ::std::condition_variable time_wait; - extern ::std::mutex time_wait_mutex; + extern std::condition_variable time_wait; + extern std::mutex time_wait_mutex; // transport::SubscriberPtr time_sub; }} diff --git a/wpilibc/wpilibC++Sim/src/AnalogInput.cpp b/wpilibc/wpilibC++Sim/src/AnalogInput.cpp index 6fe54f2574..561a6f4c03 100644 --- a/wpilibc/wpilibC++Sim/src/AnalogInput.cpp +++ b/wpilibc/wpilibC++Sim/src/AnalogInput.cpp @@ -82,11 +82,11 @@ std::string AnalogInput::GetSmartDashboardType() const { return "Analog Input"; } -void AnalogInput::InitTable(::std::shared_ptr subTable) { +void AnalogInput::InitTable(std::shared_ptr subTable) { m_table = subTable; UpdateTable(); } -::std::shared_ptr AnalogInput::GetTable() const { +std::shared_ptr AnalogInput::GetTable() const { return m_table; } diff --git a/wpilibc/wpilibC++Sim/src/AnalogPotentiometer.cpp b/wpilibc/wpilibC++Sim/src/AnalogPotentiometer.cpp index 663fd0df08..e7f6b49d36 100644 --- a/wpilibc/wpilibC++Sim/src/AnalogPotentiometer.cpp +++ b/wpilibc/wpilibC++Sim/src/AnalogPotentiometer.cpp @@ -61,7 +61,7 @@ std::string AnalogPotentiometer::GetSmartDashboardType() const { /** * Live Window code, only does anything if live window is activated. */ -void AnalogPotentiometer::InitTable(::std::shared_ptr subtable) { +void AnalogPotentiometer::InitTable(std::shared_ptr subtable) { m_table = subtable; UpdateTable(); } @@ -72,6 +72,6 @@ void AnalogPotentiometer::UpdateTable() { } } -::std::shared_ptr AnalogPotentiometer::GetTable() const { +std::shared_ptr AnalogPotentiometer::GetTable() const { return m_table; } diff --git a/wpilibc/wpilibC++Sim/src/DigitalInput.cpp b/wpilibc/wpilibC++Sim/src/DigitalInput.cpp index 4c80928e91..e7ae36dcc6 100644 --- a/wpilibc/wpilibC++Sim/src/DigitalInput.cpp +++ b/wpilibc/wpilibC++Sim/src/DigitalInput.cpp @@ -56,11 +56,11 @@ std::string DigitalInput::GetSmartDashboardType() const { return "DigitalInput"; } -void DigitalInput::InitTable(::std::shared_ptr subTable) { +void DigitalInput::InitTable(std::shared_ptr subTable) { m_table = subTable; UpdateTable(); } -::std::shared_ptr DigitalInput::GetTable() const { +std::shared_ptr DigitalInput::GetTable() const { return m_table; } diff --git a/wpilibc/wpilibC++Sim/src/DoubleSolenoid.cpp b/wpilibc/wpilibC++Sim/src/DoubleSolenoid.cpp index 77ec517cd0..c4cb6c6e96 100644 --- a/wpilibc/wpilibC++Sim/src/DoubleSolenoid.cpp +++ b/wpilibc/wpilibC++Sim/src/DoubleSolenoid.cpp @@ -75,7 +75,7 @@ DoubleSolenoid::Value DoubleSolenoid::Get() const return m_value; } -void DoubleSolenoid::ValueChanged(::std::shared_ptr source, const std::string& key, EntryValue value, bool isNew) { +void DoubleSolenoid::ValueChanged(std::shared_ptr source, const std::string& key, EntryValue value, bool isNew) { Value lvalue = kOff; std::string *val = (std::string *)value.ptr; if (*val == "Forward") @@ -109,11 +109,11 @@ std::string DoubleSolenoid::GetSmartDashboardType() const { return "Double Solenoid"; } -void DoubleSolenoid::InitTable(::std::shared_ptr subTable) { +void DoubleSolenoid::InitTable(std::shared_ptr subTable) { m_table = subTable; UpdateTable(); } -::std::shared_ptr DoubleSolenoid::GetTable() const { +std::shared_ptr DoubleSolenoid::GetTable() const { return m_table; } diff --git a/wpilibc/wpilibC++Sim/src/DriverStation.cpp b/wpilibc/wpilibC++Sim/src/DriverStation.cpp index d17f7fbce3..63bb99c72f 100644 --- a/wpilibc/wpilibC++Sim/src/DriverStation.cpp +++ b/wpilibc/wpilibC++Sim/src/DriverStation.cpp @@ -99,7 +99,7 @@ float DriverStation::GetStickAxis(uint32_t stick, uint32_t axis) return 0.0; } - ::std::unique_lock<::std::recursive_mutex> lock(m_joystickMutex); + std::unique_lock lock(m_joystickMutex); if (joysticks[stick] == nullptr || axis >= joysticks[stick]->axes().size()) { return 0.0; @@ -123,7 +123,7 @@ bool DriverStation::GetStickButton(uint32_t stick, uint32_t button) return false; } - ::std::unique_lock<::std::recursive_mutex> lock(m_joystickMutex); + std::unique_lock lock(m_joystickMutex); if (joysticks[stick] == nullptr || button >= joysticks[stick]->buttons().size()) { return false; @@ -147,7 +147,7 @@ short DriverStation::GetStickButtons(uint32_t stick) } short btns = 0, btnid; - ::std::unique_lock<::std::recursive_mutex> lock(m_joystickMutex); + std::unique_lock lock(m_joystickMutex); msgs::JoystickPtr joy = joysticks[stick]; for (btnid = 0; btnid < joy->buttons().size() && btnid < 12; btnid++) { @@ -215,7 +215,7 @@ bool DriverStation::GetDigitalOut(uint32_t channel) bool DriverStation::IsEnabled() const { - ::std::unique_lock<::std::recursive_mutex> lock(m_stateMutex); + std::unique_lock lock(m_stateMutex); return state != nullptr ? state->enabled() : false; } @@ -226,7 +226,7 @@ bool DriverStation::IsDisabled() const bool DriverStation::IsAutonomous() const { - ::std::unique_lock<::std::recursive_mutex> lock(m_stateMutex); + std::unique_lock lock(m_stateMutex); return state != nullptr ? state->state() == msgs::DriverStation_State_AUTO : false; } @@ -238,7 +238,7 @@ bool DriverStation::IsOperatorControl() const bool DriverStation::IsTest() const { - ::std::unique_lock<::std::recursive_mutex> lock(m_stateMutex); + std::unique_lock lock(m_stateMutex); return state != nullptr ? state->state() == msgs::DriverStation_State_TEST : false; } @@ -283,7 +283,7 @@ uint32_t DriverStation::GetLocation() const */ void DriverStation::WaitForData() { - ::std::unique_lock<::std::mutex> lock(m_waitForDataMutex); + std::unique_lock lock(m_waitForDataMutex); m_waitForDataCond.wait(lock); } @@ -308,9 +308,9 @@ double DriverStation::GetMatchTime() const * Report an error to the DriverStation messages window. * The error is also printed to the program console. */ -void DriverStation::ReportError(::std::string error) +void DriverStation::ReportError(std::string error) { - ::std::cout << error << ::std::endl; + std::cout << error << std::endl; } /** @@ -325,7 +325,7 @@ uint16_t DriverStation::GetTeamNumber() const void DriverStation::stateCallback(const msgs::ConstDriverStationPtr &msg) { { - ::std::unique_lock<::std::recursive_mutex> lock(m_stateMutex); + std::unique_lock lock(m_stateMutex); *state = *msg; } m_waitForDataCond.notify_all(); @@ -334,7 +334,7 @@ void DriverStation::stateCallback(const msgs::ConstDriverStationPtr &msg) void DriverStation::joystickCallback(const msgs::ConstJoystickPtr &msg, int i) { - ::std::unique_lock<::std::recursive_mutex> lock(m_joystickMutex); + std::unique_lock lock(m_joystickMutex); *(joysticks[i]) = *msg; } diff --git a/wpilibc/wpilibC++Sim/src/Encoder.cpp b/wpilibc/wpilibC++Sim/src/Encoder.cpp index bb5042ae14..f4c1436e08 100644 --- a/wpilibc/wpilibC++Sim/src/Encoder.cpp +++ b/wpilibc/wpilibC++Sim/src/Encoder.cpp @@ -355,11 +355,11 @@ std::string Encoder::GetSmartDashboardType() const { return "Encoder"; } -void Encoder::InitTable(::std::shared_ptr subTable) { +void Encoder::InitTable(std::shared_ptr subTable) { m_table = subTable; UpdateTable(); } -::std::shared_ptr Encoder::GetTable() const { +std::shared_ptr Encoder::GetTable() const { return m_table; } diff --git a/wpilibc/wpilibC++Sim/src/Gyro.cpp b/wpilibc/wpilibC++Sim/src/Gyro.cpp index 6987b5da1d..cf0e6f3adb 100644 --- a/wpilibc/wpilibC++Sim/src/Gyro.cpp +++ b/wpilibc/wpilibC++Sim/src/Gyro.cpp @@ -125,11 +125,11 @@ std::string Gyro::GetSmartDashboardType() const { return "Gyro"; } -void Gyro::InitTable(::std::shared_ptr subTable) { +void Gyro::InitTable(std::shared_ptr subTable) { m_table = subTable; UpdateTable(); } -::std::shared_ptr Gyro::GetTable() const { +std::shared_ptr Gyro::GetTable() const { return m_table; } diff --git a/wpilibc/wpilibC++Sim/src/Notifier.cpp b/wpilibc/wpilibC++Sim/src/Notifier.cpp index 94df0b10ab..e92e77c905 100644 --- a/wpilibc/wpilibC++Sim/src/Notifier.cpp +++ b/wpilibc/wpilibC++Sim/src/Notifier.cpp @@ -12,7 +12,7 @@ Notifier *Notifier::timerQueueHead = nullptr; priority_recursive_mutex Notifier::queueMutex; int Notifier::refcount = 0; -::std::atomic Notifier::m_stopped(false); +std::atomic Notifier::m_stopped(false); /** * Create a Notifier for timer event notification. @@ -35,7 +35,7 @@ Notifier::Notifier(TimerEventHandler handler, void *param) // do the first time intialization of static variables if (refcount == 0) { - m_task = ::std::thread(Run); + m_task = std::thread(Run); } refcount++; } diff --git a/wpilibc/wpilibC++Sim/src/PIDController.cpp b/wpilibc/wpilibC++Sim/src/PIDController.cpp index 7f636b900e..1a6f025f4c 100644 --- a/wpilibc/wpilibC++Sim/src/PIDController.cpp +++ b/wpilibc/wpilibC++Sim/src/PIDController.cpp @@ -84,7 +84,7 @@ void PIDController::Initialize(float Kp, float Ki, float Kd, float Kf, m_pidOutput = output; m_period = period; - m_controlLoop = ::std::make_unique(PIDController::CallCalculate, this); + m_controlLoop = std::make_unique(PIDController::CallCalculate, this); m_controlLoop->StartPeriodic(m_period); static int32_t instances = 0; @@ -491,7 +491,7 @@ std::string PIDController::GetSmartDashboardType() const { return "PIDController"; } -void PIDController::InitTable(::std::shared_ptr table){ +void PIDController::InitTable(std::shared_ptr table){ if(m_table!=nullptr) m_table->RemoveTableListener(this); m_table = table; @@ -506,11 +506,11 @@ void PIDController::InitTable(::std::shared_ptr table){ } } -::std::shared_ptr PIDController::GetTable() const { +std::shared_ptr PIDController::GetTable() const { return m_table; } -void PIDController::ValueChanged(::std::shared_ptr source, const std::string& key, EntryValue value, bool isNew){ +void PIDController::ValueChanged(std::shared_ptr source, const std::string& key, EntryValue value, bool isNew){ if (key==kP || key==kI || key==kD || key==kF) { if (m_P != m_table->GetNumber(kP) || m_I != m_table->GetNumber(kI) || m_D != m_table->GetNumber(kD) || m_F != m_table->GetNumber(kF) ) { SetPID(m_table->GetNumber(kP, 0.0), m_table->GetNumber(kI, 0.0), m_table->GetNumber(kD, 0.0), m_table->GetNumber(kF, 0.0)); diff --git a/wpilibc/wpilibC++Sim/src/PWM.cpp b/wpilibc/wpilibC++Sim/src/PWM.cpp index fa8b613a6d..3632fd480f 100644 --- a/wpilibc/wpilibC++Sim/src/PWM.cpp +++ b/wpilibc/wpilibC++Sim/src/PWM.cpp @@ -217,7 +217,7 @@ void PWM::SetPeriodMultiplier(PeriodMultiplier mult) } -void PWM::ValueChanged(::std::shared_ptr source, const std::string& key, EntryValue value, bool isNew) { +void PWM::ValueChanged(std::shared_ptr source, const std::string& key, EntryValue value, bool isNew) { SetSpeed(value.f); } @@ -245,11 +245,11 @@ std::string PWM::GetSmartDashboardType() const { return "Speed Controller"; } -void PWM::InitTable(::std::shared_ptr subTable) { +void PWM::InitTable(std::shared_ptr subTable) { m_table = subTable; UpdateTable(); } -::std::shared_ptr PWM::GetTable() const { +std::shared_ptr PWM::GetTable() const { return m_table; } diff --git a/wpilibc/wpilibC++Sim/src/Relay.cpp b/wpilibc/wpilibC++Sim/src/Relay.cpp index 2571c53b37..17df05f375 100644 --- a/wpilibc/wpilibC++Sim/src/Relay.cpp +++ b/wpilibc/wpilibC++Sim/src/Relay.cpp @@ -140,7 +140,7 @@ Relay::Value Relay::Get() const { } } -void Relay::ValueChanged(::std::shared_ptr source, const std::string& key, EntryValue value, bool isNew) { +void Relay::ValueChanged(std::shared_ptr source, const std::string& key, EntryValue value, bool isNew) { std::string *val = (std::string *) value.ptr; if (*val == "Off") Set(kOff); else if (*val == "Forward") Set(kForward); @@ -180,11 +180,11 @@ std::string Relay::GetSmartDashboardType() const { return "Relay"; } -void Relay::InitTable(::std::shared_ptr subTable) { +void Relay::InitTable(std::shared_ptr subTable) { m_table = subTable; UpdateTable(); } -::std::shared_ptr Relay::GetTable() const { +std::shared_ptr Relay::GetTable() const { return m_table; } diff --git a/wpilibc/wpilibC++Sim/src/Solenoid.cpp b/wpilibc/wpilibC++Sim/src/Solenoid.cpp index dab5bca05c..26a38a9764 100644 --- a/wpilibc/wpilibC++Sim/src/Solenoid.cpp +++ b/wpilibc/wpilibC++Sim/src/Solenoid.cpp @@ -54,7 +54,7 @@ bool Solenoid::Get() const } -void Solenoid::ValueChanged(::std::shared_ptr source, const std::string& key, EntryValue value, bool isNew) { +void Solenoid::ValueChanged(std::shared_ptr source, const std::string& key, EntryValue value, bool isNew) { Set(value.b); } @@ -82,11 +82,11 @@ std::string Solenoid::GetSmartDashboardType() const { return "Solenoid"; } -void Solenoid::InitTable(::std::shared_ptr subTable) { +void Solenoid::InitTable(std::shared_ptr subTable) { m_table = subTable; UpdateTable(); } -::std::shared_ptr Solenoid::GetTable() const { +std::shared_ptr Solenoid::GetTable() const { return m_table; } diff --git a/wpilibc/wpilibC++Sim/src/Timer.cpp b/wpilibc/wpilibC++Sim/src/Timer.cpp index 536cc2f6bb..954f3f295e 100644 --- a/wpilibc/wpilibC++Sim/src/Timer.cpp +++ b/wpilibc/wpilibC++Sim/src/Timer.cpp @@ -27,7 +27,7 @@ void Wait(double seconds) double start = wpilib::internal::simTime; while ((wpilib::internal::simTime - start) < seconds) { - ::std::unique_lock<::std::mutex> lock(wpilib::internal::time_wait_mutex); + std::unique_lock lock(wpilib::internal::time_wait_mutex); wpilib::internal::time_wait.wait(lock); } } diff --git a/wpilibc/wpilibC++Sim/src/Utility.cpp b/wpilibc/wpilibC++Sim/src/Utility.cpp index d71aea5680..dfd332ca83 100644 --- a/wpilibc/wpilibC++Sim/src/Utility.cpp +++ b/wpilibc/wpilibC++Sim/src/Utility.cpp @@ -75,7 +75,7 @@ bool wpi_assert_impl(bool conditionValue, const std::string &conditionText, } // Print to console and send to remote dashboard - ::std::cout << "\n\n>>>>" << error; + std::cout << "\n\n>>>>" << error; wpi_handleTracing(); } diff --git a/wpilibc/wpilibC++Sim/src/simulation/msgs/bool.pb.cpp b/wpilibc/wpilibC++Sim/src/simulation/msgs/bool.pb.cpp index c22631fed2..e61ae1a02d 100644 --- a/wpilibc/wpilibC++Sim/src/simulation/msgs/bool.pb.cpp +++ b/wpilibc/wpilibC++Sim/src/simulation/msgs/bool.pb.cpp @@ -59,7 +59,7 @@ inline void protobuf_AssignDescriptorsOnce() { &protobuf_AssignDesc_msgs_2fbool_2eproto); } -void protobuf_RegisterTypes(const ::std::string&) { +void protobuf_RegisterTypes(const std::string&) { protobuf_AssignDescriptorsOnce(); ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage( Bool_descriptor_, &Bool::default_instance()); diff --git a/wpilibc/wpilibC++Sim/src/simulation/msgs/driver-station.pb.cpp b/wpilibc/wpilibC++Sim/src/simulation/msgs/driver-station.pb.cpp index 4f5289139f..3b9f1389d5 100644 --- a/wpilibc/wpilibC++Sim/src/simulation/msgs/driver-station.pb.cpp +++ b/wpilibc/wpilibC++Sim/src/simulation/msgs/driver-station.pb.cpp @@ -62,7 +62,7 @@ inline void protobuf_AssignDescriptorsOnce() { &protobuf_AssignDesc_msgs_2fdriver_2dstation_2eproto); } -void protobuf_RegisterTypes(const ::std::string&) { +void protobuf_RegisterTypes(const std::string&) { protobuf_AssignDescriptorsOnce(); ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage( DriverStation_descriptor_, &DriverStation::default_instance()); diff --git a/wpilibc/wpilibC++Sim/src/simulation/msgs/float64.pb.cpp b/wpilibc/wpilibC++Sim/src/simulation/msgs/float64.pb.cpp index 37701e1dbb..2f2c94d104 100644 --- a/wpilibc/wpilibC++Sim/src/simulation/msgs/float64.pb.cpp +++ b/wpilibc/wpilibC++Sim/src/simulation/msgs/float64.pb.cpp @@ -59,7 +59,7 @@ inline void protobuf_AssignDescriptorsOnce() { &protobuf_AssignDesc_msgs_2ffloat64_2eproto); } -void protobuf_RegisterTypes(const ::std::string&) { +void protobuf_RegisterTypes(const std::string&) { protobuf_AssignDescriptorsOnce(); ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage( Float64_descriptor_, &Float64::default_instance()); diff --git a/wpilibc/wpilibC++Sim/src/simulation/msgs/joystick.pb.cpp b/wpilibc/wpilibC++Sim/src/simulation/msgs/joystick.pb.cpp index 8677b26a14..306e2471bb 100644 --- a/wpilibc/wpilibC++Sim/src/simulation/msgs/joystick.pb.cpp +++ b/wpilibc/wpilibC++Sim/src/simulation/msgs/joystick.pb.cpp @@ -60,7 +60,7 @@ inline void protobuf_AssignDescriptorsOnce() { &protobuf_AssignDesc_msgs_2fjoystick_2eproto); } -void protobuf_RegisterTypes(const ::std::string&) { +void protobuf_RegisterTypes(const std::string&) { protobuf_AssignDescriptorsOnce(); ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage( Joystick_descriptor_, &Joystick::default_instance());