diff --git a/Arduino/Drv/AnalogDriver/AnalogDriver.cpp b/Arduino/Drv/AnalogDriver/AnalogDriver.cpp index 3e15ac6..e77b30a 100644 --- a/Arduino/Drv/AnalogDriver/AnalogDriver.cpp +++ b/Arduino/Drv/AnalogDriver/AnalogDriver.cpp @@ -5,54 +5,36 @@ // ====================================================================== #include -#include #include -namespace Arduino -{ - - // ---------------------------------------------------------------------- - // Construction, initialization, and destruction - // ---------------------------------------------------------------------- - - AnalogDriver :: - AnalogDriver( - const char *const compName) : AnalogDriverComponentBase(compName), m_pin(-1) - { - } - - AnalogDriver :: - ~AnalogDriver() - { - } - - bool AnalogDriver ::open(NATIVE_INT_TYPE pin, GpioDirection direction) - { - m_pin = pin; - pinMode(m_pin, (direction == IN) ? Arduino::DEF_INPUT : Arduino::DEF_OUTPUT); - return true; - } - - // ---------------------------------------------------------------------- - // Handler implementations for user-defined typed input ports - // ---------------------------------------------------------------------- - - Fw::Success AnalogDriver :: - readAnalog_handler( - const NATIVE_INT_TYPE portNum, - U16 &val) - { - val = analogRead(m_pin); - return Fw::Success::SUCCESS; - } - - Fw::Success AnalogDriver :: - setAnalog_handler( - const NATIVE_INT_TYPE portNum, - U8 val) - { - analogWrite(m_pin, val); - return Fw::Success::SUCCESS; - } - -} // end namespace Arduino +namespace Arduino { + +// ---------------------------------------------------------------------- +// Construction, initialization, and destruction +// ---------------------------------------------------------------------- + +AnalogDriver ::AnalogDriver(const char* const compName) : AnalogDriverComponentBase(compName), m_pin(-1) {} + +AnalogDriver ::~AnalogDriver() {} + +bool AnalogDriver ::open(FwIndexType pin, GpioDirection direction) { + m_pin = pin; + pinMode(m_pin, (direction == IN) ? Arduino::DEF_INPUT : Arduino::DEF_OUTPUT); + return true; +} + +// ---------------------------------------------------------------------- +// Handler implementations for user-defined typed input ports +// ---------------------------------------------------------------------- + +Fw::Success AnalogDriver ::readAnalog_handler(const FwIndexType portNum, U16& val) { + val = analogRead(m_pin); + return Fw::Success::SUCCESS; +} + +Fw::Success AnalogDriver ::setAnalog_handler(const FwIndexType portNum, U8 val) { + analogWrite(m_pin, val); + return Fw::Success::SUCCESS; +} + +} // end namespace Arduino diff --git a/Arduino/Drv/AnalogDriver/AnalogDriver.hpp b/Arduino/Drv/AnalogDriver/AnalogDriver.hpp index 83ea9a8..2222927 100644 --- a/Arduino/Drv/AnalogDriver/AnalogDriver.hpp +++ b/Arduino/Drv/AnalogDriver/AnalogDriver.hpp @@ -9,57 +9,48 @@ #include "Arduino/Drv/AnalogDriver/AnalogDriverComponentAc.hpp" -namespace Arduino -{ - - class AnalogDriver : public AnalogDriverComponentBase - { - - public: - //! configure GPIO - enum GpioDirection - { - IN, //!< input - OUT, //!< output - }; - // ---------------------------------------------------------------------- - // Construction, initialization, and destruction - // ---------------------------------------------------------------------- - - //! Construct object AnalogDriver - //! - AnalogDriver( - const char *const compName /*!< The component name*/ - ); +namespace Arduino { + +class AnalogDriver : public AnalogDriverComponentBase { + public: + //! configure GPIO + enum GpioDirection { + IN, //!< input + OUT, //!< output + }; + // ---------------------------------------------------------------------- + // Construction, initialization, and destruction + // ---------------------------------------------------------------------- - //! Destroy object AnalogDriver - //! - ~AnalogDriver(); + //! Construct object AnalogDriver + //! + AnalogDriver(const char* const compName /*!< The component name*/ + ); - bool open(NATIVE_INT_TYPE pin, GpioDirection direction); + //! Destroy object AnalogDriver + //! + ~AnalogDriver(); - PRIVATE : + bool open(FwIndexType pin, GpioDirection direction); - // ---------------------------------------------------------------------- - // Handler implementations for user-defined typed input ports - // ---------------------------------------------------------------------- + private: + // ---------------------------------------------------------------------- + // Handler implementations for user-defined typed input ports + // ---------------------------------------------------------------------- - //! Handler implementation for readAnalog - //! - Fw::Success - readAnalog_handler( - const NATIVE_INT_TYPE portNum, /*!< The port number*/ - U16 &val); + //! Handler implementation for readAnalog + //! + Fw::Success readAnalog_handler(const FwIndexType portNum, /*!< The port number*/ + U16& val); - //! Handler implementation for setAnalog - //! - Fw::Success setAnalog_handler( - const NATIVE_INT_TYPE portNum, /*!< The port number*/ - U8 val); + //! Handler implementation for setAnalog + //! + Fw::Success setAnalog_handler(const FwIndexType portNum, /*!< The port number*/ + U8 val); - PlatformIntType m_pin; - }; + PlatformIntType m_pin; +}; -} // end namespace Arduino +} // end namespace Arduino #endif diff --git a/Arduino/Drv/HardwareRateDriver/HardwareRateDriverTeensy.cpp b/Arduino/Drv/HardwareRateDriver/HardwareRateDriverTeensy.cpp index ece90a1..e68a1fb 100644 --- a/Arduino/Drv/HardwareRateDriver/HardwareRateDriverTeensy.cpp +++ b/Arduino/Drv/HardwareRateDriver/HardwareRateDriverTeensy.cpp @@ -1,7 +1,6 @@ -#include +#include #include #include -#include #include namespace Arduino { @@ -9,7 +8,7 @@ IntervalTimer s_itimer; void HardwareRateDriver::start() { U32 microseconds = m_interval * 1000; - (void) s_itimer.begin(HardwareRateDriver::s_timerISR, microseconds); + (void)s_itimer.begin(HardwareRateDriver::s_timerISR, microseconds); Fw::Logger::log("Starting base rate group clock with period of %" PRIu32 " microseconds\n", microseconds); } @@ -21,4 +20,4 @@ void HardwareRateDriver::s_timerISR() { s_timer(s_driver); } -}; +}; // namespace Arduino diff --git a/Arduino/Drv/I2cDriver/I2cDriver.cpp b/Arduino/Drv/I2cDriver/I2cDriver.cpp index 993518e..a592697 100644 --- a/Arduino/Drv/I2cDriver/I2cDriver.cpp +++ b/Arduino/Drv/I2cDriver/I2cDriver.cpp @@ -4,60 +4,35 @@ // \brief cpp file for I2cDriver component implementation class // ====================================================================== - #include -#include #include "Fw/Types/Assert.hpp" namespace Arduino { - // ---------------------------------------------------------------------- - // Construction, initialization, and destruction - // ---------------------------------------------------------------------- - - I2cDriver :: - I2cDriver( - const char *const compName - ) : I2cDriverComponentBase(compName), - m_port_pointer(static_cast(NULL)) - { - - } +// ---------------------------------------------------------------------- +// Construction, initialization, and destruction +// ---------------------------------------------------------------------- - I2cDriver :: - ~I2cDriver() - { +I2cDriver ::I2cDriver(const char* const compName) : I2cDriverComponentBase(compName), m_port_pointer(nullptr) {} - } +I2cDriver ::~I2cDriver() {} - // ---------------------------------------------------------------------- - // Handler implementations for user-defined typed input ports - // ---------------------------------------------------------------------- +// ---------------------------------------------------------------------- +// Handler implementations for user-defined typed input ports +// ---------------------------------------------------------------------- - Drv::I2cStatus I2cDriver :: - read_handler( - const NATIVE_INT_TYPE portNum, - U32 addr, - Fw::Buffer &serBuffer - ) - { +Drv::I2cStatus I2cDriver ::read_handler(const FwIndexType portNum, U32 addr, Fw::Buffer& serBuffer) { // Ensure buffer is not a nullptr FW_ASSERT(serBuffer.getData()); return read_data(addr, serBuffer); - } - - Drv::I2cStatus I2cDriver :: - write_handler( - const NATIVE_INT_TYPE portNum, - U32 addr, - Fw::Buffer &serBuffer - ) - { +} + +Drv::I2cStatus I2cDriver ::write_handler(const FwIndexType portNum, U32 addr, Fw::Buffer& serBuffer) { // Ensure buffer is not a nullptr FW_ASSERT(serBuffer.getData()); - + return write_data(addr, serBuffer); - } +} -} // end namespace Arduino +} // end namespace Arduino diff --git a/Arduino/Drv/I2cDriver/I2cDriverArduino.cpp b/Arduino/Drv/I2cDriver/I2cDriverArduino.cpp index e8a33c9..46bd1e2 100644 --- a/Arduino/Drv/I2cDriver/I2cDriverArduino.cpp +++ b/Arduino/Drv/I2cDriver/I2cDriverArduino.cpp @@ -4,27 +4,24 @@ // \brief cpp file for I2cDriver component implementation class // ====================================================================== - #include -#include #include "Fw/Types/Assert.hpp" namespace Arduino { - void I2cDriver::open(TwoWire *wire) { +void I2cDriver::open(TwoWire* wire) { FW_ASSERT(wire != nullptr); m_port_pointer = wire; wire->begin(); - } +} - void I2cDriver::close() { +void I2cDriver::close() { FW_ASSERT(m_port_pointer != 0); TwoWire* wire_ptr = reinterpret_cast(m_port_pointer); wire_ptr->end(); - } +} - Drv::I2cStatus I2cDriver::read_data(U32 addr, Fw::Buffer& fwBuffer) - { +Drv::I2cStatus I2cDriver::read_data(U32 addr, Fw::Buffer& fwBuffer) { TwoWire* wire_ptr = reinterpret_cast(m_port_pointer); wire_ptr->requestFrom(static_cast(addr), fwBuffer.getSize()); @@ -39,10 +36,9 @@ namespace Arduino { fwBuffer.setSize(count); return Drv::I2cStatus::I2C_OK; - } +} - Drv::I2cStatus I2cDriver::write_data(U32 addr, Fw::Buffer& fwBuffer) - { +Drv::I2cStatus I2cDriver::write_data(U32 addr, Fw::Buffer& fwBuffer) { FW_ASSERT(m_port_pointer != 0); TwoWire* wire_ptr = reinterpret_cast(m_port_pointer); @@ -51,6 +47,6 @@ namespace Arduino { wire_ptr->endTransmission(); return Drv::I2cStatus::I2C_OK; - } +} -} // end namespace Arduino +} // end namespace Arduino diff --git a/Arduino/Drv/I2cNodeDriver/I2cNodeDriver.cpp b/Arduino/Drv/I2cNodeDriver/I2cNodeDriver.cpp index 9da3a68..1051d72 100644 --- a/Arduino/Drv/I2cNodeDriver/I2cNodeDriver.cpp +++ b/Arduino/Drv/I2cNodeDriver/I2cNodeDriver.cpp @@ -5,7 +5,6 @@ // ====================================================================== #include "Arduino/Drv/I2cNodeDriver/I2cNodeDriver.hpp" -#include "FpConfig.hpp" #include "Fw/Types/Assert.hpp" namespace Arduino { @@ -19,9 +18,9 @@ I2cNodeDriver ::I2cNodeDriver(const char* const compName) : I2cNodeDriverCompone I2cNodeDriver ::~I2cNodeDriver() {} -void I2cNodeDriver ::configure(const U16 address, TwoWire &wire) { +void I2cNodeDriver ::configure(const U16 address, TwoWire& wire) { FW_ASSERT(this->m_wire == nullptr); - FW_ASSERT(I2cNodeDriver::s_component == nullptr); // Cannot run multiple I2cNodes at once + FW_ASSERT(I2cNodeDriver::s_component == nullptr); // Cannot run multiple I2cNodes at once this->m_wire = &wire; I2cNodeDriver ::s_component = this; this->m_wire->begin(address); @@ -31,14 +30,14 @@ void I2cNodeDriver ::configure(const U16 address, TwoWire &wire) { void I2cNodeDriver ::write(int size) { FW_ASSERT(this->m_wire != nullptr); - FW_ASSERT(this->m_wire->available() >= size); // If size was reported available, then at least that size must be + FW_ASSERT(this->m_wire->available() >= size); // If size was reported available, then at least that size must be this->m_wire->readBytes(this->m_buffer, size); Fw::Buffer writeData(this->m_buffer, size); this->write_out(0, this->m_address, writeData); } void I2cNodeDriver ::writeCallback(int size) { - FW_ASSERT(I2cNodeDriver::s_component != nullptr); // To reach this statement, this variable must be set + FW_ASSERT(I2cNodeDriver::s_component != nullptr); // To reach this statement, this variable must be set I2cNodeDriver::s_component->write(size); } @@ -50,7 +49,7 @@ void I2cNodeDriver ::read() { } void I2cNodeDriver ::readCallback() { - FW_ASSERT(I2cNodeDriver::s_component != nullptr); // To reach this statement, this variable must be set + FW_ASSERT(I2cNodeDriver::s_component != nullptr); // To reach this statement, this variable must be set I2cNodeDriver::s_component->read(); } diff --git a/Arduino/Drv/Ip/CMakeLists.txt b/Arduino/Drv/Ip/CMakeLists.txt new file mode 100644 index 0000000..e959d40 --- /dev/null +++ b/Arduino/Drv/Ip/CMakeLists.txt @@ -0,0 +1,14 @@ +#### +# F prime CMakeLists.txt: +# +# SOURCE_FILES: combined list of source and autocoding files +# MOD_DEPS: (optional) module dependencies +# +#### +restrict_platforms(ArduinoFw) + +set(SOURCE_FILES + +) + +register_fprime_module() \ No newline at end of file diff --git a/Arduino/Drv/Ip/IpSocket.hpp b/Arduino/Drv/Ip/IpSocket.hpp new file mode 100644 index 0000000..a2104c3 --- /dev/null +++ b/Arduino/Drv/Ip/IpSocket.hpp @@ -0,0 +1,43 @@ +// ====================================================================== +// \title IpSocket.hpp +// \author ethan +// \brief hpp file for IpSocket component implementation class +// ====================================================================== +#ifndef Arduino_Drv_IP_IPHELPER_HPP_ +#define Arduino_Drv_IP_IPHELPER_HPP_ + +namespace Arduino { + +struct SocketDescriptor final { + void* fd = nullptr; //!< Used for all sockets to track the communication file descriptor + void* serverFd = nullptr; //!< Used for server sockets to track the server file descriptor +}; + +/** + * \brief Status enumeration for socket return values + */ +enum SocketIpStatus { + SOCK_SUCCESS = 0, //!< Socket operation successful + SOCK_FAILED_TO_GET_SOCKET = -1, //!< Socket open failed + SOCK_FAILED_TO_GET_HOST_IP = -2, //!< Host IP lookup failed + SOCK_INVALID_IP_ADDRESS = -3, //!< Bad IP address supplied + SOCK_FAILED_TO_CONNECT = -4, //!< Failed to connect socket + SOCK_FAILED_TO_SET_SOCKET_OPTIONS = -5, //!< Failed to configure socket + SOCK_INTERRUPTED_TRY_AGAIN = -6, //!< Interrupted status for retries + SOCK_READ_ERROR = -7, //!< Failed to read socket + SOCK_DISCONNECTED = -8, //!< Failed to read socket with disconnect + SOCK_FAILED_TO_BIND = -9, //!< Failed to bind to socket + SOCK_FAILED_TO_LISTEN = -10, //!< Failed to listen on socket + SOCK_FAILED_TO_ACCEPT = -11, //!< Failed to accept connection + SOCK_SEND_ERROR = -13, //!< Failed to send after configured retries + SOCK_NOT_STARTED = -14, //!< Socket has not been started + SOCK_FAILED_TO_READ_BACK_PORT = -15, //!< Failed to read back port from connection + SOCK_NO_DATA_AVAILABLE = -16, //!< No data available or read operation would block + SOCK_ANOTHER_THREAD_OPENING = -17, //!< Another thread is opening + SOCK_AUTO_CONNECT_DISABLED = -18, //!< Automatic connections are disabled + SOCK_INVALID_CALL = -19 //!< Operation is invalid +}; + +} // namespace Arduino + +#endif /* Arduino_Drv_SOCKETIPDRIVER_SOCKETHELPER_HPP_ */ diff --git a/Arduino/Drv/PwmDriver/PwmDriver.cpp b/Arduino/Drv/PwmDriver/PwmDriver.cpp index bdf205a..000c197 100644 --- a/Arduino/Drv/PwmDriver/PwmDriver.cpp +++ b/Arduino/Drv/PwmDriver/PwmDriver.cpp @@ -4,53 +4,35 @@ // \brief cpp file for PwmDriver component implementation class // ====================================================================== - #include -#include #include namespace Arduino { - // ---------------------------------------------------------------------- - // Construction, initialization, and destruction - // ---------------------------------------------------------------------- - - PwmDriver :: - PwmDriver( - const char *const compName - ) : PwmDriverComponentBase(compName), m_pin(-1) - { - - } +// ---------------------------------------------------------------------- +// Construction, initialization, and destruction +// ---------------------------------------------------------------------- - PwmDriver :: - ~PwmDriver() - { +PwmDriver ::PwmDriver(const char* const compName) : PwmDriverComponentBase(compName), m_pin(-1) {} - } +PwmDriver ::~PwmDriver() {} - void PwmDriver::open(NATIVE_INT_TYPE gpio) - { +void PwmDriver::open(FwIndexType gpio) { this->m_pin = gpio; pinMode(this->m_pin, Arduino::DEF_OUTPUT); - } - - // ---------------------------------------------------------------------- - // Handler implementations for user-defined typed input ports - // ---------------------------------------------------------------------- - - Fw::Success PwmDriver :: - setDutyCycle_handler( - const NATIVE_INT_TYPE portNum, - U8 dutyCycle - ) - { +} + +// ---------------------------------------------------------------------- +// Handler implementations for user-defined typed input ports +// ---------------------------------------------------------------------- + +Fw::Success PwmDriver ::setDutyCycle_handler(const FwIndexType portNum, U8 dutyCycle) { if (dutyCycle > 100) { dutyCycle = 100; } analogWrite(this->m_pin, 255 * (static_cast(dutyCycle) / 100)); return Fw::Success::SUCCESS; - } +} -} // end namespace Arduino +} // end namespace Arduino diff --git a/Arduino/Drv/PwmDriver/PwmDriver.hpp b/Arduino/Drv/PwmDriver/PwmDriver.hpp index 83fad37..9055ecc 100644 --- a/Arduino/Drv/PwmDriver/PwmDriver.hpp +++ b/Arduino/Drv/PwmDriver/PwmDriver.hpp @@ -11,47 +11,38 @@ namespace Arduino { - class PwmDriver : - public PwmDriverComponentBase - { - - public: - - // ---------------------------------------------------------------------- - // Construction, initialization, and destruction - // ---------------------------------------------------------------------- - - //! Construct object PwmDriver - //! - PwmDriver( - const char *const compName /*!< The component name*/ - ); - - //! Destroy object PwmDriver - //! - ~PwmDriver(); - - //! Setup PWM Pin - //! - void open(NATIVE_INT_TYPE gpio); - - PRIVATE: - - // ---------------------------------------------------------------------- - // Handler implementations for user-defined typed input ports - // ---------------------------------------------------------------------- - - //! Handler implementation for setDutyCycle - //! - Fw::Success setDutyCycle_handler( - const NATIVE_INT_TYPE portNum, /*!< The port number*/ - U8 dutyCycle - ); - - PlatformIntType m_pin; - - }; - -} // end namespace Arduino +class PwmDriver : public PwmDriverComponentBase { + public: + // ---------------------------------------------------------------------- + // Construction, initialization, and destruction + // ---------------------------------------------------------------------- + + //! Construct object PwmDriver + //! + PwmDriver(const char* const compName /*!< The component name*/ + ); + + //! Destroy object PwmDriver + //! + ~PwmDriver(); + + //! Setup PWM Pin + //! + void open(FwIndexType gpio); + + private: + // ---------------------------------------------------------------------- + // Handler implementations for user-defined typed input ports + // ---------------------------------------------------------------------- + + //! Handler implementation for setDutyCycle + //! + Fw::Success setDutyCycle_handler(const FwIndexType portNum, /*!< The port number*/ + U8 dutyCycle); + + PlatformIntType m_pin; +}; + +} // end namespace Arduino #endif diff --git a/Arduino/Drv/SpiDriver/CMakeLists.txt b/Arduino/Drv/SpiDriver/CMakeLists.txt index fc412cf..3a60337 100644 --- a/Arduino/Drv/SpiDriver/CMakeLists.txt +++ b/Arduino/Drv/SpiDriver/CMakeLists.txt @@ -10,10 +10,8 @@ set(SOURCE_FILES "${CMAKE_CURRENT_LIST_DIR}/SpiDriver.fpp" "${CMAKE_CURRENT_LIST_DIR}/SpiDriver.cpp" ) -if(FPRIME_ARDUINO) - list(APPEND SOURCE_FILES "${CMAKE_CURRENT_LIST_DIR}/SpiDriverArduino.cpp") - target_use_arduino_libraries("SPI") -else() - list(APPEND SOURCE_FILES "${CMAKE_CURRENT_LIST_DIR}/SpiDriverLinux.cpp") -endif() + +list(APPEND SOURCE_FILES "${CMAKE_CURRENT_LIST_DIR}/SpiDriverArduino.cpp") +target_use_arduino_libraries("SPI") + register_fprime_module() diff --git a/Arduino/Drv/SpiDriver/SpiDriver.cpp b/Arduino/Drv/SpiDriver/SpiDriver.cpp index d632b53..838a45f 100644 --- a/Arduino/Drv/SpiDriver/SpiDriver.cpp +++ b/Arduino/Drv/SpiDriver/SpiDriver.cpp @@ -4,47 +4,28 @@ // \brief cpp file for SpiDriver component implementation class // ====================================================================== - #include -#include #include "Fw/Types/Assert.hpp" namespace Arduino { - // ---------------------------------------------------------------------- - // Construction, initialization, and destruction - // ---------------------------------------------------------------------- - - SpiDriver :: - SpiDriver( - const char *const compName - ) : SpiDriverComponentBase(compName), - m_port_pointer(static_cast(NULL)) - { - - } +// ---------------------------------------------------------------------- +// Construction, initialization, and destruction +// ---------------------------------------------------------------------- - SpiDriver :: - ~SpiDriver() - { +SpiDriver ::SpiDriver(const char* const compName) : SpiDriverComponentBase(compName), m_port_pointer(nullptr) {} - } +SpiDriver ::~SpiDriver() {} - // ---------------------------------------------------------------------- - // Handler implementations for user-defined typed input ports - // ---------------------------------------------------------------------- +// ---------------------------------------------------------------------- +// Handler implementations for user-defined typed input ports +// ---------------------------------------------------------------------- - void SpiDriver :: - SpiReadWrite_handler( - const NATIVE_INT_TYPE portNum, - Fw::Buffer &writeBuffer, - Fw::Buffer &readBuffer - ) - { +void SpiDriver ::SpiReadWrite_handler(const FwIndexType portNum, Fw::Buffer& writeBuffer, Fw::Buffer& readBuffer) { FW_ASSERT(readBuffer.getData()); FW_ASSERT(writeBuffer.getData()); read_write_data(readBuffer, writeBuffer); - } +} -} // end namespace Arduino +} // end namespace Arduino diff --git a/Arduino/Drv/SpiDriver/SpiDriver.hpp b/Arduino/Drv/SpiDriver/SpiDriver.hpp index 0e22d27..f51f41d 100644 --- a/Arduino/Drv/SpiDriver/SpiDriver.hpp +++ b/Arduino/Drv/SpiDriver/SpiDriver.hpp @@ -7,8 +7,8 @@ #ifndef SpiDriver_HPP #define SpiDriver_HPP -#include "Arduino/Drv/SpiDriver/SpiDriverComponentAc.hpp" #include +#include "Arduino/Drv/SpiDriver/SpiDriverComponentAc.hpp" #ifdef SPI_MSBFIRST #define MSBFIRST SPI_MSBFIRST @@ -19,77 +19,69 @@ namespace Arduino { - class SpiDriver : - public SpiDriverComponentBase - { - - public: - - enum SpiFrequency - { +class SpiDriver : public SpiDriverComponentBase { + public: + enum SpiFrequency { SPI_FREQUENCY_1MHZ = 1000000UL, SPI_FREQUENCY_2MHZ = 2000000UL, SPI_FREQUENCY_3MHZ = 3000000UL, SPI_FREQUENCY_4MHZ = 4000000UL, - }; - - enum SpiMode - { - SPI_MODE_CPOL_LOW_CPHA_LOW, ///< (CPOL = 0, CPHA = 0) - SPI_MODE_CPOL_LOW_CPHA_HIGH, ///< (CPOL = 0, CPHA = 1) - SPI_MODE_CPOL_HIGH_CPHA_LOW, ///< (CPOL = 1, CPHA = 0) - SPI_MODE_CPOL_HIGH_CPHA_HIGH, ///< (CPOL = 1, CPHA = 1) - }; - - enum SpiBitOrder - { - SPI_LSB_FIRST, - SPI_MSB_FIRST, - }; - - // ---------------------------------------------------------------------- - // Construction, initialization, and destruction - // ---------------------------------------------------------------------- - - //! Construct object SpiDriver - //! - SpiDriver( - const char *const compName /*!< The component name*/ - ); - - //! Destroy object SpiDriver - //! - ~SpiDriver(); - - void open(SPIClass *spi, SpiFrequency clock, NATIVE_INT_TYPE ss_pin, SpiMode spiMode = SpiMode::SPI_MODE_CPOL_LOW_CPHA_LOW, SpiBitOrder bitOrder = SpiBitOrder::SPI_MSB_FIRST); - void close(); - - PRIVATE: - - //! Read the actual data - void read_write_data(Fw::Buffer& readBuffer, Fw::Buffer& writeBuffer); - - // ---------------------------------------------------------------------- - // Handler implementations for user-defined typed input ports - // ---------------------------------------------------------------------- - - //! Handler implementation for SpiReadWrite - //! - void SpiReadWrite_handler( - const NATIVE_INT_TYPE portNum, /*!< The port number*/ - Fw::Buffer &writeBuffer, - Fw::Buffer &readBuffer - ); + }; - //! Stores the open SPI port, POINTER_CAST so Linux and Ardunio may use different types - void* m_port_pointer; - SpiFrequency m_clock; - NATIVE_INT_TYPE m_ss_pin; - U8 m_spiMode; - SpiBitOrder m_bitOrder; + enum SpiMode { + SPI_MODE_CPOL_LOW_CPHA_LOW, ///< (CPOL = 0, CPHA = 0) + SPI_MODE_CPOL_LOW_CPHA_HIGH, ///< (CPOL = 0, CPHA = 1) + SPI_MODE_CPOL_HIGH_CPHA_LOW, ///< (CPOL = 1, CPHA = 0) + SPI_MODE_CPOL_HIGH_CPHA_HIGH, ///< (CPOL = 1, CPHA = 1) + }; + enum SpiBitOrder { + SPI_LSB_FIRST, + SPI_MSB_FIRST, }; -} // end namespace Arduino + // ---------------------------------------------------------------------- + // Construction, initialization, and destruction + // ---------------------------------------------------------------------- + + //! Construct object SpiDriver + //! + SpiDriver(const char* const compName /*!< The component name*/ + ); + + //! Destroy object SpiDriver + //! + ~SpiDriver(); + + void open(SPIClass* spi, + SpiFrequency clock, + FwIndexType ss_pin, + SpiMode spiMode = SpiMode::SPI_MODE_CPOL_LOW_CPHA_LOW, + SpiBitOrder bitOrder = SpiBitOrder::SPI_MSB_FIRST); + void close(); + + private: + //! Read the actual data + void read_write_data(Fw::Buffer& readBuffer, Fw::Buffer& writeBuffer); + + // ---------------------------------------------------------------------- + // Handler implementations for user-defined typed input ports + // ---------------------------------------------------------------------- + + //! Handler implementation for SpiReadWrite + //! + void SpiReadWrite_handler(const FwIndexType portNum, /*!< The port number*/ + Fw::Buffer& writeBuffer, + Fw::Buffer& readBuffer); + + //! Stores the open SPI port, POINTER_CAST so Linux and Ardunio may use different types + void* m_port_pointer; + SpiFrequency m_clock; + FwIndexType m_ss_pin; + U8 m_spiMode; + SpiBitOrder m_bitOrder; +}; + +} // end namespace Arduino #endif diff --git a/Arduino/Drv/SpiDriver/SpiDriverArduino.cpp b/Arduino/Drv/SpiDriver/SpiDriverArduino.cpp index 7de70a3..4941ed0 100644 --- a/Arduino/Drv/SpiDriver/SpiDriverArduino.cpp +++ b/Arduino/Drv/SpiDriver/SpiDriverArduino.cpp @@ -4,36 +4,33 @@ // \brief cpp file for SpiDriver component implementation class // ====================================================================== - #include -#include -#include "Fw/Types/Assert.hpp" #include +#include "Fw/Types/Assert.hpp" namespace Arduino { - void SpiDriver::open(SPIClass *spi, SpiFrequency clock, NATIVE_INT_TYPE ss_pin, SpiMode spiMode, SpiBitOrder bitOrder) - { +void SpiDriver::open(SPIClass* spi, SpiFrequency clock, FwIndexType ss_pin, SpiMode spiMode, SpiBitOrder bitOrder) { FW_ASSERT(spi != nullptr); U8 mode = SPI_MODE0; - switch(spiMode) { - case SpiMode::SPI_MODE_CPOL_LOW_CPHA_LOW: - mode = SPI_MODE0; - break; - case SpiMode::SPI_MODE_CPOL_LOW_CPHA_HIGH: - mode = SPI_MODE1; - break; - case SpiMode::SPI_MODE_CPOL_HIGH_CPHA_LOW: - mode = SPI_MODE2; - break; - case SpiMode::SPI_MODE_CPOL_HIGH_CPHA_HIGH: - mode = SPI_MODE3; - break; - default: - //Assert if the device SPI Mode is not in the correct range - FW_ASSERT(0, spiMode); - break; + switch (spiMode) { + case SpiMode::SPI_MODE_CPOL_LOW_CPHA_LOW: + mode = SPI_MODE0; + break; + case SpiMode::SPI_MODE_CPOL_LOW_CPHA_HIGH: + mode = SPI_MODE1; + break; + case SpiMode::SPI_MODE_CPOL_HIGH_CPHA_LOW: + mode = SPI_MODE2; + break; + case SpiMode::SPI_MODE_CPOL_HIGH_CPHA_HIGH: + mode = SPI_MODE3; + break; + default: + // Assert if the device SPI Mode is not in the correct range + FW_ASSERT(0, spiMode); + break; } this->m_port_pointer = spi; @@ -44,25 +41,23 @@ namespace Arduino { pinMode(m_ss_pin, Arduino::DEF_OUTPUT); spi->begin(); - } +} - void SpiDriver::close() - { +void SpiDriver::close() { FW_ASSERT(m_port_pointer != 0); SPIClass* spi_ptr = reinterpret_cast(m_port_pointer); spi_ptr->end(); - } +} - void SpiDriver::read_write_data(Fw::Buffer& readBuffer, Fw::Buffer& writeBuffer) - { +void SpiDriver::read_write_data(Fw::Buffer& readBuffer, Fw::Buffer& writeBuffer) { FW_ASSERT(m_port_pointer != 0); SPIClass* spi_ptr = reinterpret_cast(m_port_pointer); - if(this->m_bitOrder == SpiBitOrder::SPI_MSB_FIRST) - spi_ptr->beginTransaction(SPISettings(this->m_clock, MSBFIRST, this->m_spiMode)); + if (this->m_bitOrder == SpiBitOrder::SPI_MSB_FIRST) + spi_ptr->beginTransaction(SPISettings(this->m_clock, MSBFIRST, this->m_spiMode)); else - spi_ptr->beginTransaction(SPISettings(this->m_clock, LSBFIRST, this->m_spiMode)); + spi_ptr->beginTransaction(SPISettings(this->m_clock, LSBFIRST, this->m_spiMode)); digitalWrite(m_ss_pin, Arduino::DEF_LOW); spi_ptr->transfer(reinterpret_cast(writeBuffer.getData()), writeBuffer.getSize()); @@ -71,6 +66,6 @@ namespace Arduino { spi_ptr->endTransaction(); memcpy(readBuffer.getData(), writeBuffer.getData(), writeBuffer.getSize()); - } +} -} // end namespace Arduino +} // end namespace Arduino diff --git a/Arduino/Drv/SpiDriver/SpiDriverLinux.cpp b/Arduino/Drv/SpiDriver/SpiDriverLinux.cpp deleted file mode 100644 index 5a8dba6..0000000 --- a/Arduino/Drv/SpiDriver/SpiDriverLinux.cpp +++ /dev/null @@ -1,28 +0,0 @@ -// ====================================================================== -// \title SpiDriver.cpp -// \author ethanchee -// \brief cpp file for SpiDriver component implementation class -// ====================================================================== - - -#include -#include - -namespace Arduino { - - void SpiDriver::open(SPIClass *spi, SpiFrequency clock, NATIVE_INT_TYPE ss_pin, SpiMode spiMode, SpiBitOrder bitOrder) - { - - } - - void SpiDriver::close() - { - - } - - void SpiDriver::read_write_data(Fw::Buffer& readBuffer, Fw::Buffer& writeBuffer) - { - - } - -} // end namespace Arduino diff --git a/Arduino/Drv/StreamDriver/CMakeLists.txt b/Arduino/Drv/StreamDriver/CMakeLists.txt index a1eab19..df82808 100644 --- a/Arduino/Drv/StreamDriver/CMakeLists.txt +++ b/Arduino/Drv/StreamDriver/CMakeLists.txt @@ -8,10 +8,7 @@ set(SOURCE_FILES "${CMAKE_CURRENT_LIST_DIR}/StreamDriver.fpp" "${CMAKE_CURRENT_LIST_DIR}/StreamDriver.cpp" + "${CMAKE_CURRENT_LIST_DIR}/StreamDriverArduino.cpp" ) -if(FPRIME_ARDUINO) - list(APPEND SOURCE_FILES "${CMAKE_CURRENT_LIST_DIR}/StreamDriverArduino.cpp") -else() - list(APPEND SOURCE_FILES "${CMAKE_CURRENT_LIST_DIR}/StreamDriverLinux.cpp") -endif() + register_fprime_module() diff --git a/Arduino/Drv/StreamDriver/StreamDriver.cpp b/Arduino/Drv/StreamDriver/StreamDriver.cpp index 9a3509c..2569c18 100644 --- a/Arduino/Drv/StreamDriver/StreamDriver.cpp +++ b/Arduino/Drv/StreamDriver/StreamDriver.cpp @@ -14,9 +14,7 @@ namespace Arduino { // ---------------------------------------------------------------------- StreamDriver ::StreamDriver(const char* compName) - : StreamDriverComponentBase(compName), - m_port_number(0), - m_port_pointer(nullptr) {} + : StreamDriverComponentBase(compName), m_port_number(0), m_port_pointer(nullptr) {} StreamDriver ::~StreamDriver(void) {} @@ -37,7 +35,7 @@ void StreamDriver ::schedIn_handler(const FwIndexType portNum, U32 context) { if (not reinterpret_cast(m_port_pointer)->available()) { return; } - + Fw::Buffer recv_buffer = this->allocate_out(0, SERIAL_BUFFER_SIZE); read_data(recv_buffer); recv_out(0, recv_buffer, Drv::ByteStreamStatus::OP_OK); diff --git a/Arduino/Drv/StreamDriver/StreamDriver.hpp b/Arduino/Drv/StreamDriver/StreamDriver.hpp index fd499ec..1675903 100644 --- a/Arduino/Drv/StreamDriver/StreamDriver.hpp +++ b/Arduino/Drv/StreamDriver/StreamDriver.hpp @@ -7,9 +7,9 @@ #ifndef StreamDriver_HPP #define StreamDriver_HPP +#include #include "Arduino/Drv/StreamDriver/StreamDriverComponentAc.hpp" #include "Os/Task.hpp" -#include namespace Arduino { // Allow for setting serial ports on linux from the inputs @@ -53,12 +53,12 @@ class StreamDriver : public StreamDriverComponentBase { //! Handler implementation for send //! void send_handler(const FwIndexType portNum, /*!< The port number*/ - Fw::Buffer& fwBuffer) override; + Fw::Buffer& fwBuffer) override; //! Handler implementation for schedIn //! void schedIn_handler(const FwIndexType portNum, /*!< The port number*/ - U32 context /*!< The call order*/ + U32 context /*!< The call order*/ ); //! Port number to open diff --git a/Arduino/Drv/StreamDriver/StreamDriverArduino.cpp b/Arduino/Drv/StreamDriver/StreamDriverArduino.cpp index e709161..90d0ee7 100644 --- a/Arduino/Drv/StreamDriver/StreamDriverArduino.cpp +++ b/Arduino/Drv/StreamDriver/StreamDriverArduino.cpp @@ -6,8 +6,8 @@ #include #include -#include "Fw/Types/BasicTypes.hpp" #include "Fw/Types/Assert.hpp" +#include "Fw/Types/BasicTypes.hpp" namespace Arduino { @@ -25,8 +25,7 @@ void StreamDriver::configure(Stream* streamDriver) { void StreamDriver ::write_data(Fw::Buffer& fwBuffer) { FW_ASSERT(m_port_pointer != 0); - reinterpret_cast(m_port_pointer) - ->write(reinterpret_cast(fwBuffer.getData()), fwBuffer.getSize()); + reinterpret_cast(m_port_pointer)->write(reinterpret_cast(fwBuffer.getData()), fwBuffer.getSize()); } void StreamDriver ::read_data(Fw::Buffer& fwBuffer) { diff --git a/Arduino/Drv/StreamDriver/StreamDriverLinux.cpp b/Arduino/Drv/StreamDriver/StreamDriverLinux.cpp deleted file mode 100644 index 7856064..0000000 --- a/Arduino/Drv/StreamDriver/StreamDriverLinux.cpp +++ /dev/null @@ -1,50 +0,0 @@ -// ====================================================================== -// \title StreamDriverImpl.cpp -// \author lestarch -// \brief cpp file for StreamDriver component implementation class -// ====================================================================== - -#include -#include -#include -#include -#include "Fw/Types/BasicTypes.hpp" - -#define SERIAL_FILE_LINUX_TMPL "/dev/pts/%d" - -namespace Arduino { -char** SERIAL_PORT = NULL; -void StreamDriver ::init(const FwIndexType port_number, const PlatformIntType baud) { - char name[1024]; - StreamDriverComponentBase::init(instance); - // NULL ports use above template - if (SERIAL_PORT == NULL) { - snprintf(name, 1024, SERIAL_FILE_LINUX_TMPL, m_port_number + 20); - SERIAL_PORT = reinterpret_cast(&name); - } - printf("Opening serial port: '%s'\n", *SERIAL_PORT); - m_port_pointer = open(*SERIAL_PORT, O_RDWR); - int flags = fcntl(m_port_pointer, F_GETFL, 0); - fcntl(m_port_pointer, F_SETFL, flags | O_NONBLOCK); -} - -// ---------------------------------------------------------------------- -// Handler implementations for user-defined typed input ports -// ---------------------------------------------------------------------- - -void StreamDriver ::write_data(Fw::Buffer& fwBuffer) { - if (m_port_pointer != -1) { - write(m_port_pointer, reinterpret_cast(fwBuffer.getdata()), fwBuffer.getsize()); - } -} - -void StreamDriver ::read_data(Fw::Buffer& fwBuffer) { - NATIVE_INT_TYPE result; - if ((m_port_pointer != -1) && - (-1 != (result = read(m_port_pointer, reinterpret_cast(fwBuffer.getdata()), fwBuffer.getsize())))) { - fwBuffer.setsize(result); - } else { - fwBuffer.setsize(0); - } -} -} // namespace Arduino diff --git a/Arduino/Drv/TcpClient/CMakeLists.txt b/Arduino/Drv/TcpClient/CMakeLists.txt index cf8932a..9600f2d 100644 --- a/Arduino/Drv/TcpClient/CMakeLists.txt +++ b/Arduino/Drv/TcpClient/CMakeLists.txt @@ -6,14 +6,16 @@ # UT_SOURCE_FILES: list of source files for unit tests # #### -if (NOT ARDUINO_WIFI_ENABLED) - return() -endif() set(SOURCE_FILES "${CMAKE_CURRENT_LIST_DIR}/TcpClient.fpp" "${CMAKE_CURRENT_LIST_DIR}/TcpClient.cpp" ) -target_use_arduino_libraries("WiFi") +if (ARDUINO_WIFI_ENABLED) + list(APPEND SOURCE_FILES "${CMAKE_CURRENT_LIST_DIR}/TcpClientWiFi.cpp") + target_use_arduino_libraries("WiFi") +else() + list(APPEND SOURCE_FILES "${CMAKE_CURRENT_LIST_DIR}/TcpClientBasic.cpp") +endif() register_fprime_module() diff --git a/Arduino/Drv/TcpClient/TcpClient.cpp b/Arduino/Drv/TcpClient/TcpClient.cpp index a709e47..7c97ba1 100644 --- a/Arduino/Drv/TcpClient/TcpClient.cpp +++ b/Arduino/Drv/TcpClient/TcpClient.cpp @@ -5,8 +5,6 @@ // ====================================================================== #include -#include -#include namespace Arduino { @@ -14,72 +12,52 @@ namespace Arduino { // Construction, initialization, and destruction // ---------------------------------------------------------------------- -TcpClient ::TcpClient(const char* const compName) : TcpClientComponentBase(compName), client_connected(false) {} +TcpClient ::TcpClient(const char* const compName) : TcpClientComponentBase(compName) {} -TcpClient ::~TcpClient() { - if (client_connected) - client.stop(); -} - -Drv::SocketIpStatus TcpClient::setupWiFi(char* ssid, const char* password) { - WiFi.begin(ssid, password); - - if (WiFi.status() != WL_CONNECTED) - return Drv::SocketIpStatus::SOCK_FAILED_TO_BIND; +TcpClient ::~TcpClient() {} - return Drv::SocketIpStatus::SOCK_SUCCESS; +void TcpClient::start(const Fw::StringBase& name, + const Os::Task::ParamType priority, + const Os::Task::ParamType stack, + const Os::Task::ParamType cpuAffinity) { + FW_ASSERT(m_task.getState() == + Os::Task::State::NOT_STARTED); // It is a coding error to start this task multiple times + // Note: the first step is for the IP socket to open the port + Os::Task::Arguments arguments(name, TcpClient::readTask, this, priority, stack, cpuAffinity); + Os::Task::Status stat = m_task.start(arguments); + FW_ASSERT(Os::Task::OP_OK == stat, static_cast(stat)); } -Drv::SocketIpStatus TcpClient::configure(const char* hostname, - const U16 port, - const U32 send_timeout_seconds, - const U32 send_timeout_microseconds) { - if (not client.connect(hostname, port)) { - return Drv::SocketIpStatus::SOCK_FAILED_TO_CONNECT; - } - - if (this->isConnected_ready_OutputPort(0)) { - this->ready_out(0); - } - - client_connected = true; - - return Drv::SocketIpStatus::SOCK_SUCCESS; +void TcpClient::readTask(void* pointer) { + FW_ASSERT(pointer); + TcpClient* self = reinterpret_cast(pointer); + self->readLoop(); } // ---------------------------------------------------------------------- // Handler implementations for user-defined typed input ports // ---------------------------------------------------------------------- -void TcpClient ::schedIn_handler(const NATIVE_INT_TYPE portNum, NATIVE_UINT_TYPE context) { - if (not client_connected) { - return; +void TcpClient::send_handler(const FwIndexType portNum, Fw::Buffer& fwBuffer) { + SocketIpStatus status = this->send(fwBuffer.getData(), fwBuffer.getSize()); + Drv::ByteStreamStatus returnStatus; + switch (status) { + case SOCK_INTERRUPTED_TRY_AGAIN: + returnStatus = Drv::ByteStreamStatus::SEND_RETRY; + break; + case SOCK_SUCCESS: + returnStatus = Drv::ByteStreamStatus::OP_OK; + break; + default: + returnStatus = Drv::ByteStreamStatus::OTHER_ERROR; + break; } - - Fw::Buffer recvBuffer = this->allocate_out(0, Svc::STATIC_MEMORY_ALLOCATION_SIZE); - - int byte = 0; - NATIVE_UINT_TYPE count = 0; - U8* raw_data = reinterpret_cast(recvBuffer.getData()); - - while ((client.available() > 0) && (count < recvBuffer.getSize()) && ((byte = client.read()) != -1)) { - *(raw_data + count) = static_cast(byte); - count++; - } - - recvBuffer.setSize(count); - - this->recv_out(0, recvBuffer, Drv::RecvStatus::RECV_OK); + // Return the buffer and status to the caller + this->sendReturnOut_out(0, fwBuffer, returnStatus); } -Drv::SendStatus TcpClient ::send_handler(const NATIVE_INT_TYPE portNum, Fw::Buffer& sendBuffer) { - if (client_connected && sendBuffer.getSize() > 0) { - client.write(sendBuffer.getData(), sendBuffer.getSize()); - } - - this->deallocate_out(0, sendBuffer); - - return Drv::SendStatus::SEND_OK; +void TcpClient::recvReturnIn_handler(FwIndexType portNum, Fw::Buffer& fwBuffer) { + this->deallocate_out(0, fwBuffer); } } // end namespace Arduino diff --git a/Arduino/Drv/TcpClient/TcpClient.fpp b/Arduino/Drv/TcpClient/TcpClient.fpp index 3f728d2..815fcf1 100644 --- a/Arduino/Drv/TcpClient/TcpClient.fpp +++ b/Arduino/Drv/TcpClient/TcpClient.fpp @@ -2,23 +2,13 @@ module Arduino { @ TcpClient for Arduino board with WiFi support passive component TcpClient { - @ Polling for receiving data - sync input port schedIn: Svc.Sched + include "../../../../fprime/Drv/Interfaces/ByteStreamDriverInterface.fppi" - @ Indicates the driver has connected to the UART device - output port ready: Drv.ByteStreamReady - - @Allocate new buffer + @ Allocation for received data output port allocate: Fw.BufferGet - @return the allocated buffer + @ Deallocation of allocated buffers output port deallocate: Fw.BufferSend - @ Takes data to transmit out the UART device - guarded input port $send: Drv.ByteStreamSend - - @ Takes data to transmit out the UART device - output port $recv: Drv.ByteStreamRecv - } } \ No newline at end of file diff --git a/Arduino/Drv/TcpClient/TcpClient.hpp b/Arduino/Drv/TcpClient/TcpClient.hpp index cb6c67c..72f23fe 100644 --- a/Arduino/Drv/TcpClient/TcpClient.hpp +++ b/Arduino/Drv/TcpClient/TcpClient.hpp @@ -7,67 +7,120 @@ #ifndef TcpClient_HPP #define TcpClient_HPP -#include -#include +#include #include "Arduino/Drv/TcpClient/TcpClientComponentAc.hpp" -#include namespace Arduino { - class TcpClient : - public TcpClientComponentBase - { - - public: - - // ---------------------------------------------------------------------- - // Construction, initialization, and destruction - // ---------------------------------------------------------------------- - - //! Construct object TcpClient - //! - TcpClient( - const char *const compName /*!< The component name*/ - ); - - //! Destroy object TcpClient - //! - ~TcpClient(); - - Drv::SocketIpStatus setupWiFi(char* ssid, const char* password); - - Drv::SocketIpStatus configure(const char* hostname, - const U16 port, - const U32 send_timeout_seconds = SOCKET_SEND_TIMEOUT_SECONDS, - const U32 send_timeout_microseconds = SOCKET_SEND_TIMEOUT_MICROSECONDS); - - PRIVATE: - - // ---------------------------------------------------------------------- - // Handler implementations for user-defined typed input ports - // ---------------------------------------------------------------------- - - //! Handler implementation for schedIn - //! - void schedIn_handler( - const NATIVE_INT_TYPE portNum, /*!< The port number*/ - NATIVE_UINT_TYPE context /*!< - The call order - */ - ); - - //! Handler implementation for send - //! - Drv::SendStatus send_handler( - const NATIVE_INT_TYPE portNum, /*!< The port number*/ - Fw::Buffer &sendBuffer - ); - - WiFiClient client; - bool client_connected; - - }; - -} // end namespace Arduino +class TcpClient : public TcpClientComponentBase { + public: + // ---------------------------------------------------------------------- + // Construction, initialization, and destruction + // ---------------------------------------------------------------------- + + //! Construct object TcpClient + //! + TcpClient(const char* const compName /*!< The component name*/ + ); + + //! Destroy object TcpClient + //! + ~TcpClient(); + + /** + * \brief Configures the TcpClient settings but does not open the connection + * + * The TcpClientComponent needs to connect to a remote TCP server. This call configures the hostname, port and send + * timeouts for that socket connection. This call should be performed on system startup before recv or send + * are called. Note: hostname must be a dot-notation IP address of the form "x.x.x.x". DNS translation is left up + * to the user. + * + * \param hostname: ip address of remote tcp server in the form x.x.x.x + * \param password: password for the WiFi connection + * \param port: port of remote tcp server + * \param buffer_size: size of the buffer to be allocated. Defaults to 1024. + * \return status of the configure + */ + SocketIpStatus configure(const char* ssid, + const char* password, + const char* hostname, + const U16 port=50000, + FwSizeType buffer_size = 1024); + + /** + * \brief start the socket read task to start producing data + * + * Starts up the socket reading task and when reopen was configured, will open up the socket. + * + * \note: users must now use `setAutomaticOpen` to configure the socket to automatically open connections. The + * default behavior is to automatically open connections. + * + * \param name: name of the task + * \param priority: priority of the started task. See: Os::Task::start. Default: TASK_DEFAULT, not prioritized + * \param stack: stack size provided to the task. See: Os::Task::start. Default: TASK_DEFAULT, posix threads default + * \param cpuAffinity: cpu affinity provided to task. See: Os::Task::start. Default: TASK_DEFAULT, don't care + */ + void start(const Fw::StringBase& name, + const Os::Task::ParamType priority = Os::Task::TASK_DEFAULT, + const Os::Task::ParamType stack = Os::Task::TASK_DEFAULT, + const Os::Task::ParamType cpuAffinity = Os::Task::TASK_DEFAULT); + + SocketIpStatus send(const U8* data, U32 size); + + SocketIpStatus reconnect(); + + protected: + /** + * \brief receive off the TCP socket + */ + virtual void readLoop(); + /** + * \brief a task designed to read from the socket and output incoming data + * + * \param pointer: pointer to "this" component + */ + static void readTask(void* pointer); + + private: + // ---------------------------------------------------------------------- + // Handler implementations for user-defined typed input ports + // ---------------------------------------------------------------------- + + /** + * \brief Send data out of the TcpClient + * + * Passing data to this port will send data from the TcpClient to whatever TCP server this component has + * connected to. Should the socket not be opened or was disconnected, then this port call will return SEND_RETRY + * and critical transmissions should be retried. OTHER_ERROR indicates an unresolvable error. OP_OK is returned + * when the data has been sent. + * + * Note: this component delegates the reopening of the socket to the read thread and thus the caller should + * retry after the read thread has attempted to reopen the port but does not need to reopen the port manually. + * + * \param portNum: fprime port number of the incoming port call + * \param fwBuffer: buffer containing data to be sent + */ + void send_handler(const FwIndexType portNum, Fw::Buffer& fwBuffer) override; + + //! Handler implementation for recvReturnIn + //! + //! Port receiving back ownership of data sent out on $recv port + void recvReturnIn_handler(FwIndexType portNum, //!< The port number + Fw::Buffer& fwBuffer //!< The buffer + ) override; + + protected: + Os::Task m_task; + SocketDescriptor m_socket; //!< The socket descriptor for the TCP socket + bool m_reopen = false; //!< Flag to indicate if the socket should be reopened automatically + + const char* m_hostname; //!< Hostname of the remote TCP server + U16 m_port; //!< Port of the remote TCP server + + private: + FwSizeType m_allocation_size; +}; + +} // end namespace Arduino #endif diff --git a/Arduino/Drv/TcpClient/TcpClientBasic.cpp b/Arduino/Drv/TcpClient/TcpClientBasic.cpp new file mode 100644 index 0000000..fbe9bcf --- /dev/null +++ b/Arduino/Drv/TcpClient/TcpClientBasic.cpp @@ -0,0 +1,34 @@ +// ====================================================================== +// \title TcpClient.cpp +// \author ethanchee +// \brief cpp file for TcpClient component implementation class +// ====================================================================== + +#include + +namespace Arduino { + +SocketIpStatus TcpClient::configure(const char* ssid, + const char* password, + const char* hostname, + const U16 port, + FwSizeType buffer_size) { + // Not implemented + return SocketIpStatus::SOCK_INVALID_CALL; +} + +SocketIpStatus TcpClient::reconnect() { + // Not implemented + return SocketIpStatus::SOCK_INVALID_CALL; +} + +SocketIpStatus TcpClient::send(const U8* data, U32 size) { + // Not implemented + return SocketIpStatus::SOCK_INVALID_CALL; +} + +void TcpClient::readLoop() { + return; // Not implemented +} + +} // end namespace Arduino diff --git a/Arduino/Drv/TcpClient/TcpClientWiFi.cpp b/Arduino/Drv/TcpClient/TcpClientWiFi.cpp new file mode 100644 index 0000000..d950f79 --- /dev/null +++ b/Arduino/Drv/TcpClient/TcpClientWiFi.cpp @@ -0,0 +1,128 @@ +// ====================================================================== +// \title TcpClientWiFi.cpp +// \author ethanchee +// \brief cpp file for TcpClientWiFi component implementation class +// ====================================================================== + +#include +#include +#include + +namespace Arduino { + +SocketIpStatus TcpClient::configure(const char* ssid, + const char* password, + const char* hostname, + const U16 port, + FwSizeType buffer_size) { + FW_ASSERT(buffer_size <= std::numeric_limits::max(), static_cast(buffer_size)); + this->m_allocation_size = buffer_size; + this->m_hostname = hostname; + this->m_port = port; + + Fw::Logger::log("Connecting to WiFi SSID: %s\nThis may take a moment...\n", ssid); + + WiFi.begin(ssid, password); + + if (WiFi.status() != WL_CONNECTED) { + return SocketIpStatus::SOCK_FAILED_TO_BIND; + } + + Fw::Logger::log("WiFi connected with IP: %s\n", WiFi.localIP().toString().c_str()); + + this->m_socket.fd = new WiFiClient(); + if (not reinterpret_cast(this->m_socket.fd)->connect(this->m_hostname, this->m_port)) { + Fw::Logger::log("Failed to connect to server at %s:%d\n", this->m_hostname, this->m_port); + return SocketIpStatus::SOCK_FAILED_TO_CONNECT; + } + Fw::Logger::log("Connected to server at %s:%d\n", this->m_hostname, this->m_port); + + if (this->isConnected_ready_OutputPort(0)) { + this->ready_out(0); + } + + return SocketIpStatus::SOCK_SUCCESS; +} + +/** + * NOT CURRENTLY BEING USED + * WiFiClient.connect() function blocks so I am not using it for now. + * + * I am keeping this function here in case I figure something out later. + */ +SocketIpStatus TcpClient::reconnect() { + if (this->m_socket.fd == nullptr) { + return SocketIpStatus::SOCK_NOT_STARTED; // Socket not initialized + } + + WiFiClient* client = reinterpret_cast(this->m_socket.fd); + if (client->connected()) { + return SocketIpStatus::SOCK_SUCCESS; // Already connected + } + + // Attempt to reconnect + if (not client->connect(this->m_hostname, this->m_port)) { + return SocketIpStatus::SOCK_FAILED_TO_CONNECT; + } + + Fw::Logger::log("Connected to server at %s:%d\n", this->m_hostname, this->m_port); + if (this->isConnected_ready_OutputPort(0)) { + this->ready_out(0); + } + return SocketIpStatus::SOCK_SUCCESS; +} + +SocketIpStatus TcpClient::send(const U8* data, U32 size) { + if (this->m_socket.fd == nullptr) { + return SocketIpStatus::SOCK_NOT_STARTED; + } + + WiFiClient* client = reinterpret_cast(this->m_socket.fd); + + if (not client->connected()) { + return SocketIpStatus::SOCK_DISCONNECTED; + } + + FwSizeType bytesSent = client->write(data, size); + if (bytesSent != size) { + return SocketIpStatus::SOCK_INTERRUPTED_TRY_AGAIN; + } + + return SocketIpStatus::SOCK_SUCCESS; +} + +void TcpClient::readLoop() { + if (this->m_socket.fd == nullptr) { + return; // Socket not initialized + } + + WiFiClient* client = reinterpret_cast(this->m_socket.fd); + + if (not client->connected()) { + // TODO: non-blocking reconnect + return; + } + + Fw::Buffer buffer = this->allocate_out(0, static_cast(this->m_allocation_size)); + U8* data = buffer.getData(); + FW_ASSERT(data); + U32 size = buffer.getSize(); + + Drv::ByteStreamStatus recvStatus = Drv::ByteStreamStatus::OP_OK; + if (client->available()) { + FwSizeType recvSize = client->read(data, size); + if (recvSize > 0) { + buffer.setSize(recvSize); + } else { + buffer.setSize(0); // Clear the buffer if no data was read + recvStatus = Drv::ByteStreamStatus::RECV_NO_DATA; + } + } else { + buffer.setSize(0); // Clear the buffer if no data is available + recvStatus = Drv::ByteStreamStatus::RECV_NO_DATA; + } + + this->recv_out(0, buffer, recvStatus); +} + +} // end namespace Arduino diff --git a/Arduino/Drv/TcpClient/docs/sdd.md b/Arduino/Drv/TcpClient/docs/sdd.md index b02cf25..f381b3d 100644 --- a/Arduino/Drv/TcpClient/docs/sdd.md +++ b/Arduino/Drv/TcpClient/docs/sdd.md @@ -3,7 +3,18 @@ TcpClient for Arduino board with WiFi support ## Usage Examples -Add usage examples here + +### Configure comDriver + +```cpp +comDriver.configure("wifi-ssid", "wifi-password", "gds-ip-address", 50000); +``` + +### F Prime GDS + +```sh +fprime-gds -n --dictionary +``` ### Diagrams Add diagrams here diff --git a/Arduino/Drv/TcpServer/CMakeLists.txt b/Arduino/Drv/TcpServer/CMakeLists.txt new file mode 100644 index 0000000..7cd0733 --- /dev/null +++ b/Arduino/Drv/TcpServer/CMakeLists.txt @@ -0,0 +1,24 @@ +#### +# FPrime CMakeLists.txt: +# +# SOURCE_FILES: combined list of source and autocoding files +# MOD_DEPS: (optional) module dependencies +# UT_SOURCE_FILES: list of source files for unit tests +# +# More information in the F´ CMake API documentation: +# https://fprime.jpl.nasa.gov/latest/docs/user-manual/build-system/cmake-api/ +# +#### +set(SOURCE_FILES + "${CMAKE_CURRENT_LIST_DIR}/TcpServer.fpp" + "${CMAKE_CURRENT_LIST_DIR}/TcpServer.cpp" +) + +if (ARDUINO_WIFI_ENABLED) + list(APPEND SOURCE_FILES "${CMAKE_CURRENT_LIST_DIR}/TcpServerWiFi.cpp") + target_use_arduino_libraries("WiFi") +else() + list(APPEND SOURCE_FILES "${CMAKE_CURRENT_LIST_DIR}/TcpServerBasic.cpp") +endif() + +register_fprime_module() diff --git a/Arduino/Drv/TcpServer/TcpServer.cpp b/Arduino/Drv/TcpServer/TcpServer.cpp new file mode 100644 index 0000000..fd0c25a --- /dev/null +++ b/Arduino/Drv/TcpServer/TcpServer.cpp @@ -0,0 +1,59 @@ +// ====================================================================== +// \title TcpServer.cpp +// \author ethan +// \brief cpp file for TcpServer component implementation class +// ====================================================================== + +#include "Arduino/Drv/TcpServer/TcpServer.hpp" + +namespace Arduino { + +// ---------------------------------------------------------------------- +// Component construction and destruction +// ---------------------------------------------------------------------- + +TcpServer ::TcpServer(const char* const compName) : TcpServerComponentBase(compName) {} + +TcpServer ::~TcpServer() {} + +void TcpServer::start(const Fw::StringBase &name, + const Os::Task::ParamType priority, + const Os::Task::ParamType stack, + const Os::Task::ParamType cpuAffinity) { + FW_ASSERT(m_task.getState() == Os::Task::State::NOT_STARTED); // It is a coding error to start this task multiple times + // Note: the first step is for the IP socket to open the port + Os::Task::Arguments arguments(name, TcpServer::readTask, this, priority, stack, cpuAffinity); + Os::Task::Status stat = m_task.start(arguments); + FW_ASSERT(Os::Task::OP_OK == stat, static_cast(stat)); +} + +void TcpServer::readTask(void* pointer) { + FW_ASSERT(pointer); + TcpServer* self = reinterpret_cast(pointer); + self->readLoop(); +} + +// ---------------------------------------------------------------------- +// Handler implementations for typed input ports +// ---------------------------------------------------------------------- + +void TcpServer ::recvReturnIn_handler(FwIndexType portNum, Fw::Buffer& fwBuffer) { + this->deallocate_out(0, fwBuffer); +} + +void TcpServer ::send_handler(FwIndexType portNum, Fw::Buffer& fwBuffer) { + SocketIpStatus status = this->send(fwBuffer.getData(), fwBuffer.getSize()); + Drv::ByteStreamStatus returnStatus; + switch (status) { + case SOCK_SUCCESS: + returnStatus = Drv::ByteStreamStatus::OP_OK; + break; + default: + returnStatus = Drv::ByteStreamStatus::OTHER_ERROR; + break; + } + // Return the buffer and status to the caller + this->sendReturnOut_out(0, fwBuffer, returnStatus); +} + +} // namespace Arduino diff --git a/Arduino/Drv/TcpServer/TcpServer.fpp b/Arduino/Drv/TcpServer/TcpServer.fpp new file mode 100644 index 0000000..c33b552 --- /dev/null +++ b/Arduino/Drv/TcpServer/TcpServer.fpp @@ -0,0 +1,14 @@ +module Arduino { + @ TCP Server for Arduino board with WiFi support + passive component TcpServer { + + include "../../../../fprime/Drv/Interfaces/ByteStreamDriverInterface.fppi" + + @ Allocation for received data + output port allocate: Fw.BufferGet + + @ Deallocation of allocated buffers + output port deallocate: Fw.BufferSend + + } +} diff --git a/Arduino/Drv/TcpServer/TcpServer.hpp b/Arduino/Drv/TcpServer/TcpServer.hpp new file mode 100644 index 0000000..2fb7fd0 --- /dev/null +++ b/Arduino/Drv/TcpServer/TcpServer.hpp @@ -0,0 +1,94 @@ +// ====================================================================== +// \title TcpServer.hpp +// \author ethan +// \brief hpp file for TcpServer component implementation class +// ====================================================================== + +#ifndef Arduino_TcpServer_HPP +#define Arduino_TcpServer_HPP + +#include +#include "Arduino/Drv/TcpServer/TcpServerComponentAc.hpp" + +namespace Arduino { + +class TcpServer final : public TcpServerComponentBase { + public: + // ---------------------------------------------------------------------- + // Component construction and destruction + // ---------------------------------------------------------------------- + + //! Construct TcpServer object + TcpServer(const char* const compName //!< The component name + ); + + //! Destroy TcpServer object + ~TcpServer(); + + // For WiFi if available + SocketIpStatus configure(const char* ssid, const char* password, U16 port=50000, FwSizeType buffer_size=1024); + + /** + * \brief start the socket read task to start producing data + * + * Starts up the socket reading task and when reopen was configured, will open up the socket. + * + * \note: users must now use `setAutomaticOpen` to configure the socket to automatically open connections. The + * default behavior is to automatically open connections. + * + * \param name: name of the task + * \param priority: priority of the started task. See: Os::Task::start. Default: TASK_DEFAULT, not prioritized + * \param stack: stack size provided to the task. See: Os::Task::start. Default: TASK_DEFAULT, posix threads default + * \param cpuAffinity: cpu affinity provided to task. See: Os::Task::start. Default: TASK_DEFAULT, don't care + */ + void start(const Fw::StringBase& name, + const Os::Task::ParamType priority = Os::Task::TASK_DEFAULT, + const Os::Task::ParamType stack = Os::Task::TASK_DEFAULT, + const Os::Task::ParamType cpuAffinity = Os::Task::TASK_DEFAULT); + + SocketIpStatus send(const U8* data, U32 size); + + SocketIpStatus reconnect(); + + protected: + /** + * \brief receive off the TCP socket + */ + virtual void readLoop(); + /** + * \brief a task designed to read from the socket and output incoming data + * + * \param pointer: pointer to "this" component + */ + static void readTask(void* pointer); + + private: + // ---------------------------------------------------------------------- + // Handler implementations for typed input ports + // ---------------------------------------------------------------------- + + //! Handler implementation for recvReturnIn + //! + //! Port receiving back ownership of data sent out on $recv port + void recvReturnIn_handler(FwIndexType portNum, //!< The port number + Fw::Buffer& fwBuffer //!< The buffer + ) override; + + //! Handler implementation for send + //! + //! Invoke this port to send data out the driver + void send_handler(FwIndexType portNum, //!< The port number + Fw::Buffer& fwBuffer //!< The buffer + ) override; + + protected: + Os::Task m_task; + SocketDescriptor m_socket; //!< The socket descriptor for the TCP socket + + private: + FwSizeType m_allocation_size; +}; + +} // namespace Arduino + +#endif diff --git a/Arduino/Drv/TcpServer/TcpServerBasic.cpp b/Arduino/Drv/TcpServer/TcpServerBasic.cpp new file mode 100644 index 0000000..1c98536 --- /dev/null +++ b/Arduino/Drv/TcpServer/TcpServerBasic.cpp @@ -0,0 +1,30 @@ +// ====================================================================== +// \title TcpServer.cpp +// \author ethan +// \brief cpp file for TcpServer component implementation class +// ====================================================================== + +#include "Arduino/Drv/TcpServer/TcpServer.hpp" + +namespace Arduino { + +SocketIpStatus TcpServer::configure(const char* ssid, const char* password, U16 port, FwSizeType buffer_size) { + // Not implemented + return SocketIpStatus::SOCK_INVALID_CALL; +} + +SocketIpStatus TcpServer::reconnect() { + // Not implemented + return SocketIpStatus::SOCK_INVALID_CALL; +} + +SocketIpStatus TcpServer::send(const U8* data, U32 size) { + // Not implemented + return SocketIpStatus::SOCK_INVALID_CALL; +} + +void TcpServer::readLoop() { + return; // Not implemented +} + +} // namespace Arduino diff --git a/Arduino/Drv/TcpServer/TcpServerWiFi.cpp b/Arduino/Drv/TcpServer/TcpServerWiFi.cpp new file mode 100644 index 0000000..e90aee3 --- /dev/null +++ b/Arduino/Drv/TcpServer/TcpServerWiFi.cpp @@ -0,0 +1,104 @@ +// ====================================================================== +// \title TcpServer.cpp +// \author ethan +// \brief cpp file for TcpServer component implementation class +// ====================================================================== + +#include +#include +#include "Arduino/Drv/TcpServer/TcpServer.hpp" + +namespace Arduino { + +SocketIpStatus TcpServer::configure(const char* ssid, const char* password, U16 port, FwSizeType buffer_size) { + FW_ASSERT(buffer_size <= std::numeric_limits::max(), static_cast(buffer_size)); + this->m_allocation_size = buffer_size; + + Fw::Logger::log("Connecting to WiFi SSID: %s\nThis may take a moment...\n", ssid); + + this->m_socket.serverFd = new WiFiServer(port); + + WiFi.begin(ssid, password); + + if (WiFi.status() != WL_CONNECTED) + return SocketIpStatus::SOCK_FAILED_TO_BIND; + + Fw::Logger::log("WiFi connected with IP: %s\n", WiFi.localIP().toString().c_str()); + + reinterpret_cast(this->m_socket.serverFd)->begin(); + + return SocketIpStatus::SOCK_SUCCESS; +} + +SocketIpStatus TcpServer::reconnect() { + if (this->m_socket.serverFd == nullptr) { + return SocketIpStatus::SOCK_NOT_STARTED; // Socket not initialized + } + + WiFiClient client = reinterpret_cast(this->m_socket.serverFd)->accept(); + if (!client) { + return SocketIpStatus::SOCK_FAILED_TO_CONNECT; // No client connected + } + this->m_socket.fd = new WiFiClient(client); + if (this->isConnected_ready_OutputPort(0)) { + this->ready_out(0); + } + + Fw::Logger::log("Client connected: %s\n", + reinterpret_cast(this->m_socket.fd)->remoteIP().toString().c_str()); + + return SocketIpStatus::SOCK_SUCCESS; +} + +SocketIpStatus TcpServer::send(const U8* data, U32 size) { + if (this->m_socket.serverFd == nullptr) { + return SocketIpStatus::SOCK_NOT_STARTED; // Socket not initialized + } + + if (this->m_socket.fd == nullptr) { + return SocketIpStatus::SOCK_NO_DATA_AVAILABLE; // No client connected + } + + FwSizeType sentBytes = reinterpret_cast(this->m_socket.fd)->write(data, size); + + if (sentBytes != size) { + return SocketIpStatus::SOCK_INTERRUPTED_TRY_AGAIN; // Failed to send data + } + + return SocketIpStatus::SOCK_SUCCESS; +} + +void TcpServer::readLoop() { + if (this->m_socket.serverFd == nullptr) { + return; // Socket not initialized + } + + if (this->m_socket.fd == nullptr) { + if (this->reconnect() != SocketIpStatus::SOCK_SUCCESS) { + return; // Failed to reconnect + } + } + + if (not reinterpret_cast(this->m_socket.fd)->connected()) { + delete reinterpret_cast(this->m_socket.fd); + this->m_socket.fd = nullptr; + Fw::Logger::log("Client disconnected\n"); + return; + } + + Fw::Buffer buffer = this->allocate_out(0, static_cast(this->m_allocation_size)); + U8* data = buffer.getData(); + FW_ASSERT(data); + U32 size = buffer.getSize(); + FwSizeType recvSize = reinterpret_cast(this->m_socket.fd)->read(data, size); + buffer.setSize(recvSize); + + Drv::ByteStreamStatus recvStatus = Drv::ByteStreamStatus::OP_OK; + if (recvSize == 0) { + recvStatus = Drv::ByteStreamStatus::RECV_NO_DATA; + } + + this->recv_out(0, buffer, recvStatus); +} + +} // namespace Arduino diff --git a/Arduino/Drv/TcpServer/docs/sdd.md b/Arduino/Drv/TcpServer/docs/sdd.md new file mode 100644 index 0000000..4007dee --- /dev/null +++ b/Arduino/Drv/TcpServer/docs/sdd.md @@ -0,0 +1,77 @@ +# Arduino::TcpServer + +TCP Server for Arduino + +## Usage Examples + +### Configure comDriver + +```cpp +comDriver.configure("wifi-ssid", "wifi-password", 50000); +``` + +### F Prime GDS + +```sh +fprime-gds -n --dictionary --ip-client --ip-address +``` + +### Diagrams +Add diagrams here + +### Typical Usage +And the typical usage of the component here + +## Class Diagram +Add a class diagram here + +## Port Descriptions +| Name | Description | +|---|---| +|---|---| + +## Component States +Add component states in the chart below +| Name | Description | +|---|---| +|---|---| + +## Sequence Diagrams +Add sequence diagrams here + +## Parameters +| Name | Description | +|---|---| +|---|---| + +## Commands +| Name | Description | +|---|---| +|---|---| + +## Events +| Name | Description | +|---|---| +|---|---| + +## Telemetry +| Name | Description | +|---|---| +|---|---| + +## Unit Tests +Add unit test descriptions in the chart below +| Name | Description | Output | Coverage | +|---|---|---|---| +|---|---|---|---| + +## Requirements +Add requirements in the chart below +| Name | Description | Validation | +|---|---|---| +|---|---|---| + +## Change Log +| Date | Description | +|---|---| +|---| Initial Draft | \ No newline at end of file diff --git a/Arduino/Svc/LifeLed/LifeLed.cpp b/Arduino/Svc/LifeLed/LifeLed.cpp index 5cc00e5..65c08fd 100644 --- a/Arduino/Svc/LifeLed/LifeLed.cpp +++ b/Arduino/Svc/LifeLed/LifeLed.cpp @@ -5,7 +5,6 @@ // ====================================================================== #include "Arduino/Svc/LifeLed/LifeLed.hpp" -#include "FpConfig.hpp" namespace Arduino { @@ -13,19 +12,20 @@ namespace Arduino { // Component construction and destruction // ---------------------------------------------------------------------- -LifeLed ::LifeLed(const char* const compName) : LifeLedComponentBase(compName), m_blink_count(0), m_pin(Arduino::DEF_LED_BUILTIN), m_configured(false) {} +LifeLed ::LifeLed(const char* const compName) + : LifeLedComponentBase(compName), m_blink_count(0), m_pin(Arduino::DEF_LED_BUILTIN), m_configured(false) {} LifeLed ::~LifeLed() {} void LifeLed::configure(PlatformIntType pin) { - FW_ASSERT(pin >= 0); // LED_BUILTIN is likely undefined, please provide an LED or discontinue use of this module + FW_ASSERT(pin >= 0); // LED_BUILTIN is likely undefined, please provide an LED or discontinue use of this module this->m_pin = pin; pinMode(this->m_pin, Arduino::DEF_OUTPUT); digitalWrite(this->m_pin, Arduino::DEF_LOW); this->m_configured = true; } -void LifeLed::set(const Fw::On::T &on_off) { +void LifeLed::set(const Fw::On::T& on_off) { if (this->m_configured) { digitalWrite(this->m_pin, (on_off == Fw::On::ON) ? Arduino::DEF_HIGH : Arduino::DEF_LOW); } @@ -35,15 +35,14 @@ void LifeLed::set(const Fw::On::T &on_off) { // Handler implementations for user-defined typed input ports // ---------------------------------------------------------------------- -void LifeLed ::run_handler(NATIVE_INT_TYPE portNum, NATIVE_UINT_TYPE context) { +void LifeLed ::run_handler(FwIndexType portNum, U32 context) { Fw::ParamValid is_valid; U16 count_period = this->paramGet_LED_PERIOD(is_valid); // Only operate when the parameter is valid if (is_valid != Fw::ParamValid::INVALID) { this->m_blink_count = (this->m_blink_count + 1) % count_period; - this->set((this->m_blink_count < (count_period/2)) ? Fw::On::ON : Fw::On::OFF); + this->set((this->m_blink_count < (count_period / 2)) ? Fw::On::ON : Fw::On::OFF); } } - } // namespace Arduino diff --git a/Arduino/Svc/LifeLed/LifeLed.hpp b/Arduino/Svc/LifeLed/LifeLed.hpp index 842f435..2cfb335 100644 --- a/Arduino/Svc/LifeLed/LifeLed.hpp +++ b/Arduino/Svc/LifeLed/LifeLed.hpp @@ -27,13 +27,12 @@ class LifeLed : public LifeLedComponentBase { ~LifeLed(); //! Set the arduino pin to own - void configure(PlatformIntType pin=Arduino::DEF_LED_BUILTIN); + void configure(PlatformIntType pin = Arduino::DEF_LED_BUILTIN); //! Set the pin state void set(const Fw::On::T& on_off); - - PRIVATE: + private: // ---------------------------------------------------------------------- // Handler implementations for user-defined typed input ports // ---------------------------------------------------------------------- @@ -41,8 +40,8 @@ class LifeLed : public LifeLedComponentBase { //! Handler implementation for run //! //! Rate group port - void run_handler(NATIVE_INT_TYPE portNum, //!< The port number - NATIVE_UINT_TYPE context //!< The call order + void run_handler(FwIndexType portNum, //!< The port number + U32 context //!< The call order ) override; U16 m_blink_count; PlatformIntType m_pin; diff --git a/docs/arduino-cli-install.md b/docs/arduino-cli-install.md index b0a5619..55bdf7a 100644 --- a/docs/arduino-cli-install.md +++ b/docs/arduino-cli-install.md @@ -81,3 +81,34 @@ Add udev rules. Download/save the `.rules` files located [here](https://github.c ## Uploading Deployment to Hardware Upon successful build of an F Prime deployment, it is time to upload it to your board. The steps differ between boards. Refer to the [board list's](./board-list.md) `Upload Guide` column READMEs for guidance. + +### Windows WSL 2 + +> [!NOTE] +> If you are running Windows WSL 2, follow the steps below to mount your board as a USB device within WSL 2. + +List your connected USB devices and find the `BUSID` of your board. +```powershell +# Windows Powershell +usbipd list +``` + +If the `STATE` of that device is not `Shared`, run: +```powershell +# Windows Powershell +usbipd bind --busid +``` + +Attach the device to the WSL2 instance. +```powershell +# Windows Powershell +usbipd attach --wsl --build +``` + +Now your board should be accessible in WSL2 via one of the `/dev/tty` devices. + +You can detatch the device from WSL2 back into your host machine by running: +```powershell +# Windows Powershell +usbipd detach --busid +``` diff --git a/fprime-arduino.cmake b/fprime-arduino.cmake index 040df78..4166902 100644 --- a/fprime-arduino.cmake +++ b/fprime-arduino.cmake @@ -14,6 +14,7 @@ add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/Arduino/Drv/I2cNodeDriver") add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/Arduino/Drv/SpiDriver") add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/Arduino/Drv/PwmDriver") add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/Arduino/Drv/TcpClient") +add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/Arduino/Drv/TcpServer") add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/Arduino/Drv/HardwareRateDriver") add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/Arduino/Drv/AnalogDriver") add_fprime_subdirectory("${CMAKE_CURRENT_LIST_DIR}/Arduino/Svc/LifeLed")