diff --git a/CMakeLists.txt b/CMakeLists.txt index 926eff84b2..b18a7fb550 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,7 +1,11 @@ cmake_minimum_required(VERSION 2.8) project(All-WPILib) set(CMAKE_BUILD_TYPE Debug) -set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wno-unused-parameter -fPIC") +# TODO: When the compiler allows us to actually call deprecated functions from +# within deprecated functions, remove -Wno-error=deprecated-declarations +# (this will cause calling deprecated functions to be treated as a warning +# rather than an error). +set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wno-unused-parameter -Wno-error=deprecated-declarations -fPIC") file(GLOB_RECURSE NI_LIBS ni-libraries/*.so*) list(REMOVE_ITEM NI_LIBS ${CMAKE_CURRENT_SOURCE_DIR}/ni-libraries/libwpi.so ${CMAKE_CURRENT_SOURCE_DIR}/ni-libraries/libwpi_2015.so) diff --git a/build.gradle b/build.gradle index 819ce447e4..10e2c09150 100644 --- a/build.gradle +++ b/build.gradle @@ -106,6 +106,10 @@ subprojects { cppCompiler.withArguments { args -> args << '-std=c++1y' << '-Wformat=2' << '-Wall' << '-Wextra' << '-Werror' << '-pedantic' args << '-Wno-psabi' << '-Wno-unused-parameter' << '-fPIC' << '-O0' << '-g3' << '-rdynamic' + //TODO: When the compiler allows us to actually call deprecated functions from within + // deprecated function, remove this line (this will cause calling deprecated functions + // to be treated as a warning rather than an error). + args << '-Wno-error=deprecated-declarations' args.remove('-m32') } linker.withArguments { args -> diff --git a/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/command-based/Robot.cpp b/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/command-based/Robot.cpp index 04cfc17f3a..471a9f3c32 100644 --- a/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/command-based/Robot.cpp +++ b/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/command-based/Robot.cpp @@ -27,7 +27,7 @@ private: void DisabledPeriodic() { - Scheduler::GetInstance()->Run(); + Scheduler::GetInstance().Run(); } void AutonomousInit() @@ -38,7 +38,7 @@ private: void AutonomousPeriodic() { - Scheduler::GetInstance()->Run(); + Scheduler::GetInstance().Run(); } void TeleopInit() @@ -53,7 +53,7 @@ private: void TeleopPeriodic() { - Scheduler::GetInstance()->Run(); + Scheduler::GetInstance().Run(); } void TestPeriodic() diff --git a/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/GearsBot/src/Robot.cpp b/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/GearsBot/src/Robot.cpp index 801eb89985..b225c29782 100644 --- a/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/GearsBot/src/Robot.cpp +++ b/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/GearsBot/src/Robot.cpp @@ -33,7 +33,7 @@ void Robot::AutonomousInit() { } void Robot::AutonomousPeriodic() { - Scheduler::GetInstance()->Run(); + Scheduler::GetInstance().Run(); } void Robot::TeleopInit() { @@ -46,7 +46,7 @@ void Robot::TeleopInit() { } void Robot::TeleopPeriodic() { - Scheduler::GetInstance()->Run(); + Scheduler::GetInstance().Run(); } void Robot::TestPeriodic() { diff --git a/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/PacGoat/src/Robot.cpp b/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/PacGoat/src/Robot.cpp index 1b0e36132f..137480071d 100644 --- a/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/PacGoat/src/Robot.cpp +++ b/eclipse-plugins/edu.wpi.first.wpilib.plugins.cpp/resources/templates/examples/PacGoat/src/Robot.cpp @@ -45,7 +45,7 @@ void Robot::AutonomousInit() { } void Robot::AutonomousPeriodic() { - Scheduler::GetInstance()->Run(); + Scheduler::GetInstance().Run(); Log(); } @@ -61,7 +61,7 @@ void Robot::TeleopInit() { } void Robot::TeleopPeriodic() { - Scheduler::GetInstance()->Run(); + Scheduler::GetInstance().Run(); Log(); } diff --git a/hal/include/HAL/cpp/Resource.hpp b/hal/include/HAL/cpp/Resource.hpp index 999c4b62c1..f624f62774 100644 --- a/hal/include/HAL/cpp/Resource.hpp +++ b/hal/include/HAL/cpp/Resource.hpp @@ -9,6 +9,12 @@ #include "HAL/cpp/priority_mutex.h" #include +#include + +// TODO: Replace this with something appropriate to avoid conflicts with +// wpilibC++ Resource class (which performs an essentially identical function). +namespace hal { + /** * The Resource class is a convenient way to track allocated resources. * It tracks them as indicies in the range [0 .. elements - 1]. @@ -23,19 +29,18 @@ class Resource public: Resource(const Resource&) = delete; Resource& operator=(const Resource&) = delete; - virtual ~Resource(); + explicit Resource(uint32_t size); + virtual ~Resource() = default; static void CreateResourceObject(Resource **r, uint32_t elements); uint32_t Allocate(const char *resourceDesc); uint32_t Allocate(uint32_t index, const char *resourceDesc); void Free(uint32_t index); private: - explicit Resource(uint32_t size); - - bool *m_isAllocated; + ::std::vector m_isAllocated; priority_recursive_mutex m_allocateLock; - uint32_t m_size; static priority_recursive_mutex m_createLock; }; +} // namespace hal diff --git a/hal/lib/Athena/Analog.cpp b/hal/lib/Athena/Analog.cpp index e96c07754c..ab18ad350b 100644 --- a/hal/lib/Athena/Analog.cpp +++ b/hal/lib/Athena/Analog.cpp @@ -574,11 +574,11 @@ struct trigger_t { }; typedef struct trigger_t AnalogTrigger; -static Resource *triggers = NULL; +static hal::Resource *triggers = NULL; void* initializeAnalogTrigger(void* port_pointer, uint32_t *index, int32_t *status) { Port* port = (Port*) port_pointer; - Resource::CreateResourceObject(&triggers, tAnalogTrigger::kNumSystems); + hal::Resource::CreateResourceObject(&triggers, tAnalogTrigger::kNumSystems); AnalogTrigger* trigger = new AnalogTrigger(); trigger->port = (AnalogPort*) initializeAnalogInputPort(port, status); diff --git a/hal/lib/Athena/Digital.cpp b/hal/lib/Athena/Digital.cpp index beb61af8a1..93241449f2 100644 --- a/hal/lib/Athena/Digital.cpp +++ b/hal/lib/Athena/Digital.cpp @@ -66,9 +66,9 @@ priority_recursive_mutex digitalI2CMXPMutex; tDIO* digitalSystem = NULL; tRelay* relaySystem = NULL; tPWM* pwmSystem = NULL; -Resource *DIOChannels = NULL; -Resource *DO_PWMGenerators = NULL; -Resource *PWMChannels = NULL; +hal::Resource *DIOChannels = NULL; +hal::Resource *DO_PWMGenerators = NULL; +hal::Resource *PWMChannels = NULL; bool digitalSystemsInitialized = false; @@ -92,9 +92,9 @@ tSPI *spiSystem; void initializeDigital(int32_t *status) { if (digitalSystemsInitialized) return; - Resource::CreateResourceObject(&DIOChannels, tDIO::kNumSystems * kDigitalPins); - Resource::CreateResourceObject(&DO_PWMGenerators, tDIO::kNumPWMDutyCycleAElements + tDIO::kNumPWMDutyCycleBElements); - Resource::CreateResourceObject(&PWMChannels, tPWM::kNumSystems * kPwmPins); + hal::Resource::CreateResourceObject(&DIOChannels, tDIO::kNumSystems * kDigitalPins); + hal::Resource::CreateResourceObject(&DO_PWMGenerators, tDIO::kNumPWMDutyCycleAElements + tDIO::kNumPWMDutyCycleBElements); + hal::Resource::CreateResourceObject(&PWMChannels, tPWM::kNumSystems * kPwmPins); digitalSystem = tDIO::create(status); // Relay Setup @@ -292,7 +292,7 @@ void setPWMDutyCycle(void* pwmGenerator, double dutyCycle, int32_t *status) { } if(id < 4) digitalSystem->writePWMDutyCycleA(id, (uint8_t)rawDutyCycle, status); - else + else digitalSystem->writePWMDutyCycleB(id - 4, (uint8_t)rawDutyCycle, status); } } @@ -594,10 +594,10 @@ struct counter_t { }; typedef struct counter_t Counter; -static Resource *counters = NULL; +static hal::Resource *counters = NULL; void* initializeCounter(Mode mode, uint32_t *index, int32_t *status) { - Resource::CreateResourceObject(&counters, tCounter::kNumSystems); + hal::Resource::CreateResourceObject(&counters, tCounter::kNumSystems); *index = counters->Allocate("Counter"); if (*index == ~0ul) { *status = NO_AVAILABLE_RESOURCES; @@ -919,7 +919,7 @@ struct encoder_t { typedef struct encoder_t Encoder; static const double DECODING_SCALING_FACTOR = 0.25; -static Resource *quadEncoders = NULL; +static hal::Resource *quadEncoders = NULL; void* initializeEncoder(uint8_t port_a_module, uint32_t port_a_pin, bool port_a_analog_trigger, uint8_t port_b_module, uint32_t port_b_pin, bool port_b_analog_trigger, @@ -931,7 +931,7 @@ void* initializeEncoder(uint8_t port_a_module, uint32_t port_a_pin, bool port_a_ remapDigitalSource(port_a_analog_trigger, port_a_pin, port_a_module); remapDigitalSource(port_b_analog_trigger, port_b_pin, port_b_module); - Resource::CreateResourceObject(&quadEncoders, tEncoder::kNumSystems); + hal::Resource::CreateResourceObject(&quadEncoders, tEncoder::kNumSystems); encoder->index = quadEncoders->Allocate("4X Encoder"); *index = encoder->index; // TODO: if (index == ~0ul) { CloneError(quadEncoders); return; } diff --git a/hal/lib/Athena/cpp/Resource.cpp b/hal/lib/Athena/cpp/Resource.cpp index f6ec0813ef..41146ce526 100644 --- a/hal/lib/Athena/cpp/Resource.cpp +++ b/hal/lib/Athena/cpp/Resource.cpp @@ -9,6 +9,8 @@ #include #include "HAL/cpp/priority_mutex.h" +namespace hal { + priority_recursive_mutex Resource::m_createLock; /** @@ -16,15 +18,9 @@ priority_recursive_mutex Resource::m_createLock; * Allocate a bool array of values that will get initialized to indicate that no resources * have been allocated yet. The indicies of the resources are [0 .. elements - 1]. */ -Resource::Resource(uint32_t elements) -{ - std::unique_lock sync(m_createLock); - m_size = elements; - m_isAllocated = new bool[m_size]; - for (uint32_t i=0; i < m_size; i++) - { - m_isAllocated[i] = false; - } +Resource::Resource(uint32_t elements) { + std::unique_lock sync(m_createLock); + m_isAllocated = std::vector(elements, false); } /** @@ -46,15 +42,6 @@ Resource::Resource(uint32_t elements) } } -/** - * Delete the allocated array or resources. - * This happens when the module is unloaded (provided it was statically allocated). - */ -Resource::~Resource() -{ - delete[] m_isAllocated; -} - /** * Allocate a resource. * When a resource is requested, mark it allocated. In this case, a free resource value @@ -63,7 +50,7 @@ Resource::~Resource() uint32_t Resource::Allocate(const char *resourceDesc) { std::unique_lock sync(m_allocateLock); - for (uint32_t i=0; i < m_size; i++) + for (uint32_t i=0; i < m_isAllocated.size(); i++) { if (!m_isAllocated[i]) { @@ -83,7 +70,7 @@ uint32_t Resource::Allocate(const char *resourceDesc) uint32_t Resource::Allocate(uint32_t index, const char *resourceDesc) { std::unique_lock sync(m_allocateLock); - if (index >= m_size) + if (index >= m_isAllocated.size()) { // TODO: wpi_setWPIErrorWithContext(ChannelIndexOutOfRange, resourceDesc); return ~0ul; @@ -107,7 +94,7 @@ void Resource::Free(uint32_t index) { std::unique_lock sync(m_allocateLock); if (index == ~0ul) return; - if (index >= m_size) + if (index >= m_isAllocated.size()) { // TODO: wpi_setWPIError(NotAllocated); return; @@ -119,3 +106,5 @@ void Resource::Free(uint32_t index) } m_isAllocated[index] = false; } + +} // namespace hal diff --git a/networktables/cpp/include/networktables/NetworkTableKeyListenerAdapter.h b/networktables/cpp/include/networktables/NetworkTableKeyListenerAdapter.h index a7a332f5db..46f24c6e6b 100644 --- a/networktables/cpp/include/networktables/NetworkTableKeyListenerAdapter.h +++ b/networktables/cpp/include/networktables/NetworkTableKeyListenerAdapter.h @@ -28,6 +28,10 @@ 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, + 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 5b0fd70072..c4da9eb939 100644 --- a/networktables/cpp/include/networktables/NetworkTableListenerAdapter.h +++ b/networktables/cpp/include/networktables/NetworkTableListenerAdapter.h @@ -14,17 +14,22 @@ class NetworkTableListenerAdapter; #include "tables/ITable.h" #include +class NetworkTableListenerAdapter : public ITableListener { + private: + std::string prefix; + ITable* targetSource; + ITableListener* targetListener; -class NetworkTableListenerAdapter : public ITableListener{ -private: - std::string prefix; - ITable* targetSource; - ITableListener* targetListener; -public: - NetworkTableListenerAdapter(std::string prefix, ITable* targetSource, ITableListener* targetListener); - virtual ~NetworkTableListenerAdapter(); - void ValueChanged(ITable* source, const std::string& key, EntryValue value, bool isNew); + public: + NetworkTableListenerAdapter(std::string prefix, ITable* targetSource, + ITableListener* targetListener); + virtual ~NetworkTableListenerAdapter(); + void ValueChanged(ITable* source, const std::string& key, EntryValue value, + bool isNew); + void ValueChanged(::std::shared_ptr source, const std::string& key, + EntryValue value, bool isNew) { + ValueChanged(source.get(), key, value, isNew); + } }; - #endif /* NETWORKTABLELISTENERADAPTER_H_ */ diff --git a/networktables/cpp/include/networktables/NetworkTableSubListenerAdapter.h b/networktables/cpp/include/networktables/NetworkTableSubListenerAdapter.h index 58d53b5432..bdad00af66 100644 --- a/networktables/cpp/include/networktables/NetworkTableSubListenerAdapter.h +++ b/networktables/cpp/include/networktables/NetworkTableSubListenerAdapter.h @@ -29,6 +29,10 @@ 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, + 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 af114c3aa5..239b508dd7 100644 --- a/networktables/cpp/include/tables/ITableListener.h +++ b/networktables/cpp/include/tables/ITableListener.h @@ -14,12 +14,11 @@ class ITableListener; #include "tables/ITable.h" - - +#include /** * A listener that listens to changes in values in a {@link ITable} - * + * * @author Mitchell * */ @@ -34,7 +33,18 @@ 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(ITable* 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); + } + + private: + template + struct[[deprecated]] NullDeleter { + void operator()(T*) const noexcept {}; + }; }; diff --git a/wpilibc/wpilibC++/include/Base.h b/wpilibc/wpilibC++/include/Base.h index 8ad11df12e..b4fbe7f202 100644 --- a/wpilibc/wpilibC++/include/Base.h +++ b/wpilibc/wpilibC++/include/Base.h @@ -11,3 +11,12 @@ TypeName& operator=(const TypeName&) = delete; \ TypeName(TypeName&&) = default; \ TypeName& operator=(TypeName&&) = default + +// A struct to use as a deleter when a std::shared_ptr must wrap a raw pointer +// that is being deleted by someone else. +// This should only be called in deprecated functions; using it anywhere else +// will throw warnings. +template +struct [[deprecated]] NullDeleter { + void operator()(T *) const noexcept {}; +}; diff --git a/wpilibc/wpilibC++/include/Buttons/NetworkButton.h b/wpilibc/wpilibC++/include/Buttons/NetworkButton.h index 19d2249213..be003d3a17 100644 --- a/wpilibc/wpilibC++/include/Buttons/NetworkButton.h +++ b/wpilibc/wpilibC++/include/Buttons/NetworkButton.h @@ -10,17 +10,18 @@ #include "Buttons/Button.h" #include +#include class NetworkButton : public Button { public: NetworkButton(const char *tableName, const char *field); - NetworkButton(ITable *table, const char *field); + NetworkButton(::std::shared_ptr table, const char *field); virtual ~NetworkButton() = default; virtual bool Get(); private: - ITable *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 c5e38a42c5..d78ad7e141 100644 --- a/wpilibc/wpilibC++/include/Buttons/Trigger.h +++ b/wpilibc/wpilibC++/include/Buttons/Trigger.h @@ -9,6 +9,7 @@ #define __TRIGGER_H__ #include "SmartDashboard/Sendable.h" +#include class Command; @@ -41,12 +42,12 @@ class Trigger : public Sendable { void CancelWhenActive(Command *command); void ToggleWhenActive(Command *command); - virtual void InitTable(ITable *table); - virtual ITable *GetTable() const; + virtual void InitTable(::std::shared_ptr table); + virtual ::std::shared_ptr GetTable() const; virtual std::string GetSmartDashboardType() const; protected: - ITable *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 99d4feb7f7..6f2747bc3d 100644 --- a/wpilibc/wpilibC++/include/Commands/Command.h +++ b/wpilibc/wpilibC++/include/Commands/Command.h @@ -12,6 +12,7 @@ #include "SmartDashboard/NamedSendable.h" #include #include +#include class CommandGroup; class Subsystem; @@ -175,14 +176,14 @@ class Command : public ErrorBase, public NamedSendable, public ITableListener { public: virtual std::string GetName(); - virtual void InitTable(ITable *table); - virtual ITable *GetTable() const; + virtual void InitTable(::std::shared_ptr table); + virtual ::std::shared_ptr GetTable() const; virtual std::string GetSmartDashboardType() const; - virtual void ValueChanged(ITable *source, const std::string &key, + virtual void ValueChanged(::std::shared_ptr source, const std::string &key, EntryValue value, bool isNew); protected: - ITable *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 0e09c7b7b1..a4038cb135 100644 --- a/wpilibc/wpilibC++/include/Commands/PIDCommand.h +++ b/wpilibc/wpilibC++/include/Commands/PIDCommand.h @@ -12,6 +12,8 @@ #include "PIDSource.h" #include "PIDOutput.h" +#include + class PIDController; class PIDCommand : public Command, public PIDOutput, public PIDSource { @@ -23,7 +25,7 @@ class PIDCommand : public Command, public PIDOutput, public PIDSource { PIDCommand(double p, double i, double d); PIDCommand(double p, double i, double d, double period); PIDCommand(double p, double i, double d, double f, double period); - virtual ~PIDCommand(); + virtual ~PIDCommand() = default; void SetSetpointRelative(double deltaSetpoint); @@ -47,10 +49,10 @@ class PIDCommand : public Command, public PIDOutput, public PIDSource { private: /** The internal {@link PIDController} */ - PIDController *m_controller; + std::unique_ptr m_controller; public: - virtual void InitTable(ITable *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 63a771c861..f5e4e14280 100644 --- a/wpilibc/wpilibC++/include/Commands/PIDSubsystem.h +++ b/wpilibc/wpilibC++/include/Commands/PIDSubsystem.h @@ -13,6 +13,8 @@ #include "PIDSource.h" #include "PIDOutput.h" +#include + /** * This class is designed to handle the case where there is a {@link Subsystem} * which uses a single {@link PIDController} almost constantly (for instance, @@ -34,7 +36,7 @@ class PIDSubsystem : public Subsystem, public PIDOutput, public PIDSource { PIDSubsystem(double p, double i, double d); PIDSubsystem(double p, double i, double d, double f); PIDSubsystem(double p, double i, double d, double f, double period); - virtual ~PIDSubsystem(); + virtual ~PIDSubsystem() = default; void Enable(); void Disable(); @@ -63,10 +65,10 @@ class PIDSubsystem : public Subsystem, public PIDOutput, public PIDSource { private: /** The internal {@link PIDController} */ - PIDController *m_controller; + std::unique_ptr m_controller; public: - virtual void InitTable(ITable *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 ee085d91c4..7e89d6d4fb 100644 --- a/wpilibc/wpilibC++/include/Commands/Scheduler.h +++ b/wpilibc/wpilibC++/include/Commands/Scheduler.h @@ -17,6 +17,7 @@ #include "SmartDashboard/SmartDashboard.h" #include #include +#include #include #include #include "HAL/cpp/priority_mutex.h" @@ -26,7 +27,7 @@ class Subsystem; class Scheduler : public ErrorBase, public NamedSendable { public: - static Scheduler *GetInstance(); + static Scheduler &GetInstance(); void AddCommand(Command *command); void AddButton(ButtonScheduler *button); @@ -39,8 +40,8 @@ class Scheduler : public ErrorBase, public NamedSendable { void UpdateTable(); std::string GetSmartDashboardType() const; - void InitTable(ITable *subTable); - ITable *GetTable() const; + void InitTable(::std::shared_ptr subTable); + ::std::shared_ptr GetTable() const; std::string GetName(); std::string GetType() const; @@ -64,7 +65,7 @@ class Scheduler : public ErrorBase, public NamedSendable { StringArray *commands = nullptr; NumberArray *ids = nullptr; NumberArray *toCancel = nullptr; - ITable *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 df6d5d86eb..9192c5155a 100644 --- a/wpilibc/wpilibC++/include/Commands/Subsystem.h +++ b/wpilibc/wpilibC++/include/Commands/Subsystem.h @@ -11,6 +11,7 @@ #include "ErrorBase.h" #include "SmartDashboard/NamedSendable.h" #include +#include class Command; @@ -38,12 +39,12 @@ class Subsystem : public ErrorBase, public NamedSendable { public: virtual std::string GetName(); - virtual void InitTable(ITable *table); - virtual ITable *GetTable() const; + virtual void InitTable(::std::shared_ptr table); + virtual ::std::shared_ptr GetTable() const; virtual std::string GetSmartDashboardType() const; protected: - ITable *m_table = nullptr; + ::std::shared_ptr m_table = nullptr; }; #endif diff --git a/wpilibc/wpilibC++/include/Error.h b/wpilibc/wpilibC++/include/Error.h index 828dfca2e5..243799c6c3 100644 --- a/wpilibc/wpilibC++/include/Error.h +++ b/wpilibc/wpilibC++/include/Error.h @@ -21,18 +21,18 @@ class Error { typedef int32_t Code; Error(); - void Clone(Error& error); + void Clone(const Error& error); Code GetCode() const; - const char* GetMessage() const; - const char* GetFilename() const; - const char* GetFunction() const; + std::string GetMessage() const; + std::string GetFilename() const; + std::string GetFunction() const; uint32_t GetLineNumber() const; const ErrorBase* GetOriginatingObject() const; double GetTimestamp() const; void Clear(); - void Set(Code code, const char* contextMessage, const char* filename, - const char* function, uint32_t lineNumber, - const ErrorBase* originatingObject); + void Set(Code code, const std::string& contextMessage, + const std::string& filename, const std::string& function, + uint32_t lineNumber, const ErrorBase* originatingObject); private: void Report(); diff --git a/wpilibc/wpilibC++/include/ErrorBase.h b/wpilibc/wpilibC++/include/ErrorBase.h index 0ec96a3384..4d0540f11b 100644 --- a/wpilibc/wpilibC++/include/ErrorBase.h +++ b/wpilibc/wpilibC++/include/ErrorBase.h @@ -56,26 +56,33 @@ class ErrorBase { virtual ~ErrorBase() = default; virtual Error& GetError(); virtual const Error& GetError() const; - virtual void SetErrnoError(const char* contextMessage, const char* filename, - const char* function, uint32_t lineNumber) const; - virtual void SetImaqError(int success, const char* contextMessage, - const char* filename, const char* function, + virtual void SetErrnoError(const std::string& contextMessage, + const std::string& filename, + const std::string& function, + uint32_t lineNumber) const; + virtual void SetImaqError(int success, const std::string& contextMessage, + const std::string& filename, + const std::string& function, uint32_t lineNumber) const; - virtual void SetError(Error::Code code, const char* contextMessage, - const char* filename, const char* function, - uint32_t lineNumber) const; - virtual void SetWPIError(const char* errorMessage, Error::Code code, - const char* contextMessage, const char* filename, - const char* function, uint32_t lineNumber) const; - virtual void CloneError(ErrorBase* rhs) const; + virtual void SetError(Error::Code code, const std::string& contextMessage, + const std::string& filename, + const std::string& function, uint32_t lineNumber) const; + virtual void SetWPIError(const std::string& errorMessage, Error::Code code, + const std::string& contextMessage, + const std::string& filename, + const std::string& function, + uint32_t lineNumber) const; + virtual void CloneError(const ErrorBase& rhs) const; virtual void ClearError() const; virtual bool StatusIsFatal() const; - static void SetGlobalError(Error::Code code, const char* contextMessage, - const char* filename, const char* function, - uint32_t lineNumber); - static void SetGlobalWPIError(const char* errorMessage, - const char* contextMessage, - const char* filename, const char* function, + static void SetGlobalError(Error::Code code, + const std::string& contextMessage, + const std::string& filename, + const std::string& function, uint32_t lineNumber); + static void SetGlobalWPIError(const std::string& errorMessage, + const std::string& contextMessage, + const std::string& filename, + const std::string& function, uint32_t lineNumber); static Error& GetGlobalError(); diff --git a/wpilibc/wpilibC++/include/LiveWindow/LiveWindow.h b/wpilibc/wpilibC++/include/LiveWindow/LiveWindow.h index 3b4b8f2260..1a50f2e2b2 100644 --- a/wpilibc/wpilibC++/include/LiveWindow/LiveWindow.h +++ b/wpilibc/wpilibC++/include/LiveWindow/LiveWindow.h @@ -6,6 +6,7 @@ #include "Commands/Scheduler.h" #include #include +#include struct LiveWindowComponent { std::string subsystem; @@ -29,12 +30,22 @@ struct LiveWindowComponent { */ class LiveWindow { public: - static LiveWindow *GetInstance(); + static LiveWindow &GetInstance(); void Run(); + [[deprecated( + "Raw pointers are deprecated; pass the component using shared_ptr " + "instead.")]] void AddSensor(const char *subsystem, const char *name, LiveWindowSendable *component); + void AddSensor(const char *subsystem, const char *name, + ::std::shared_ptr component); + [[deprecated( + "Raw pointers are deprecated; pass the component using shared_ptr " + "instead.")]] void AddActuator(const char *subsystem, const char *name, LiveWindowSendable *component); + void AddActuator(const char *subsystem, const char *name, + ::std::shared_ptr component); void AddSensor(std::string type, int channel, LiveWindowSendable *component); void AddActuator(std::string type, int channel, LiveWindowSendable *component); @@ -53,13 +64,13 @@ class LiveWindow { void Initialize(); void InitializeLiveWindowComponents(); - std::vector m_sensors; - std::map m_components; + std::vector<::std::shared_ptr> m_sensors; + std::map<::std::shared_ptr, LiveWindowComponent> m_components; - ITable *m_liveWindowTable; - ITable *m_statusTable; + ::std::shared_ptr m_liveWindowTable; + ::std::shared_ptr m_statusTable; - Scheduler *m_scheduler; + Scheduler &m_scheduler; bool m_enabled = false; bool m_firstTime = true; diff --git a/wpilibc/wpilibC++/include/LiveWindow/LiveWindowStatusListener.h b/wpilibc/wpilibC++/include/LiveWindow/LiveWindowStatusListener.h index 22e4f9935b..a1d4d6aa13 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(ITable* 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/PIDController.h b/wpilibc/wpilibC++/include/PIDController.h index b04f374ea4..a36a78e297 100644 --- a/wpilibc/wpilibC++/include/PIDController.h +++ b/wpilibc/wpilibC++/include/PIDController.h @@ -11,10 +11,12 @@ #include "LiveWindow/LiveWindow.h" #include "PIDInterface.h" #include "HAL/cpp/priority_mutex.h" +#include "Notifier.h" + +#include class PIDOutput; class PIDSource; -class Notifier; /** * Class implements a PID Control Loop. @@ -31,7 +33,7 @@ class PIDController : public LiveWindowSendable, float period = 0.05); PIDController(float p, float i, float d, float f, PIDSource *source, PIDOutput *output, float period = 0.05); - virtual ~PIDController(); + virtual ~PIDController() = default; virtual float Get() const; virtual void SetContinuous(bool continuous = true); virtual void SetInputRange(float minimumInput, float maximumInput); @@ -59,7 +61,7 @@ class PIDController : public LiveWindowSendable, virtual void Reset() override; - virtual void InitTable(ITable *table) override; + virtual void InitTable(::std::shared_ptr table) override; private: float m_P; // factor for "proportional" control @@ -92,22 +94,22 @@ class PIDController : public LiveWindowSendable, PIDSource *m_pidInput; PIDOutput *m_pidOutput; - Notifier *m_controlLoop; + std::unique_ptr m_controlLoop; void Initialize(float p, float i, float d, float f, PIDSource *source, PIDOutput *output, float period = 0.05); static void CallCalculate(void *controller); - virtual ITable *GetTable() const override; + virtual ::std::shared_ptr GetTable() const override; virtual std::string GetSmartDashboardType() const override; - virtual void ValueChanged(ITable *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: - ITable *m_table = nullptr; + ::std::shared_ptr m_table = nullptr; virtual void Calculate(); DISALLOW_COPY_AND_ASSIGN(PIDController); diff --git a/wpilibc/wpilibC++/include/Resource.h b/wpilibc/wpilibC++/include/Resource.h index 339ce04992..599c73f16e 100644 --- a/wpilibc/wpilibC++/include/Resource.h +++ b/wpilibc/wpilibC++/include/Resource.h @@ -8,6 +8,8 @@ #include "ErrorBase.h" #include +#include +#include #include "HAL/cpp/priority_mutex.h" @@ -22,18 +24,16 @@ */ class Resource : public ErrorBase { public: - virtual ~Resource(); - static void CreateResourceObject(Resource **r, uint32_t elements); + virtual ~Resource() = default; + static void CreateResourceObject(::std::unique_ptr& r, uint32_t elements); + explicit Resource(uint32_t size); uint32_t Allocate(const char *resourceDesc); uint32_t Allocate(uint32_t index, const char *resourceDesc); void Free(uint32_t index); private: - explicit Resource(uint32_t size); - - bool *m_isAllocated; + std::vector m_isAllocated; priority_recursive_mutex m_allocateLock; - uint32_t m_size; static priority_recursive_mutex m_createLock; diff --git a/wpilibc/wpilibC++/include/RobotState.h b/wpilibc/wpilibC++/include/RobotState.h index 941afc38e3..252c1a197b 100644 --- a/wpilibc/wpilibC++/include/RobotState.h +++ b/wpilibc/wpilibC++/include/RobotState.h @@ -5,6 +5,8 @@ /*----------------------------------------------------------------------------*/ #pragma once +#include + class RobotStateInterface { public: virtual ~RobotStateInterface() = default; @@ -17,10 +19,11 @@ class RobotStateInterface { class RobotState { private: - static RobotStateInterface* impl; + static ::std::shared_ptr impl; public: - static void SetImplementation(RobotStateInterface* i); + static void SetImplementation(RobotStateInterface& 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 ad0899b8cc..6b8ffd6a0e 100644 --- a/wpilibc/wpilibC++/include/SmartDashboard/Sendable.h +++ b/wpilibc/wpilibC++/include/SmartDashboard/Sendable.h @@ -9,6 +9,7 @@ #define __SMART_DASHBOARD_DATA__ #include +#include #include "tables/ITable.h" class Sendable { @@ -17,12 +18,12 @@ class Sendable { * Initializes a table for this sendable object. * @param subtable The table to put the values in. */ - virtual void InitTable(ITable* subtable) = 0; + virtual void InitTable(::std::shared_ptr subtable) = 0; /** * @return the table that is currently associated with the sendable */ - virtual ITable* 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 c3512506a4..652244fd70 100644 --- a/wpilibc/wpilibC++/include/SmartDashboard/SendableChooser.h +++ b/wpilibc/wpilibC++/include/SmartDashboard/SendableChooser.h @@ -11,6 +11,7 @@ #include "SmartDashboard/Sendable.h" #include "tables/ITable.h" #include +#include #include /** @@ -38,14 +39,14 @@ class SendableChooser : public Sendable { void AddDefault(const char *name, void *object); void *GetSelected(); - virtual void InitTable(ITable *subtable); - virtual ITable *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; - ITable *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 ce32caae27..ecf7364891 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 ITable *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 m_tablesToData; + static std::map<::std::shared_ptr , Sendable *> m_tablesToData; }; #endif diff --git a/wpilibc/wpilibC++/include/Task.h b/wpilibc/wpilibC++/include/Task.h index 5a8e9f5a57..1501a214eb 100644 --- a/wpilibc/wpilibC++/include/Task.h +++ b/wpilibc/wpilibC++/include/Task.h @@ -12,6 +12,8 @@ #include #include +#include + /** * WPI task is a wrapper for the native Task object. * All WPILib tasks are managed by a static task manager for simplified cleanup. diff --git a/wpilibc/wpilibC++/src/Buttons/ButtonScheduler.cpp b/wpilibc/wpilibC++/src/Buttons/ButtonScheduler.cpp index ddc9025fe4..43c7c148f9 100644 --- a/wpilibc/wpilibC++/src/Buttons/ButtonScheduler.cpp +++ b/wpilibc/wpilibC++/src/Buttons/ButtonScheduler.cpp @@ -12,4 +12,4 @@ ButtonScheduler::ButtonScheduler(bool last, Trigger *button, Command *orders) : m_pressedLast(last), m_button(button), m_command(orders) {} -void ButtonScheduler::Start() { Scheduler::GetInstance()->AddButton(this); } +void ButtonScheduler::Start() { Scheduler::GetInstance().AddButton(this); } diff --git a/wpilibc/wpilibC++/src/Buttons/NetworkButton.cpp b/wpilibc/wpilibC++/src/Buttons/NetworkButton.cpp index 4c5f05ae92..e8020e1af8 100644 --- a/wpilibc/wpilibC++/src/Buttons/NetworkButton.cpp +++ b/wpilibc/wpilibC++/src/Buttons/NetworkButton.cpp @@ -13,7 +13,7 @@ NetworkButton::NetworkButton(const char *tableName, const char *field) m_netTable(NetworkTable::GetTable(tableName)), m_field(field) {} -NetworkButton::NetworkButton(ITable *table, const char *field) +NetworkButton::NetworkButton(::std::shared_ptr table, const char *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 0715868e8d..51a65ac846 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(ITable *table) { +void Trigger::InitTable(::std::shared_ptr table) { m_table = table; if (m_table != nullptr) { m_table->PutBoolean("pressed", Get()); } } -ITable *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 5c6af1b472..395e184fb5 100644 --- a/wpilibc/wpilibC++/src/Commands/Command.cpp +++ b/wpilibc/wpilibC++/src/Commands/Command.cpp @@ -145,7 +145,7 @@ void Command::Start() { CommandIllegalUse, "Can not start a command that is part of a command group"); - Scheduler::GetInstance()->AddCommand(this); + Scheduler::GetInstance().AddCommand(this); } /** @@ -369,7 +369,7 @@ std::string Command::GetName() { std::string Command::GetSmartDashboardType() const { return "Command"; } -void Command::InitTable(ITable *table) { +void Command::InitTable(::std::shared_ptr table) { if (m_table != nullptr) m_table->RemoveTableListener(this); m_table = table; if (m_table != nullptr) { @@ -380,9 +380,9 @@ void Command::InitTable(ITable *table) { } } -ITable *Command::GetTable() const { return m_table; } +::std::shared_ptr Command::GetTable() const { return m_table; } -void Command::ValueChanged(ITable *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 e4b832617c..b3a4c9829b 100644 --- a/wpilibc/wpilibC++/src/Commands/PIDCommand.cpp +++ b/wpilibc/wpilibC++/src/Commands/PIDCommand.cpp @@ -13,34 +13,32 @@ PIDCommand::PIDCommand(const char *name, double p, double i, double d, double f, double period) : Command(name) { - m_controller = new PIDController(p, i, d, this, this, period); + m_controller = std::make_unique(p, i, d, this, this, period); } PIDCommand::PIDCommand(double p, double i, double d, double f, double period) { - m_controller = new PIDController(p, i, d, f, this, this, period); + m_controller = std::make_unique(p, i, d, f, this, this, period); } PIDCommand::PIDCommand(const char *name, double p, double i, double d) : Command(name) { - m_controller = new PIDController(p, i, d, this, this); + m_controller = std::make_unique(p, i, d, this, this); } PIDCommand::PIDCommand(const char *name, double p, double i, double d, double period) : Command(name) { - m_controller = new PIDController(p, i, d, this, this, period); + m_controller = std::make_unique(p, i, d, this, this, period); } PIDCommand::PIDCommand(double p, double i, double d) { - m_controller = new PIDController(p, i, d, this, this); + m_controller = std::make_unique(p, i, d, this, this); } PIDCommand::PIDCommand(double p, double i, double d, double period) { - m_controller = new PIDController(p, i, d, this, this, period); + m_controller = std::make_unique(p, i, d, this, this, period); } -PIDCommand::~PIDCommand() { delete m_controller; } - void PIDCommand::_Initialize() { m_controller->Enable(); } void PIDCommand::_End() { m_controller->Disable(); } @@ -55,7 +53,7 @@ void PIDCommand::PIDWrite(float output) { UsePIDOutput(output); } double PIDCommand::PIDGet() const { return ReturnPIDInput(); } -PIDController *PIDCommand::GetPIDController() const { return m_controller; } +PIDController *PIDCommand::GetPIDController() const { return m_controller.get(); } void PIDCommand::SetSetpoint(double setpoint) { m_controller->SetSetpoint(setpoint); @@ -66,7 +64,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(ITable *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 e6c341ddb5..1dcdc6b240 100644 --- a/wpilibc/wpilibC++/src/Commands/PIDSubsystem.cpp +++ b/wpilibc/wpilibC++/src/Commands/PIDSubsystem.cpp @@ -19,7 +19,7 @@ */ PIDSubsystem::PIDSubsystem(const char *name, double p, double i, double d) : Subsystem(name) { - m_controller = new PIDController(p, i, d, this, this); + m_controller = std::make_unique(p, i, d, this, this); } /** @@ -34,7 +34,7 @@ PIDSubsystem::PIDSubsystem(const char *name, double p, double i, double d) PIDSubsystem::PIDSubsystem(const char *name, double p, double i, double d, double f) : Subsystem(name) { - m_controller = new PIDController(p, i, d, f, this, this); + m_controller = std::make_unique(p, i, d, f, this, this); } /** @@ -51,7 +51,7 @@ PIDSubsystem::PIDSubsystem(const char *name, double p, double i, double d, PIDSubsystem::PIDSubsystem(const char *name, double p, double i, double d, double f, double period) : Subsystem(name) { - m_controller = new PIDController(p, i, d, f, this, this, period); + m_controller = std::make_unique(p, i, d, f, this, this, period); } /** @@ -64,7 +64,7 @@ PIDSubsystem::PIDSubsystem(const char *name, double p, double i, double d, */ PIDSubsystem::PIDSubsystem(double p, double i, double d) : Subsystem("PIDSubsystem") { - m_controller = new PIDController(p, i, d, this, this); + m_controller = std::make_unique(p, i, d, this, this); } /** @@ -78,7 +78,7 @@ PIDSubsystem::PIDSubsystem(double p, double i, double d) */ PIDSubsystem::PIDSubsystem(double p, double i, double d, double f) : Subsystem("PIDSubsystem") { - m_controller = new PIDController(p, i, d, f, this, this); + m_controller = std::make_unique(p, i, d, f, this, this); } /** @@ -96,11 +96,9 @@ PIDSubsystem::PIDSubsystem(double p, double i, double d, double f) PIDSubsystem::PIDSubsystem(double p, double i, double d, double f, double period) : Subsystem("PIDSubsystem") { - m_controller = new PIDController(p, i, d, f, this, this, period); + m_controller = std::make_unique(p, i, d, f, this, this, period); } -PIDSubsystem::~PIDSubsystem() { delete m_controller; } - /** * Enables the internal {@link PIDController} */ @@ -117,7 +115,7 @@ void PIDSubsystem::Disable() { m_controller->Disable(); } * * @return the {@link PIDController} used by this {@link PIDSubsystem} */ -PIDController *PIDSubsystem::GetPIDController() { return m_controller; } +PIDController *PIDSubsystem::GetPIDController() { return m_controller.get(); } /** * Sets the setpoint to the given value. If {@link PIDCommand#SetRange(double, @@ -213,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(ITable *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 f40fe92560..96a7646422 100644 --- a/wpilibc/wpilibC++/src/Commands/Scheduler.cpp +++ b/wpilibc/wpilibC++/src/Commands/Scheduler.cpp @@ -23,9 +23,9 @@ Scheduler::Scheduler() { * Returns the {@link Scheduler}, creating it if one does not exist. * @return the {@link Scheduler} */ -Scheduler *Scheduler::GetInstance() { +Scheduler &Scheduler::GetInstance() { static Scheduler instance; - return &instance; + return instance; } void Scheduler::SetEnabled(bool enabled) { m_enabled = enabled; } @@ -258,7 +258,7 @@ std::string Scheduler::GetType() const { return "Scheduler"; } std::string Scheduler::GetSmartDashboardType() const { return "Scheduler"; } -void Scheduler::InitTable(ITable *subTable) { +void Scheduler::InitTable(::std::shared_ptr subTable) { m_table = subTable; commands = new StringArray(); ids = new NumberArray(); @@ -269,4 +269,4 @@ void Scheduler::InitTable(ITable *subTable) { m_table->PutValue("Cancel", *toCancel); } -ITable *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 53dbfcf74c..cda458994d 100644 --- a/wpilibc/wpilibC++/src/Commands/Subsystem.cpp +++ b/wpilibc/wpilibC++/src/Commands/Subsystem.cpp @@ -17,7 +17,7 @@ */ Subsystem::Subsystem(const char *name) { m_name = name; - Scheduler::GetInstance()->RegisterSubsystem(this); + Scheduler::GetInstance().RegisterSubsystem(this); } /** * Initialize the default command for this subsystem @@ -126,7 +126,7 @@ std::string Subsystem::GetName() { return m_name; } std::string Subsystem::GetSmartDashboardType() const { return "Subsystem"; } -void Subsystem::InitTable(ITable *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(ITable *table) { } } -ITable *Subsystem::GetTable() const { return m_table; } +::std::shared_ptr Subsystem::GetTable() const { return m_table; } diff --git a/wpilibc/wpilibC++/src/Error.cpp b/wpilibc/wpilibC++/src/Error.cpp index 0f566c2397..ba6ee10590 100644 --- a/wpilibc/wpilibC++/src/Error.cpp +++ b/wpilibc/wpilibC++/src/Error.cpp @@ -19,7 +19,7 @@ Error::Error() {} -void Error::Clone(Error& error) { +void Error::Clone(const Error& error) { m_code = error.m_code; m_message = error.m_message; m_filename = error.m_filename; @@ -31,11 +31,11 @@ void Error::Clone(Error& error) { Error::Code Error::GetCode() const { return m_code; } -const char* Error::GetMessage() const { return m_message.c_str(); } +std::string Error::GetMessage() const { return m_message; } -const char* Error::GetFilename() const { return m_filename.c_str(); } +std::string Error::GetFilename() const { return m_filename; } -const char* Error::GetFunction() const { return m_function.c_str(); } +std::string Error::GetFunction() const { return m_function; } uint32_t Error::GetLineNumber() const { return m_lineNumber; } @@ -45,9 +45,9 @@ const ErrorBase* Error::GetOriginatingObject() const { double Error::GetTimestamp() const { return m_timestamp; } -void Error::Set(Code code, const char* contextMessage, const char* filename, - const char* function, uint32_t lineNumber, - const ErrorBase* originatingObject) { +void Error::Set(Code code, const std::string& contextMessage, + const std::string& filename, const std::string& function, + uint32_t lineNumber, const ErrorBase* originatingObject) { bool report = true; if (code == m_code && GetTime() - m_timestamp < 1) { diff --git a/wpilibc/wpilibC++/src/ErrorBase.cpp b/wpilibc/wpilibC++/src/ErrorBase.cpp index adfe387b8d..5e1506eb9d 100644 --- a/wpilibc/wpilibC++/src/ErrorBase.cpp +++ b/wpilibc/wpilibC++/src/ErrorBase.cpp @@ -12,6 +12,7 @@ #include #include #include +#include priority_mutex ErrorBase::_globalErrorMutex; Error ErrorBase::_globalError; @@ -42,15 +43,19 @@ void ErrorBase::ClearError() const { m_error.Clear(); } * @param function Function of the error source * @param lineNumber Line number of the error source */ -void ErrorBase::SetErrnoError(const char* contextMessage, const char* filename, - const char* function, uint32_t lineNumber) const { - char err[256]; +void ErrorBase::SetErrnoError(const std::string& contextMessage, + const std::string& filename, + const std::string& function, + uint32_t lineNumber) const { + std::string err; int errNo = errno; if (errNo == 0) { - sprintf(err, "OK: %s", contextMessage); + err = "OK: " + contextMessage; } else { - snprintf(err, 256, "%s (0x%08X): %s", strerror(errNo), errNo, - contextMessage); + char buf[256]; + snprintf(buf, 256, "%s (0x%08X): %s", strerror(errNo), errNo, + contextMessage.c_str()); + err = buf; } // Set the current error information for this object. @@ -73,16 +78,17 @@ void ErrorBase::SetErrnoError(const char* contextMessage, const char* filename, * @param function Function of the error source * @param lineNumber Line number of the error source */ -void ErrorBase::SetImaqError(int success, const char* contextMessage, - const char* filename, const char* function, +void ErrorBase::SetImaqError(int success, const std::string& contextMessage, + const std::string& filename, + const std::string& function, uint32_t lineNumber) const { // If there was an error if (success <= 0) { - char err[256]; - sprintf(err, "%i: %s", success, contextMessage); + std::stringstream err; + err << success << ": " << contextMessage; // Set the current error information for this object. - m_error.Set(success, err, filename, function, lineNumber, this); + m_error.Set(success, err.str(), filename, function, lineNumber, this); // Update the global error if there is not one already set. std::unique_lock mutex(_globalErrorMutex); @@ -101,8 +107,9 @@ void ErrorBase::SetImaqError(int success, const char* contextMessage, * @param function Function of the error source * @param lineNumber Line number of the error source */ -void ErrorBase::SetError(Error::Code code, const char* contextMessage, - const char* filename, const char* function, +void ErrorBase::SetError(Error::Code code, const std::string& contextMessage, + const std::string& filename, + const std::string& function, uint32_t lineNumber) const { // If there was an error if (code != 0) { @@ -126,11 +133,12 @@ void ErrorBase::SetError(Error::Code code, const char* contextMessage, * @param function Function of the error source * @param lineNumber Line number of the error source */ -void ErrorBase::SetWPIError(const char* errorMessage, Error::Code code, - const char* contextMessage, const char* filename, - const char* function, uint32_t lineNumber) const { - char err[256]; - sprintf(err, "%s: %s", errorMessage, contextMessage); +void ErrorBase::SetWPIError(const std::string& errorMessage, Error::Code code, + const std::string& contextMessage, + const std::string& filename, + const std::string& function, + uint32_t lineNumber) const { + std::string err = errorMessage + ": " + contextMessage; // Set the current error information for this object. m_error.Set(code, err, filename, function, lineNumber, this); @@ -142,8 +150,8 @@ void ErrorBase::SetWPIError(const char* errorMessage, Error::Code code, } } -void ErrorBase::CloneError(ErrorBase* rhs) const { - m_error.Clone(rhs->GetError()); +void ErrorBase::CloneError(const ErrorBase& rhs) const { + m_error.Clone(rhs.GetError()); } /** @@ -153,8 +161,10 @@ void ErrorBase::CloneError(ErrorBase* rhs) const { */ bool ErrorBase::StatusIsFatal() const { return m_error.GetCode() < 0; } -void ErrorBase::SetGlobalError(Error::Code code, const char* contextMessage, - const char* filename, const char* function, +void ErrorBase::SetGlobalError(Error::Code code, + const std::string& contextMessage, + const std::string& filename, + const std::string& function, uint32_t lineNumber) { // If there was an error if (code != 0) { @@ -166,12 +176,12 @@ void ErrorBase::SetGlobalError(Error::Code code, const char* contextMessage, } } -void ErrorBase::SetGlobalWPIError(const char* errorMessage, - const char* contextMessage, - const char* filename, const char* function, +void ErrorBase::SetGlobalWPIError(const std::string& errorMessage, + const std::string& contextMessage, + const std::string& filename, + const std::string& function, uint32_t lineNumber) { - char err[256]; - sprintf(err, "%s: %s", errorMessage, contextMessage); + std::string err = errorMessage + ": " + contextMessage; std::unique_lock mutex(_globalErrorMutex); if (_globalError.GetCode() != 0) { diff --git a/wpilibc/wpilibC++/src/LiveWindow/LiveWindow.cpp b/wpilibc/wpilibC++/src/LiveWindow/LiveWindow.cpp index a211115ea6..a7ed789853 100644 --- a/wpilibc/wpilibC++/src/LiveWindow/LiveWindow.cpp +++ b/wpilibc/wpilibC++/src/LiveWindow/LiveWindow.cpp @@ -9,19 +9,18 @@ * regardless of * how many times GetInstance is called. */ -LiveWindow *LiveWindow::GetInstance() { +LiveWindow &LiveWindow::GetInstance() { static LiveWindow instance; - return &instance; + return instance; } /** * LiveWindow constructor. * Allocate the necessary tables. */ -LiveWindow::LiveWindow() { - m_liveWindowTable = NetworkTable::GetTable("LiveWindow"); - m_statusTable = m_liveWindowTable->GetSubTable("~STATUS~"); - m_scheduler = Scheduler::GetInstance(); +LiveWindow::LiveWindow() : m_scheduler(Scheduler::GetInstance()) { + m_liveWindowTable.reset(NetworkTable::GetTable("LiveWindow")); + m_statusTable.reset(m_liveWindowTable->GetSubTable("~STATUS~")); } /** @@ -35,8 +34,8 @@ void LiveWindow::SetEnabled(bool enabled) { InitializeLiveWindowComponents(); m_firstTime = false; } - m_scheduler->SetEnabled(false); - m_scheduler->RemoveAll(); + m_scheduler.SetEnabled(false); + m_scheduler.RemoveAll(); for (auto& elem : m_components) { elem.first->StartLiveWindowMode(); } @@ -44,7 +43,7 @@ void LiveWindow::SetEnabled(bool enabled) { for (auto& elem : m_components) { elem.first->StopLiveWindowMode(); } - m_scheduler->SetEnabled(true); + m_scheduler.SetEnabled(true); } m_enabled = enabled; m_statusTable->PutBoolean("LW Enabled", m_enabled); @@ -58,12 +57,17 @@ void LiveWindow::SetEnabled(bool enabled) { * @param component A LiveWindowSendable component that represents a sensor. */ void LiveWindow::AddSensor(const char *subsystem, const char *name, - LiveWindowSendable *component) { + ::std::shared_ptr component) { m_components[component].subsystem = subsystem; m_components[component].name = name; m_components[component].isSensor = true; } +void LiveWindow::AddSensor(const char *subsystem, const char *name, LiveWindowSendable *component) { + AddSensor(subsystem, name, ::std::shared_ptr( + component, NullDeleter())); +} + /** * Add an Actuator associated with the subsystem and with call it by the given * name. @@ -72,15 +76,23 @@ void LiveWindow::AddSensor(const char *subsystem, const char *name, * @param component A LiveWindowSendable component that represents a actuator. */ void LiveWindow::AddActuator(const char *subsystem, const char *name, - LiveWindowSendable *component) { + ::std::shared_ptr component) { m_components[component].subsystem = subsystem; m_components[component].name = name; m_components[component].isSensor = false; } +void LiveWindow::AddActuator(const char *subsystem, const char *name, + LiveWindowSendable *component) { + AddActuator(subsystem, name, + ::std::shared_ptr( + component, NullDeleter())); +} + /** * INTERNAL */ +[[deprecated]] void LiveWindow::AddSensor(std::string type, int channel, LiveWindowSendable *component) { std::ostringstream oss; @@ -90,9 +102,11 @@ void LiveWindow::AddSensor(std::string type, int channel, types.copy(cc, types.size()); cc[types.size()] = '\0'; AddSensor("Ungrouped", cc, component); - if (std::find(m_sensors.begin(), m_sensors.end(), component) == + ::std::shared_ptr component_stl( + component, NullDeleter()); + if (std::find(m_sensors.begin(), m_sensors.end(), component_stl) == m_sensors.end()) - m_sensors.push_back(component); + m_sensors.push_back(component_stl); } /** @@ -106,7 +120,8 @@ 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, component); + AddActuator("Ungrouped", cc, ::std::shared_ptr( + component, [](LiveWindowSendable *) {})); } /** @@ -120,7 +135,8 @@ 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, component); + AddActuator("Ungrouped", cc, ::std::shared_ptr( + component, [](LiveWindowSendable *) {})); } /** @@ -146,25 +162,21 @@ void LiveWindow::Run() { /** * Initialize all the LiveWindow elements the first time we enter LiveWindow - * mode. - * By holding off creating the NetworkTable entries, it allows them to be - * redefined - * before the first time in LiveWindow mode. This allows default sensor and - * actuator - * values to be created that are replaced with the custom names from users - * calling - * addActuator and addSensor. + * mode. By holding off creating the NetworkTable entries, it allows them to be + * redefined before the first time in LiveWindow mode. This allows default + * sensor and actuator values to be created that are replaced with the custom + * names from users calling addActuator and addSensor. */ void LiveWindow::InitializeLiveWindowComponents() { for (auto& elem : m_components) { - LiveWindowSendable *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"); - ITable *table = - m_liveWindowTable->GetSubTable(subsystem)->GetSubTable(name); + ::std::shared_ptr table( + m_liveWindowTable->GetSubTable(subsystem)->GetSubTable(name)); table->PutString("~TYPE~", component->GetSmartDashboardType()); table->PutString("Name", name); table->PutString("Subsystem", subsystem); diff --git a/wpilibc/wpilibC++/src/LiveWindow/LiveWindowStatusListener.cpp b/wpilibc/wpilibC++/src/LiveWindow/LiveWindowStatusListener.cpp index 1c03e7c809..9e9fa0f92e 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(ITable* 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 296f47970d..37cd093dc6 100644 --- a/wpilibc/wpilibC++/src/Resource.cpp +++ b/wpilibc/wpilibC++/src/Resource.cpp @@ -20,11 +20,7 @@ priority_recursive_mutex Resource::m_createLock; */ Resource::Resource(uint32_t elements) { std::unique_lock sync(m_createLock); - m_size = elements; - m_isAllocated = new bool[m_size]; - for (uint32_t i = 0; i < m_size; i++) { - m_isAllocated[i] = false; - } + m_isAllocated = ::std::vector(elements, false); } /** @@ -37,21 +33,14 @@ Resource::Resource(uint32_t elements) { * track, that is, it will allocate resource numbers in the range * [0 .. elements - 1]. */ -/*static*/ void Resource::CreateResourceObject(Resource **r, +/*static*/ void Resource::CreateResourceObject(::std::unique_ptr& r, uint32_t elements) { std::unique_lock sync(m_createLock); - if (*r == nullptr) { - *r = new Resource(elements); + if (!r) { + r = std::make_unique(elements); } } -/** - * Delete the allocated array or resources. - * This happens when the module is unloaded (provided it was statically - * allocated). - */ -Resource::~Resource() { delete[] m_isAllocated; } - /** * Allocate a resource. * When a resource is requested, mark it allocated. In this case, a free @@ -60,7 +49,7 @@ Resource::~Resource() { delete[] m_isAllocated; } */ uint32_t Resource::Allocate(const char *resourceDesc) { std::unique_lock sync(m_allocateLock); - for (uint32_t i = 0; i < m_size; i++) { + for (uint32_t i = 0; i < m_isAllocated.size(); i++) { if (!m_isAllocated[i]) { m_isAllocated[i] = true; return i; @@ -78,7 +67,7 @@ uint32_t Resource::Allocate(const char *resourceDesc) { */ uint32_t Resource::Allocate(uint32_t index, const char *resourceDesc) { std::unique_lock sync(m_allocateLock); - if (index >= m_size) { + if (index >= m_isAllocated.size()) { wpi_setWPIErrorWithContext(ChannelIndexOutOfRange, resourceDesc); return ~0ul; } @@ -100,7 +89,7 @@ uint32_t Resource::Allocate(uint32_t index, const char *resourceDesc) { void Resource::Free(uint32_t index) { std::unique_lock sync(m_allocateLock); if (index == ~0ul) return; - if (index >= m_size) { + if (index >= m_isAllocated.size()) { wpi_setWPIError(NotAllocated); return; } diff --git a/wpilibc/wpilibC++/src/RobotState.cpp b/wpilibc/wpilibC++/src/RobotState.cpp index 076c9c8e21..805bdc9e9d 100644 --- a/wpilibc/wpilibC++/src/RobotState.cpp +++ b/wpilibc/wpilibC++/src/RobotState.cpp @@ -1,8 +1,18 @@ #include "RobotState.h" -RobotStateInterface* RobotState::impl = nullptr; +#include "Base.h" -void RobotState::SetImplementation(RobotStateInterface* i) { impl = i; } +::std::shared_ptr RobotState::impl = nullptr; + +void RobotState::SetImplementation(RobotStateInterface& i) { + impl = ::std::shared_ptr( + &i, NullDeleter()); +} + +void RobotState::SetImplementation( + ::std::shared_ptr i) { + impl = i; +} bool RobotState::IsDisabled() { if (impl != nullptr) { diff --git a/wpilibc/wpilibC++/src/SmartDashboard/SendableChooser.cpp b/wpilibc/wpilibC++/src/SmartDashboard/SendableChooser.cpp index 9e9434ef02..24885de7d1 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(ITable *subtable) { +void SendableChooser::InitTable(::std::shared_ptr subtable) { StringArray keys; m_table = subtable; if (m_table != nullptr) { @@ -66,7 +66,7 @@ void SendableChooser::InitTable(ITable *subtable) { } } -ITable *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 5724a97578..b2dfc02fec 100644 --- a/wpilibc/wpilibC++/src/SmartDashboard/SmartDashboard.cpp +++ b/wpilibc/wpilibC++/src/SmartDashboard/SmartDashboard.cpp @@ -13,11 +13,11 @@ #include "networktables/NetworkTable.h" #include "HLUsageReporting.h" -ITable *SmartDashboard::m_table = nullptr; -std::map SmartDashboard::m_tablesToData; +::std::shared_ptr SmartDashboard::m_table = nullptr; +std::map<::std::shared_ptr , Sendable *> SmartDashboard::m_tablesToData; void SmartDashboard::init() { - m_table = NetworkTable::GetTable("SmartDashboard"); + m_table.reset(NetworkTable::GetTable("SmartDashboard")); HLUsageReporting::ReportSmartDashboard(); } @@ -35,7 +35,7 @@ void SmartDashboard::PutData(std::string key, Sendable *data) { wpi_setGlobalWPIErrorWithContext(NullParameter, "value"); return; } - ITable *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) { - ITable *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 8e07ccfbd9..0954409e1b 100644 --- a/wpilibc/wpilibC++Devices/include/ADXL345_I2C.h +++ b/wpilibc/wpilibC++Devices/include/ADXL345_I2C.h @@ -9,6 +9,7 @@ #include "interfaces/Accelerometer.h" #include "I2C.h" #include "LiveWindow/LiveWindowSendable.h" +#include /** * ADXL345 Accelerometer on I2C. @@ -63,12 +64,12 @@ class ADXL345_I2C : public Accelerometer, virtual AllAxes GetAccelerations(); virtual std::string GetSmartDashboardType() const override; - virtual void InitTable(ITable *subtable) override; + virtual void InitTable(::std::shared_ptr subtable) override; virtual void UpdateTable() override; - virtual ITable *GetTable() const override; + virtual ::std::shared_ptr GetTable() const override; virtual void StartLiveWindowMode() override {} virtual void StopLiveWindowMode() override {} private: - ITable *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 974cb7b3e5..a95054d0e7 100644 --- a/wpilibc/wpilibC++Devices/include/ADXL345_SPI.h +++ b/wpilibc/wpilibC++Devices/include/ADXL345_SPI.h @@ -11,6 +11,8 @@ #include "SPI.h" #include "LiveWindow/LiveWindowSendable.h" +#include + class DigitalInput; class DigitalOutput; @@ -54,7 +56,7 @@ class ADXL345_SPI : public Accelerometer, public: ADXL345_SPI(SPI::Port port, Range range = kRange_2G); - virtual ~ADXL345_SPI(); + virtual ~ADXL345_SPI() = default; // Accelerometer interface virtual void SetRange(Range range) override; @@ -66,18 +68,18 @@ class ADXL345_SPI : public Accelerometer, virtual AllAxes GetAccelerations(); virtual std::string GetSmartDashboardType() const override; - virtual void InitTable(ITable* subtable) override; + virtual void InitTable(::std::shared_ptr subtable) override; virtual void UpdateTable() override; - virtual ITable* GetTable() const override; + virtual ::std::shared_ptr GetTable() const override; virtual void StartLiveWindowMode() override {} virtual void StopLiveWindowMode() override {} protected: void Init(Range range); - SPI* m_spi; + std::unique_ptr m_spi; SPI::Port m_port; private: - ITable* m_table; + ::std::shared_ptr m_table; }; diff --git a/wpilibc/wpilibC++Devices/include/AnalogAccelerometer.h b/wpilibc/wpilibC++Devices/include/AnalogAccelerometer.h index cd14381dd1..8bd77e8586 100644 --- a/wpilibc/wpilibC++Devices/include/AnalogAccelerometer.h +++ b/wpilibc/wpilibC++Devices/include/AnalogAccelerometer.h @@ -11,6 +11,8 @@ #include "PIDSource.h" #include "LiveWindow/LiveWindowSendable.h" +#include + /** * Handle operation of an analog accelerometer. * The accelerometer reads acceleration directly through the sensor. Many @@ -24,8 +26,14 @@ class AnalogAccelerometer : public SensorBase, public LiveWindowSendable { public: explicit AnalogAccelerometer(int32_t channel); + [[deprecated( + "Raw pointers are deprecated; if you just want to construct an " + "AnalogAccelerometer with its own AnalogInput, then call the " + "AnalogAccelerometer(int channel). If you want to keep your own copy of " + "the AnalogInput, use std::shared_ptr.")]] explicit AnalogAccelerometer(AnalogInput *channel); - virtual ~AnalogAccelerometer(); + explicit AnalogAccelerometer(::std::shared_ptr channel); + virtual ~AnalogAccelerometer() = default; float GetAcceleration() const; void SetSensitivity(float sensitivity); @@ -36,16 +44,16 @@ class AnalogAccelerometer : public SensorBase, void StartLiveWindowMode() override; void StopLiveWindowMode() override; std::string GetSmartDashboardType() const override; - void InitTable(ITable *subTable) override; - ITable *GetTable() const override; + void InitTable(::std::shared_ptr subTable) override; + ::std::shared_ptr GetTable() const override; private: void InitAccelerometer(); - AnalogInput *m_AnalogInput; + ::std::shared_ptr m_analogInput; float m_voltsPerG = 1.0; float m_zeroGVoltage = 2.5; bool m_allocatedChannel; - ITable *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 f91c512731..6caf6a6c48 100644 --- a/wpilibc/wpilibC++Devices/include/AnalogInput.h +++ b/wpilibc/wpilibC++Devices/include/AnalogInput.h @@ -10,6 +10,8 @@ #include "PIDSource.h" #include "LiveWindow/LiveWindowSendable.h" +#include + /** * Analog input class. * @@ -60,7 +62,7 @@ class AnalogInput : public SensorBase, void SetAccumulatorDeadband(int32_t deadband); int64_t GetAccumulatorValue() const; uint32_t GetAccumulatorCount() const; - void GetAccumulatorOutput(int64_t *value, uint32_t *count) const; + void GetAccumulatorOutput(int64_t &value, uint32_t &count) const; static void SetSampleRate(float samplesPerSecond); static float GetSampleRate(); @@ -71,13 +73,14 @@ class AnalogInput : public SensorBase, void StartLiveWindowMode() override; void StopLiveWindowMode() override; std::string GetSmartDashboardType() const override; - void InitTable(ITable *subTable) override; - ITable *GetTable() const override; + void InitTable(::std::shared_ptr subTable) override; + ::std::shared_ptr GetTable() const override; private: uint32_t m_channel; + //TODO: Adjust HAL to avoid use of raw pointers. void *m_port; int64_t m_accumulatorOffset; - ITable *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 e0e091ef4f..ef55816af9 100644 --- a/wpilibc/wpilibC++Devices/include/AnalogOutput.h +++ b/wpilibc/wpilibC++Devices/include/AnalogOutput.h @@ -10,6 +10,7 @@ #include "HAL/HAL.hpp" #include "SensorBase.h" #include "LiveWindow/LiveWindowSendable.h" +#include /** * MXP analog output class. @@ -26,12 +27,12 @@ class AnalogOutput : public SensorBase, public LiveWindowSendable { void StartLiveWindowMode() override; void StopLiveWindowMode() override; std::string GetSmartDashboardType() const override; - void InitTable(ITable *subTable) override; - ITable *GetTable() const override; + void InitTable(::std::shared_ptr subTable) override; + ::std::shared_ptr GetTable() const override; protected: uint32_t m_channel; void *m_port; - ITable *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 67920721dd..5c3412fc19 100644 --- a/wpilibc/wpilibC++Devices/include/AnalogPotentiometer.h +++ b/wpilibc/wpilibC++Devices/include/AnalogPotentiometer.h @@ -1,8 +1,9 @@ - #include "AnalogInput.h" #include "interfaces/Potentiometer.h" #include "LiveWindow/LiveWindowSendable.h" +#include + /** * Class for reading analog potentiometers. Analog potentiometers read * in an analog voltage that corresponds to a position. The position is @@ -35,13 +36,18 @@ class AnalogPotentiometer : public Potentiometer, public LiveWindowSendable { explicit AnalogPotentiometer(int channel, double fullRange = 1.0, double offset = 0.0); + [[deprecated( + "Raw pointers are deprecated; if you just want to construct an " + "AnalogPotentiometer with its own AnalogInput, then call the " + "AnalogPotentiometer(int channel). If you want to keep your own copy of " + "the AnalogInput, use std::shared_ptr.")]] explicit AnalogPotentiometer(AnalogInput *input, double fullRange = 1.0, double offset = 0.0); - explicit AnalogPotentiometer(AnalogInput &input, double fullRange = 1.0, - double offset = 0.0); + explicit AnalogPotentiometer(::std::shared_ptr input, + double fullRange = 1.0, double offset = 0.0); - virtual ~AnalogPotentiometer(); + virtual ~AnalogPotentiometer() = default; /** * Get the current reading of the potentiomer. @@ -61,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(ITable *subtable) override; + virtual void InitTable(::std::shared_ptr subtable) override; virtual void UpdateTable() override; - virtual ITable *GetTable() const override; + virtual ::std::shared_ptr GetTable() const override; /** * AnalogPotentiometers don't have to do anything special when entering the @@ -78,13 +84,8 @@ class AnalogPotentiometer : public Potentiometer, public LiveWindowSendable { virtual void StopLiveWindowMode() override {} private: + ::std::shared_ptr m_analog_input; double m_fullRange, m_offset; - AnalogInput *m_analog_input; - ITable *m_table; + ::std::shared_ptr m_table; bool m_init_analog_input; - - /** - * Common initialization code called by all constructors. - */ - void initPot(AnalogInput *input, double fullRange, double offset); }; diff --git a/wpilibc/wpilibC++Devices/include/AnalogTrigger.h b/wpilibc/wpilibC++Devices/include/AnalogTrigger.h index 6b1df97967..b25d84c023 100644 --- a/wpilibc/wpilibC++Devices/include/AnalogTrigger.h +++ b/wpilibc/wpilibC++Devices/include/AnalogTrigger.h @@ -24,10 +24,10 @@ class AnalogTrigger : public SensorBase { void SetLimitsRaw(int32_t lower, int32_t upper); void SetAveraged(bool useAveragedValue); void SetFiltered(bool useFilteredValue); - uint32_t GetIndex(); + uint32_t GetIndex() const; bool GetInWindow(); bool GetTriggerState(); - AnalogTriggerOutput *CreateOutput(AnalogTriggerType type); + ::std::shared_ptr CreateOutput(AnalogTriggerType type) const; private: uint8_t m_index; diff --git a/wpilibc/wpilibC++Devices/include/AnalogTriggerOutput.h b/wpilibc/wpilibC++Devices/include/AnalogTriggerOutput.h index 1e0c54f60f..27ad3b8360 100644 --- a/wpilibc/wpilibC++Devices/include/AnalogTriggerOutput.h +++ b/wpilibc/wpilibC++Devices/include/AnalogTriggerOutput.h @@ -66,9 +66,12 @@ class AnalogTriggerOutput : public DigitalSource { virtual bool GetAnalogTriggerForRouting() const override; protected: - AnalogTriggerOutput(AnalogTrigger *trigger, AnalogTriggerType outputType); + AnalogTriggerOutput(const AnalogTrigger &trigger, AnalogTriggerType outputType); private: - AnalogTrigger *m_trigger; + // Uses reference rather than smart pointer because a user can not construct + // an AnalogTriggerOutput themselves and because the AnalogTriggerOutput + // should always be in scope at the same time as an AnalogTrigger. + const AnalogTrigger &m_trigger; AnalogTriggerType m_outputType; }; diff --git a/wpilibc/wpilibC++Devices/include/BuiltInAccelerometer.h b/wpilibc/wpilibC++Devices/include/BuiltInAccelerometer.h index 2fe26c6c26..a8112519cf 100644 --- a/wpilibc/wpilibC++Devices/include/BuiltInAccelerometer.h +++ b/wpilibc/wpilibC++Devices/include/BuiltInAccelerometer.h @@ -9,6 +9,8 @@ #include "SensorBase.h" #include "LiveWindow/LiveWindowSendable.h" +#include + /** * Built-in accelerometer. * @@ -28,12 +30,12 @@ class BuiltInAccelerometer : public Accelerometer, virtual double GetZ() override; virtual std::string GetSmartDashboardType() const override; - virtual void InitTable(ITable *subtable) override; + virtual void InitTable(::std::shared_ptr subtable) override; virtual void UpdateTable() override; - virtual ITable *GetTable() const override; + virtual ::std::shared_ptr GetTable() const override; virtual void StartLiveWindowMode() override {} virtual void StopLiveWindowMode() override {} private: - ITable *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 068ebe630f..873f698d75 100644 --- a/wpilibc/wpilibC++Devices/include/CANJaguar.h +++ b/wpilibc/wpilibC++Devices/include/CANJaguar.h @@ -20,7 +20,9 @@ #include #include "HAL/cpp/priority_mutex.h" +#include #include +#include /** * Luminary Micro / Vex Robotics Jaguar Speed Control @@ -132,7 +134,7 @@ class CANJaguar : public MotorSafety, void StopMotor() override; bool IsSafetyEnabled() const override; void SetSafetyEnabled(bool enabled) override; - void GetDescription(char *desc) const override; + void GetDescription(std::ostringstream& desc) const override; uint8_t GetDeviceID() const; // SpeedController overrides @@ -228,18 +230,18 @@ class CANJaguar : public MotorSafety, void verify(); - MotorSafetyHelper *m_safetyHelper = nullptr; + std::unique_ptr m_safetyHelper; - void ValueChanged(ITable *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(ITable *subTable) override; - ITable *GetTable() const override; + void InitTable(::std::shared_ptr subTable) override; + ::std::shared_ptr GetTable() const override; - ITable *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 f6dfdec0a3..a3d679a446 100644 --- a/wpilibc/wpilibC++Devices/include/CANTalon.h +++ b/wpilibc/wpilibC++Devices/include/CANTalon.h @@ -14,6 +14,8 @@ #include "LiveWindow/LiveWindowSendable.h" #include "tables/ITable.h" +#include + class CanTalonSRX; /** @@ -42,7 +44,7 @@ class CANTalon : public MotorSafety, }; explicit CANTalon(int deviceNumber); explicit CANTalon(int deviceNumber, int controlPeriodMs); - virtual ~CANTalon(); + virtual ~CANTalon() = default; // PIDOutput interface virtual void PIDWrite(float output) override; @@ -57,7 +59,7 @@ class CANTalon : public MotorSafety, virtual void StopMotor() override; virtual void SetSafetyEnabled(bool enabled) override; virtual bool IsSafetyEnabled() const override; - virtual void GetDescription(char *desc) const override; + virtual void GetDescription(std::ostringstream& desc) const override; // CANSpeedController interface virtual float Get() const override; @@ -155,14 +157,14 @@ class CANTalon : public MotorSafety, double GetSetpoint() const override; // LiveWindow stuff. - void ValueChanged(ITable *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(ITable *subTable) override; - ITable *GetTable() const override; + void InitTable(::std::shared_ptr subTable) override; + ::std::shared_ptr GetTable() const override; // SpeedController overrides virtual void SetInverted(bool isInverted) override; @@ -181,10 +183,10 @@ class CANTalon : public MotorSafety, }; int m_deviceNumber; - CanTalonSRX *m_impl; - MotorSafetyHelper *m_safetyHelper; + std::unique_ptr m_impl; + std::unique_ptr m_safetyHelper; int m_profile = 0; // Profile from CANTalon to use. Set to zero until we can - // actually test this. + // actually test this. bool m_controlEnabled = true; ControlMode m_controlMode = kPercentVbus; @@ -201,6 +203,6 @@ class CANTalon : public MotorSafety, void ApplyControlMode(CANSpeedController::ControlMode mode); // LiveWindow stuff. - ITable *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 df82a05c0b..e8cf2c113f 100644 --- a/wpilibc/wpilibC++Devices/include/Compressor.h +++ b/wpilibc/wpilibC++Devices/include/Compressor.h @@ -12,6 +12,8 @@ #include "tables/ITableListener.h" #include "LiveWindow/LiveWindowSendable.h" +#include + /** * PCM compressor */ @@ -46,9 +48,9 @@ class Compressor : public SensorBase, void StartLiveWindowMode() override; void StopLiveWindowMode() override; std::string GetSmartDashboardType() const override; - void InitTable(ITable *subTable) override; - ITable *GetTable() const override; - void ValueChanged(ITable *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: @@ -57,7 +59,7 @@ class Compressor : public SensorBase, private: void SetCompressor(bool on); - ITable *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 d04c1e1371..5faf3292db 100644 --- a/wpilibc/wpilibC++Devices/include/Counter.h +++ b/wpilibc/wpilibC++Devices/include/Counter.h @@ -12,6 +12,8 @@ #include "SensorBase.h" #include "LiveWindow/LiveWindowSendable.h" +#include + /** * Class for counting the number of ticks on a digital input channel. * This is a general purpose class for counting repetitive events. It can return @@ -29,28 +31,52 @@ class Counter : public SensorBase, public: explicit Counter(Mode mode = kTwoPulse); explicit Counter(int32_t channel); + [[deprecated( + "Raw pointers are deprecated; if you just want to construct a Counter " + "with its own DigitalSource, then call the Counter(int channel). If you " + "want to keep your own copy of the DigitalSource, use " + "std::shared_ptr.")]] explicit Counter(DigitalSource *source); - explicit Counter(DigitalSource &source); + explicit Counter(::std::shared_ptr source); + [[deprecated( + "Raw pointers are deprecated. Use pass-by-reference instead.")]] explicit Counter(AnalogTrigger *trigger); - explicit Counter(AnalogTrigger &trigger); + explicit Counter(const AnalogTrigger &trigger); + [[deprecated( + "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); virtual ~Counter(); void SetUpSource(int32_t channel); + [[deprecated( + "Raw pointers are deprecated; prefer to call either SetUpSource(int) or " + "SetUpSource(shared_ptr).")]] void SetUpSource(AnalogTrigger *analogTrigger, AnalogTriggerType triggerType); - void SetUpSource(AnalogTrigger &analogTrigger, AnalogTriggerType triggerType); + 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); + [[deprecated("References are deprecated. Use std::shared_ptr instead.")]] void SetUpSource(DigitalSource &source); void SetUpSourceEdge(bool risingEdge, bool fallingEdge); void ClearUpSource(); void SetDownSource(int32_t channel); + [[deprecated( + "Raw pointers are deprecated; prefer to call either SetDownSource(int) " + "or SetDownSource(shared_ptr).")]] void SetDownSource(AnalogTrigger *analogTrigger, AnalogTriggerType triggerType); - void SetDownSource(AnalogTrigger &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); + [[deprecated("References are deprecated. Use std::shared_ptr instead.")]] void SetDownSource(DigitalSource &source); void SetDownSourceEdge(bool risingEdge, bool fallingEdge); void ClearDownSource(); @@ -79,17 +105,18 @@ class Counter : public SensorBase, void StartLiveWindowMode() override; void StopLiveWindowMode() override; virtual std::string GetSmartDashboardType() const override; - void InitTable(ITable *subTable) override; - ITable *GetTable() const override; + void InitTable(::std::shared_ptr subTable) override; + ::std::shared_ptr GetTable() const override; protected: - DigitalSource *m_upSource = nullptr; ///< What makes the counter count up. - DigitalSource *m_downSource = nullptr; ///< What makes the counter count down. - void *m_counter = nullptr; ///< The FPGA counter object. + // Makes the counter count up. + ::std::shared_ptr m_upSource; + // Makes the counter count down. + ::std::shared_ptr m_downSource; + // The FPGA counter object + void *m_counter = nullptr; ///< The FPGA counter object. private: - bool m_allocatedUpSource = false; ///< Was the upSource allocated locally? - bool m_allocatedDownSource = false; ///< Was the downSource allocated locally? uint32_t m_index = 0; ///< The index of this counter. - ITable *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 d019fba1a8..a4bce19f77 100644 --- a/wpilibc/wpilibC++Devices/include/DigitalInput.h +++ b/wpilibc/wpilibC++Devices/include/DigitalInput.h @@ -9,6 +9,8 @@ #include "DigitalSource.h" #include "LiveWindow/LiveWindowSendable.h" +#include + /** * Class to read a digital input. * This class will read digital inputs and return the current value on the @@ -35,11 +37,11 @@ class DigitalInput : public DigitalSource, public LiveWindowSendable { void StartLiveWindowMode(); void StopLiveWindowMode(); std::string GetSmartDashboardType() const; - void InitTable(ITable *subTable); - ITable *GetTable() const; + void InitTable(::std::shared_ptr subTable); + ::std::shared_ptr GetTable() const; private: uint32_t m_channel; - ITable *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 b73b141a6f..ce72fed76f 100644 --- a/wpilibc/wpilibC++Devices/include/DigitalOutput.h +++ b/wpilibc/wpilibC++Devices/include/DigitalOutput.h @@ -10,6 +10,8 @@ #include "LiveWindow/LiveWindowSendable.h" #include "tables/ITableListener.h" +#include + /** * Class to write to digital outputs. * Write values to the digital output channels. Other devices implemented @@ -36,18 +38,18 @@ class DigitalOutput : public DigitalSource, virtual uint32_t GetModuleForRouting() const; virtual bool GetAnalogTriggerForRouting() const; - virtual void ValueChanged(ITable *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(ITable *subTable); - ITable *GetTable() const; + void InitTable(::std::shared_ptr subTable); + ::std::shared_ptr GetTable() const; private: uint32_t m_channel; void *m_pwmGenerator; - ITable *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 48ab49c107..0e883bea4b 100644 --- a/wpilibc/wpilibC++Devices/include/DoubleSolenoid.h +++ b/wpilibc/wpilibC++Devices/include/DoubleSolenoid.h @@ -10,6 +10,8 @@ #include "LiveWindow/LiveWindowSendable.h" #include "tables/ITableListener.h" +#include + /** * DoubleSolenoid class for running 2 channels of high voltage Digital Output * (PCM). @@ -32,14 +34,14 @@ class DoubleSolenoid : public SolenoidBase, bool IsFwdSolenoidBlackListed() const; bool IsRevSolenoidBlackListed() const; - void ValueChanged(ITable* 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(ITable* subTable); - ITable* 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. @@ -47,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. - ITable* m_table = nullptr; + ::std::shared_ptr m_table = nullptr; }; diff --git a/wpilibc/wpilibC++Devices/include/DriverStation.h b/wpilibc/wpilibC++Devices/include/DriverStation.h index ce278f49ac..f2918f2d53 100644 --- a/wpilibc/wpilibC++Devices/include/DriverStation.h +++ b/wpilibc/wpilibC++Devices/include/DriverStation.h @@ -27,7 +27,7 @@ class DriverStation : public SensorBase, public RobotStateInterface { enum Alliance { kRed, kBlue, kInvalid }; virtual ~DriverStation(); - static DriverStation *GetInstance(); + static DriverStation &GetInstance(); static void ReportError(std::string error); static const uint32_t kJoystickPorts = 6; diff --git a/wpilibc/wpilibC++Devices/include/Encoder.h b/wpilibc/wpilibC++Devices/include/Encoder.h index 9b0f859bc6..9e4ed839cd 100644 --- a/wpilibc/wpilibC++Devices/include/Encoder.h +++ b/wpilibc/wpilibC++Devices/include/Encoder.h @@ -13,6 +13,8 @@ #include "PIDSource.h" #include "LiveWindow/LiveWindowSendable.h" +#include + class DigitalSource; /** @@ -47,8 +49,19 @@ 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, + bool reverseDirection = false, EncodingType encodingType = k4X); + [[deprecated( + "Raw pointers are deprecated; if you wish to construct your own copy of " + "the DigitalSource and pass it to the constructor, use an " + "std::shared_ptr instead.")]] Encoder(DigitalSource *aSource, DigitalSource *bSource, bool reverseDirection = false, EncodingType encodingType = k4X); + [[deprecated( + "References are deprecated; if you wish to construct your own copy of " + "the DigitalSource and pass it to the constructor, use an " + "std::shared_ptr instead.")]] Encoder(DigitalSource &aSource, DigitalSource &bSource, bool reverseDirection = false, EncodingType encodingType = k4X); virtual ~Encoder(); @@ -74,17 +87,18 @@ class Encoder : public SensorBase, double PIDGet() const override; void SetIndexSource(uint32_t channel, IndexingType type = kResetOnRisingEdge); + [[deprecated("Raw pointers are deprecated; use references instead.")]] void SetIndexSource(DigitalSource *source, IndexingType type = kResetOnRisingEdge); - void SetIndexSource(DigitalSource &source, + void SetIndexSource(const DigitalSource &source, IndexingType type = kResetOnRisingEdge); void UpdateTable() override; void StartLiveWindowMode() override; void StopLiveWindowMode() override; std::string GetSmartDashboardType() const override; - void InitTable(ITable *subTable) override; - ITable *GetTable() const override; + void InitTable(::std::shared_ptr subTable) override; + ::std::shared_ptr GetTable() const override; int32_t GetFPGAIndex() const { return m_index; } @@ -92,18 +106,17 @@ class Encoder : public SensorBase, void InitEncoder(bool _reverseDirection, EncodingType encodingType); double DecodingScaleFactor() const; - DigitalSource *m_aSource; // the A phase of the quad encoder - DigitalSource *m_bSource; // the B phase of the quad encoder - bool m_allocatedASource; // was the A source allocated locally? - bool m_allocatedBSource; // was the B source allocated locally? + ::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 - Counter *m_counter = nullptr; // Counter object for 1x and 2x encoding + ::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 - ITable *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 fd6a4bac32..7b28fa4f32 100644 --- a/wpilibc/wpilibC++Devices/include/GearTooth.h +++ b/wpilibc/wpilibC++Devices/include/GearTooth.h @@ -7,6 +7,7 @@ #pragma once #include "Counter.h" +#include /** * Alias for counter class. @@ -22,7 +23,8 @@ class GearTooth : public Counter { static constexpr double kGearToothThreshold = 55e-6; GearTooth(uint32_t channel, bool directionSensitive = false); GearTooth(DigitalSource *source, bool directionSensitive = false); - GearTooth(DigitalSource &source, bool directionSensitive = false); + 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 598f9d95f1..f89c31f941 100644 --- a/wpilibc/wpilibC++Devices/include/Gyro.h +++ b/wpilibc/wpilibC++Devices/include/Gyro.h @@ -10,6 +10,8 @@ #include "PIDSource.h" #include "LiveWindow/LiveWindowSendable.h" +#include + class AnalogInput; /** @@ -37,9 +39,12 @@ class Gyro : public SensorBase, public PIDSource, public LiveWindowSendable { static constexpr float kDefaultVoltsPerDegreePerSecond = 0.007; explicit Gyro(int32_t channel); + [[deprecated( + "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(AnalogInput &channel); - virtual ~Gyro(); + explicit Gyro(::std::shared_ptr channel); + virtual ~Gyro() = default; virtual float GetAngle() const; virtual double GetRate() const; void SetSensitivity(float voltsPerDegreePerSecond); @@ -55,18 +60,17 @@ class Gyro : public SensorBase, public PIDSource, public LiveWindowSendable { void StartLiveWindowMode() override; void StopLiveWindowMode() override; std::string GetSmartDashboardType() const override; - void InitTable(ITable *subTable) override; - ITable *GetTable() const override; + void InitTable(::std::shared_ptr subTable) override; + ::std::shared_ptr GetTable() const override; protected: - AnalogInput *m_analog; + ::std::shared_ptr m_analog; private: float m_voltsPerDegreePerSecond; float m_offset; - bool m_channelAllocated; uint32_t m_center; PIDSourceParameter m_pidSource; - ITable *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 07e961cb04..b64f148672 100644 --- a/wpilibc/wpilibC++Devices/include/InterruptableSensorBase.h +++ b/wpilibc/wpilibC++Devices/include/InterruptableSensorBase.h @@ -10,6 +10,8 @@ #include "SensorBase.h" #include "Resource.h" +#include + class InterruptableSensorBase : public SensorBase { public: enum WaitResult { @@ -46,5 +48,5 @@ class InterruptableSensorBase : public SensorBase { uint32_t m_interruptIndex; void AllocateInterrupts(bool watcher); - static Resource *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 94ad3714d4..11920e4d4f 100644 --- a/wpilibc/wpilibC++Devices/include/Joystick.h +++ b/wpilibc/wpilibC++Devices/include/Joystick.h @@ -9,6 +9,8 @@ #define JOYSTICK_H_ #include +#include +#include #include "GenericHID.h" #include "ErrorBase.h" @@ -62,7 +64,7 @@ class Joystick : public GenericHID, public ErrorBase { } HIDType; explicit Joystick(uint32_t port); Joystick(uint32_t port, uint32_t numAxisTypes, uint32_t numButtonTypes); - virtual ~Joystick(); + virtual ~Joystick() = default; uint32_t GetAxisChannel(AxisType axis) const; void SetAxisChannel(AxisType axis, uint32_t channel); @@ -103,10 +105,10 @@ class Joystick : public GenericHID, public ErrorBase { private: DISALLOW_COPY_AND_ASSIGN(Joystick); - DriverStation *m_ds = nullptr; + DriverStation &m_ds; uint32_t m_port; - uint32_t *m_axes = nullptr; - uint32_t *m_buttons = nullptr; + ::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/MotorSafety.h b/wpilibc/wpilibC++Devices/include/MotorSafety.h index e7e8c8b945..6963ae792c 100644 --- a/wpilibc/wpilibC++Devices/include/MotorSafety.h +++ b/wpilibc/wpilibC++Devices/include/MotorSafety.h @@ -8,6 +8,8 @@ #define DEFAULT_SAFETY_EXPIRATION 0.1 +#include + class MotorSafety { public: virtual void SetExpiration(float timeout) = 0; @@ -16,5 +18,5 @@ class MotorSafety { virtual void StopMotor() = 0; virtual void SetSafetyEnabled(bool enabled) = 0; virtual bool IsSafetyEnabled() const = 0; - virtual void GetDescription(char *desc) const = 0; + virtual void GetDescription(std::ostringstream& desc) const = 0; }; diff --git a/wpilibc/wpilibC++Devices/include/MotorSafetyHelper.h b/wpilibc/wpilibC++Devices/include/MotorSafetyHelper.h index 8381567c60..3e2f97e1dd 100644 --- a/wpilibc/wpilibC++Devices/include/MotorSafetyHelper.h +++ b/wpilibc/wpilibC++Devices/include/MotorSafetyHelper.h @@ -9,6 +9,8 @@ #include "ErrorBase.h" #include "HAL/cpp/priority_mutex.h" +#include + class MotorSafety; class MotorSafetyHelper : public ErrorBase { @@ -31,10 +33,8 @@ class MotorSafetyHelper : public ErrorBase { mutable priority_recursive_mutex m_syncMutex; // protect accesses to the state for this object MotorSafety *m_safeObject; // the object that is using the helper - MotorSafetyHelper * - m_nextHelper; // next object in the list of MotorSafetyHelpers - static MotorSafetyHelper * - m_headHelper; // the head of the list of MotorSafetyHelper objects + // List of all existing MotorSafetyHelper objects. + 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 ca874c4098..425ce2a338 100644 --- a/wpilibc/wpilibC++Devices/include/PWM.h +++ b/wpilibc/wpilibC++Devices/include/PWM.h @@ -10,6 +10,8 @@ #include "LiveWindow/LiveWindowSendable.h" #include "tables/ITableListener.h" +#include + /** * Class implements the PWM generation in the FPGA. * @@ -97,16 +99,16 @@ class PWM : public SensorBase, int32_t m_deadbandMinPwm; int32_t m_minPwm; - void ValueChanged(ITable* 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(ITable* subTable) override; - ITable* GetTable() const override; + void InitTable(::std::shared_ptr subTable) override; + ::std::shared_ptr GetTable() const override; - ITable* 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 44a873d813..0c87c63cf0 100644 --- a/wpilibc/wpilibC++Devices/include/PowerDistributionPanel.h +++ b/wpilibc/wpilibC++Devices/include/PowerDistributionPanel.h @@ -12,6 +12,8 @@ #include "SensorBase.h" #include "LiveWindow/LiveWindowSendable.h" +#include + /** * Class for getting voltage, current, temperature, power and energy from the * CAN PDP. @@ -36,11 +38,11 @@ class PowerDistributionPanel : public SensorBase, public LiveWindowSendable { void StartLiveWindowMode() override; void StopLiveWindowMode() override; std::string GetSmartDashboardType() const override; - void InitTable(ITable *subTable) override; - ITable *GetTable() const override; + void InitTable(::std::shared_ptr subTable) override; + ::std::shared_ptr GetTable() const override; private: - ITable *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 927af5f8c0..c6b5a12a6a 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(ITable *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 9279a1ec5b..186ab68d59 100644 --- a/wpilibc/wpilibC++Devices/include/Relay.h +++ b/wpilibc/wpilibC++Devices/include/Relay.h @@ -11,6 +11,8 @@ #include "LiveWindow/LiveWindowSendable.h" #include "tables/ITable.h" +#include + /** * Class for Spike style relay outputs. * Relays are intended to be connected to spikes or similar relays. The relay @@ -38,16 +40,16 @@ class Relay : public SensorBase, void Set(Value value); Value Get() const; - void ValueChanged(ITable* 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(ITable* subTable) override; - ITable* GetTable() const override; + void InitTable(::std::shared_ptr subTable) override; + ::std::shared_ptr GetTable() const override; - ITable* m_table = nullptr; + ::std::shared_ptr m_table = nullptr; private: uint32_t m_channel; diff --git a/wpilibc/wpilibC++Devices/include/RobotBase.h b/wpilibc/wpilibC++Devices/include/RobotBase.h index 25bb6d4181..4c4b23f74d 100644 --- a/wpilibc/wpilibC++Devices/include/RobotBase.h +++ b/wpilibc/wpilibC++Devices/include/RobotBase.h @@ -62,7 +62,7 @@ class RobotBase { virtual void Prestart(); Task *m_task = nullptr; - DriverStation *m_ds = nullptr; + DriverStation &m_ds; private: static RobotBase *m_instance; diff --git a/wpilibc/wpilibC++Devices/include/RobotDrive.h b/wpilibc/wpilibC++Devices/include/RobotDrive.h index 04d46bf403..8078a973e6 100644 --- a/wpilibc/wpilibC++Devices/include/RobotDrive.h +++ b/wpilibc/wpilibC++Devices/include/RobotDrive.h @@ -8,6 +8,8 @@ #include "ErrorBase.h" #include +#include +#include #include "HAL/HAL.hpp" #include "MotorSafety.h" #include "MotorSafetyHelper.h" @@ -42,13 +44,23 @@ class RobotDrive : public MotorSafety, public ErrorBase { RobotDrive(uint32_t leftMotorChannel, uint32_t rightMotorChannel); RobotDrive(uint32_t frontLeftMotorChannel, uint32_t rearLeftMotorChannel, uint32_t frontRightMotorChannel, uint32_t rearRightMotorChannel); + [[deprecated("Raw pointers are deprecated; use shared_ptr instead.")]] 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); + [[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); - virtual ~RobotDrive(); + RobotDrive(::std::shared_ptr frontLeftMotor, + ::std::shared_ptr rearLeftMotor, + ::std::shared_ptr frontRightMotor, + ::std::shared_ptr rearRightMotor); + virtual ~RobotDrive() = default; void Drive(float outputMagnitude, float curve); void TankDrive(GenericHID *leftStick, GenericHID *rightStick, @@ -88,7 +100,7 @@ class RobotDrive : public MotorSafety, public ErrorBase { void StopMotor() override; bool IsSafetyEnabled() const override; void SetSafetyEnabled(bool enabled) override; - void GetDescription(char *desc) const override; + void GetDescription(std::ostringstream& desc) const override; protected: void InitRobotDrive(); @@ -99,12 +111,11 @@ class RobotDrive : public MotorSafety, public ErrorBase { static const int32_t kMaxNumberOfMotors = 4; float m_sensitivity = 0.5; double m_maxOutput = 1.0; - bool m_deleteSpeedControllers; - SpeedController *m_frontLeftMotor = nullptr; - SpeedController *m_frontRightMotor = nullptr; - SpeedController *m_rearLeftMotor = nullptr; - SpeedController *m_rearRightMotor = nullptr; - MotorSafetyHelper *m_safetyHelper = 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; private: diff --git a/wpilibc/wpilibC++Devices/include/SafePWM.h b/wpilibc/wpilibC++Devices/include/SafePWM.h index f672dc6210..f364626d21 100644 --- a/wpilibc/wpilibC++Devices/include/SafePWM.h +++ b/wpilibc/wpilibC++Devices/include/SafePWM.h @@ -8,8 +8,9 @@ #include "MotorSafety.h" #include "PWM.h" - -class MotorSafetyHelper; +#include "MotorSafetyHelper.h" +#include +#include /** * A safe version of the PWM class. @@ -23,7 +24,7 @@ class MotorSafetyHelper; class SafePWM : public PWM, public MotorSafety { public: explicit SafePWM(uint32_t channel); - ~SafePWM(); + virtual ~SafePWM() = default; void SetExpiration(float timeout); float GetExpiration() const; @@ -31,10 +32,10 @@ class SafePWM : public PWM, public MotorSafety { void StopMotor(); bool IsSafetyEnabled() const; void SetSafetyEnabled(bool enabled); - void GetDescription(char *desc) const; + void GetDescription(std::ostringstream& desc) const; virtual void SetSpeed(float speed); private: - MotorSafetyHelper *m_safetyHelper; + std::unique_ptr m_safetyHelper; }; diff --git a/wpilibc/wpilibC++Devices/include/Servo.h b/wpilibc/wpilibC++Devices/include/Servo.h index 8386023fff..bc9d10ee59 100644 --- a/wpilibc/wpilibC++Devices/include/Servo.h +++ b/wpilibc/wpilibC++Devices/include/Servo.h @@ -9,6 +9,8 @@ #include "SafePWM.h" #include "SpeedController.h" +#include + /** * Standard hobby style servo. * @@ -28,16 +30,16 @@ class Servo : public SafePWM { static float GetMaxAngle() { return kMaxServoAngle; } static float GetMinAngle() { return kMinServoAngle; } - void ValueChanged(ITable* 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(ITable* subTable) override; - ITable* GetTable() const override; + void InitTable(::std::shared_ptr subTable) override; + ::std::shared_ptr GetTable() const override; - ITable* 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 a760413805..ab0aff6d91 100644 --- a/wpilibc/wpilibC++Devices/include/Solenoid.h +++ b/wpilibc/wpilibC++Devices/include/Solenoid.h @@ -10,6 +10,8 @@ #include "LiveWindow/LiveWindowSendable.h" #include "tables/ITableListener.h" +#include + /** * Solenoid class for running high voltage Digital Output (PCM). * @@ -28,16 +30,16 @@ class Solenoid : public SolenoidBase, virtual bool Get() const; bool IsBlackListed() const; - void ValueChanged(ITable* 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(ITable* subTable); - ITable* 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. - ITable* 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 3c864a2186..2732e86219 100644 --- a/wpilibc/wpilibC++Devices/include/SolenoidBase.h +++ b/wpilibc/wpilibC++Devices/include/SolenoidBase.h @@ -11,6 +11,8 @@ #include "HAL/HAL.hpp" #include "Port.h" +#include + /** * SolenoidBase class is the common base class for the Solenoid and * DoubleSolenoid classes. @@ -33,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 Resource* 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 420fadf5f2..6ac4d18ead 100644 --- a/wpilibc/wpilibC++Devices/include/Ultrasonic.h +++ b/wpilibc/wpilibC++Devices/include/Ultrasonic.h @@ -7,6 +7,7 @@ #pragma once #include "SensorBase.h" +#include "Counter.h" #include "Task.h" #include "PIDSource.h" #include "LiveWindow/LiveWindowSendable.h" @@ -14,7 +15,8 @@ #include "HAL/cpp/priority_mutex.h" -class Counter; +#include + class DigitalInput; class DigitalOutput; @@ -40,10 +42,21 @@ class Ultrasonic : public SensorBase, public: enum DistanceUnit { kInches = 0, kMilliMeters = 1 }; + [[deprecated( + "Raw pointers are deprecated; prefer either specifying the channel " + "numbers as integers or passing shared_ptrs.")]] Ultrasonic(DigitalOutput *pingChannel, DigitalInput *echoChannel, DistanceUnit units = kInches); + + [[deprecated( + "References are deprecated; prefer either specifying the channel numbers " + "as integers or passing shared_ptrs.")]] Ultrasonic(DigitalOutput &pingChannel, DigitalInput &echoChannel, DistanceUnit units = kInches); + + Ultrasonic(::std::shared_ptr pingChannel, + ::std::shared_ptr echoChannel, + DistanceUnit units = kInches); Ultrasonic(uint32_t pingChannel, uint32_t echoChannel, DistanceUnit units = kInches); virtual ~Ultrasonic(); @@ -64,8 +77,8 @@ class Ultrasonic : public SensorBase, void StartLiveWindowMode() override; void StopLiveWindowMode() override; std::string GetSmartDashboardType() const override; - void InitTable(ITable *subTable) override; - ITable *GetTable() const override; + void InitTable(::std::shared_ptr subTable) override; + ::std::shared_ptr GetTable() const override; private: void Initialize(); @@ -85,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 - DigitalInput *m_echoChannel; - DigitalOutput *m_pingChannel; + ::std::shared_ptr m_pingChannel; + ::std::shared_ptr m_echoChannel; bool m_allocatedChannels; bool m_enabled; - Counter *m_counter; + Counter m_counter; Ultrasonic *m_nextSensor; DistanceUnit m_units; - ITable *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 5ebdb08c02..5287e58459 100644 --- a/wpilibc/wpilibC++Devices/src/ADXL345_I2C.cpp +++ b/wpilibc/wpilibC++Devices/src/ADXL345_I2C.cpp @@ -32,7 +32,7 @@ ADXL345_I2C::ADXL345_I2C(Port port, Range range) : I2C(port, kAddress) { HALReport(HALUsageReporting::kResourceType_ADXL345, HALUsageReporting::kADXL345_I2C, 0); - LiveWindow::GetInstance()->AddSensor("ADXL345_I2C", port, this); + LiveWindow::GetInstance().AddSensor("ADXL345_I2C", port, this); } /** {@inheritdoc} */ @@ -88,17 +88,15 @@ std::string ADXL345_I2C::GetSmartDashboardType() const { return "3AxisAccelerometer"; } -void ADXL345_I2C::InitTable(ITable *subtable) { +void ADXL345_I2C::InitTable(::std::shared_ptr subtable) { m_table = subtable; UpdateTable(); } void ADXL345_I2C::UpdateTable() { - if (m_table != nullptr) { - m_table->PutNumber("X", GetX()); - m_table->PutNumber("Y", GetY()); - m_table->PutNumber("Z", GetZ()); - } + m_table->PutNumber("X", GetX()); + m_table->PutNumber("Y", GetY()); + m_table->PutNumber("Z", GetZ()); } -ITable *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 7e430ced6b..ef742a6ea8 100644 --- a/wpilibc/wpilibC++Devices/src/ADXL345_SPI.cpp +++ b/wpilibc/wpilibC++Devices/src/ADXL345_SPI.cpp @@ -25,14 +25,14 @@ constexpr double ADXL345_SPI::kGsPerLSB; ADXL345_SPI::ADXL345_SPI(SPI::Port port, ADXL345_SPI::Range range) { m_port = port; Init(range); - LiveWindow::GetInstance()->AddSensor("ADXL345_SPI", port, this); + LiveWindow::GetInstance().AddSensor("ADXL345_SPI", port, this); } /** * Internal common init function. */ void ADXL345_SPI::Init(Range range) { - m_spi = new SPI(m_port); + m_spi = std::make_unique(m_port); m_spi->SetClockRate(500000); m_spi->SetMSBFirst(); m_spi->SetSampleDataOnFalling(); @@ -51,14 +51,6 @@ void ADXL345_SPI::Init(Range range) { HALUsageReporting::kADXL345_SPI); } -/** - * Destructor. - */ -ADXL345_SPI::~ADXL345_SPI() { - delete m_spi; - m_spi = nullptr; -} - /** {@inheritdoc} */ void ADXL345_SPI::SetRange(Range range) { uint8_t commands[2]; @@ -130,7 +122,7 @@ std::string ADXL345_SPI::GetSmartDashboardType() const { return "3AxisAccelerometer"; } -void ADXL345_SPI::InitTable(ITable* subtable) { +void ADXL345_SPI::InitTable(::std::shared_ptr subtable) { m_table = subtable; UpdateTable(); } @@ -143,4 +135,4 @@ void ADXL345_SPI::UpdateTable() { } } -ITable* 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 45b5743b84..e33645c6c2 100644 --- a/wpilibc/wpilibC++Devices/src/AnalogAccelerometer.cpp +++ b/wpilibc/wpilibC++Devices/src/AnalogAccelerometer.cpp @@ -15,9 +15,9 @@ */ void AnalogAccelerometer::InitAccelerometer() { HALReport(HALUsageReporting::kResourceType_Accelerometer, - m_AnalogInput->GetChannel()); - LiveWindow::GetInstance()->AddSensor("Accelerometer", - m_AnalogInput->GetChannel(), this); + m_analogInput->GetChannel()); + LiveWindow::GetInstance().AddSensor("Accelerometer", + m_analogInput->GetChannel(), this); } /** @@ -27,37 +27,41 @@ void AnalogAccelerometer::InitAccelerometer() { * connected to */ AnalogAccelerometer::AnalogAccelerometer(int32_t channel) { - m_AnalogInput = new AnalogInput(channel); - m_allocatedChannel = true; + m_analogInput = ::std::make_shared(channel); InitAccelerometer(); } /** * Create a new instance of Accelerometer from an existing AnalogInput. * Make a new instance of accelerometer given an AnalogInput. This is - * particularly - * useful if the port is going to be read as an analog channel as well as - * through - * the Accelerometer class. + * particularly useful if the port is going to be read as an analog channel as + * well as through the Accelerometer class. * @param channel The existing AnalogInput object for the analog input the * accelerometer is connected to */ -AnalogAccelerometer::AnalogAccelerometer(AnalogInput *channel) { +AnalogAccelerometer::AnalogAccelerometer(AnalogInput *channel) + : m_analogInput(channel, NullDeleter()) { if (channel == nullptr) { wpi_setWPIError(NullParameter); } else { - m_AnalogInput = channel; InitAccelerometer(); } - m_allocatedChannel = false; } /** - * Delete the analog components used for the accelerometer. + * Create a new instance of Accelerometer from an existing AnalogInput. + * Make a new instance of accelerometer given an AnalogInput. This is + * particularly useful if the port is going to be read as an analog channel as + * well as through the Accelerometer class. + * @param channel The existing AnalogInput object for the analog input the + * accelerometer is connected to */ -AnalogAccelerometer::~AnalogAccelerometer() { - if (m_allocatedChannel) { - delete m_AnalogInput; +AnalogAccelerometer::AnalogAccelerometer(::std::shared_ptr channel) + : m_analogInput(channel) { + if (channel == nullptr) { + wpi_setWPIError(NullParameter); + } else { + InitAccelerometer(); } } @@ -69,7 +73,7 @@ AnalogAccelerometer::~AnalogAccelerometer() { * @return The current acceleration of the sensor in Gs. */ float AnalogAccelerometer::GetAcceleration() const { - return (m_AnalogInput->GetAverageVoltage() - m_zeroGVoltage) / m_voltsPerG; + return (m_analogInput->GetAverageVoltage() - m_zeroGVoltage) / m_voltsPerG; } /** @@ -117,9 +121,9 @@ std::string AnalogAccelerometer::GetSmartDashboardType() const { return "Accelerometer"; } -void AnalogAccelerometer::InitTable(ITable *subTable) { +void AnalogAccelerometer::InitTable(::std::shared_ptr subTable) { m_table = subTable; UpdateTable(); } -ITable *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 ef3ab5915d..e063909ba3 100644 --- a/wpilibc/wpilibC++Devices/src/AnalogInput.cpp +++ b/wpilibc/wpilibC++Devices/src/AnalogInput.cpp @@ -11,7 +11,7 @@ #include "WPIErrors.h" #include "LiveWindow/LiveWindow.h" -static Resource *inputs = nullptr; +static ::std::unique_ptr inputs; const uint8_t AnalogInput::kAccumulatorModuleNumber; const uint32_t AnalogInput::kAccumulatorNumChannels; @@ -25,7 +25,7 @@ const uint32_t AnalogInput::kAccumulatorChannels[] = {0, 1}; */ AnalogInput::AnalogInput(uint32_t channel) { char buf[64]; - Resource::CreateResourceObject(&inputs, kAnalogInputs); + Resource::CreateResourceObject(inputs, kAnalogInputs); if (!checkAnalogInputChannel(channel)) { snprintf(buf, 64, "analog input %d", channel); @@ -35,7 +35,7 @@ AnalogInput::AnalogInput(uint32_t channel) { snprintf(buf, 64, "Analog Input %d", channel); if (inputs->Allocate(channel, buf) == ~0ul) { - CloneError(inputs); + CloneError(*inputs); return; } @@ -46,7 +46,7 @@ AnalogInput::AnalogInput(uint32_t channel) { m_port = initializeAnalogInputPort(port, &status); wpi_setErrorWithContext(status, getHALErrorMessage(status)); - LiveWindow::GetInstance()->AddSensor("AnalogInput", channel, this); + LiveWindow::GetInstance().AddSensor("AnalogInput", channel, this); HALReport(HALUsageReporting::kResourceType_AnalogChannel, channel); } @@ -353,15 +353,15 @@ uint32_t AnalogInput::GetAccumulatorCount() const { * This function reads the value and count from the FPGA atomically. * This can be used for averaging. * - * @param value Pointer to the 64-bit accumulated output. - * @param count Pointer to the number of accumulation cycles. + * @param value Reference to the 64-bit accumulated output. + * @param count Reference to the number of accumulation cycles. */ -void AnalogInput::GetAccumulatorOutput(int64_t *value, uint32_t *count) const { +void AnalogInput::GetAccumulatorOutput(int64_t &value, uint32_t &count) const { if (StatusIsFatal()) return; int32_t status = 0; - getAccumulatorOutput(m_port, value, count, &status); + getAccumulatorOutput(m_port, &value, &count, &status); wpi_setErrorWithContext(status, getHALErrorMessage(status)); - *value += m_accumulatorOffset; + value += m_accumulatorOffset; } /** @@ -412,9 +412,9 @@ std::string AnalogInput::GetSmartDashboardType() const { return "Analog Input"; } -void AnalogInput::InitTable(ITable *subTable) { +void AnalogInput::InitTable(::std::shared_ptr subTable) { m_table = subTable; UpdateTable(); } -ITable *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 c6f2def0c2..e449b4a177 100644 --- a/wpilibc/wpilibC++Devices/src/AnalogOutput.cpp +++ b/wpilibc/wpilibC++Devices/src/AnalogOutput.cpp @@ -10,7 +10,7 @@ #include "WPIErrors.h" #include "LiveWindow/LiveWindow.h" -static Resource *outputs = nullptr; +static ::std::unique_ptr outputs; /** * Construct an analog output on the given channel. @@ -18,7 +18,7 @@ static Resource *outputs = nullptr; * @param The channel number on the roboRIO to represent. */ AnalogOutput::AnalogOutput(uint32_t channel) { - Resource::CreateResourceObject(&outputs, kAnalogOutputs); + Resource::CreateResourceObject(outputs, kAnalogOutputs); char buf[64]; @@ -29,7 +29,7 @@ AnalogOutput::AnalogOutput(uint32_t channel) { } if (outputs->Allocate(channel, buf) == ~0ul) { - CloneError(outputs); + CloneError(*outputs); return; } @@ -40,7 +40,7 @@ AnalogOutput::AnalogOutput(uint32_t channel) { m_port = initializeAnalogOutputPort(port, &status); wpi_setErrorWithContext(status, getHALErrorMessage(status)); - LiveWindow::GetInstance()->AddActuator("AnalogOutput", m_channel, this); + LiveWindow::GetInstance().AddActuator("AnalogOutput", m_channel, this); HALReport(HALUsageReporting::kResourceType_AnalogOutput, m_channel); } @@ -89,9 +89,9 @@ std::string AnalogOutput::GetSmartDashboardType() const { return "Analog Output"; } -void AnalogOutput::InitTable(ITable *subTable) { +void AnalogOutput::InitTable(::std::shared_ptr subTable) { m_table = subTable; UpdateTable(); } -ITable *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 c529fa39a9..74152a2096 100644 --- a/wpilibc/wpilibC++Devices/src/AnalogPotentiometer.cpp +++ b/wpilibc/wpilibC++Devices/src/AnalogPotentiometer.cpp @@ -1,17 +1,6 @@ - #include "AnalogPotentiometer.h" #include "ControllerPower.h" -/** - * Common initialization code called by all constructors. - */ -void AnalogPotentiometer::initPot(AnalogInput *input, double fullRange, - double offset) { - m_fullRange = fullRange; - m_offset = offset; - m_analog_input = input; -} - /** * Construct an Analog Potentiometer object from a channel number. * @param channel The channel number on the roboRIO to represent. 0-3 are @@ -22,10 +11,10 @@ void AnalogPotentiometer::initPot(AnalogInput *input, double fullRange, * output at 0V. */ AnalogPotentiometer::AnalogPotentiometer(int channel, double fullRange, - double offset) { - m_init_analog_input = true; - initPot(new AnalogInput(channel), fullRange, offset); -} + double offset) + : m_analog_input(::std::make_unique(channel)), + m_fullRange(fullRange), + m_offset(offset) {} /** * Construct an Analog Potentiometer object from an existing Analog Input @@ -37,36 +26,23 @@ AnalogPotentiometer::AnalogPotentiometer(int channel, double fullRange, * output at 0V. */ AnalogPotentiometer::AnalogPotentiometer(AnalogInput *input, double fullRange, - double offset) { - m_init_analog_input = false; - initPot(input, fullRange, offset); -} + double offset) + : m_analog_input(input, NullDeleter()), + m_fullRange(fullRange), + m_offset(offset) {} /** * Construct an Analog Potentiometer object from an existing Analog Input - * reference. - * @param channel The existing Analog Input reference + * pointer. + * @param channel The existing Analog Input pointer * @param fullRange The angular value (in desired units) representing the full * 0-5V range of the input. * @param offset The angular value (in desired units) representing the angular * output at 0V. */ -AnalogPotentiometer::AnalogPotentiometer(AnalogInput &input, double fullRange, - double offset) { - m_init_analog_input = false; - initPot(&input, fullRange, offset); -} - -/** - * Destructor. Releases the Analog Input resource if it was allocated by this - * object - */ -AnalogPotentiometer::~AnalogPotentiometer() { - if (m_init_analog_input) { - delete m_analog_input; - m_init_analog_input = false; - } -} +AnalogPotentiometer::AnalogPotentiometer(::std::shared_ptr input, + double fullRange, double offset) + : m_analog_input(input), m_fullRange(fullRange), m_offset(offset) {} /** * Get the current reading of the potentiometer. @@ -97,7 +73,7 @@ std::string AnalogPotentiometer::GetSmartDashboardType() const { /** * Live Window code, only does anything if live window is activated. */ -void AnalogPotentiometer::InitTable(ITable *subtable) { +void AnalogPotentiometer::InitTable(::std::shared_ptr subtable) { m_table = subtable; UpdateTable(); } @@ -108,4 +84,4 @@ void AnalogPotentiometer::UpdateTable() { } } -ITable *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 9289a2ca58..de9b92f6cc 100644 --- a/wpilibc/wpilibC++Devices/src/AnalogTrigger.cpp +++ b/wpilibc/wpilibC++Devices/src/AnalogTrigger.cpp @@ -11,6 +11,7 @@ //#include "NetworkCommunication/UsageReporting.h" #include "Resource.h" #include "WPIErrors.h" +#include /** * Constructor for an analog trigger given a channel number. @@ -109,7 +110,7 @@ void AnalogTrigger::SetFiltered(bool useFilteredValue) { * This is the FPGA index of this analog trigger instance. * @return The index of the analog trigger. */ -uint32_t AnalogTrigger::GetIndex() { +uint32_t AnalogTrigger::GetIndex() const { if (StatusIsFatal()) return ~0ul; return m_index; } @@ -150,7 +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. */ -AnalogTriggerOutput *AnalogTrigger::CreateOutput(AnalogTriggerType type) { +::std::shared_ptr AnalogTrigger::CreateOutput( + AnalogTriggerType type) const { if (StatusIsFatal()) return nullptr; - return new AnalogTriggerOutput(this, type); + return ::std::shared_ptr( + new AnalogTriggerOutput(*this, type), NullDeleter()); } diff --git a/wpilibc/wpilibC++Devices/src/AnalogTriggerOutput.cpp b/wpilibc/wpilibC++Devices/src/AnalogTriggerOutput.cpp index 68348e54fc..9d75fbb7ab 100644 --- a/wpilibc/wpilibC++Devices/src/AnalogTriggerOutput.cpp +++ b/wpilibc/wpilibC++Devices/src/AnalogTriggerOutput.cpp @@ -22,11 +22,11 @@ * @param outputType An enum that specifies the output on the trigger to * represent. */ -AnalogTriggerOutput::AnalogTriggerOutput(AnalogTrigger *trigger, +AnalogTriggerOutput::AnalogTriggerOutput(const AnalogTrigger &trigger, AnalogTriggerType outputType) : m_trigger(trigger), m_outputType(outputType) { HALReport(HALUsageReporting::kResourceType_AnalogTriggerOutput, - trigger->GetIndex(), outputType); + trigger.GetIndex(), outputType); } AnalogTriggerOutput::~AnalogTriggerOutput() { @@ -46,7 +46,7 @@ AnalogTriggerOutput::~AnalogTriggerOutput() { bool AnalogTriggerOutput::Get() const { int32_t status = 0; bool result = - getAnalogTriggerOutput(m_trigger->m_trigger, m_outputType, &status); + getAnalogTriggerOutput(m_trigger.m_trigger, m_outputType, &status); wpi_setErrorWithContext(status, getHALErrorMessage(status)); return result; } @@ -55,7 +55,7 @@ bool AnalogTriggerOutput::Get() const { * @return The value to be written to the channel field of a routing mux. */ uint32_t AnalogTriggerOutput::GetChannelForRouting() const { - return (m_trigger->m_index << 2) + m_outputType; + return (m_trigger.m_index << 2) + m_outputType; } /** diff --git a/wpilibc/wpilibC++Devices/src/BuiltInAccelerometer.cpp b/wpilibc/wpilibC++Devices/src/BuiltInAccelerometer.cpp index 0de2820249..46ed7f7ab0 100644 --- a/wpilibc/wpilibC++Devices/src/BuiltInAccelerometer.cpp +++ b/wpilibc/wpilibC++Devices/src/BuiltInAccelerometer.cpp @@ -18,7 +18,7 @@ BuiltInAccelerometer::BuiltInAccelerometer(Range range) { HALReport(HALUsageReporting::kResourceType_Accelerometer, 0, 0, "Built-in accelerometer"); - LiveWindow::GetInstance()->AddSensor((std::string) "BuiltInAccel", 0, this); + LiveWindow::GetInstance().AddSensor((std::string) "BuiltInAccel", 0, this); } /** {@inheritdoc} */ @@ -52,7 +52,7 @@ std::string BuiltInAccelerometer::GetSmartDashboardType() const { return "3AxisAccelerometer"; } -void BuiltInAccelerometer::InitTable(ITable* subtable) { +void BuiltInAccelerometer::InitTable(::std::shared_ptr subtable) { m_table = subtable; UpdateTable(); } @@ -65,4 +65,4 @@ void BuiltInAccelerometer::UpdateTable() { } } -ITable* 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 442c326b4b..da229dcbd5 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 Resource *allocated = nullptr; +static ::std::unique_ptr allocated; static int32_t sendMessageHelper(uint32_t messageID, const uint8_t *data, uint8_t dataSize, int32_t period) { @@ -72,7 +72,7 @@ static int32_t sendMessageHelper(uint32_t messageID, const uint8_t *data, * Common initialization code called by all constructors. */ void CANJaguar::InitCANJaguar() { - m_safetyHelper = new MotorSafetyHelper(this); + m_safetyHelper = std::make_unique(this); bool receivedFirmwareVersion = false; uint8_t dataBuffer[8]; @@ -149,7 +149,7 @@ void CANJaguar::InitCANJaguar() { } HALReport(HALUsageReporting::kResourceType_CANJaguar, m_deviceNumber, m_controlMode); - LiveWindow::GetInstance()->AddActuator("CANJaguar", m_deviceNumber, this); + LiveWindow::GetInstance().AddActuator("CANJaguar", m_deviceNumber, this); } /** @@ -180,10 +180,10 @@ CANJaguar::CANJaguar(uint8_t deviceNumber) : m_deviceNumber(deviceNumber) { char buf[64]; snprintf(buf, 64, "CANJaguar device number %d", m_deviceNumber); - Resource::CreateResourceObject(&allocated, 63); + Resource::CreateResourceObject(allocated, 63); if (allocated->Allocate(m_deviceNumber - 1, buf) == ~0ul) { - CloneError(allocated); + CloneError(*allocated); return; } @@ -218,9 +218,6 @@ CANJaguar::~CANJaguar() { FRC_NetworkCommunication_CANSessionMux_sendMessage( m_deviceNumber | LM_API_VCOMP_T_SET, nullptr, 0, CAN_SEND_PERIOD_STOP_REPEATING, &status); - - delete m_safetyHelper; - m_safetyHelper = nullptr; } /** @@ -1926,8 +1923,8 @@ void CANJaguar::SetSafetyEnabled(bool enabled) { if (m_safetyHelper) m_safetyHelper->SetSafetyEnabled(enabled); } -void CANJaguar::GetDescription(char *desc) const { - sprintf(desc, "CANJaguar ID %d", m_deviceNumber); +void CANJaguar::GetDescription(std::ostringstream& desc) const { + desc << "CANJaguar ID " << m_deviceNumber; } uint8_t CANJaguar::GetDeviceID() const { return m_deviceNumber; } @@ -1940,7 +1937,7 @@ uint8_t CANJaguar::GetDeviceID() const { return m_deviceNumber; } */ void CANJaguar::StopMotor() { DisableControl(); } -void CANJaguar::ValueChanged(ITable *source, const std::string &key, +void CANJaguar::ValueChanged(::std::shared_ptr source, const std::string &key, EntryValue value, bool isNew) { Set(value.f); } @@ -1982,9 +1979,9 @@ std::string CANJaguar::GetSmartDashboardType() const { return "Speed Controller"; } -void CANJaguar::InitTable(ITable *subTable) { +void CANJaguar::InitTable(::std::shared_ptr subTable) { m_table = subTable; UpdateTable(); } -ITable *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 0d8f5407bb..3e2c8073ff 100644 --- a/wpilibc/wpilibC++Devices/src/CANTalon.cpp +++ b/wpilibc/wpilibC++Devices/src/CANTalon.cpp @@ -8,10 +8,12 @@ #include "WPIErrors.h" #include "ctre/CanTalonSRX.h" #include // usleep - /** - * Constructor for the CANTalon device. - * @param deviceNumber The CAN ID of the Talon SRX - */ +#include + +/** + * Constructor for the CANTalon device. + * @param deviceNumber The CAN ID of the Talon SRX + */ CANTalon::CANTalon(int deviceNumber) : m_deviceNumber(deviceNumber), m_impl(new CanTalonSRX(deviceNumber)), @@ -41,10 +43,6 @@ CANTalon::CANTalon(int deviceNumber, int controlPeriodMs) ApplyControlMode(m_controlMode); m_impl->SetProfileSlotSelect(m_profile); } -CANTalon::~CANTalon() { - delete m_impl; - delete m_safetyHelper; -} /** * Write out the PID value as seen in the PIDOutput base object. @@ -1246,8 +1244,8 @@ void CANTalon::SetSafetyEnabled(bool enabled) { m_safetyHelper->SetSafetyEnabled(enabled); } -void CANTalon::GetDescription(char* desc) const { - sprintf(desc, "CANTalon ID %d", m_deviceNumber); +void CANTalon::GetDescription(std::ostringstream& desc) const { + desc << "CANTalon ID " << m_deviceNumber; } /** @@ -1273,7 +1271,7 @@ bool CANTalon::GetInverted() const { return m_isInverted; } */ void CANTalon::StopMotor() { Disable(); } -void CANTalon::ValueChanged(ITable* source, const std::string& key, +void CANTalon::ValueChanged(::std::shared_ptr source, const std::string& key, EntryValue value, bool isNew) { Set(value.f); } @@ -1300,9 +1298,9 @@ std::string CANTalon::GetSmartDashboardType() const { return "Speed Controller"; } -void CANTalon::InitTable(ITable* subTable) { +void CANTalon::InitTable(::std::shared_ptr subTable) { m_table = subTable; UpdateTable(); } -ITable* 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 1d31eb3f54..50a07ec2ed 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(ITable* subTable) { +void Compressor::InitTable(::std::shared_ptr subTable) { m_table = subTable; UpdateTable(); } -ITable* Compressor::GetTable() const { return m_table; } +::std::shared_ptr Compressor::GetTable() const { return m_table; } -void Compressor::ValueChanged(ITable* 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 c4e333ce83..c6edddb9b5 100644 --- a/wpilibc/wpilibC++Devices/src/Counter.cpp +++ b/wpilibc/wpilibC++Devices/src/Counter.cpp @@ -60,11 +60,11 @@ Counter::Counter(DigitalSource *source) : Counter() { * an Analog Trigger). * * The counter will start counting immediately. - * @param source A reference to the existing DigitalSource object. It will be + * @param source A pointer to the existing DigitalSource object. It will be * set as the Up Source. */ -Counter::Counter(DigitalSource &source) : Counter() { - SetUpSource(&source); +Counter::Counter(::std::shared_ptr source) : Counter() { + SetUpSource(source); ClearDownSource(); } @@ -92,7 +92,6 @@ Counter::Counter(int32_t channel) : Counter() { Counter::Counter(AnalogTrigger *trigger) : Counter() { SetUpSource(trigger->CreateOutput(kState)); ClearDownSource(); - m_allocatedUpSource = true; } /** @@ -103,10 +102,9 @@ Counter::Counter(AnalogTrigger *trigger) : Counter() { * The counter will start counting immediately. * @param trigger The reference to the existing AnalogTrigger object. */ -Counter::Counter(AnalogTrigger &trigger) : Counter() { +Counter::Counter(const AnalogTrigger &trigger) : Counter() { SetUpSource(trigger.CreateOutput(kState)); ClearDownSource(); - m_allocatedUpSource = true; } /** @@ -117,10 +115,27 @@ Counter::Counter(AnalogTrigger &trigger) : Counter() { * @param downSource The pointer to the DigitalSource to set as the down source * @param inverted True to invert the output (reverse the direction) */ - Counter::Counter(EncodingType encodingType, DigitalSource *upSource, DigitalSource *downSource, bool inverted) - : Counter(kExternalDirection) { + : Counter(encodingType, + ::std::shared_ptr(upSource, + NullDeleter()), + ::std::shared_ptr(downSource, + NullDeleter()), + inverted) {} + +/** + * Create an instance of a Counter object. + * Creates a full up-down counter given two Digital Sources + * @param encodingType The quadrature decoding mode (1x or 2x) + * @param upSource The pointer to the DigitalSource to set as the up source + * @param downSource The pointer to the DigitalSource to set as the down source + * @param inverted True to invert the output (reverse the direction) + */ +Counter::Counter(EncodingType encodingType, + ::std::shared_ptr upSource, + ::std::shared_ptr downSource, bool inverted) + : Counter(kExternalDirection) { if (encodingType != k1X && encodingType != k2X) { wpi_setWPIErrorWithContext( ParameterOutOfRange, @@ -148,14 +163,6 @@ Counter::Counter(EncodingType encodingType, DigitalSource *upSource, */ Counter::~Counter() { SetUpdateWhenEmpty(true); - if (m_allocatedUpSource) { - delete m_upSource; - m_upSource = nullptr; - } - if (m_allocatedDownSource) { - delete m_downSource; - m_downSource = nullptr; - } int32_t status = 0; freeCounter(m_counter, &status); @@ -170,8 +177,7 @@ Counter::~Counter() { */ void Counter::SetUpSource(int32_t channel) { if (StatusIsFatal()) return; - SetUpSource(new DigitalInput(channel)); - m_allocatedUpSource = true; + SetUpSource(::std::make_shared(channel)); } /** @@ -181,9 +187,9 @@ void Counter::SetUpSource(int32_t channel) { */ void Counter::SetUpSource(AnalogTrigger *analogTrigger, AnalogTriggerType triggerType) { - if (StatusIsFatal()) return; - SetUpSource(analogTrigger->CreateOutput(triggerType)); - m_allocatedUpSource = true; + SetUpSource(::std::shared_ptr(analogTrigger, + NullDeleter()), + triggerType); } /** @@ -191,9 +197,10 @@ 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(AnalogTrigger &analogTrigger, +void Counter::SetUpSource(::std::shared_ptr analogTrigger, AnalogTriggerType triggerType) { - SetUpSource(&analogTrigger, triggerType); + if (StatusIsFatal()) return; + SetUpSource(analogTrigger->CreateOutput(triggerType)); } /** @@ -201,16 +208,11 @@ void Counter::SetUpSource(AnalogTrigger &analogTrigger, * Set the up counting DigitalSource. * @param source Pointer to the DigitalSource object to set as the up source */ -void Counter::SetUpSource(DigitalSource *source) { +void Counter::SetUpSource(::std::shared_ptr source) { if (StatusIsFatal()) return; - if (m_allocatedUpSource) { - delete m_upSource; - m_upSource = nullptr; - m_allocatedUpSource = false; - } m_upSource = source; if (m_upSource->StatusIsFatal()) { - CloneError(m_upSource); + CloneError(*m_upSource); } else { int32_t status = 0; setCounterUpSource(m_counter, source->GetChannelForRouting(), @@ -219,12 +221,20 @@ void Counter::SetUpSource(DigitalSource *source) { } } +void Counter::SetUpSource(DigitalSource *source) { + SetUpSource( + ::std::shared_ptr(source, NullDeleter())); +} + /** * Set the source object that causes the counter to count up. * Set the up counting DigitalSource. * @param source Reference to the DigitalSource object to set as the up source */ -void Counter::SetUpSource(DigitalSource &source) { SetUpSource(&source); } +void Counter::SetUpSource(DigitalSource &source) { + SetUpSource( + ::std::shared_ptr(&source, NullDeleter())); +} /** * Set the edge sensitivity on an up counting source. @@ -249,11 +259,7 @@ void Counter::SetUpSourceEdge(bool risingEdge, bool fallingEdge) { */ void Counter::ClearUpSource() { if (StatusIsFatal()) return; - if (m_allocatedUpSource) { - delete m_upSource; - m_upSource = nullptr; - m_allocatedUpSource = false; - } + m_upSource.reset(); int32_t status = 0; clearCounterUpSource(m_counter, &status); wpi_setErrorWithContext(status, getHALErrorMessage(status)); @@ -266,8 +272,7 @@ void Counter::ClearUpSource() { */ void Counter::SetDownSource(int32_t channel) { if (StatusIsFatal()) return; - SetDownSource(new DigitalInput(channel)); - m_allocatedDownSource = true; + SetDownSource(::std::make_shared(channel)); } /** @@ -278,9 +283,7 @@ void Counter::SetDownSource(int32_t channel) { */ void Counter::SetDownSource(AnalogTrigger *analogTrigger, AnalogTriggerType triggerType) { - if (StatusIsFatal()) return; - SetDownSource(analogTrigger->CreateOutput(triggerType)); - m_allocatedDownSource = true; + SetDownSource(::std::shared_ptr(analogTrigger, NullDeleter()), triggerType); } /** @@ -289,9 +292,10 @@ void Counter::SetDownSource(AnalogTrigger *analogTrigger, * Source * @param triggerType The analog trigger output that will trigger the counter. */ -void Counter::SetDownSource(AnalogTrigger &analogTrigger, +void Counter::SetDownSource(::std::shared_ptr analogTrigger, AnalogTriggerType triggerType) { - SetDownSource(&analogTrigger, triggerType); + if (StatusIsFatal()) return; + SetDownSource(analogTrigger->CreateOutput(triggerType)); } /** @@ -299,16 +303,11 @@ void Counter::SetDownSource(AnalogTrigger &analogTrigger, * Set the down counting DigitalSource. * @param source Pointer to the DigitalSource object to set as the down source */ -void Counter::SetDownSource(DigitalSource *source) { +void Counter::SetDownSource(::std::shared_ptr source) { if (StatusIsFatal()) return; - if (m_allocatedDownSource) { - delete m_downSource; - m_downSource = nullptr; - m_allocatedDownSource = false; - } m_downSource = source; if (m_downSource->StatusIsFatal()) { - CloneError(m_downSource); + CloneError(*m_downSource); } else { int32_t status = 0; setCounterDownSource(m_counter, source->GetChannelForRouting(), @@ -317,12 +316,18 @@ void Counter::SetDownSource(DigitalSource *source) { } } +void Counter::SetDownSource(DigitalSource *source) { + SetDownSource(::std::shared_ptr(source, NullDeleter())); +} + /** * Set the source object that causes the counter to count down. * Set the down counting DigitalSource. * @param source Reference to the DigitalSource object to set as the down source */ -void Counter::SetDownSource(DigitalSource &source) { SetDownSource(&source); } +void Counter::SetDownSource(DigitalSource &source) { + SetDownSource(::std::shared_ptr(&source, NullDeleter())); +} /** * Set the edge sensitivity on a down counting source. @@ -347,11 +352,7 @@ void Counter::SetDownSourceEdge(bool risingEdge, bool fallingEdge) { */ void Counter::ClearDownSource() { if (StatusIsFatal()) return; - if (m_allocatedDownSource) { - delete m_downSource; - m_downSource = nullptr; - m_allocatedDownSource = false; - } + m_downSource.reset(); int32_t status = 0; clearCounterDownSource(m_counter, &status); wpi_setErrorWithContext(status, getHALErrorMessage(status)); @@ -581,9 +582,9 @@ void Counter::StopLiveWindowMode() {} std::string Counter::GetSmartDashboardType() const { return "Counter"; } -void Counter::InitTable(ITable *subTable) { +void Counter::InitTable(::std::shared_ptr subTable) { m_table = subTable; UpdateTable(); } -ITable *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 b80bebd4d7..def300e5f2 100644 --- a/wpilibc/wpilibC++Devices/src/DigitalInput.cpp +++ b/wpilibc/wpilibC++Devices/src/DigitalInput.cpp @@ -31,7 +31,7 @@ DigitalInput::DigitalInput(uint32_t channel) { allocateDIO(m_digital_ports[channel], true, &status); wpi_setErrorWithContext(status, getHALErrorMessage(status)); - LiveWindow::GetInstance()->AddSensor("DigitalInput", channel, this); + LiveWindow::GetInstance().AddSensor("DigitalInput", channel, this); HALReport(HALUsageReporting::kResourceType_DigitalInput, channel); } @@ -98,9 +98,9 @@ std::string DigitalInput::GetSmartDashboardType() const { return "DigitalInput"; } -void DigitalInput::InitTable(ITable *subTable) { +void DigitalInput::InitTable(::std::shared_ptr subTable) { m_table = subTable; UpdateTable(); } -ITable *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 56157661c1..c5619f1108 100644 --- a/wpilibc/wpilibC++Devices/src/DigitalOutput.cpp +++ b/wpilibc/wpilibC++Devices/src/DigitalOutput.cpp @@ -194,7 +194,7 @@ uint32_t DigitalOutput::GetModuleForRouting() const { return 0; } */ bool DigitalOutput::GetAnalogTriggerForRouting() const { return false; } -void DigitalOutput::ValueChanged(ITable *source, const std::string &key, +void DigitalOutput::ValueChanged(::std::shared_ptr source, const std::string &key, EntryValue value, bool isNew) { Set(value.b); } @@ -217,9 +217,9 @@ std::string DigitalOutput::GetSmartDashboardType() const { return "Digital Output"; } -void DigitalOutput::InitTable(ITable *subTable) { +void DigitalOutput::InitTable(::std::shared_ptr subTable) { m_table = subTable; UpdateTable(); } -ITable *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 ede689f573..9a5e72a485 100644 --- a/wpilibc/wpilibC++Devices/src/DoubleSolenoid.cpp +++ b/wpilibc/wpilibC++Devices/src/DoubleSolenoid.cpp @@ -9,6 +9,10 @@ #include "WPIErrors.h" #include "LiveWindow/LiveWindow.h" +::std::unique_ptr SolenoidBase::m_allocated = + ::std::make_unique(solenoid_kNumDO7_0Elements * + kSolenoidChannels); + /** * Constructor. * Uses the default PCM ID of 0 @@ -47,13 +51,13 @@ DoubleSolenoid::DoubleSolenoid(uint8_t moduleNumber, uint32_t forwardChannel, return; } Resource::CreateResourceObject( - &m_allocated, solenoid_kNumDO7_0Elements * kSolenoidChannels); + m_allocated, solenoid_kNumDO7_0Elements * kSolenoidChannels); snprintf(buf, 64, "Solenoid %d (Module: %d)", m_forwardChannel, m_moduleNumber); if (m_allocated->Allocate( m_moduleNumber * kSolenoidChannels + m_forwardChannel, buf) == ~0ul) { - CloneError(m_allocated); + CloneError(*m_allocated); return; } @@ -61,7 +65,7 @@ DoubleSolenoid::DoubleSolenoid(uint8_t moduleNumber, uint32_t forwardChannel, m_moduleNumber); if (m_allocated->Allocate( m_moduleNumber * kSolenoidChannels + m_reverseChannel, buf) == ~0ul) { - CloneError(m_allocated); + CloneError(*m_allocated); return; } @@ -71,7 +75,7 @@ DoubleSolenoid::DoubleSolenoid(uint8_t moduleNumber, uint32_t forwardChannel, m_moduleNumber); HALReport(HALUsageReporting::kResourceType_Solenoid, m_reverseChannel, m_moduleNumber); - LiveWindow::GetInstance()->AddActuator("DoubleSolenoid", m_moduleNumber, + LiveWindow::GetInstance().AddActuator("DoubleSolenoid", m_moduleNumber, m_forwardChannel, this); } @@ -147,7 +151,7 @@ bool DoubleSolenoid::IsRevSolenoidBlackListed() const { return (blackList & m_reverseMask) ? 1 : 0; } -void DoubleSolenoid::ValueChanged(ITable *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; @@ -184,9 +188,9 @@ std::string DoubleSolenoid::GetSmartDashboardType() const { return "Double Solenoid"; } -void DoubleSolenoid::InitTable(ITable *subTable) { +void DoubleSolenoid::InitTable(::std::shared_ptr subTable) { m_table = subTable; UpdateTable(); } -ITable *DoubleSolenoid::GetTable() const { return m_table; } +::std::shared_ptr DoubleSolenoid::GetTable() const { return m_table; } diff --git a/wpilibc/wpilibC++Devices/src/DriverStation.cpp b/wpilibc/wpilibC++Devices/src/DriverStation.cpp index ce40bd70c6..2234fce24e 100644 --- a/wpilibc/wpilibC++Devices/src/DriverStation.cpp +++ b/wpilibc/wpilibC++Devices/src/DriverStation.cpp @@ -88,9 +88,9 @@ void DriverStation::Run() { * Return a pointer to the singleton DriverStation. * @return Pointer to the DS instance */ -DriverStation* DriverStation::GetInstance() { +DriverStation &DriverStation::GetInstance() { static DriverStation instance; - return &instance; + return instance; } /** diff --git a/wpilibc/wpilibC++Devices/src/Encoder.cpp b/wpilibc/wpilibC++Devices/src/Encoder.cpp index c254b5b34f..5924aa3329 100644 --- a/wpilibc/wpilibC++Devices/src/Encoder.cpp +++ b/wpilibc/wpilibC++Devices/src/Encoder.cpp @@ -36,11 +36,11 @@ void Encoder::InitEncoder(bool reverseDirection, EncodingType encodingType) { case k4X: { m_encodingScale = 4; if (m_aSource->StatusIsFatal()) { - CloneError(m_aSource); + CloneError(*m_aSource); return; } if (m_bSource->StatusIsFatal()) { - CloneError(m_bSource); + CloneError(*m_bSource); return; } int32_t status = 0; @@ -58,8 +58,8 @@ void Encoder::InitEncoder(bool reverseDirection, EncodingType encodingType) { case k1X: case k2X: { m_encodingScale = encodingType == k1X ? 1 : 2; - m_counter = - new Counter(m_encodingType, m_aSource, m_bSource, reverseDirection); + m_counter = ::std::make_unique(m_encodingType, m_aSource, + m_bSource, reverseDirection); m_index = m_counter->GetFPGAIndex(); break; } @@ -69,7 +69,7 @@ void Encoder::InitEncoder(bool reverseDirection, EncodingType encodingType) { } HALReport(HALUsageReporting::kResourceType_Encoder, m_index, encodingType); - LiveWindow::GetInstance()->AddSensor("Encoder", + LiveWindow::GetInstance().AddSensor("Encoder", m_aSource->GetChannelForRouting(), this); } @@ -98,21 +98,16 @@ void Encoder::InitEncoder(bool reverseDirection, EncodingType encodingType) { */ Encoder::Encoder(uint32_t aChannel, uint32_t bChannel, bool reverseDirection, EncodingType encodingType) { - m_aSource = new DigitalInput(aChannel); - m_bSource = new DigitalInput(bChannel); + m_aSource = ::std::make_shared(aChannel); + m_bSource = ::std::make_shared(bChannel); InitEncoder(reverseDirection, encodingType); - m_allocatedASource = true; - m_allocatedBSource = true; } /** * Encoder constructor. * Construct a Encoder given a and b channels as digital inputs. This is used in - * the case - * where the digital inputs are shared. The Encoder class will not allocate the - * digital inputs - * and assume that they already are counted. - * + * the case where the digital inputs are shared. The Encoder class will not + * allocate the digital inputs and assume that they already are counted. * The counter will start counting immediately. * * @param aSource The source that should be used for the a channel. @@ -131,11 +126,19 @@ Encoder::Encoder(uint32_t aChannel, uint32_t bChannel, bool reverseDirection, * or be double (2x) the spec'd count. */ Encoder::Encoder(DigitalSource *aSource, DigitalSource *bSource, - bool reverseDirection, EncodingType encodingType) { - m_aSource = aSource; - m_bSource = bSource; - m_allocatedASource = false; - m_allocatedBSource = false; + bool reverseDirection, EncodingType encodingType) + : m_aSource(aSource, NullDeleter()), + m_bSource(bSource, NullDeleter()) { + if (m_aSource == nullptr || m_bSource == nullptr) + wpi_setWPIError(NullParameter); + else + InitEncoder(reverseDirection, encodingType); +} + +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) wpi_setWPIError(NullParameter); else @@ -168,11 +171,10 @@ Encoder::Encoder(DigitalSource *aSource, DigitalSource *bSource, * or be double (2x) the spec'd count. */ Encoder::Encoder(DigitalSource &aSource, DigitalSource &bSource, - bool reverseDirection, EncodingType encodingType) { - m_aSource = &aSource; - m_bSource = &bSource; - m_allocatedASource = false; - m_allocatedBSource = false; + bool reverseDirection, EncodingType encodingType) + : m_aSource(&aSource, NullDeleter()), + m_bSource(&bSource, NullDeleter()) +{ InitEncoder(reverseDirection, encodingType); } @@ -181,11 +183,7 @@ Encoder::Encoder(DigitalSource &aSource, DigitalSource &bSource, * Frees the FPGA resources associated with an Encoder. */ Encoder::~Encoder() { - if (m_allocatedASource) delete m_aSource; - if (m_allocatedBSource) delete m_bSource; - if (m_counter) { - delete m_counter; - } else { + if (!m_counter) { int32_t status = 0; freeEncoder(m_encoder, &status); wpi_setErrorWithContext(status, getHALErrorMessage(status)); @@ -524,15 +522,7 @@ void Encoder::SetIndexSource(uint32_t channel, Encoder::IndexingType type) { */ void Encoder::SetIndexSource(DigitalSource *source, Encoder::IndexingType type) { - int32_t status = 0; - bool activeHigh = (type == kResetWhileHigh) || (type == kResetOnRisingEdge); - bool edgeSensitive = - (type == kResetOnFallingEdge) || (type == kResetOnRisingEdge); - - setEncoderIndexSource(m_encoder, source->GetChannelForRouting(), - source->GetAnalogTriggerForRouting(), activeHigh, - edgeSensitive, &status); - wpi_setGlobalErrorWithContext(status, getHALErrorMessage(status)); + SetIndexSource(*source, type); } /** @@ -542,9 +532,17 @@ void Encoder::SetIndexSource(DigitalSource *source, * @param channel A digital source to set as the encoder index * @param type The state that will cause the encoder to reset */ -void Encoder::SetIndexSource(DigitalSource &source, +void Encoder::SetIndexSource(const DigitalSource &source, Encoder::IndexingType type) { - SetIndexSource(&source, type); + int32_t status = 0; + bool activeHigh = (type == kResetWhileHigh) || (type == kResetOnRisingEdge); + bool edgeSensitive = + (type == kResetOnFallingEdge) || (type == kResetOnRisingEdge); + + setEncoderIndexSource(m_encoder, source.GetChannelForRouting(), + source.GetAnalogTriggerForRouting(), activeHigh, + edgeSensitive, &status); + wpi_setGlobalErrorWithContext(status, getHALErrorMessage(status)); } void Encoder::UpdateTable() { @@ -566,9 +564,9 @@ std::string Encoder::GetSmartDashboardType() const { return "Encoder"; } -void Encoder::InitTable(ITable *subTable) { +void Encoder::InitTable(::std::shared_ptr subTable) { m_table = subTable; UpdateTable(); } -ITable *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 5984e15bd1..294e94b787 100644 --- a/wpilibc/wpilibC++Devices/src/GearTooth.cpp +++ b/wpilibc/wpilibC++Devices/src/GearTooth.cpp @@ -30,7 +30,7 @@ void GearTooth::EnableDirectionSensing(bool directionSensitive) { GearTooth::GearTooth(uint32_t channel, bool directionSensitive) : Counter(channel) { EnableDirectionSensing(directionSensitive); - LiveWindow::GetInstance()->AddSensor("GearTooth", channel, this); + LiveWindow::GetInstance().AddSensor("GearTooth", channel, this); } /** @@ -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(DigitalSource &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 3652d35598..2d6ed18a9d 100644 --- a/wpilibc/wpilibC++Devices/src/Gyro.cpp +++ b/wpilibc/wpilibC++Devices/src/Gyro.cpp @@ -34,10 +34,7 @@ void Gyro::InitGyro() { if (!m_analog->IsAccumulatorChannel()) { wpi_setWPIErrorWithContext(ParameterOutOfRange, " channel (must be accumulator channel)"); - if (m_channelAllocated) { - delete m_analog; - m_analog = nullptr; - } + m_analog = nullptr; return; } @@ -55,7 +52,7 @@ void Gyro::InitGyro() { int64_t value; uint32_t count; - m_analog->GetAccumulatorOutput(&value, &count); + m_analog->GetAccumulatorOutput(value, count); m_center = (uint32_t)((float)value / (float)count + .5); @@ -68,7 +65,7 @@ void Gyro::InitGyro() { SetPIDSourceParameter(kAngle); HALReport(HALUsageReporting::kResourceType_Gyro, m_analog->GetChannel()); - LiveWindow::GetInstance()->AddSensor("Gyro", m_analog->GetChannel(), this); + LiveWindow::GetInstance().AddSensor("Gyro", m_analog->GetChannel(), this); } /** @@ -78,8 +75,7 @@ void Gyro::InitGyro() { can only be used on on-board Analog Inputs 0-1. */ Gyro::Gyro(int32_t channel) { - m_analog = new AnalogInput(channel); - m_channelAllocated = true; + m_analog = ::std::make_shared(channel); InitGyro(); } @@ -92,28 +88,24 @@ Gyro::Gyro(int32_t channel) { * @param channel A pointer to the AnalogInput object that the gyro is connected * to. */ -Gyro::Gyro(AnalogInput *channel) { - m_analog = channel; - m_channelAllocated = false; - if (channel == nullptr) { - wpi_setWPIError(NullParameter); - } else { - InitGyro(); - } -} +Gyro::Gyro(AnalogInput *channel) + : Gyro(::std::shared_ptr(channel, + NullDeleter())) {} /** * Gyro constructor with a precreated AnalogInput object. * Use this constructor when the analog channel needs to be shared. * This object will not clean up the AnalogInput object when using this * constructor - * @param channel A reference to the AnalogInput object that the gyro is + * @param channel A pointer to the AnalogInput object that the gyro is * connected to. */ -Gyro::Gyro(AnalogInput &channel) { - m_analog = &channel; - m_channelAllocated = false; - InitGyro(); +Gyro::Gyro(::std::shared_ptr channel) : m_analog(channel) { + if (channel == nullptr) { + wpi_setWPIError(NullParameter); + } else { + InitGyro(); + } } /** @@ -124,13 +116,6 @@ Gyro::Gyro(AnalogInput &channel) { */ void Gyro::Reset() { m_analog->ResetAccumulator(); } -/** - * Delete (free) the accumulator and the analog components used for the gyro. - */ -Gyro::~Gyro() { - if (m_channelAllocated) delete m_analog; -} - /** * Return the actual angle in degrees that the robot is currently facing. * @@ -149,7 +134,7 @@ Gyro::~Gyro() { float Gyro::GetAngle() const { int64_t rawValue; uint32_t count; - m_analog->GetAccumulatorOutput(&rawValue, &count); + m_analog->GetAccumulatorOutput(rawValue, count); int64_t value = rawValue - (int64_t)((float)count * m_offset); @@ -240,9 +225,9 @@ void Gyro::StopLiveWindowMode() {} std::string Gyro::GetSmartDashboardType() const { return "Gyro"; } -void Gyro::InitTable(ITable *subTable) { +void Gyro::InitTable(::std::shared_ptr subTable) { m_table = subTable; UpdateTable(); } -ITable *Gyro::GetTable() const { return m_table; } +::std::shared_ptr Gyro::GetTable() const { return m_table; } diff --git a/wpilibc/wpilibC++Devices/src/I2C.cpp b/wpilibc/wpilibC++Devices/src/I2C.cpp index 258da4ee68..0d622a66df 100644 --- a/wpilibc/wpilibC++Devices/src/I2C.cpp +++ b/wpilibc/wpilibC++Devices/src/I2C.cpp @@ -177,6 +177,7 @@ bool I2C::ReadOnly(uint8_t count, uint8_t *buffer) { * @param registerAddress The register to write on all devices on the bus. * @param data The value to write to the devices. */ +[[gnu::warning("I2C::Broadcast() is not implemented.")]] void I2C::Broadcast(uint8_t registerAddress, uint8_t data) {} /** diff --git a/wpilibc/wpilibC++Devices/src/InterruptableSensorBase.cpp b/wpilibc/wpilibC++Devices/src/InterruptableSensorBase.cpp index d4551d3127..4262adac5a 100644 --- a/wpilibc/wpilibC++Devices/src/InterruptableSensorBase.cpp +++ b/wpilibc/wpilibC++Devices/src/InterruptableSensorBase.cpp @@ -9,10 +9,10 @@ #include "Utility.h" #include "WPIErrors.h" -Resource *InterruptableSensorBase::m_interrupts = nullptr; +::std::unique_ptr InterruptableSensorBase::m_interrupts = + ::std::make_unique(interrupt_kNumSystems); InterruptableSensorBase::InterruptableSensorBase() { - Resource::CreateResourceObject(&m_interrupts, interrupt_kNumSystems); } /** @@ -29,7 +29,7 @@ void InterruptableSensorBase::RequestInterrupts( if (StatusIsFatal()) return; uint32_t index = m_interrupts->Allocate("Async Interrupt"); if (index == ~0ul) { - CloneError(m_interrupts); + CloneError(*m_interrupts); return; } m_interruptIndex = index; @@ -56,7 +56,7 @@ void InterruptableSensorBase::RequestInterrupts() { if (StatusIsFatal()) return; uint32_t index = m_interrupts->Allocate("Sync Interrupt"); if (index == ~0ul) { - CloneError(m_interrupts); + CloneError(*m_interrupts); return; } m_interruptIndex = index; diff --git a/wpilibc/wpilibC++Devices/src/IterativeRobot.cpp b/wpilibc/wpilibC++Devices/src/IterativeRobot.cpp index a5a5c0f9ab..d367615369 100644 --- a/wpilibc/wpilibC++Devices/src/IterativeRobot.cpp +++ b/wpilibc/wpilibC++Devices/src/IterativeRobot.cpp @@ -31,7 +31,7 @@ void IterativeRobot::StartCompetition() { HALReport(HALUsageReporting::kResourceType_Framework, HALUsageReporting::kFramework_Iterative); - LiveWindow *lw = LiveWindow::GetInstance(); + LiveWindow &lw = LiveWindow::GetInstance(); // first and one-time initialization SmartDashboard::init(); NetworkTable::GetTable("LiveWindow") @@ -46,14 +46,14 @@ void IterativeRobot::StartCompetition() { HALNetworkCommunicationObserveUserProgramStarting(); // loop forever, calling the appropriate mode-dependent function - lw->SetEnabled(false); + lw.SetEnabled(false); while (true) { // Call the appropriate function depending upon the current robot mode if (IsDisabled()) { // call DisabledInit() if we are now just entering disabled mode from // either a different mode or from power-on if (!m_disabledInitialized) { - lw->SetEnabled(false); + lw.SetEnabled(false); DisabledInit(); m_disabledInitialized = true; // reset the initialization flags for the other modes @@ -67,7 +67,7 @@ void IterativeRobot::StartCompetition() { // call AutonomousInit() if we are now just entering autonomous mode from // either a different mode or from power-on if (!m_autonomousInitialized) { - lw->SetEnabled(false); + lw.SetEnabled(false); AutonomousInit(); m_autonomousInitialized = true; // reset the initialization flags for the other modes @@ -81,7 +81,7 @@ void IterativeRobot::StartCompetition() { // call TestInit() if we are now just entering test mode from // either a different mode or from power-on if (!m_testInitialized) { - lw->SetEnabled(true); + lw.SetEnabled(true); TestInit(); m_testInitialized = true; // reset the initialization flags for the other modes @@ -95,20 +95,20 @@ void IterativeRobot::StartCompetition() { // call TeleopInit() if we are now just entering teleop mode from // either a different mode or from power-on if (!m_teleopInitialized) { - lw->SetEnabled(false); + lw.SetEnabled(false); TeleopInit(); m_teleopInitialized = true; // reset the initialization flags for the other modes m_disabledInitialized = false; m_autonomousInitialized = false; m_testInitialized = false; - Scheduler::GetInstance()->SetEnabled(true); + Scheduler::GetInstance().SetEnabled(true); } HALNetworkCommunicationObserveUserProgramTeleop(); TeleopPeriodic(); } // wait for driver station data so the loop doesn't hog the CPU - m_ds->WaitForData(); + m_ds.WaitForData(); } } diff --git a/wpilibc/wpilibC++Devices/src/Jaguar.cpp b/wpilibc/wpilibC++Devices/src/Jaguar.cpp index 9b02302eb9..2351874912 100644 --- a/wpilibc/wpilibC++Devices/src/Jaguar.cpp +++ b/wpilibc/wpilibC++Devices/src/Jaguar.cpp @@ -30,7 +30,7 @@ Jaguar::Jaguar(uint32_t channel) : SafePWM(channel) { SetZeroLatch(); HALReport(HALUsageReporting::kResourceType_Jaguar, GetChannel()); - LiveWindow::GetInstance()->AddActuator("Jaguar", GetChannel(), this); + LiveWindow::GetInstance().AddActuator("Jaguar", GetChannel(), this); } /** diff --git a/wpilibc/wpilibC++Devices/src/Joystick.cpp b/wpilibc/wpilibC++Devices/src/Joystick.cpp index 6bf01fceda..a7a299ced8 100644 --- a/wpilibc/wpilibC++Devices/src/Joystick.cpp +++ b/wpilibc/wpilibC++Devices/src/Joystick.cpp @@ -55,7 +55,10 @@ Joystick::Joystick(uint32_t port) */ Joystick::Joystick(uint32_t port, uint32_t numAxisTypes, uint32_t numButtonTypes) - : m_port(port) { + : m_ds(DriverStation::GetInstance()), + m_port(port), + m_axes(numAxisTypes), + m_buttons(numButtonTypes) { if (!joySticksInitialized) { for (auto& joystick : joysticks) joystick = nullptr; joySticksInitialized = true; @@ -65,10 +68,6 @@ Joystick::Joystick(uint32_t port, uint32_t numAxisTypes, } else { joysticks[m_port] = this; } - - m_ds = DriverStation::GetInstance(); - m_axes = new uint32_t[numAxisTypes]; - m_buttons = new uint32_t[numButtonTypes]; } Joystick *Joystick::GetStickForPort(uint32_t port) { @@ -80,11 +79,6 @@ Joystick *Joystick::GetStickForPort(uint32_t port) { return stick; } -Joystick::~Joystick() { - delete[] m_buttons; - delete[] m_axes; -} - /** * Get the X value of the joystick. * This depends on the mapping of the joystick connected to the current port. @@ -132,7 +126,7 @@ float Joystick::GetThrottle() const { * @return The value of the axis. */ float Joystick::GetRawAxis(uint32_t axis) const { - return m_ds->GetStickAxis(m_port, axis); + return m_ds.GetStickAxis(m_port, axis); } /** @@ -209,7 +203,7 @@ bool Joystick::GetBumper(JoystickHand hand) const { * @return The state of the button. **/ bool Joystick::GetRawButton(uint32_t button) const { - return m_ds->GetStickButton(m_port, button); + return m_ds.GetStickButton(m_port, button); } /** @@ -219,7 +213,7 @@ bool Joystick::GetRawButton(uint32_t button) const { * @return the angle of the POV in degrees, or -1 if the POV is not pressed. */ int Joystick::GetPOV(uint32_t pov) const { - return m_ds->GetStickPOV(m_port, pov); + return m_ds.GetStickPOV(m_port, pov); } /** @@ -246,14 +240,14 @@ bool Joystick::GetButton(ButtonType button) const { * * @return the number of axis for the current joystick */ -int Joystick::GetAxisCount() const { return m_ds->GetStickAxisCount(m_port); } +int Joystick::GetAxisCount() const { return m_ds.GetStickAxisCount(m_port); } /** * Get the value of isXbox for the joystick. * * @return A boolean that is true if the joystick is an xbox controller. */ -bool Joystick::GetIsXbox() const { return m_ds->GetJoystickIsXbox(m_port); } +bool Joystick::GetIsXbox() const { return m_ds.GetJoystickIsXbox(m_port); } /** * Get the HID type of the controller. @@ -261,7 +255,7 @@ bool Joystick::GetIsXbox() const { return m_ds->GetJoystickIsXbox(m_port); } * @return the HID type of the controller. */ Joystick::HIDType Joystick::GetType() const { - return static_cast(m_ds->GetJoystickType(m_port)); + return static_cast(m_ds.GetJoystickType(m_port)); } /** @@ -269,11 +263,11 @@ Joystick::HIDType Joystick::GetType() const { * * @return the name of the controller. */ -std::string Joystick::GetName() const { return m_ds->GetJoystickName(m_port); } +std::string Joystick::GetName() const { return m_ds.GetJoystickName(m_port); } // int Joystick::GetAxisType(uint8_t axis) const //{ -// return m_ds->GetJoystickAxisType(m_port, axis); +// return m_ds.GetJoystickAxisType(m_port, axis); //} /** @@ -282,7 +276,7 @@ std::string Joystick::GetName() const { return m_ds->GetJoystickName(m_port); } * @return the number of buttons on the current joystick */ int Joystick::GetButtonCount() const { - return m_ds->GetStickButtonCount(m_port); + return m_ds.GetStickButtonCount(m_port); } /** @@ -290,7 +284,7 @@ int Joystick::GetButtonCount() const { * * @return then umber of POVs for the current joystick */ -int Joystick::GetPOVCount() const { return m_ds->GetStickPOVCount(m_port); } +int Joystick::GetPOVCount() const { return m_ds.GetStickPOVCount(m_port); } /** * Get the channel currently associated with the specified axis. diff --git a/wpilibc/wpilibC++Devices/src/MotorSafetyHelper.cpp b/wpilibc/wpilibC++Devices/src/MotorSafetyHelper.cpp index 68b5806493..e276fe2a82 100644 --- a/wpilibc/wpilibC++Devices/src/MotorSafetyHelper.cpp +++ b/wpilibc/wpilibC++Devices/src/MotorSafetyHelper.cpp @@ -13,8 +13,9 @@ #include "WPIErrors.h" #include +#include -MotorSafetyHelper *MotorSafetyHelper::m_headHelper = nullptr; +::std::set MotorSafetyHelper::m_helperList; priority_recursive_mutex MotorSafetyHelper::m_listMutex; /** @@ -30,27 +31,19 @@ priority_recursive_mutex MotorSafetyHelper::m_listMutex; * This is used * to call the Stop() method on the motor. */ -MotorSafetyHelper::MotorSafetyHelper(MotorSafety *safeObject) { - m_safeObject = safeObject; +MotorSafetyHelper::MotorSafetyHelper(MotorSafety *safeObject) + : m_safeObject(safeObject) { m_enabled = false; m_expiration = DEFAULT_SAFETY_EXPIRATION; m_stopTime = Timer::GetFPGATimestamp(); std::unique_lock sync(m_listMutex); - m_nextHelper = m_headHelper; - m_headHelper = this; + m_helperList.insert(this); } MotorSafetyHelper::~MotorSafetyHelper() { std::unique_lock sync(m_listMutex); - if (m_headHelper == this) { - m_headHelper = m_nextHelper; - } else { - MotorSafetyHelper *prev = nullptr; - MotorSafetyHelper *cur = m_headHelper; - while (cur != this && cur != nullptr) prev = cur, cur = cur->m_nextHelper; - if (cur == this) prev->m_nextHelper = cur->m_nextHelper; - } + m_helperList.erase(this); } /** @@ -99,16 +92,15 @@ bool MotorSafetyHelper::IsAlive() const { * updated again. */ void MotorSafetyHelper::Check() { - DriverStation *ds = DriverStation::GetInstance(); - if (!m_enabled || ds->IsDisabled() || ds->IsTest()) return; + DriverStation &ds = DriverStation::GetInstance(); + if (!m_enabled || ds.IsDisabled() || ds.IsTest()) return; std::unique_lock sync(m_syncMutex); if (m_stopTime < Timer::GetFPGATimestamp()) { - char buf[128]; - char desc[64]; + std::ostringstream desc; m_safeObject->GetDescription(desc); - snprintf(buf, 128, "%s... Output not updated often enough.", desc); - wpi_setWPIErrorWithContext(Timeout, buf); + desc << "... Output not updated often enough."; + wpi_setWPIErrorWithContext(Timeout, desc.str().c_str()); m_safeObject->StopMotor(); } } @@ -141,8 +133,7 @@ bool MotorSafetyHelper::IsSafetyEnabled() const { */ void MotorSafetyHelper::CheckMotors() { std::unique_lock sync(m_listMutex); - for (MotorSafetyHelper *msh = m_headHelper; msh != nullptr; - msh = msh->m_nextHelper) { - msh->Check(); + for (auto elem : m_helperList) { + elem->Check(); } } diff --git a/wpilibc/wpilibC++Devices/src/PIDController.cpp b/wpilibc/wpilibC++Devices/src/PIDController.cpp index d7d62cc24b..415e18b627 100644 --- a/wpilibc/wpilibC++Devices/src/PIDController.cpp +++ b/wpilibc/wpilibC++Devices/src/PIDController.cpp @@ -55,7 +55,7 @@ PIDController::PIDController(float Kp, float Ki, float Kd, float Kf, void PIDController::Initialize(float Kp, float Ki, float Kd, float Kf, PIDSource *source, PIDOutput *output, float period) { - m_controlLoop = new Notifier(PIDController::CallCalculate, this); + m_controlLoop = std::make_unique(PIDController::CallCalculate, this); m_P = Kp; m_I = Ki; @@ -73,13 +73,6 @@ void PIDController::Initialize(float Kp, float Ki, float Kd, float Kf, HALReport(HALUsageReporting::kResourceType_PIDController, instances); } -/** - * Free the PID object - */ -PIDController::~PIDController() { - delete m_controlLoop; -} - /** * Call the Calculate method as a non-static method. This avoids having to * prepend @@ -463,7 +456,7 @@ std::string PIDController::GetSmartDashboardType() const { return "PIDController"; } -void PIDController::InitTable(ITable *table) { +void PIDController::InitTable(::std::shared_ptr table) { if (m_table != nullptr) m_table->RemoveTableListener(this); m_table = table; if (m_table != nullptr) { @@ -477,9 +470,9 @@ void PIDController::InitTable(ITable *table) { } } -ITable *PIDController::GetTable() const { return m_table; } +::std::shared_ptr PIDController::GetTable() const { return m_table; } -void PIDController::ValueChanged(ITable *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 e5efc069ac..996105438e 100644 --- a/wpilibc/wpilibC++Devices/src/PWM.cpp +++ b/wpilibc/wpilibC++Devices/src/PWM.cpp @@ -335,7 +335,7 @@ void PWM::SetZeroLatch() { wpi_setErrorWithContext(status, getHALErrorMessage(status)); } -void PWM::ValueChanged(ITable* 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); } @@ -362,9 +362,9 @@ void PWM::StopLiveWindowMode() { std::string PWM::GetSmartDashboardType() const { return "Speed Controller"; } -void PWM::InitTable(ITable* subTable) { +void PWM::InitTable(::std::shared_ptr subTable) { m_table = subTable; UpdateTable(); } -ITable* 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 d127cb9b0a..24ac8a800b 100644 --- a/wpilibc/wpilibC++Devices/src/PowerDistributionPanel.cpp +++ b/wpilibc/wpilibC++Devices/src/PowerDistributionPanel.cpp @@ -180,9 +180,9 @@ std::string PowerDistributionPanel::GetSmartDashboardType() const { return "PowerDistributionPanel"; } -void PowerDistributionPanel::InitTable(ITable *subTable) { +void PowerDistributionPanel::InitTable(::std::shared_ptr subTable) { m_table = subTable; UpdateTable(); } -ITable *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 a9255d598e..cdf48cc557 100644 --- a/wpilibc/wpilibC++Devices/src/Preferences.cpp +++ b/wpilibc/wpilibC++Devices/src/Preferences.cpp @@ -356,7 +356,8 @@ void Preferences::Put(const char *key, std::string value) { else ret.first->second = value; - NetworkTable::GetTable(kTableName)->PutString(key, value); + NetworkTable* table = NetworkTable::GetTable(kTableName); + table->PutString(key, value); } /** @@ -512,7 +513,7 @@ static bool isKeyAcceptable(const std::string &value) { return true; } -void Preferences::ValueChanged(ITable *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 98948e5818..3d0fcca907 100644 --- a/wpilibc/wpilibC++Devices/src/Relay.cpp +++ b/wpilibc/wpilibC++Devices/src/Relay.cpp @@ -15,7 +15,7 @@ #include "HAL/HAL.hpp" // Allocate each direction separately. -static Resource *relayChannels = nullptr; +static ::std::unique_ptr relayChannels; /** * Relay constructor given a channel. @@ -28,7 +28,7 @@ static Resource *relayChannels = nullptr; Relay::Relay(uint32_t channel, Relay::Direction direction) : m_channel(channel), m_direction(direction) { char buf[64]; - Resource::CreateResourceObject(&relayChannels, + Resource::CreateResourceObject(relayChannels, dio_kNumSystems * kRelayChannels * 2); if (!SensorBase::CheckRelayChannel(m_channel)) { snprintf(buf, 64, "Relay Channel %d", m_channel); @@ -39,7 +39,7 @@ Relay::Relay(uint32_t channel, Relay::Direction direction) if (m_direction == kBothDirections || m_direction == kForwardOnly) { snprintf(buf, 64, "Forward Relay %d", m_channel); if (relayChannels->Allocate(m_channel * 2, buf) == ~0ul) { - CloneError(relayChannels); + CloneError(*relayChannels); return; } @@ -48,7 +48,7 @@ Relay::Relay(uint32_t channel, Relay::Direction direction) if (m_direction == kBothDirections || m_direction == kReverseOnly) { snprintf(buf, 64, "Reverse Relay %d", m_channel); if (relayChannels->Allocate(m_channel * 2 + 1, buf) == ~0ul) { - CloneError(relayChannels); + CloneError(*relayChannels); return; } @@ -60,7 +60,7 @@ Relay::Relay(uint32_t channel, Relay::Direction direction) setRelayReverse(m_relay_ports[m_channel], false, &status); wpi_setErrorWithContext(status, getHALErrorMessage(status)); - LiveWindow::GetInstance()->AddActuator("Relay", 1, m_channel, this); + LiveWindow::GetInstance().AddActuator("Relay", 1, m_channel, this); } /** @@ -187,7 +187,7 @@ Relay::Value Relay::Get() const { wpi_setErrorWithContext(status, getHALErrorMessage(status)); } -void Relay::ValueChanged(ITable *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") @@ -228,9 +228,9 @@ void Relay::StopLiveWindowMode() { std::string Relay::GetSmartDashboardType() const { return "Relay"; } -void Relay::InitTable(ITable *subTable) { +void Relay::InitTable(::std::shared_ptr subTable) { m_table = subTable; UpdateTable(); } -ITable *Relay::GetTable() const { return m_table; } +::std::shared_ptr Relay::GetTable() const { return m_table; } diff --git a/wpilibc/wpilibC++Devices/src/RobotBase.cpp b/wpilibc/wpilibC++Devices/src/RobotBase.cpp index fd1fc4ee99..9adc51f638 100644 --- a/wpilibc/wpilibC++Devices/src/RobotBase.cpp +++ b/wpilibc/wpilibC++Devices/src/RobotBase.cpp @@ -45,8 +45,7 @@ void RobotBase::robotSetup(RobotBase *robot) { * nice to put this code into it's own task that loads on boot so ensure that it * runs. */ -RobotBase::RobotBase() { - m_ds = DriverStation::GetInstance(); +RobotBase::RobotBase() : m_ds(DriverStation::GetInstance()) { RobotState::SetImplementation(DriverStation::GetInstance()); HLUsageReporting::SetImplementation(new HardwareHLReporting()); @@ -76,34 +75,34 @@ RobotBase::~RobotBase() { * Determine if the Robot is currently enabled. * @return True if the Robot is currently enabled by the field controls. */ -bool RobotBase::IsEnabled() const { return m_ds->IsEnabled(); } +bool RobotBase::IsEnabled() const { return m_ds.IsEnabled(); } /** * Determine if the Robot is currently disabled. * @return True if the Robot is currently disabled by the field controls. */ -bool RobotBase::IsDisabled() const { return m_ds->IsDisabled(); } +bool RobotBase::IsDisabled() const { return m_ds.IsDisabled(); } /** * Determine if the robot is currently in Autonomous mode. * @return True if the robot is currently operating Autonomously as determined * by the field controls. */ -bool RobotBase::IsAutonomous() const { return m_ds->IsAutonomous(); } +bool RobotBase::IsAutonomous() const { return m_ds.IsAutonomous(); } /** * Determine if the robot is currently in Operator Control mode. * @return True if the robot is currently operating in Tele-Op mode as * determined by the field controls. */ -bool RobotBase::IsOperatorControl() const { return m_ds->IsOperatorControl(); } +bool RobotBase::IsOperatorControl() const { return m_ds.IsOperatorControl(); } /** * Determine if the robot is currently in Test mode. * @return True if the robot is currently running tests as determined by the * field controls. */ -bool RobotBase::IsTest() const { return m_ds->IsTest(); } +bool RobotBase::IsTest() const { return m_ds.IsTest(); } /** * This hook is called right before startCompetition(). By default, tell the DS @@ -123,7 +122,7 @@ void RobotBase::Prestart() { * @return Has new data arrived over the network since the last time this * function was called? */ -bool RobotBase::IsNewDataAvailable() const { return m_ds->IsNewControlData(); } +bool RobotBase::IsNewDataAvailable() const { return m_ds.IsNewControlData(); } /** * This class exists for the sole purpose of getting its destructor called when diff --git a/wpilibc/wpilibC++Devices/src/RobotDrive.cpp b/wpilibc/wpilibC++Devices/src/RobotDrive.cpp index 5d1f648515..428d726c2d 100644 --- a/wpilibc/wpilibC++Devices/src/RobotDrive.cpp +++ b/wpilibc/wpilibC++Devices/src/RobotDrive.cpp @@ -21,6 +21,11 @@ const int32_t RobotDrive::kMaxNumberOfMotors; +[[deprecated]] +static auto make_shared_nodelete(SpeedController *ptr) { + return ::std::shared_ptr(ptr, NullDeleter()); +} + /* * Driving functions * These functions provide an interface to multiple motors that is used for C @@ -37,7 +42,7 @@ const int32_t RobotDrive::kMaxNumberOfMotors; * robot drive. */ void RobotDrive::InitRobotDrive() { - m_safetyHelper = new MotorSafetyHelper(this); + m_safetyHelper = std::make_unique(this); m_safetyHelper->SetSafetyEnabled(true); } @@ -53,10 +58,9 @@ void RobotDrive::InitRobotDrive() { */ RobotDrive::RobotDrive(uint32_t leftMotorChannel, uint32_t rightMotorChannel) { InitRobotDrive(); - m_rearLeftMotor = new Talon(leftMotorChannel); - m_rearRightMotor = new Talon(rightMotorChannel); + m_rearLeftMotor = ::std::make_shared(leftMotorChannel); + m_rearRightMotor = ::std::make_shared(rightMotorChannel); SetLeftRightMotorOutputs(0.0, 0.0); - m_deleteSpeedControllers = true; } /** @@ -76,12 +80,11 @@ 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 = new Talon(rearLeftMotor); - m_rearRightMotor = new Talon(rearRightMotor); - m_frontLeftMotor = new Talon(frontLeftMotor); - m_frontRightMotor = new Talon(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); - m_deleteSpeedControllers = true; } /** @@ -103,17 +106,28 @@ RobotDrive::RobotDrive(SpeedController *leftMotor, m_rearLeftMotor = m_rearRightMotor = nullptr; return; } - m_rearLeftMotor = leftMotor; - m_rearRightMotor = rightMotor; - m_deleteSpeedControllers = false; + m_rearLeftMotor = make_shared_nodelete(leftMotor); + m_rearRightMotor = make_shared_nodelete(rightMotor); } +//TODO: Change to rvalue references & move syntax. RobotDrive::RobotDrive(SpeedController &leftMotor, SpeedController &rightMotor) { InitRobotDrive(); - m_rearLeftMotor = &leftMotor; - m_rearRightMotor = &rightMotor; - m_deleteSpeedControllers = false; + m_rearLeftMotor = make_shared_nodelete(&leftMotor); + m_rearRightMotor = make_shared_nodelete(&rightMotor); +} + +RobotDrive::RobotDrive(::std::shared_ptr leftMotor, + ::std::shared_ptr rightMotor) { + InitRobotDrive(); + if (leftMotor == nullptr || rightMotor == nullptr) { + wpi_setWPIError(NullParameter); + m_rearLeftMotor = m_rearRightMotor = nullptr; + return; + } + m_rearLeftMotor = leftMotor; + m_rearRightMotor = rightMotor; } /** @@ -139,11 +153,10 @@ RobotDrive::RobotDrive(SpeedController *frontLeftMotor, wpi_setWPIError(NullParameter); return; } - m_frontLeftMotor = frontLeftMotor; - m_rearLeftMotor = rearLeftMotor; - m_frontRightMotor = frontRightMotor; - m_rearRightMotor = rearRightMotor; - m_deleteSpeedControllers = false; + m_frontLeftMotor = make_shared_nodelete(frontLeftMotor); + m_rearLeftMotor = make_shared_nodelete(rearLeftMotor); + m_frontRightMotor = make_shared_nodelete(frontRightMotor); + m_rearRightMotor = make_shared_nodelete(rearRightMotor); } RobotDrive::RobotDrive(SpeedController &frontLeftMotor, @@ -151,25 +164,26 @@ RobotDrive::RobotDrive(SpeedController &frontLeftMotor, SpeedController &frontRightMotor, SpeedController &rearRightMotor) { InitRobotDrive(); - m_frontLeftMotor = &frontLeftMotor; - m_rearLeftMotor = &rearLeftMotor; - m_frontRightMotor = &frontRightMotor; - m_rearRightMotor = &rearRightMotor; - m_deleteSpeedControllers = false; + m_frontLeftMotor = make_shared_nodelete(&frontLeftMotor); + m_rearLeftMotor = make_shared_nodelete(&rearLeftMotor); + m_frontRightMotor = make_shared_nodelete(&frontRightMotor); + m_rearRightMotor = make_shared_nodelete(&rearRightMotor); } -/** - * RobotDrive destructor. - * Deletes motor objects that were not passed in and created internally only. - **/ -RobotDrive::~RobotDrive() { - if (m_deleteSpeedControllers) { - delete m_frontLeftMotor; - delete m_rearLeftMotor; - delete m_frontRightMotor; - delete m_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) { + wpi_setWPIError(NullParameter); + return; } - delete m_safetyHelper; + m_frontLeftMotor = frontLeftMotor; + m_rearLeftMotor = rearLeftMotor; + m_frontRightMotor = frontRightMotor; + m_rearRightMotor = rearRightMotor; } /** @@ -722,8 +736,8 @@ void RobotDrive::SetSafetyEnabled(bool enabled) { m_safetyHelper->SetSafetyEnabled(enabled); } -void RobotDrive::GetDescription(char *desc) const { - sprintf(desc, "RobotDrive"); +void RobotDrive::GetDescription(std::ostringstream& desc) const { + desc << "RobotDrive"; } void RobotDrive::StopMotor() { diff --git a/wpilibc/wpilibC++Devices/src/SafePWM.cpp b/wpilibc/wpilibC++Devices/src/SafePWM.cpp index 09689eddbd..801e3eef6f 100644 --- a/wpilibc/wpilibC++Devices/src/SafePWM.cpp +++ b/wpilibc/wpilibC++Devices/src/SafePWM.cpp @@ -7,20 +7,16 @@ #include "SafePWM.h" -#include "MotorSafetyHelper.h" - /** * Constructor for a SafePWM object taking a channel number. * @param channel The PWM channel number 0-9 are on-board, 10-19 are on the MXP * port */ SafePWM::SafePWM(uint32_t channel) : PWM(channel) { - m_safetyHelper = new MotorSafetyHelper(this); + m_safetyHelper = std::make_unique(this); m_safetyHelper->SetSafetyEnabled(false); } -SafePWM::~SafePWM() { delete m_safetyHelper; } - /** * Set the expiration time for the PWM object * @param timeout The timeout (in seconds) for this motor object @@ -68,8 +64,8 @@ bool SafePWM::IsSafetyEnabled() const { return m_safetyHelper->IsSafetyEnabled(); } -void SafePWM::GetDescription(char *desc) const { - sprintf(desc, "PWM %d", GetChannel()); +void SafePWM::GetDescription(std::ostringstream& desc) const { + desc << "PWM " << GetChannel(); } /** diff --git a/wpilibc/wpilibC++Devices/src/SampleRobot.cpp b/wpilibc/wpilibC++Devices/src/SampleRobot.cpp index 407e60ef4a..2fa9bebc5b 100644 --- a/wpilibc/wpilibC++Devices/src/SampleRobot.cpp +++ b/wpilibc/wpilibC++Devices/src/SampleRobot.cpp @@ -101,7 +101,7 @@ void SampleRobot::RobotMain() { m_robotMainOverridden = false; } * robot to be enabled again. */ void SampleRobot::StartCompetition() { - LiveWindow *lw = LiveWindow::GetInstance(); + LiveWindow &lw = LiveWindow::GetInstance(); HALReport(HALUsageReporting::kResourceType_Framework, HALUsageReporting::kFramework_Simple); @@ -115,32 +115,32 @@ void SampleRobot::StartCompetition() { if (!m_robotMainOverridden) { // first and one-time initialization - lw->SetEnabled(false); + lw.SetEnabled(false); RobotInit(); while (true) { if (IsDisabled()) { - m_ds->InDisabled(true); + m_ds.InDisabled(true); Disabled(); - m_ds->InDisabled(false); - while (IsDisabled()) m_ds->WaitForData(); + m_ds.InDisabled(false); + while (IsDisabled()) m_ds.WaitForData(); } else if (IsAutonomous()) { - m_ds->InAutonomous(true); + m_ds.InAutonomous(true); Autonomous(); - m_ds->InAutonomous(false); - while (IsAutonomous() && IsEnabled()) m_ds->WaitForData(); + m_ds.InAutonomous(false); + while (IsAutonomous() && IsEnabled()) m_ds.WaitForData(); } else if (IsTest()) { - lw->SetEnabled(true); - m_ds->InTest(true); + lw.SetEnabled(true); + m_ds.InTest(true); Test(); - m_ds->InTest(false); - while (IsTest() && IsEnabled()) m_ds->WaitForData(); - lw->SetEnabled(false); + m_ds.InTest(false); + while (IsTest() && IsEnabled()) m_ds.WaitForData(); + lw.SetEnabled(false); } else { - m_ds->InOperatorControl(true); + m_ds.InOperatorControl(true); OperatorControl(); - m_ds->InOperatorControl(false); - while (IsOperatorControl() && IsEnabled()) m_ds->WaitForData(); + m_ds.InOperatorControl(false); + while (IsOperatorControl() && IsEnabled()) m_ds.WaitForData(); } } } diff --git a/wpilibc/wpilibC++Devices/src/Servo.cpp b/wpilibc/wpilibC++Devices/src/Servo.cpp index 304c97cb32..e5a3cc31ba 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(ITable* 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(ITable* subTable) { +void Servo::InitTable(::std::shared_ptr subTable) { m_table = subTable; UpdateTable(); } -ITable* 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 422c5adeeb..97078cdaa7 100644 --- a/wpilibc/wpilibC++Devices/src/Solenoid.cpp +++ b/wpilibc/wpilibC++Devices/src/Solenoid.cpp @@ -37,16 +37,16 @@ Solenoid::Solenoid(uint8_t moduleNumber, uint32_t channel) wpi_setWPIErrorWithContext(ChannelIndexOutOfRange, buf); return; } - Resource::CreateResourceObject(&m_allocated, kSolenoidChannels * 63); + Resource::CreateResourceObject(m_allocated, kSolenoidChannels * 63); snprintf(buf, 64, "Solenoid %d (Module: %d)", m_channel, m_moduleNumber); if (m_allocated->Allocate(m_moduleNumber * kSolenoidChannels + m_channel, buf) == ~0ul) { - CloneError(m_allocated); + CloneError(*m_allocated); return; } - LiveWindow::GetInstance()->AddActuator("Solenoid", m_moduleNumber, m_channel, + LiveWindow::GetInstance().AddActuator("Solenoid", m_moduleNumber, m_channel, this); HALReport(HALUsageReporting::kResourceType_Solenoid, m_channel, m_moduleNumber); @@ -97,7 +97,7 @@ bool Solenoid::IsBlackListed() const { return (value != 0); } -void Solenoid::ValueChanged(ITable* source, const std::string& key, +void Solenoid::ValueChanged(::std::shared_ptr source, const std::string& key, EntryValue value, bool isNew) { Set(value.b); } @@ -124,9 +124,9 @@ void Solenoid::StopLiveWindowMode() { std::string Solenoid::GetSmartDashboardType() const { return "Solenoid"; } -void Solenoid::InitTable(ITable* subTable) { +void Solenoid::InitTable(::std::shared_ptr subTable) { m_table = subTable; UpdateTable(); } -ITable* Solenoid::GetTable() const { return m_table; } +::std::shared_ptr Solenoid::GetTable() const { return m_table; } diff --git a/wpilibc/wpilibC++Devices/src/SolenoidBase.cpp b/wpilibc/wpilibC++Devices/src/SolenoidBase.cpp index 9ce51b5e60..b6b47980b4 100644 --- a/wpilibc/wpilibC++Devices/src/SolenoidBase.cpp +++ b/wpilibc/wpilibC++Devices/src/SolenoidBase.cpp @@ -7,9 +7,6 @@ #include "SolenoidBase.h" -// Needs to be global since the protected resource spans all Solenoid objects. -Resource* SolenoidBase::m_allocated = nullptr; - void* SolenoidBase::m_ports[m_maxModules][m_maxPorts]; /** * Constructor diff --git a/wpilibc/wpilibC++Devices/src/Talon.cpp b/wpilibc/wpilibC++Devices/src/Talon.cpp index 1270af839b..b9be294a7f 100644 --- a/wpilibc/wpilibC++Devices/src/Talon.cpp +++ b/wpilibc/wpilibC++Devices/src/Talon.cpp @@ -35,7 +35,7 @@ Talon::Talon(uint32_t channel) : SafePWM(channel) { SetZeroLatch(); HALReport(HALUsageReporting::kResourceType_Talon, GetChannel()); - LiveWindow::GetInstance()->AddActuator("Talon", GetChannel(), this); + LiveWindow::GetInstance().AddActuator("Talon", GetChannel(), this); } /** diff --git a/wpilibc/wpilibC++Devices/src/TalonSRX.cpp b/wpilibc/wpilibC++Devices/src/TalonSRX.cpp index 6e6115f872..ea00cd440e 100644 --- a/wpilibc/wpilibC++Devices/src/TalonSRX.cpp +++ b/wpilibc/wpilibC++Devices/src/TalonSRX.cpp @@ -34,7 +34,7 @@ TalonSRX::TalonSRX(uint32_t channel) : SafePWM(channel) { SetZeroLatch(); HALReport(HALUsageReporting::kResourceType_TalonSRX, GetChannel()); - LiveWindow::GetInstance()->AddActuator("TalonSRX", GetChannel(), this); + LiveWindow::GetInstance().AddActuator("TalonSRX", GetChannel(), this); } /** diff --git a/wpilibc/wpilibC++Devices/src/Ultrasonic.cpp b/wpilibc/wpilibC++Devices/src/Ultrasonic.cpp index d228899448..551bf1c467 100644 --- a/wpilibc/wpilibC++Devices/src/Ultrasonic.cpp +++ b/wpilibc/wpilibC++Devices/src/Ultrasonic.cpp @@ -72,17 +72,16 @@ void Ultrasonic::Initialize() { m_firstSensor = this; } - m_counter = new Counter(m_echoChannel); // set up counter for this sensor - m_counter->SetMaxPeriod(1.0); - m_counter->SetSemiPeriodMode(true); - m_counter->Reset(); + m_counter.SetMaxPeriod(1.0); + m_counter.SetSemiPeriodMode(true); + m_counter.Reset(); m_enabled = true; // make it available for round robin scheduling SetAutomaticMode(originalMode); static int instances = 0; instances++; HALReport(HALUsageReporting::kResourceType_Ultrasonic, instances); - LiveWindow::GetInstance()->AddSensor("Ultrasonic", + LiveWindow::GetInstance().AddSensor("Ultrasonic", m_echoChannel->GetChannel(), this); } @@ -99,10 +98,10 @@ void Ultrasonic::Initialize() { * @param units The units returned in either kInches or kMilliMeters */ Ultrasonic::Ultrasonic(uint32_t pingChannel, uint32_t echoChannel, - DistanceUnit units) { - m_pingChannel = new DigitalOutput(pingChannel); - m_echoChannel = new DigitalInput(echoChannel); - m_allocatedChannels = true; + DistanceUnit units) + : m_pingChannel(::std::make_shared(pingChannel)), + m_echoChannel(::std::make_shared(echoChannel)), + m_counter(m_echoChannel) { m_units = units; Initialize(); } @@ -118,14 +117,14 @@ Ultrasonic::Ultrasonic(uint32_t pingChannel, uint32_t echoChannel, * @param units The units returned in either kInches or kMilliMeters */ Ultrasonic::Ultrasonic(DigitalOutput *pingChannel, DigitalInput *echoChannel, - DistanceUnit units) { + DistanceUnit units) + : m_pingChannel(pingChannel, NullDeleter()), + m_echoChannel(echoChannel, NullDeleter()), + m_counter(m_echoChannel) { if (pingChannel == nullptr || echoChannel == nullptr) { wpi_setWPIError(NullParameter); return; } - m_allocatedChannels = false; - m_pingChannel = pingChannel; - m_echoChannel = echoChannel; m_units = units; Initialize(); } @@ -141,10 +140,30 @@ Ultrasonic::Ultrasonic(DigitalOutput *pingChannel, DigitalInput *echoChannel, * @param units The units returned in either kInches or kMilliMeters */ Ultrasonic::Ultrasonic(DigitalOutput &pingChannel, DigitalInput &echoChannel, - DistanceUnit units) { - m_allocatedChannels = false; - m_pingChannel = &pingChannel; - m_echoChannel = &echoChannel; + DistanceUnit units) + : m_pingChannel(&pingChannel, NullDeleter()), + m_echoChannel(&echoChannel, NullDeleter()), + m_counter(m_echoChannel) { + m_units = units; + Initialize(); +} + +/** + * Create an instance of an Ultrasonic Sensor from a DigitalInput for the echo + * channel and a DigitalOutput + * for the ping channel. + * @param pingChannel The digital output object that starts the sensor doing a + * ping. Requires a 10uS pulse to start. + * @param echoChannel The digital input object that times the return pulse to + * determine the range. + * @param units The units returned in either kInches or kMilliMeters + */ +Ultrasonic::Ultrasonic(::std::shared_ptr pingChannel, + ::std::shared_ptr echoChannel, + DistanceUnit units) + : m_pingChannel(pingChannel), + m_echoChannel(echoChannel), + m_counter(m_echoChannel) { m_units = units; Initialize(); } @@ -160,10 +179,6 @@ Ultrasonic::Ultrasonic(DigitalOutput &pingChannel, DigitalInput &echoChannel, Ultrasonic::~Ultrasonic() { bool wasAutomaticMode = m_automaticEnabled; SetAutomaticMode(false); - if (m_allocatedChannels) { - delete m_pingChannel; - delete m_echoChannel; - } wpi_assert(m_firstSensor != nullptr); { @@ -194,7 +209,7 @@ Ultrasonic::~Ultrasonic() { * the ultrasonic sensors. This * scheduling method assures that the sensors are non-interfering because no two * sensors fire at the same time. - * If another scheduling algorithm is preffered, it can be implemented by + * If another scheduling algorithm is prefered, it can be implemented by * pinging the sensors manually and waiting * for the results to come back. */ @@ -206,7 +221,7 @@ void Ultrasonic::SetAutomaticMode(bool enabling) { // enabling automatic mode. // Clear all the counters so no data is valid for (Ultrasonic *u = m_firstSensor; u != nullptr; u = u->m_nextSensor) { - u->m_counter->Reset(); + u->m_counter.Reset(); } // Start round robin task wpi_assert(m_task.Verify() == @@ -225,7 +240,7 @@ void Ultrasonic::SetAutomaticMode(bool enabling) { // clear all the counters (data now invalid) since automatic mode is stopped for (Ultrasonic *u = m_firstSensor; u != nullptr; u = u->m_nextSensor) { - u->m_counter->Reset(); + u->m_counter.Reset(); } m_automaticEnabled = false; m_task.join(); @@ -242,7 +257,7 @@ void Ultrasonic::SetAutomaticMode(bool enabling) { */ void Ultrasonic::Ping() { wpi_assert(!m_automaticEnabled); - m_counter->Reset(); // reset the counter to zero (invalid data now) + m_counter.Reset(); // reset the counter to zero (invalid data now) m_pingChannel->Pulse( kPingTime); // do the ping to start getting a single range } @@ -254,7 +269,7 @@ void Ultrasonic::Ping() { * signal. If the count is not at least 2, then the range has not yet been * measured, and is invalid. */ -bool Ultrasonic::IsRangeValid() const { return m_counter->Get() > 1; } +bool Ultrasonic::IsRangeValid() const { return m_counter.Get() > 1; } /** * Get the range in inches from the ultrasonic sensor. @@ -265,7 +280,7 @@ bool Ultrasonic::IsRangeValid() const { return m_counter->Get() > 1; } */ double Ultrasonic::GetRangeInches() const { if (IsRangeValid()) - return m_counter->GetPeriod() * kSpeedOfSoundInchesPerSec / 2.0; + return m_counter.GetPeriod() * kSpeedOfSoundInchesPerSec / 2.0; else return 0; } @@ -324,9 +339,9 @@ void Ultrasonic::StopLiveWindowMode() {} std::string Ultrasonic::GetSmartDashboardType() const { return "Ultrasonic"; } -void Ultrasonic::InitTable(ITable *subTable) { +void Ultrasonic::InitTable(::std::shared_ptr subTable) { m_table = subTable; UpdateTable(); } -ITable *Ultrasonic::GetTable() const { return m_table; } +::std::shared_ptr Ultrasonic::GetTable() const { return m_table; } diff --git a/wpilibc/wpilibC++Devices/src/Victor.cpp b/wpilibc/wpilibC++Devices/src/Victor.cpp index 30202db528..f20e1904d9 100644 --- a/wpilibc/wpilibC++Devices/src/Victor.cpp +++ b/wpilibc/wpilibC++Devices/src/Victor.cpp @@ -35,7 +35,7 @@ Victor::Victor(uint32_t channel) : SafePWM(channel) { SetRaw(m_centerPwm); SetZeroLatch(); - LiveWindow::GetInstance()->AddActuator("Victor", GetChannel(), this); + LiveWindow::GetInstance().AddActuator("Victor", GetChannel(), this); HALReport(HALUsageReporting::kResourceType_Victor, GetChannel()); } diff --git a/wpilibc/wpilibC++Devices/src/VictorSP.cpp b/wpilibc/wpilibC++Devices/src/VictorSP.cpp index 5341ccfb93..81af2c3d91 100644 --- a/wpilibc/wpilibC++Devices/src/VictorSP.cpp +++ b/wpilibc/wpilibC++Devices/src/VictorSP.cpp @@ -39,7 +39,7 @@ VictorSP::VictorSP(uint32_t channel) : SafePWM(channel) { SetZeroLatch(); HALReport(HALUsageReporting::kResourceType_VictorSP, GetChannel()); - LiveWindow::GetInstance()->AddActuator("VictorSP", GetChannel(), this); + LiveWindow::GetInstance().AddActuator("VictorSP", GetChannel(), this); } /** diff --git a/wpilibc/wpilibC++IntegrationTests/src/AnalogLoopTest.cpp b/wpilibc/wpilibC++IntegrationTests/src/AnalogLoopTest.cpp index d03c62dc88..190caeea70 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 - AnalogTriggerOutput *triggerOutput = trigger.CreateOutput(kState); + ::std::shared_ptr triggerOutput = trigger.CreateOutput(kState); triggerOutput->RequestInterrupts(InterruptHandler, ¶m); triggerOutput->EnableInterrupts(); @@ -121,6 +121,4 @@ TEST_F(AnalogLoopTest, AsynchronusInterruptWorks) { // Then the int should be 12345 Wait(kDelayTime); EXPECT_EQ(12345, param) << "The interrupt did not run."; - - delete triggerOutput; } diff --git a/wpilibc/wpilibC++IntegrationTests/src/FakeEncoderTest.cpp b/wpilibc/wpilibC++IntegrationTests/src/FakeEncoderTest.cpp index e6c86a684a..2f408b6da5 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; - AnalogTriggerOutput *m_indexAnalogTriggerOutput; + ::std::shared_ptr m_indexAnalogTriggerOutput; virtual void SetUp() override { m_outputA = new DigitalOutput(TestBench::kLoop2OutputChannel); @@ -43,7 +43,6 @@ class FakeEncoderTest : public testing::Test { delete m_indexOutput; delete m_encoder; delete m_indexAnalogTrigger; - delete m_indexAnalogTriggerOutput; } /** @@ -95,7 +94,7 @@ TEST_F(FakeEncoderTest, TestCountUp) { * Test that the encoder can stay reset while the index source is high */ TEST_F(FakeEncoderTest, TestResetWhileHigh) { - m_encoder->SetIndexSource(m_indexAnalogTriggerOutput, + m_encoder->SetIndexSource(*m_indexAnalogTriggerOutput, Encoder::IndexingType::kResetWhileHigh); SetIndexLow(); @@ -111,7 +110,7 @@ TEST_F(FakeEncoderTest, TestResetWhileHigh) { * Test that the encoder can reset when the index source goes from low to high */ TEST_F(FakeEncoderTest, TestResetOnRisingEdge) { - m_encoder->SetIndexSource(m_indexAnalogTriggerOutput, + m_encoder->SetIndexSource(*m_indexAnalogTriggerOutput, Encoder::IndexingType::kResetOnRisingEdge); SetIndexLow(); @@ -127,7 +126,7 @@ TEST_F(FakeEncoderTest, TestResetOnRisingEdge) { * Test that the encoder can stay reset while the index source is low */ TEST_F(FakeEncoderTest, TestResetWhileLow) { - m_encoder->SetIndexSource(m_indexAnalogTriggerOutput, + m_encoder->SetIndexSource(*m_indexAnalogTriggerOutput, Encoder::IndexingType::kResetWhileLow); SetIndexHigh(); @@ -143,7 +142,7 @@ TEST_F(FakeEncoderTest, TestResetWhileLow) { * Test that the encoder can reset when the index source goes from high to low */ TEST_F(FakeEncoderTest, TestResetOnFallingEdge) { - m_encoder->SetIndexSource(m_indexAnalogTriggerOutput, + m_encoder->SetIndexSource(*m_indexAnalogTriggerOutput, Encoder::IndexingType::kResetOnFallingEdge); SetIndexHigh(); diff --git a/wpilibc/wpilibC++IntegrationTests/src/TestEnvironment.cpp b/wpilibc/wpilibC++IntegrationTests/src/TestEnvironment.cpp index 2d21303c4a..6163a050e8 100644 --- a/wpilibc/wpilibC++IntegrationTests/src/TestEnvironment.cpp +++ b/wpilibc/wpilibC++IntegrationTests/src/TestEnvironment.cpp @@ -28,11 +28,11 @@ class TestEnvironment : public testing::Environment { station returns that the robot is enabled, to ensure that tests will be able to run on the hardware. */ HALNetworkCommunicationObserveUserProgramStarting(); - LiveWindow::GetInstance()->SetEnabled(false); + LiveWindow::GetInstance().SetEnabled(false); std::cout << "Waiting for enable" << std::endl; - while (!DriverStation::GetInstance()->IsEnabled()) { + while (!DriverStation::GetInstance().IsEnabled()) { Wait(0.1); } } diff --git a/wpilibc/wpilibC++IntegrationTests/src/command/CommandTest.cpp b/wpilibc/wpilibC++IntegrationTests/src/command/CommandTest.cpp index 4b62fa35b4..019e67a87a 100644 --- a/wpilibc/wpilibC++IntegrationTests/src/command/CommandTest.cpp +++ b/wpilibc/wpilibC++IntegrationTests/src/command/CommandTest.cpp @@ -15,7 +15,7 @@ class CommandTest : public testing::Test { protected: virtual void SetUp() override { RobotState::SetImplementation(DriverStation::GetInstance()); - Scheduler::GetInstance()->SetEnabled(true); + Scheduler::GetInstance().SetEnabled(true); } /** @@ -27,7 +27,7 @@ class CommandTest : public testing::Test { * is called outside of the * scope of the test. */ - void TeardownScheduler() { Scheduler::GetInstance()->ResetAll(); } + void TeardownScheduler() { Scheduler::GetInstance().ResetAll(); } void AssertCommandState(MockCommand &command, int initialize, int execute, int isFinished, int end, int interrupted) { @@ -69,24 +69,24 @@ TEST_F(CommandTest, ParallelCommands) { commandGroup.Start(); AssertCommandState(command1, 0, 0, 0, 0, 0); AssertCommandState(command2, 0, 0, 0, 0, 0); - Scheduler::GetInstance()->Run(); + Scheduler::GetInstance().Run(); AssertCommandState(command1, 0, 0, 0, 0, 0); AssertCommandState(command2, 0, 0, 0, 0, 0); - Scheduler::GetInstance()->Run(); + Scheduler::GetInstance().Run(); AssertCommandState(command1, 1, 1, 1, 0, 0); AssertCommandState(command2, 1, 1, 1, 0, 0); - Scheduler::GetInstance()->Run(); + Scheduler::GetInstance().Run(); AssertCommandState(command1, 1, 2, 2, 0, 0); AssertCommandState(command2, 1, 2, 2, 0, 0); command1.SetHasFinished(true); - Scheduler::GetInstance()->Run(); + Scheduler::GetInstance().Run(); AssertCommandState(command1, 1, 3, 3, 1, 0); AssertCommandState(command2, 1, 3, 3, 0, 0); - Scheduler::GetInstance()->Run(); + Scheduler::GetInstance().Run(); AssertCommandState(command1, 1, 3, 3, 1, 0); AssertCommandState(command2, 1, 4, 4, 0, 0); command2.SetHasFinished(true); - Scheduler::GetInstance()->Run(); + Scheduler::GetInstance().Run(); AssertCommandState(command1, 1, 3, 3, 1, 0); AssertCommandState(command2, 1, 5, 5, 1, 0); @@ -99,17 +99,17 @@ TEST_F(CommandTest, RunAndTerminate) { MockCommand command; command.Start(); AssertCommandState(command, 0, 0, 0, 0, 0); - Scheduler::GetInstance()->Run(); + Scheduler::GetInstance().Run(); AssertCommandState(command, 0, 0, 0, 0, 0); - Scheduler::GetInstance()->Run(); + Scheduler::GetInstance().Run(); AssertCommandState(command, 1, 1, 1, 0, 0); - Scheduler::GetInstance()->Run(); + Scheduler::GetInstance().Run(); AssertCommandState(command, 1, 2, 2, 0, 0); command.SetHasFinished(true); AssertCommandState(command, 1, 2, 2, 0, 0); - Scheduler::GetInstance()->Run(); + Scheduler::GetInstance().Run(); AssertCommandState(command, 1, 3, 3, 1, 0); - Scheduler::GetInstance()->Run(); + Scheduler::GetInstance().Run(); AssertCommandState(command, 1, 3, 3, 1, 0); TeardownScheduler(); @@ -119,19 +119,19 @@ TEST_F(CommandTest, RunAndCancel) { MockCommand command; command.Start(); AssertCommandState(command, 0, 0, 0, 0, 0); - Scheduler::GetInstance()->Run(); + Scheduler::GetInstance().Run(); AssertCommandState(command, 0, 0, 0, 0, 0); - Scheduler::GetInstance()->Run(); + Scheduler::GetInstance().Run(); AssertCommandState(command, 1, 1, 1, 0, 0); - Scheduler::GetInstance()->Run(); + Scheduler::GetInstance().Run(); AssertCommandState(command, 1, 2, 2, 0, 0); - Scheduler::GetInstance()->Run(); + Scheduler::GetInstance().Run(); AssertCommandState(command, 1, 3, 3, 0, 0); command.Cancel(); AssertCommandState(command, 1, 3, 3, 0, 0); - Scheduler::GetInstance()->Run(); + Scheduler::GetInstance().Run(); AssertCommandState(command, 1, 3, 3, 0, 1); - Scheduler::GetInstance()->Run(); + Scheduler::GetInstance().Run(); AssertCommandState(command, 1, 3, 3, 0, 1); TeardownScheduler(); @@ -162,34 +162,34 @@ TEST_F(CommandTest, ThreeCommandOnSubSystem) { AssertCommandState(command2, 0, 0, 0, 0, 0); AssertCommandState(command3, 0, 0, 0, 0, 0); - Scheduler::GetInstance()->Run(); + Scheduler::GetInstance().Run(); AssertCommandState(command1, 0, 0, 0, 0, 0); AssertCommandState(command2, 0, 0, 0, 0, 0); AssertCommandState(command3, 0, 0, 0, 0, 0); - Scheduler::GetInstance()->Run(); + Scheduler::GetInstance().Run(); AssertCommandState(command1, 1, 1, 1, 0, 0); AssertCommandState(command2, 0, 0, 0, 0, 0); AssertCommandState(command3, 0, 0, 0, 0, 0); Wait(1); // command 1 timeout - Scheduler::GetInstance()->Run(); + Scheduler::GetInstance().Run(); AssertCommandState(command1, 1, 1, 1, 0, 1); AssertCommandState(command2, 1, 1, 1, 0, 0); AssertCommandState(command3, 0, 0, 0, 0, 0); - Scheduler::GetInstance()->Run(); + Scheduler::GetInstance().Run(); AssertCommandState(command1, 1, 1, 1, 0, 1); AssertCommandState(command2, 1, 2, 2, 0, 0); AssertCommandState(command3, 0, 0, 0, 0, 0); Wait(2); // command 2 timeout - Scheduler::GetInstance()->Run(); + Scheduler::GetInstance().Run(); AssertCommandState(command1, 1, 1, 1, 0, 1); AssertCommandState(command2, 1, 2, 2, 0, 1); AssertCommandState(command3, 1, 1, 1, 0, 0); - Scheduler::GetInstance()->Run(); + Scheduler::GetInstance().Run(); AssertCommandState(command1, 1, 1, 1, 0, 1); AssertCommandState(command2, 1, 2, 2, 0, 1); AssertCommandState(command3, 1, 2, 2, 0, 0); @@ -198,12 +198,12 @@ TEST_F(CommandTest, ThreeCommandOnSubSystem) { AssertCommandState(command2, 1, 2, 2, 0, 1); AssertCommandState(command3, 1, 2, 2, 0, 0); - Scheduler::GetInstance()->Run(); + Scheduler::GetInstance().Run(); AssertCommandState(command1, 1, 1, 1, 0, 1); AssertCommandState(command2, 1, 2, 2, 0, 1); AssertCommandState(command3, 1, 3, 3, 1, 0); - Scheduler::GetInstance()->Run(); + Scheduler::GetInstance().Run(); AssertCommandState(command1, 1, 1, 1, 0, 1); AssertCommandState(command2, 1, 2, 2, 0, 1); AssertCommandState(command3, 1, 3, 3, 1, 0); @@ -227,19 +227,19 @@ TEST_F(CommandTest, OneCommandSupersedingAnotherBecauseOfDependencies) { AssertCommandState(command1, 0, 0, 0, 0, 0); AssertCommandState(command2, 0, 0, 0, 0, 0); - Scheduler::GetInstance()->Run(); + Scheduler::GetInstance().Run(); AssertCommandState(command1, 0, 0, 0, 0, 0); AssertCommandState(command2, 0, 0, 0, 0, 0); - Scheduler::GetInstance()->Run(); + Scheduler::GetInstance().Run(); AssertCommandState(command1, 1, 1, 1, 0, 0); AssertCommandState(command2, 0, 0, 0, 0, 0); - Scheduler::GetInstance()->Run(); + Scheduler::GetInstance().Run(); AssertCommandState(command1, 1, 2, 2, 0, 0); AssertCommandState(command2, 0, 0, 0, 0, 0); - Scheduler::GetInstance()->Run(); + Scheduler::GetInstance().Run(); AssertCommandState(command1, 1, 3, 3, 0, 0); AssertCommandState(command2, 0, 0, 0, 0, 0); @@ -247,19 +247,19 @@ TEST_F(CommandTest, OneCommandSupersedingAnotherBecauseOfDependencies) { AssertCommandState(command1, 1, 3, 3, 0, 0); AssertCommandState(command2, 0, 0, 0, 0, 0); - Scheduler::GetInstance()->Run(); + Scheduler::GetInstance().Run(); AssertCommandState(command1, 1, 4, 4, 0, 1); AssertCommandState(command2, 0, 0, 0, 0, 0); - Scheduler::GetInstance()->Run(); + Scheduler::GetInstance().Run(); AssertCommandState(command1, 1, 4, 4, 0, 1); AssertCommandState(command2, 1, 1, 1, 0, 0); - Scheduler::GetInstance()->Run(); + Scheduler::GetInstance().Run(); AssertCommandState(command1, 1, 4, 4, 0, 1); AssertCommandState(command2, 1, 2, 2, 0, 0); - Scheduler::GetInstance()->Run(); + Scheduler::GetInstance().Run(); AssertCommandState(command1, 1, 4, 4, 0, 1); AssertCommandState(command2, 1, 3, 3, 0, 0); @@ -284,19 +284,19 @@ TEST_F(CommandTest, AssertCommandState(command1, 0, 0, 0, 0, 0); AssertCommandState(command2, 0, 0, 0, 0, 0); - Scheduler::GetInstance()->Run(); + Scheduler::GetInstance().Run(); AssertCommandState(command1, 0, 0, 0, 0, 0); AssertCommandState(command2, 0, 0, 0, 0, 0); - Scheduler::GetInstance()->Run(); + Scheduler::GetInstance().Run(); AssertCommandState(command1, 1, 1, 1, 0, 0); AssertCommandState(command2, 0, 0, 0, 0, 0); - Scheduler::GetInstance()->Run(); + Scheduler::GetInstance().Run(); AssertCommandState(command1, 1, 2, 2, 0, 0); AssertCommandState(command2, 0, 0, 0, 0, 0); - Scheduler::GetInstance()->Run(); + Scheduler::GetInstance().Run(); AssertCommandState(command1, 1, 3, 3, 0, 0); AssertCommandState(command2, 0, 0, 0, 0, 0); @@ -304,7 +304,7 @@ TEST_F(CommandTest, AssertCommandState(command1, 1, 3, 3, 0, 0); AssertCommandState(command2, 0, 0, 0, 0, 0); - Scheduler::GetInstance()->Run(); + Scheduler::GetInstance().Run(); AssertCommandState(command1, 1, 4, 4, 0, 0); AssertCommandState(command2, 0, 0, 0, 0, 0); @@ -328,18 +328,18 @@ TEST_F(CommandTest, TwoSecondTimeout) { command.Start(); AssertCommandState(command, 0, 0, 0, 0, 0); - Scheduler::GetInstance()->Run(); + Scheduler::GetInstance().Run(); AssertCommandState(command, 0, 0, 0, 0, 0); - Scheduler::GetInstance()->Run(); + Scheduler::GetInstance().Run(); AssertCommandState(command, 1, 1, 1, 0, 0); - Scheduler::GetInstance()->Run(); + Scheduler::GetInstance().Run(); AssertCommandState(command, 1, 2, 2, 0, 0); - Scheduler::GetInstance()->Run(); + Scheduler::GetInstance().Run(); AssertCommandState(command, 1, 3, 3, 0, 0); Wait(2); - Scheduler::GetInstance()->Run(); + Scheduler::GetInstance().Run(); AssertCommandState(command, 1, 4, 4, 1, 0); - Scheduler::GetInstance()->Run(); + Scheduler::GetInstance().Run(); AssertCommandState(command, 1, 4, 4, 1, 0); TeardownScheduler(); @@ -356,35 +356,35 @@ TEST_F(CommandTest, DefaultCommandWhereTheInteruptingCommandEndsItself) { subsystem.Init(&defaultCommand); AssertCommandState(defaultCommand, 0, 0, 0, 0, 0); - Scheduler::GetInstance()->Run(); + Scheduler::GetInstance().Run(); AssertCommandState(defaultCommand, 0, 0, 0, 0, 0); - Scheduler::GetInstance()->Run(); + Scheduler::GetInstance().Run(); AssertCommandState(defaultCommand, 1, 1, 1, 0, 0); - Scheduler::GetInstance()->Run(); + Scheduler::GetInstance().Run(); AssertCommandState(defaultCommand, 1, 2, 2, 0, 0); anotherCommand.Start(); AssertCommandState(defaultCommand, 1, 2, 2, 0, 0); AssertCommandState(anotherCommand, 0, 0, 0, 0, 0); - Scheduler::GetInstance()->Run(); + Scheduler::GetInstance().Run(); AssertCommandState(defaultCommand, 1, 3, 3, 0, 1); AssertCommandState(anotherCommand, 0, 0, 0, 0, 0); - Scheduler::GetInstance()->Run(); + Scheduler::GetInstance().Run(); AssertCommandState(defaultCommand, 1, 3, 3, 0, 1); AssertCommandState(anotherCommand, 1, 1, 1, 0, 0); - Scheduler::GetInstance()->Run(); + Scheduler::GetInstance().Run(); AssertCommandState(defaultCommand, 1, 3, 3, 0, 1); AssertCommandState(anotherCommand, 1, 2, 2, 0, 0); anotherCommand.SetHasFinished(true); AssertCommandState(defaultCommand, 1, 3, 3, 0, 1); AssertCommandState(anotherCommand, 1, 2, 2, 0, 0); - Scheduler::GetInstance()->Run(); + Scheduler::GetInstance().Run(); AssertCommandState(defaultCommand, 1, 3, 3, 0, 1); AssertCommandState(anotherCommand, 1, 3, 3, 1, 0); - Scheduler::GetInstance()->Run(); + Scheduler::GetInstance().Run(); AssertCommandState(defaultCommand, 2, 4, 4, 0, 1); AssertCommandState(anotherCommand, 1, 3, 3, 1, 0); - Scheduler::GetInstance()->Run(); + Scheduler::GetInstance().Run(); AssertCommandState(defaultCommand, 2, 5, 5, 0, 1); AssertCommandState(anotherCommand, 1, 3, 3, 1, 0); @@ -402,35 +402,35 @@ TEST_F(CommandTest, DefaultCommandsInterruptingCommandCanceled) { subsystem.Init(&defaultCommand); subsystem.InitDefaultCommand(); AssertCommandState(defaultCommand, 0, 0, 0, 0, 0); - Scheduler::GetInstance()->Run(); + Scheduler::GetInstance().Run(); AssertCommandState(defaultCommand, 0, 0, 0, 0, 0); - Scheduler::GetInstance()->Run(); + Scheduler::GetInstance().Run(); AssertCommandState(defaultCommand, 1, 1, 1, 0, 0); - Scheduler::GetInstance()->Run(); + Scheduler::GetInstance().Run(); AssertCommandState(defaultCommand, 1, 2, 2, 0, 0); anotherCommand.Start(); AssertCommandState(defaultCommand, 1, 2, 2, 0, 0); AssertCommandState(anotherCommand, 0, 0, 0, 0, 0); - Scheduler::GetInstance()->Run(); + Scheduler::GetInstance().Run(); AssertCommandState(defaultCommand, 1, 3, 3, 0, 1); AssertCommandState(anotherCommand, 0, 0, 0, 0, 0); - Scheduler::GetInstance()->Run(); + Scheduler::GetInstance().Run(); AssertCommandState(defaultCommand, 1, 3, 3, 0, 1); AssertCommandState(anotherCommand, 1, 1, 1, 0, 0); - Scheduler::GetInstance()->Run(); + Scheduler::GetInstance().Run(); AssertCommandState(defaultCommand, 1, 3, 3, 0, 1); AssertCommandState(anotherCommand, 1, 2, 2, 0, 0); anotherCommand.Cancel(); AssertCommandState(defaultCommand, 1, 3, 3, 0, 1); AssertCommandState(anotherCommand, 1, 2, 2, 0, 0); - Scheduler::GetInstance()->Run(); + Scheduler::GetInstance().Run(); AssertCommandState(defaultCommand, 1, 3, 3, 0, 1); AssertCommandState(anotherCommand, 1, 2, 2, 0, 1); - Scheduler::GetInstance()->Run(); + Scheduler::GetInstance().Run(); AssertCommandState(defaultCommand, 2, 4, 4, 0, 1); AssertCommandState(anotherCommand, 1, 2, 2, 0, 1); - Scheduler::GetInstance()->Run(); + Scheduler::GetInstance().Run(); AssertCommandState(defaultCommand, 2, 5, 5, 0, 1); AssertCommandState(anotherCommand, 1, 2, 2, 0, 1); diff --git a/wpilibc/wpilibC++Sim/include/AnalogInput.h b/wpilibc/wpilibC++Sim/include/AnalogInput.h index 9b17ccd9a8..0ca327c4d0 100644 --- a/wpilibc/wpilibC++Sim/include/AnalogInput.h +++ b/wpilibc/wpilibC++Sim/include/AnalogInput.h @@ -10,6 +10,8 @@ #include "PIDSource.h" #include "LiveWindow/LiveWindowSendable.h" +#include + /** * Analog input class. * @@ -41,13 +43,13 @@ public: void StartLiveWindowMode() override; void StopLiveWindowMode() override; std::string GetSmartDashboardType() const override; - void InitTable(ITable *subTable) override; - ITable * 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; - ITable *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 2abd55387f..716f9aed92 100644 --- a/wpilibc/wpilibC++Sim/include/AnalogPotentiometer.h +++ b/wpilibc/wpilibC++Sim/include/AnalogPotentiometer.h @@ -1,8 +1,11 @@ +#pragma once #include "AnalogInput.h" #include "interfaces/Potentiometer.h" #include "LiveWindow/LiveWindowSendable.h" +#include + /** * Class for reading analog potentiometers. Analog potentiometers read * in an analog voltage that corresponds to a position. Usually the @@ -55,9 +58,9 @@ public: * Live Window code, only does anything if live window is activated. */ virtual std::string GetSmartDashboardType() const override; - virtual void InitTable(ITable *subtable) override; + virtual void InitTable(::std::shared_ptr subtable) override; virtual void UpdateTable() override; - virtual ITable* GetTable() const override; + virtual ::std::shared_ptr GetTable() const override; /** * AnalogPotentiometers don't have to do anything special when entering the LiveWindow. @@ -72,7 +75,7 @@ public: private: double m_scale, m_offset; AnalogInput* m_analog_input; - ITable* 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 ade463ba47..f34d3845ec 100644 --- a/wpilibc/wpilibC++Sim/include/Counter.h +++ b/wpilibc/wpilibC++Sim/include/Counter.h @@ -10,6 +10,8 @@ #include "SensorBase.h" #include "LiveWindow/LiveWindowSendable.h" +#include + /** * Class for counting the number of ticks on a digital input channel. * This is a general purpose class for counting repetitive events. It can return the number @@ -75,17 +77,17 @@ public: void StartLiveWindowMode() override; void StopLiveWindowMode() override; virtual std::string GetSmartDashboardType() const override; - void InitTable(ITable *subTable) override; - ITable * 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. - void* m_counter; ///< The FPGA counter object. + void* m_counter; ///< The FPGA counter object. private: bool m_allocatedUpSource; ///< Was the upSource allocated locally? bool m_allocatedDownSource; ///< Was the downSource allocated locally? uint32_t m_index; ///< The index of this counter. - ITable *m_table; + ::std::shared_ptr m_table; }; diff --git a/wpilibc/wpilibC++Sim/include/DigitalInput.h b/wpilibc/wpilibC++Sim/include/DigitalInput.h index 82066068f4..40ead6ebec 100644 --- a/wpilibc/wpilibC++Sim/include/DigitalInput.h +++ b/wpilibc/wpilibC++Sim/include/DigitalInput.h @@ -8,6 +8,8 @@ #include "simulation/SimDigitalInput.h" #include "LiveWindow/LiveWindowSendable.h" +#include + /** * Class to read a digital input. * This class will read digital inputs and return the current value on the channel. Other devices @@ -26,13 +28,13 @@ public: void StartLiveWindowMode() override; void StopLiveWindowMode() override; std::string GetSmartDashboardType() const override; - void InitTable(ITable *subTable) override; - ITable * 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; - ITable *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 b9f15832a9..b363b68167 100644 --- a/wpilibc/wpilibC++Sim/include/DoubleSolenoid.h +++ b/wpilibc/wpilibC++Sim/include/DoubleSolenoid.h @@ -9,10 +9,12 @@ #include "LiveWindow/LiveWindowSendable.h" #include "tables/ITableListener.h" +#include + /** * DoubleSolenoid class for running 2 channels of high voltage Digital Output * (PCM). - * + * * The DoubleSolenoid class is typically used for pneumatics solenoids that * have two positions controlled by two separate channels. */ @@ -32,18 +34,18 @@ public: virtual void Set(Value value); virtual Value Get() const; - void ValueChanged(ITable* 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(ITable *subTable) override; - ITable * 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; - ITable *m_table; + ::std::shared_ptr m_table; }; diff --git a/wpilibc/wpilibC++Sim/include/Encoder.h b/wpilibc/wpilibC++Sim/include/Encoder.h index 3c136fd039..c3cd457a9f 100644 --- a/wpilibc/wpilibC++Sim/include/Encoder.h +++ b/wpilibc/wpilibC++Sim/include/Encoder.h @@ -12,6 +12,8 @@ #include "PIDSource.h" #include "LiveWindow/LiveWindowSendable.h" +#include + /** * Class to read quad encoders. * Quadrature encoders are devices that count shaft rotation and can sense direction. The output of @@ -58,8 +60,8 @@ public: void StartLiveWindowMode() override; void StopLiveWindowMode() override; std::string GetSmartDashboardType() const override; - void InitTable(ITable *subTable) override; - ITable * GetTable() const override; + void InitTable(::std::shared_ptr subTable) override; + ::std::shared_ptr GetTable() const override; int32_t FPGAEncoderIndex() const { @@ -82,5 +84,5 @@ private: bool m_reverseDirection; SimEncoder* impl; - ITable *m_table; + ::std::shared_ptr m_table; }; diff --git a/wpilibc/wpilibC++Sim/include/Gyro.h b/wpilibc/wpilibC++Sim/include/Gyro.h index a277bc7386..ee2e560907 100644 --- a/wpilibc/wpilibC++Sim/include/Gyro.h +++ b/wpilibc/wpilibC++Sim/include/Gyro.h @@ -10,6 +10,8 @@ #include "LiveWindow/LiveWindowSendable.h" #include "simulation/SimGyro.h" +#include + class AnalogInput; class AnalogModule; @@ -46,8 +48,8 @@ public: void StartLiveWindowMode() override; void StopLiveWindowMode() override; std::string GetSmartDashboardType() const override; - void InitTable(ITable *subTable) override; - ITable * GetTable() const override; + void InitTable(::std::shared_ptr subTable) override; + ::std::shared_ptr GetTable() const override; private: void InitGyro(int channel); @@ -55,5 +57,5 @@ private: SimGyro* impl; PIDSourceParameter m_pidSource; - ITable *m_table = nullptr; + ::std::shared_ptr m_table = nullptr; }; diff --git a/wpilibc/wpilibC++Sim/include/Joystick.h b/wpilibc/wpilibC++Sim/include/Joystick.h index 998ad886c2..71f69ee661 100644 --- a/wpilibc/wpilibC++Sim/include/Joystick.h +++ b/wpilibc/wpilibC++Sim/include/Joystick.h @@ -7,6 +7,7 @@ #ifndef JOYSTICK_H_ #define JOYSTICK_H_ +#include #include "GenericHID.h" #include "ErrorBase.h" @@ -39,7 +40,7 @@ public: explicit Joystick(uint32_t port); Joystick(uint32_t port, uint32_t numAxisTypes, uint32_t numButtonTypes); - virtual ~Joystick(); + virtual ~Joystick() = default; uint32_t GetAxisChannel(AxisType axis); void SetAxisChannel(AxisType axis, uint32_t channel); @@ -69,8 +70,8 @@ private: DriverStation *m_ds = nullptr; uint32_t m_port; - uint32_t *m_axes = nullptr; - uint32_t *m_buttons = nullptr; + std::unique_ptr m_axes; + std::unique_ptr m_buttons; }; #endif diff --git a/wpilibc/wpilibC++Sim/include/MotorSafety.h b/wpilibc/wpilibC++Sim/include/MotorSafety.h index 00820be541..c71880698a 100644 --- a/wpilibc/wpilibC++Sim/include/MotorSafety.h +++ b/wpilibc/wpilibC++Sim/include/MotorSafety.h @@ -7,6 +7,8 @@ #define DEFAULT_SAFETY_EXPIRATION 0.1 +#include + class MotorSafety { public: @@ -16,5 +18,5 @@ public: virtual void StopMotor() = 0; virtual void SetSafetyEnabled(bool enabled) = 0; virtual bool IsSafetyEnabled() const = 0; - virtual void GetDescription(char *desc) const = 0; + virtual void GetDescription(std::ostringstream& desc) const = 0; }; diff --git a/wpilibc/wpilibC++Sim/include/PWM.h b/wpilibc/wpilibC++Sim/include/PWM.h index 7a27684fd8..ab5f2d0cd4 100644 --- a/wpilibc/wpilibC++Sim/include/PWM.h +++ b/wpilibc/wpilibC++Sim/include/PWM.h @@ -10,6 +10,8 @@ #include "LiveWindow/LiveWindowSendable.h" #include "tables/ITableListener.h" +#include + /** * Class implements the PWM generation in the FPGA. * @@ -85,15 +87,15 @@ protected: bool m_eliminateDeadband; int32_t m_centerPwm; - void ValueChanged(ITable* 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(ITable *subTable) override; - ITable * GetTable() const override; + void InitTable(::std::shared_ptr subTable) override; + ::std::shared_ptr GetTable() const override; - ITable *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 7f90c34df8..b7808441d6 100644 --- a/wpilibc/wpilibC++Sim/include/Relay.h +++ b/wpilibc/wpilibC++Sim/include/Relay.h @@ -11,6 +11,8 @@ #include "LiveWindow/LiveWindowSendable.h" #include "tables/ITable.h" +#include + class DigitalModule; /** @@ -45,15 +47,15 @@ public: void Set(Value value); Value Get() const; - void ValueChanged(ITable* 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(ITable *subTable) override; - ITable * GetTable() const override; + void InitTable(::std::shared_ptr subTable) override; + ::std::shared_ptr GetTable() const override; - ITable *m_table = nullptr; + ::std::shared_ptr m_table = nullptr; private: uint32_t m_channel; diff --git a/wpilibc/wpilibC++Sim/include/RobotDrive.h b/wpilibc/wpilibC++Sim/include/RobotDrive.h index 14de22181c..4c97cfff46 100644 --- a/wpilibc/wpilibC++Sim/include/RobotDrive.h +++ b/wpilibc/wpilibC++Sim/include/RobotDrive.h @@ -72,7 +72,7 @@ public: void StopMotor() override; bool IsSafetyEnabled() const override; void SetSafetyEnabled(bool enabled) override; - void GetDescription(char *desc) const override; + void GetDescription(std::ostringstream& desc) const override; protected: void InitRobotDrive(); diff --git a/wpilibc/wpilibC++Sim/include/SafePWM.h b/wpilibc/wpilibC++Sim/include/SafePWM.h index d0d2d7bd93..577d8534ef 100644 --- a/wpilibc/wpilibC++Sim/include/SafePWM.h +++ b/wpilibc/wpilibC++Sim/include/SafePWM.h @@ -7,8 +7,8 @@ #include "MotorSafety.h" #include "PWM.h" - -class MotorSafetyHelper; +#include "MotorSafetyHelper.h" +#include /** * A safe version of the PWM class. @@ -21,7 +21,7 @@ class SafePWM : public PWM, public MotorSafety { public: explicit SafePWM(uint32_t channel); - ~SafePWM(); + virtual ~SafePWM() = default; void SetExpiration(float timeout); float GetExpiration() const; @@ -29,9 +29,9 @@ public: void StopMotor(); bool IsSafetyEnabled() const; void SetSafetyEnabled(bool enabled); - void GetDescription(char *desc) const; + void GetDescription(std::ostringstream& desc) const; virtual void SetSpeed(float speed); private: - MotorSafetyHelper *m_safetyHelper; + std::unique_ptr m_safetyHelper; }; diff --git a/wpilibc/wpilibC++Sim/include/Solenoid.h b/wpilibc/wpilibC++Sim/include/Solenoid.h index 3cc6ab7adf..eab08d91db 100644 --- a/wpilibc/wpilibC++Sim/include/Solenoid.h +++ b/wpilibc/wpilibC++Sim/include/Solenoid.h @@ -9,9 +9,11 @@ #include "LiveWindow/LiveWindowSendable.h" #include "tables/ITableListener.h" +#include + /** * Solenoid class for running high voltage Digital Output (PCM). - * + * * The Solenoid class is typically used for pneumatics solenoids, but could be used * for any device within the current spec of the PCM. */ @@ -24,17 +26,17 @@ public: virtual void Set(bool on); virtual bool Get() const; - void ValueChanged(ITable* 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(ITable *subTable) override; - ITable * GetTable() const override; + void InitTable(::std::shared_ptr subTable) override; + ::std::shared_ptr GetTable() const override; private: SimContinuousOutput* m_impl; - bool m_on; + bool m_on; - ITable *m_table; + ::std::shared_ptr m_table; }; diff --git a/wpilibc/wpilibC++Sim/src/AnalogInput.cpp b/wpilibc/wpilibC++Sim/src/AnalogInput.cpp index 29032d818c..6fe54f2574 100644 --- a/wpilibc/wpilibC++Sim/src/AnalogInput.cpp +++ b/wpilibc/wpilibC++Sim/src/AnalogInput.cpp @@ -20,7 +20,7 @@ AnalogInput::AnalogInput(uint32_t channel) int n = sprintf(buffer, "analog/%d", channel); m_impl = new SimFloatInput(buffer); - LiveWindow::GetInstance()->AddSensor("AnalogInput", channel, this); + LiveWindow::GetInstance().AddSensor("AnalogInput", channel, this); } /** @@ -82,11 +82,11 @@ std::string AnalogInput::GetSmartDashboardType() const { return "Analog Input"; } -void AnalogInput::InitTable(ITable *subTable) { +void AnalogInput::InitTable(::std::shared_ptr subTable) { m_table = subTable; UpdateTable(); } -ITable * 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 2685cbc98b..663fd0df08 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(ITable *subtable) { +void AnalogPotentiometer::InitTable(::std::shared_ptr subtable) { m_table = subtable; UpdateTable(); } @@ -72,6 +72,6 @@ void AnalogPotentiometer::UpdateTable() { } } -ITable* 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 a4b15c065b..4c80928e91 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(ITable *subTable) { +void DigitalInput::InitTable(::std::shared_ptr subTable) { m_table = subTable; UpdateTable(); } -ITable * 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 2fa6709c1f..77ec517cd0 100644 --- a/wpilibc/wpilibC++Sim/src/DoubleSolenoid.cpp +++ b/wpilibc/wpilibC++Sim/src/DoubleSolenoid.cpp @@ -39,7 +39,7 @@ DoubleSolenoid::DoubleSolenoid(uint8_t moduleNumber, uint32_t forwardChannel, ui forwardChannel, moduleNumber, reverseChannel); m_impl = new SimContinuousOutput(buffer); - LiveWindow::GetInstance()->AddActuator("DoubleSolenoid", moduleNumber, + LiveWindow::GetInstance().AddActuator("DoubleSolenoid", moduleNumber, forwardChannel, this); } @@ -75,7 +75,7 @@ DoubleSolenoid::Value DoubleSolenoid::Get() const return m_value; } -void DoubleSolenoid::ValueChanged(ITable* 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(ITable *subTable) { +void DoubleSolenoid::InitTable(::std::shared_ptr subTable) { m_table = subTable; UpdateTable(); } -ITable * DoubleSolenoid::GetTable() const { +::std::shared_ptr DoubleSolenoid::GetTable() const { return m_table; } diff --git a/wpilibc/wpilibC++Sim/src/Encoder.cpp b/wpilibc/wpilibC++Sim/src/Encoder.cpp index e3f8e961c6..bb5042ae14 100644 --- a/wpilibc/wpilibC++Sim/src/Encoder.cpp +++ b/wpilibc/wpilibC++Sim/src/Encoder.cpp @@ -36,7 +36,7 @@ void Encoder::InitEncoder(int channelA, int channelB, bool reverseDirection, Enc m_distancePerPulse = 1.0; m_pidSource = kDistance; - LiveWindow::GetInstance()->AddSensor("Encoder", channelA, this); + LiveWindow::GetInstance().AddSensor("Encoder", channelA, this); if (channelB < channelA) { // Swap ports int channel = channelB; @@ -355,11 +355,11 @@ std::string Encoder::GetSmartDashboardType() const { return "Encoder"; } -void Encoder::InitTable(ITable *subTable) { +void Encoder::InitTable(::std::shared_ptr subTable) { m_table = subTable; UpdateTable(); } -ITable * 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 717b42e7d1..6987b5da1d 100644 --- a/wpilibc/wpilibC++Sim/src/Gyro.cpp +++ b/wpilibc/wpilibC++Sim/src/Gyro.cpp @@ -31,7 +31,7 @@ void Gyro::InitGyro(int channel) int n = sprintf(buffer, "analog/%d", channel); impl = new SimGyro(buffer); - LiveWindow::GetInstance()->AddSensor("Gyro", channel, this); + LiveWindow::GetInstance().AddSensor("Gyro", channel, this); } /** @@ -125,11 +125,11 @@ std::string Gyro::GetSmartDashboardType() const { return "Gyro"; } -void Gyro::InitTable(ITable *subTable) { +void Gyro::InitTable(::std::shared_ptr subTable) { m_table = subTable; UpdateTable(); } -ITable * Gyro::GetTable() const { +::std::shared_ptr Gyro::GetTable() const { return m_table; } diff --git a/wpilibc/wpilibC++Sim/src/IterativeRobot.cpp b/wpilibc/wpilibC++Sim/src/IterativeRobot.cpp index c81e9d0b0b..a1d25a8843 100644 --- a/wpilibc/wpilibC++Sim/src/IterativeRobot.cpp +++ b/wpilibc/wpilibC++Sim/src/IterativeRobot.cpp @@ -16,7 +16,7 @@ constexpr double IterativeRobot::kDefaultPeriod; /** * Set the period for the periodic functions. - * + * * @param period The period of the periodic function calls. 0.0 means sync to driver station control data. */ void IterativeRobot::SetPeriod(double period) @@ -60,22 +60,22 @@ double IterativeRobot::GetLoopsPerSec() /** * Provide an alternate "main loop" via StartCompetition(). - * + * * This specific StartCompetition() implements "main loop" behavior like that of the FRC * control system in 2008 and earlier, with a primary (slow) loop that is - * called periodically, and a "fast loop" (a.k.a. "spin loop") that is - * called as fast as possible with no delay between calls. + * called periodically, and a "fast loop" (a.k.a. "spin loop") that is + * called as fast as possible with no delay between calls. */ void IterativeRobot::StartCompetition() { - LiveWindow *lw = LiveWindow::GetInstance(); + LiveWindow &lw = LiveWindow::GetInstance(); // first and one-time initialization SmartDashboard::init(); NetworkTable::GetTable("LiveWindow")->GetSubTable("~STATUS~")->PutBoolean("LW Enabled", false); RobotInit(); // loop forever, calling the appropriate mode-dependent function - lw->SetEnabled(false); + lw.SetEnabled(false); while (true) { // Call the appropriate function depending upon the current robot mode @@ -85,7 +85,7 @@ void IterativeRobot::StartCompetition() // either a different mode or from power-on if(!m_disabledInitialized) { - lw->SetEnabled(false); + lw.SetEnabled(false); DisabledInit(); m_disabledInitialized = true; // reset the initialization flags for the other modes @@ -105,7 +105,7 @@ void IterativeRobot::StartCompetition() // either a different mode or from power-on if(!m_autonomousInitialized) { - lw->SetEnabled(false); + lw.SetEnabled(false); AutonomousInit(); m_autonomousInitialized = true; // reset the initialization flags for the other modes @@ -125,7 +125,7 @@ void IterativeRobot::StartCompetition() // either a different mode or from power-on if(!m_testInitialized) { - lw->SetEnabled(true); + lw.SetEnabled(true); TestInit(); m_testInitialized = true; // reset the initialization flags for the other modes @@ -145,14 +145,14 @@ void IterativeRobot::StartCompetition() // either a different mode or from power-on if(!m_teleopInitialized) { - lw->SetEnabled(false); + lw.SetEnabled(false); TeleopInit(); m_teleopInitialized = true; // reset the initialization flags for the other modes m_disabledInitialized = false; m_autonomousInitialized = false; m_testInitialized = false; - Scheduler::GetInstance()->SetEnabled(true); + Scheduler::GetInstance().SetEnabled(true); } if (NextPeriodReady()) { @@ -162,7 +162,7 @@ void IterativeRobot::StartCompetition() } // wait for driver station data so the loop doesn't hog the CPU m_ds->WaitForData(); - } + } } /** @@ -190,7 +190,7 @@ bool IterativeRobot::NextPeriodReady() /** * Robot-wide initialization code should go here. - * + * * Users should override this method for default Robot-wide initialization which will * be called when the robot is first powered on. It will be called exactly 1 time. */ @@ -201,7 +201,7 @@ void IterativeRobot::RobotInit() /** * Initialization code for disabled mode should go here. - * + * * Users should override this method for initialization code which will be called each time * the robot enters disabled mode. */ @@ -212,7 +212,7 @@ void IterativeRobot::DisabledInit() /** * Initialization code for autonomous mode should go here. - * + * * Users should override this method for initialization code which will be called each time * the robot enters autonomous mode. */ @@ -223,7 +223,7 @@ void IterativeRobot::AutonomousInit() /** * Initialization code for teleop mode should go here. - * + * * Users should override this method for initialization code which will be called each time * the robot enters teleop mode. */ @@ -234,7 +234,7 @@ void IterativeRobot::TeleopInit() /** * Initialization code for test mode should go here. - * + * * Users should override this method for initialization code which will be called each time * the robot enters test mode. */ @@ -245,7 +245,7 @@ void IterativeRobot::TestInit() /** * Periodic code for disabled mode should go here. - * + * * Users should override this method for code which will be called periodically at a regular * rate while the robot is in disabled mode. */ diff --git a/wpilibc/wpilibC++Sim/src/Jaguar.cpp b/wpilibc/wpilibC++Sim/src/Jaguar.cpp index fab109d578..f6fafc499e 100644 --- a/wpilibc/wpilibC++Sim/src/Jaguar.cpp +++ b/wpilibc/wpilibC++Sim/src/Jaguar.cpp @@ -27,7 +27,7 @@ Jaguar::Jaguar(uint32_t channel) : SafePWM(channel) SetPeriodMultiplier(kPeriodMultiplier_1X); SetRaw(m_centerPwm); - LiveWindow::GetInstance()->AddActuator("Jaguar", GetChannel(), this); + LiveWindow::GetInstance().AddActuator("Jaguar", GetChannel(), this); } /** diff --git a/wpilibc/wpilibC++Sim/src/Joystick.cpp b/wpilibc/wpilibC++Sim/src/Joystick.cpp index 01439dafe0..6344d2417d 100644 --- a/wpilibc/wpilibC++Sim/src/Joystick.cpp +++ b/wpilibc/wpilibC++Sim/src/Joystick.cpp @@ -8,6 +8,7 @@ #include "DriverStation.h" #include "WPIErrors.h" #include +#include const uint32_t Joystick::kDefaultXAxis; const uint32_t Joystick::kDefaultYAxis; @@ -60,8 +61,8 @@ Joystick::Joystick(uint32_t port, uint32_t numAxisTypes, uint32_t numButtonTypes joysticks[m_port] = this; m_ds = DriverStation::GetInstance(); - m_axes = new uint32_t[numAxisTypes]; - m_buttons = new uint32_t[numButtonTypes]; + m_axes = std::make_unique(numAxisTypes); + m_buttons = std::make_unique(numButtonTypes); } Joystick * Joystick::GetStickForPort(uint32_t port) @@ -75,12 +76,6 @@ Joystick * Joystick::GetStickForPort(uint32_t port) return stick; } -Joystick::~Joystick() -{ - delete [] m_buttons; - delete [] m_axes; -} - /** * Get the X value of the joystick. * This depends on the mapping of the joystick connected to the current port. diff --git a/wpilibc/wpilibC++Sim/src/MotorSafetyHelper.cpp b/wpilibc/wpilibC++Sim/src/MotorSafetyHelper.cpp index 5a0338a762..15747f2652 100644 --- a/wpilibc/wpilibC++Sim/src/MotorSafetyHelper.cpp +++ b/wpilibc/wpilibC++Sim/src/MotorSafetyHelper.cpp @@ -109,11 +109,10 @@ void MotorSafetyHelper::Check() std::unique_lock sync(m_syncMutex); if (m_stopTime < Timer::GetFPGATimestamp()) { - char buf[128]; - char desc[64]; - m_safeObject->GetDescription(desc); - snprintf(buf, 128, "%s... Output not updated often enough.", desc); - wpi_setWPIErrorWithContext(Timeout, buf); + std::ostringstream desc; + m_safeObject->GetDescription(desc); + desc << "... Output not updated often enough."; + wpi_setWPIErrorWithContext(Timeout, desc.str().c_str()); m_safeObject->StopMotor(); } } diff --git a/wpilibc/wpilibC++Sim/src/PIDController.cpp b/wpilibc/wpilibC++Sim/src/PIDController.cpp index 352c45f01e..fae795f431 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 = new Notifier(PIDController::CallCalculate, this); + m_controlLoop = ::std::make_unique(PIDController::CallCalculate, this); m_controlLoop->StartPeriodic(m_period); static int32_t instances = 0; @@ -93,14 +93,6 @@ void PIDController::Initialize(float Kp, float Ki, float Kd, float Kf, m_toleranceType = kNoTolerance; } -/** - * Free the PID object - */ -PIDController::~PIDController() -{ - delete m_controlLoop; -} - /** * Call the Calculate method as a non-static method. This avoids having to prepend * all local variables in that method with the class pointer. This way the "this" @@ -499,7 +491,7 @@ std::string PIDController::GetSmartDashboardType() const { return "PIDController"; } -void PIDController::InitTable(ITable* table){ +void PIDController::InitTable(::std::shared_ptr table){ if(m_table!=nullptr) m_table->RemoveTableListener(this); m_table = table; @@ -514,11 +506,11 @@ void PIDController::InitTable(ITable* table){ } } -ITable* PIDController::GetTable() const { +::std::shared_ptr PIDController::GetTable() const { return m_table; } -void PIDController::ValueChanged(ITable* 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 6e5078b43e..fa8b613a6d 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(ITable* 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(ITable *subTable) { +void PWM::InitTable(::std::shared_ptr subTable) { m_table = subTable; UpdateTable(); } -ITable * 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 9f92a8fb54..2571c53b37 100644 --- a/wpilibc/wpilibC++Sim/src/Relay.cpp +++ b/wpilibc/wpilibC++Sim/src/Relay.cpp @@ -32,7 +32,7 @@ Relay::Relay(uint32_t channel, Relay::Direction direction) sprintf(buf, "relay/%d", m_channel); impl = new SimContinuousOutput(buf); // TODO: Allow two different relays (targetting the different halves of a relay) to be combined to control one motor. - LiveWindow::GetInstance()->AddActuator("Relay", 1, m_channel, this); + LiveWindow::GetInstance().AddActuator("Relay", 1, m_channel, this); go_pos = go_neg = false; } @@ -140,7 +140,7 @@ Relay::Value Relay::Get() const { } } -void Relay::ValueChanged(ITable* 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(ITable *subTable) { +void Relay::InitTable(::std::shared_ptr subTable) { m_table = subTable; UpdateTable(); } -ITable * Relay::GetTable() const { +::std::shared_ptr Relay::GetTable() const { return m_table; } diff --git a/wpilibc/wpilibC++Sim/src/RobotBase.cpp b/wpilibc/wpilibC++Sim/src/RobotBase.cpp index e0858e92c9..e641891cf5 100644 --- a/wpilibc/wpilibC++Sim/src/RobotBase.cpp +++ b/wpilibc/wpilibC++Sim/src/RobotBase.cpp @@ -27,14 +27,14 @@ RobotBase &RobotBase::getInstance() * Constructor for a generic robot program. * User code should be placed in the constuctor that runs before the Autonomous or Operator * Control period starts. The constructor will run to completion before Autonomous is entered. - * + * * This must be used to ensure that the communications code starts. In the future it would be * nice to put this code into it's own task that loads on boot so ensure that it runs. */ RobotBase::RobotBase() { m_ds = DriverStation::GetInstance(); - RobotState::SetImplementation(DriverStation::GetInstance()); + RobotState::SetImplementation(*DriverStation::GetInstance()); } /** diff --git a/wpilibc/wpilibC++Sim/src/RobotDrive.cpp b/wpilibc/wpilibC++Sim/src/RobotDrive.cpp index 5631134b61..929a27fdd0 100644 --- a/wpilibc/wpilibC++Sim/src/RobotDrive.cpp +++ b/wpilibc/wpilibC++Sim/src/RobotDrive.cpp @@ -551,7 +551,7 @@ void RobotDrive::MecanumDrive_Polar(float magnitude, float direction, float rota m_rearRightMotor->Set(wheelSpeeds[kRearRightMotor] * m_invertedMotors[kRearRightMotor] * m_maxOutput, syncGroup); // CANJaguar::UpdateSyncGroup(syncGroup); - + // FIXME: m_safetyHelper->Feed(); } @@ -712,9 +712,9 @@ void RobotDrive::SetSafetyEnabled(bool enabled) // FIXME: m_safetyHelper->SetSafetyEnabled(enabled); } -void RobotDrive::GetDescription(char *desc) const +void RobotDrive::GetDescription(std::ostringstream& desc) const { - sprintf(desc, "RobotDrive"); + desc << "RobotDrive"; } void RobotDrive::StopMotor() diff --git a/wpilibc/wpilibC++Sim/src/SafePWM.cpp b/wpilibc/wpilibC++Sim/src/SafePWM.cpp index ab57c21c14..8ba0b689e3 100644 --- a/wpilibc/wpilibC++Sim/src/SafePWM.cpp +++ b/wpilibc/wpilibC++Sim/src/SafePWM.cpp @@ -5,8 +5,8 @@ /*----------------------------------------------------------------------------*/ #include "SafePWM.h" - -#include "MotorSafetyHelper.h" +#include +#include /** * Constructor for a SafePWM object taking a channel number. @@ -14,15 +14,10 @@ */ SafePWM::SafePWM(uint32_t channel): PWM(channel) { - m_safetyHelper = new MotorSafetyHelper(this); + m_safetyHelper = std::make_unique(this); m_safetyHelper->SetSafetyEnabled(false); } -SafePWM::~SafePWM() -{ - delete m_safetyHelper; -} - /* * Set the expiration time for the PWM object * @param timeout The timeout (in seconds) for this motor object @@ -80,9 +75,9 @@ bool SafePWM::IsSafetyEnabled() const return m_safetyHelper->IsSafetyEnabled(); } -void SafePWM::GetDescription(char *desc) const +void SafePWM::GetDescription(std::ostringstream& desc) const { - sprintf(desc, "PWM %d", GetChannel()); + desc << "PWM " << GetChannel(); } /** diff --git a/wpilibc/wpilibC++Sim/src/SampleRobot.cpp b/wpilibc/wpilibC++Sim/src/SampleRobot.cpp index 345617f811..4903a3107b 100644 --- a/wpilibc/wpilibC++Sim/src/SampleRobot.cpp +++ b/wpilibc/wpilibC++Sim/src/SampleRobot.cpp @@ -20,7 +20,7 @@ SampleRobot::SampleRobot() /** * Robot-wide initialization code should go here. - * + * * Programmers should override this method for default Robot-wide initialization which will * be called each time the robot enters the disabled state. */ @@ -73,11 +73,11 @@ void SampleRobot::Test() /** * Robot main program for free-form programs. - * + * * This should be overridden by user subclasses if the intent is to not use the Autonomous() and * OperatorControl() methods. In that case, the program is responsible for sensing when to run * the autonomous and operator control functions in their program. - * + * * This method will be called immediately after the constructor is called. If it has not been * overridden by a user subclass (i.e. the default version runs), then the Autonomous() and * OperatorControl() methods will be called. @@ -97,17 +97,17 @@ void SampleRobot::RobotMain() */ void SampleRobot::StartCompetition() { - LiveWindow *lw = LiveWindow::GetInstance(); + LiveWindow &lw = LiveWindow::GetInstance(); SmartDashboard::init(); NetworkTable::GetTable("LiveWindow")->GetSubTable("~STATUS~")->PutBoolean("LW Enabled", false); RobotMain(); - + if (!m_robotMainOverridden) { // first and one-time initialization - lw->SetEnabled(false); + lw.SetEnabled(false); RobotInit(); while (true) @@ -128,12 +128,12 @@ void SampleRobot::StartCompetition() } else if (IsTest()) { - lw->SetEnabled(true); + lw.SetEnabled(true); m_ds->InTest(true); Test(); m_ds->InTest(false); while (IsTest() && IsEnabled()) sleep(1); //m_ds->WaitForData(); - lw->SetEnabled(false); + lw.SetEnabled(false); } else { diff --git a/wpilibc/wpilibC++Sim/src/Solenoid.cpp b/wpilibc/wpilibC++Sim/src/Solenoid.cpp index 9cfbc945ec..dab5bca05c 100644 --- a/wpilibc/wpilibC++Sim/src/Solenoid.cpp +++ b/wpilibc/wpilibC++Sim/src/Solenoid.cpp @@ -28,7 +28,7 @@ Solenoid::Solenoid(uint8_t moduleNumber, uint32_t channel) int n = sprintf(buffer, "pneumatic/%d/%d", moduleNumber, channel); m_impl = new SimContinuousOutput(buffer); - LiveWindow::GetInstance()->AddActuator("Solenoid", moduleNumber, channel, + LiveWindow::GetInstance().AddActuator("Solenoid", moduleNumber, channel, this); } @@ -54,7 +54,7 @@ bool Solenoid::Get() const } -void Solenoid::ValueChanged(ITable* 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(ITable *subTable) { +void Solenoid::InitTable(::std::shared_ptr subTable) { m_table = subTable; UpdateTable(); } -ITable * Solenoid::GetTable() const { +::std::shared_ptr Solenoid::GetTable() const { return m_table; } diff --git a/wpilibc/wpilibC++Sim/src/Talon.cpp b/wpilibc/wpilibC++Sim/src/Talon.cpp index 0e9505dbf4..7642d2bf9d 100644 --- a/wpilibc/wpilibC++Sim/src/Talon.cpp +++ b/wpilibc/wpilibC++Sim/src/Talon.cpp @@ -31,7 +31,7 @@ Talon::Talon(uint32_t channel) : SafePWM(channel) SetPeriodMultiplier(kPeriodMultiplier_2X); SetRaw(m_centerPwm); - LiveWindow::GetInstance()->AddActuator("Talon", GetChannel(), this); + LiveWindow::GetInstance().AddActuator("Talon", GetChannel(), this); } /** diff --git a/wpilibc/wpilibC++Sim/src/Victor.cpp b/wpilibc/wpilibC++Sim/src/Victor.cpp index 54ba61fd8d..dc8050218b 100644 --- a/wpilibc/wpilibC++Sim/src/Victor.cpp +++ b/wpilibc/wpilibC++Sim/src/Victor.cpp @@ -33,7 +33,7 @@ Victor::Victor(uint32_t channel) : SafePWM(channel) SetPeriodMultiplier(kPeriodMultiplier_2X); SetRaw(m_centerPwm); - LiveWindow::GetInstance()->AddActuator("Victor", GetChannel(), this); + LiveWindow::GetInstance().AddActuator("Victor", GetChannel(), this); } /**