From 77bed2556a9946b6bfab69839fd991205636e16a Mon Sep 17 00:00:00 2001 From: Michael D Starch Date: Wed, 15 Jan 2025 16:09:21 -0800 Subject: [PATCH 1/2] Removing DEBUG_PRINT like statements. Part of: #1708 --- Drv/LinuxI2cDriver/LinuxI2cDriver.cpp | 53 ------------------- Drv/LinuxI2cDriver/LinuxI2cDriverStub.cpp | 2 - .../LinuxSpiDriverComponentImpl.cpp | 28 ---------- Drv/LinuxUartDriver/LinuxUartDriver.cpp | 26 --------- Fw/Comp/ActiveComponentBase.cpp | 6 --- Svc/UdpReceiver/UdpReceiverComponentImpl.cpp | 4 -- Svc/UdpSender/UdpSenderComponentImpl.cpp | 5 -- Utils/Types/CircularBuffer.cpp | 15 ------ Utils/Types/CircularBuffer.hpp | 2 - 9 files changed, 141 deletions(-) diff --git a/Drv/LinuxI2cDriver/LinuxI2cDriver.cpp b/Drv/LinuxI2cDriver/LinuxI2cDriver.cpp index 8618515164..bd7ba1aa85 100644 --- a/Drv/LinuxI2cDriver/LinuxI2cDriver.cpp +++ b/Drv/LinuxI2cDriver/LinuxI2cDriver.cpp @@ -22,7 +22,6 @@ #include // required for constant definitions #include -#define DEBUG_PRINT 0 namespace Drv { @@ -72,20 +71,9 @@ namespace Drv { return I2cStatus::I2C_OPEN_ERR; } -#if DEBUG_PRINT - Fw::Logger::log("I2c addr: 0x%02X\n",addr); - for (U32 byte = 0; byte < serBuffer.getSize(); byte++) { - Fw::Logger::log("0x%02X ",serBuffer.getData()[byte]); - - } - Fw::Logger::log("\n"); -#endif // select slave address int stat = ioctl(this->m_fd, I2C_SLAVE, addr); if (stat == -1) { -#if DEBUG_PRINT - Fw::Logger::log("Status: %d Errno: %d\n", stat, errno); -#endif return I2cStatus::I2C_ADDRESS_ERR; } // make sure it isn't a null pointer @@ -93,9 +81,6 @@ namespace Drv { // write data stat = static_cast(write(this->m_fd, serBuffer.getData(), serBuffer.getSize())); if (stat == -1) { -#if DEBUG_PRINT - Fw::Logger::log("Status: %d Errno: %d\n", stat, errno); -#endif return I2cStatus::I2C_WRITE_ERR; } return I2cStatus::I2C_OK; @@ -113,15 +98,9 @@ namespace Drv { return I2cStatus::I2C_OPEN_ERR; } -#if DEBUG_PRINT - Fw::Logger::log("I2c addr: 0x%02X\n",addr); -#endif // select slave address int stat = ioctl(this->m_fd, I2C_SLAVE, addr); if (stat == -1) { -#if DEBUG_PRINT - Fw::Logger::log("Status: %d Errno: %d\n", stat, errno); -#endif return I2cStatus::I2C_ADDRESS_ERR; } // make sure it isn't a null pointer @@ -129,18 +108,8 @@ namespace Drv { // read data stat = static_cast(read(this->m_fd, serBuffer.getData(), serBuffer.getSize())); if (stat == -1) { -#if DEBUG_PRINT - Fw::Logger::log("Status: %d Errno: %d\n", stat, errno); -#endif return I2cStatus::I2C_READ_ERR; } -#if DEBUG_PRINT - for (U32 byte = 0; byte < serBuffer.getSize(); byte++) { - Fw::Logger::log("0x%02X ",serBuffer.getData()[byte]); - - } - Fw::Logger::log("\n"); -#endif return I2cStatus::I2C_OK; } @@ -162,10 +131,6 @@ namespace Drv { FW_ASSERT(writeBuffer.getData()); FW_ASSERT(readBuffer.getData()); - #if DEBUG_PRINT - Fw::Logger::log("I2c addr: 0x%02X\n",addr); - #endif - struct i2c_msg rdwr_msgs[2]; // Start address @@ -188,28 +153,10 @@ namespace Drv { NATIVE_INT_TYPE stat = ioctl(this->m_fd, I2C_RDWR, &rdwr_data); if(stat == -1){ - #if DEBUG_PRINT - Fw::Logger::log("Status: %d Errno: %d\n", stat, errno); - #endif //Because we're using ioctl to perform the transaction we dont know exactly the type of error that occurred return I2cStatus::I2C_OTHER_ERR; } -#if DEBUG_PRINT - Fw::Logger::log("Wrote:\n"); - for (U32 byte = 0; byte < writeBuffer.getSize(); byte++) { - Fw::Logger::log("0x%02X ",writeBuffer.getData()[byte]); - - } - Fw::Logger::log("\n"); - Fw::Logger::log("Read:\n"); - for (U32 byte = 0; byte < readBuffer.getSize(); byte++) { - Fw::Logger::log("0x%02X ",readBuffer.getData()[byte]); - - } - Fw::Logger::log("\n"); -#endif - return I2cStatus::I2C_OK; } diff --git a/Drv/LinuxI2cDriver/LinuxI2cDriverStub.cpp b/Drv/LinuxI2cDriver/LinuxI2cDriverStub.cpp index da3b0f673a..b4bc05b3e3 100644 --- a/Drv/LinuxI2cDriver/LinuxI2cDriverStub.cpp +++ b/Drv/LinuxI2cDriver/LinuxI2cDriverStub.cpp @@ -14,8 +14,6 @@ #include #include -#define DEBUG_PRINT 0 - namespace Drv { // ---------------------------------------------------------------------- diff --git a/Drv/LinuxSpiDriver/LinuxSpiDriverComponentImpl.cpp b/Drv/LinuxSpiDriver/LinuxSpiDriverComponentImpl.cpp index 78afd2c624..be5889bf5c 100644 --- a/Drv/LinuxSpiDriver/LinuxSpiDriverComponentImpl.cpp +++ b/Drv/LinuxSpiDriver/LinuxSpiDriverComponentImpl.cpp @@ -24,9 +24,6 @@ #include #include -//#define DEBUG_PRINT(...) printf(##__VA_ARGS__); fflush(stdout) -#define DEBUG_PRINT(...) - namespace Drv { // ---------------------------------------------------------------------- @@ -41,8 +38,6 @@ namespace Drv { return; } - DEBUG_PRINT("Writing %d bytes to SPI\n",writeBuffer.getSize()); - spi_ioc_transfer tr; // Zero for unused fields: memset(&tr, 0, sizeof(tr)); @@ -83,15 +78,11 @@ namespace Drv { snprintf(devName,sizeof(devName),"/dev/spidev%d.%d",device,select); // null terminate devName[sizeof(devName)-1] = 0; - DEBUG_PRINT("Opening SPI device %s\n",devName); fd = ::open(devName, O_RDWR); if (fd == -1) { - DEBUG_PRINT("open SPI device %d.%d failed. %d\n",device,select,errno); this->log_WARNING_HI_SPI_OpenError(device,select,fd); return false; - } else { - DEBUG_PRINT("Successfully opened SPI device %s fd %d\n",devName,fd); } this->m_fd = fd; @@ -123,20 +114,14 @@ namespace Drv { ret = ioctl(fd, SPI_IOC_WR_MODE, &mode); if (ret == -1) { - DEBUG_PRINT("ioctl SPI_IOC_WR_MODE fd %d failed. %d\n",fd,errno); this->log_WARNING_HI_SPI_ConfigError(device,select,ret); return false; - } else { - DEBUG_PRINT("SPI fd %d WR mode successfully configured to %d\n",fd,mode); } ret = ioctl(fd, SPI_IOC_RD_MODE, &mode); if (ret == -1) { - DEBUG_PRINT("ioctl SPI_IOC_RD_MODE fd %d failed. %d\n",fd,errno); this->log_WARNING_HI_SPI_ConfigError(device,select,ret); return false; - } else { - DEBUG_PRINT("SPI fd %d RD mode successfully configured to %d\n",fd,mode); } /* @@ -145,20 +130,14 @@ namespace Drv { U8 bits = 8; ret = ioctl(fd, SPI_IOC_WR_BITS_PER_WORD, &bits); if (ret == -1) { - DEBUG_PRINT("ioctl SPI_IOC_WR_BITS_PER_WORD fd %d failed. %d\n",fd,errno); this->log_WARNING_HI_SPI_ConfigError(device,select,ret); return false; - } else { - DEBUG_PRINT("SPI fd %d WR bits per word successfully configured to %d\n",fd,bits); } ret = ioctl(fd, SPI_IOC_RD_BITS_PER_WORD, &bits); if (ret == -1) { - DEBUG_PRINT("ioctl SPI_IOC_RD_BITS_PER_WORD fd %d failed. %d\n",fd,errno); this->log_WARNING_HI_SPI_ConfigError(device,select,ret); return false; - } else { - DEBUG_PRINT("SPI fd %d RD bits per word successfully configured to %d\n",fd,bits); } /* @@ -166,20 +145,14 @@ namespace Drv { */ ret = ioctl(fd, SPI_IOC_WR_MAX_SPEED_HZ, &clock); if (ret == -1) { - DEBUG_PRINT("ioctl SPI_IOC_WR_MAX_SPEED_HZ fd %d failed. %d\n",fd,errno); this->log_WARNING_HI_SPI_ConfigError(device,select,ret); return false; - } else { - DEBUG_PRINT("SPI fd %d WR freq successfully configured to %d\n",fd,clock); } ret = ioctl(fd, SPI_IOC_RD_MAX_SPEED_HZ, &clock); if (ret == -1) { - DEBUG_PRINT("ioctl SPI_IOC_RD_MAX_SPEED_HZ fd %d failed. %d\n",fd,errno); this->log_WARNING_HI_SPI_ConfigError(device,select,ret); return false; - } else { - DEBUG_PRINT("SPI fd %d RD freq successfully configured to %d\n",fd,clock); } return true; @@ -187,7 +160,6 @@ namespace Drv { } LinuxSpiDriverComponentImpl::~LinuxSpiDriverComponentImpl() { - DEBUG_PRINT("Closing SPI device %d\n",this->m_fd); (void) close(this->m_fd); } diff --git a/Drv/LinuxUartDriver/LinuxUartDriver.cpp b/Drv/LinuxUartDriver/LinuxUartDriver.cpp index ae8a06aad4..7c07d97066 100644 --- a/Drv/LinuxUartDriver/LinuxUartDriver.cpp +++ b/Drv/LinuxUartDriver/LinuxUartDriver.cpp @@ -20,10 +20,6 @@ #include #include -//#include -//#include -//#define DEBUG_PRINT(...) printf(##__VA_ARGS__); fflush(stdout) -#define DEBUG_PRINT(...) namespace Drv { @@ -47,7 +43,6 @@ bool LinuxUartDriver::open(const char* const device, this->m_device = device; - DEBUG_PRINT("Opening UART device %s\n", device); /* The O_NOCTTY flag tells UNIX that this program doesn't want to be the "controlling terminal" for that port. If you @@ -58,13 +53,10 @@ bool LinuxUartDriver::open(const char* const device, fd = ::open(device, O_RDWR | O_NOCTTY); if (fd == -1) { - DEBUG_PRINT("open UART device %s failed.\n", device); Fw::LogStringArg _arg = device; Fw::LogStringArg _err = strerror(errno); this->log_WARNING_HI_OpenError(_arg, this->m_fd, _err); return false; - } else { - DEBUG_PRINT("Successfully opened UART device %s fd %d\n", device, fd); } this->m_fd = fd; @@ -74,14 +66,11 @@ bool LinuxUartDriver::open(const char* const device, stat = tcgetattr(fd, &cfg); if (-1 == stat) { - DEBUG_PRINT("tcgetattr failed: (%d): %s\n", stat, strerror(errno)); close(fd); Fw::LogStringArg _arg = device; Fw::LogStringArg _err = strerror(errno); this->log_WARNING_HI_OpenError(_arg, fd, _err); return false; - } else { - DEBUG_PRINT("tcgetattr passed.\n"); } /* @@ -104,14 +93,11 @@ bool LinuxUartDriver::open(const char* const device, stat = tcsetattr(fd, TCSANOW, &cfg); if (-1 == stat) { - DEBUG_PRINT("tcsetattr failed: (%d): %s\n", stat, strerror(errno)); close(fd); Fw::LogStringArg _arg = device; Fw::LogStringArg _err = strerror(errno); this->log_WARNING_HI_OpenError(_arg, fd, _err); return false; - } else { - DEBUG_PRINT("tcsetattr passed.\n"); } // Set flow control @@ -120,7 +106,6 @@ bool LinuxUartDriver::open(const char* const device, stat = tcgetattr(fd, &t); if (-1 == stat) { - DEBUG_PRINT("tcgetattr UART fd %d failed\n", fd); close(fd); Fw::LogStringArg _arg = device; Fw::LogStringArg _err = strerror(errno); @@ -133,7 +118,6 @@ bool LinuxUartDriver::open(const char* const device, stat = tcsetattr(fd, TCSANOW, &t); if (-1 == stat) { - DEBUG_PRINT("tcsetattr UART fd %d failed\n", fd); close(fd); Fw::LogStringArg _arg = device; Fw::LogStringArg _err = strerror(errno); @@ -211,7 +195,6 @@ bool LinuxUartDriver::open(const char* const device, stat = tcgetattr(fd, &newtio); if (-1 == stat) { - DEBUG_PRINT("tcgetattr UART fd %d failed\n", fd); close(fd); Fw::LogStringArg _arg = device; Fw::LogStringArg _err = strerror(errno); @@ -254,7 +237,6 @@ bool LinuxUartDriver::open(const char* const device, // Set baud rate: stat = cfsetispeed(&newtio, static_cast(relayRate)); if (stat) { - DEBUG_PRINT("cfsetispeed failed\n"); close(fd); Fw::LogStringArg _arg = device; Fw::LogStringArg _err = strerror(errno); @@ -263,7 +245,6 @@ bool LinuxUartDriver::open(const char* const device, } stat = cfsetospeed(&newtio, static_cast(relayRate)); if (stat) { - DEBUG_PRINT("cfsetospeed failed\n"); close(fd); Fw::LogStringArg _arg = device; Fw::LogStringArg _err = strerror(errno); @@ -285,7 +266,6 @@ bool LinuxUartDriver::open(const char* const device, // Set attributes: stat = tcsetattr(fd, TCSANOW, &newtio); if (-1 == stat) { - DEBUG_PRINT("tcsetattr UART fd %d failed\n", fd); close(fd); Fw::LogStringArg _arg = device; Fw::LogStringArg _err = strerror(errno); @@ -304,8 +284,6 @@ bool LinuxUartDriver::open(const char* const device, LinuxUartDriver ::~LinuxUartDriver() { if (this->m_fd != -1) { - DEBUG_PRINT("Closing UART device %d\n", this->m_fd); - (void)close(this->m_fd); } } @@ -355,10 +333,6 @@ void LinuxUartDriver ::serialReadTaskEntry(void* ptr) { continue; } - // timespec stime; - // (void)clock_gettime(CLOCK_REALTIME,&stime); - // DEBUG_PRINT("<<< Calling dsp_relay_uart_relay_read() at %d %d\n", stime.tv_sec, stime.tv_nsec); - int stat = 0; // Read until something is received or an error occurs. Only loop when diff --git a/Fw/Comp/ActiveComponentBase.cpp b/Fw/Comp/ActiveComponentBase.cpp index 879cd75342..246b802087 100644 --- a/Fw/Comp/ActiveComponentBase.cpp +++ b/Fw/Comp/ActiveComponentBase.cpp @@ -4,9 +4,6 @@ #include #include -//#define DEBUG_PRINT(...) printf(##__VA_ARGS__); fflush(stdout) -#define DEBUG_PRINT(...) - namespace Fw { class ActiveComponentExitSerializableBuffer : public Fw::SerializeBufferBase { @@ -35,7 +32,6 @@ namespace Fw { } ActiveComponentBase::~ActiveComponentBase() { - DEBUG_PRINT("ActiveComponent %s destructor.\n",this->getObjName()); } void ActiveComponentBase::init(NATIVE_INT_TYPE instance) { @@ -76,11 +72,9 @@ namespace Fw { SerializeStatus stat = exitBuff.serialize(static_cast(ACTIVE_COMPONENT_EXIT)); FW_ASSERT(FW_SERIALIZE_OK == stat,static_cast(stat)); (void)this->m_queue.send(exitBuff,0,Os::Queue::BlockingType::NONBLOCKING); - DEBUG_PRINT("exit %s\n", this->getObjName()); } Os::Task::Status ActiveComponentBase::join() { - DEBUG_PRINT("join %s\n", this->getObjName()); return this->m_task.join(); } diff --git a/Svc/UdpReceiver/UdpReceiverComponentImpl.cpp b/Svc/UdpReceiver/UdpReceiverComponentImpl.cpp index 0a94b2cd1e..465afb195f 100644 --- a/Svc/UdpReceiver/UdpReceiverComponentImpl.cpp +++ b/Svc/UdpReceiver/UdpReceiverComponentImpl.cpp @@ -22,9 +22,6 @@ #include #include -//#define DEBUG_PRINT(...) printf(##__VA_ARGS__) -#define DEBUG_PRINT(...) - namespace Svc { // ---------------------------------------------------------------------- @@ -193,7 +190,6 @@ namespace Svc { } // call output port - DEBUG_PRINT("Calling port %d with %d bytes.\n",portNum,this->m_portBuff.getBuffLength()); if (this->isConnected_PortsOut_OutputPort(portNum)) { Fw::SerializeStatus stat = this->PortsOut_out(portNum,this->m_portBuff); diff --git a/Svc/UdpSender/UdpSenderComponentImpl.cpp b/Svc/UdpSender/UdpSenderComponentImpl.cpp index ad5e76b16d..d19007b527 100644 --- a/Svc/UdpSender/UdpSenderComponentImpl.cpp +++ b/Svc/UdpSender/UdpSenderComponentImpl.cpp @@ -19,9 +19,6 @@ #include #include -//#define DEBUG_PRINT(...) printf(##__VA_ARGS__) -#define DEBUG_PRINT(...) - namespace Svc { // ---------------------------------------------------------------------- @@ -105,7 +102,6 @@ namespace Svc { return; } - DEBUG_PRINT("PortsIn_handler: %d\n",portNum); Fw::SerializeStatus stat; m_sendBuff.resetSer(); @@ -119,7 +115,6 @@ namespace Svc { stat = m_sendBuff.serialize(Buffer); FW_ASSERT(Fw::FW_SERIALIZE_OK == stat,stat); // send on UDP socket - DEBUG_PRINT("Sending %d bytes\n",m_sendBuff.getBuffLength()); ssize_t sendStat = sendto(this->m_fd, m_sendBuff.getBuffAddr(), m_sendBuff.getBuffLength(), diff --git a/Utils/Types/CircularBuffer.cpp b/Utils/Types/CircularBuffer.cpp index cbb64d230d..7f1ce79dc9 100644 --- a/Utils/Types/CircularBuffer.cpp +++ b/Utils/Types/CircularBuffer.cpp @@ -16,10 +16,6 @@ #include #include -#ifdef CIRCULAR_DEBUG - #include -#endif - namespace Types { CircularBuffer :: CircularBuffer() : @@ -166,15 +162,4 @@ void CircularBuffer ::clear_high_water_mark() { m_high_water_mark = 0; } -#ifdef CIRCULAR_DEBUG -void CircularBuffer :: print() { - NATIVE_UINT_TYPE idx = m_head_idx; - Fw::Logger::log("Ring: "); - for (NATIVE_UINT_TYPE i = 0; i < m_allocated_size; ++i) { - Fw::Logger::log("%02x ", m_store[idx]); - idx = advance_idx(idx); - } - Fw::Logger::log("\n"); -} -#endif } //End Namespace Types diff --git a/Utils/Types/CircularBuffer.hpp b/Utils/Types/CircularBuffer.hpp index b885dc168c..0b73dd0db8 100644 --- a/Utils/Types/CircularBuffer.hpp +++ b/Utils/Types/CircularBuffer.hpp @@ -20,8 +20,6 @@ #include #include -//#define CIRCULAR_DEBUG - namespace Types { class CircularBuffer { From 0cb10cf07b5f0d190bb2a8f651f8cf9fe7730d02 Mon Sep 17 00:00:00 2001 From: M Starch Date: Thu, 23 Jan 2025 12:18:58 -0800 Subject: [PATCH 2/2] Review update: CIRCULAR_DEBUG --- Utils/Types/CircularBuffer.hpp | 3 --- 1 file changed, 3 deletions(-) diff --git a/Utils/Types/CircularBuffer.hpp b/Utils/Types/CircularBuffer.hpp index 0b73dd0db8..fbd0e3f7d4 100644 --- a/Utils/Types/CircularBuffer.hpp +++ b/Utils/Types/CircularBuffer.hpp @@ -132,9 +132,6 @@ class CircularBuffer { */ void clear_high_water_mark(); -#ifdef CIRCULAR_DEBUG - void print(); -#endif PRIVATE: /** * Returns a wrap-advanced index into the store.