Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
13 changes: 13 additions & 0 deletions Arduino/Drv/I2cDriver/I2cDriver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,4 +35,17 @@ Drv::I2cStatus I2cDriver ::write_handler(const FwIndexType portNum, U32 addr, Fw
return write_data(addr, serBuffer);
}

Drv::I2cStatus I2cDriver ::writeRead_handler(const FwIndexType portNum, U32 addr, Fw::Buffer& writeBuffer, Fw::Buffer& readBuffer) {
// Ensure buffer is not a nullptr
FW_ASSERT(writeBuffer.getData());
FW_ASSERT(readBuffer.getData());

Drv::I2cStatus status = write_data(addr, writeBuffer);
if (status == Drv::I2cStatus::I2C_OK) {
return read_data(addr, readBuffer);
}

return Drv::I2cStatus::I2C_OTHER_ERR;
}

} // end namespace Arduino
2 changes: 2 additions & 0 deletions Arduino/Drv/I2cDriver/I2cDriver.fpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,5 +6,7 @@ module Arduino {

guarded input port read: Drv.I2c

guarded input port writeRead: Drv.I2cWriteRead

}
}
15 changes: 15 additions & 0 deletions Arduino/Drv/I2cDriver/I2cDriver.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -71,6 +71,21 @@ namespace Arduino {
*/
);

//! Handler implementation for writeRead
//!
Drv::I2cStatus writeRead_handler(
const FwIndexType portNum, /*!< The port number*/
U32 addr, /*!<
I2C slave device address
*/
Fw::Buffer &writeBuffer, /*!<
Buffer with data to read/write to/from
*/
Fw::Buffer &readBuffer /*!<
Buffer with data to read/write to/from
*/
);

//! Stores the open wire port, POINTER_CAST so Linux and Ardunio may use different types
void* m_port_pointer;

Expand Down
18 changes: 14 additions & 4 deletions Arduino/Drv/StreamDriver/StreamDriver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,9 @@ 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) {
connection_status = ConnectionStatus::DISCONNECTED;
}

StreamDriver ::~StreamDriver(void) {}

Expand All @@ -26,12 +28,20 @@ void StreamDriver::recvReturnIn_handler(FwIndexType portNum, Fw::Buffer& fwBuffe
this->deallocate_out(0, fwBuffer);
}

Drv::ByteStreamStatus StreamDriver ::send_handler(const FwIndexType portNum, Fw::Buffer& serBuffer) {
(void) write_data(serBuffer);
return Drv::ByteStreamStatus::OP_OK;
Drv::ByteStreamStatus StreamDriver ::send_handler(const FwIndexType portNum, Fw::Buffer& serBuffer) {
Drv::ByteStreamStatus status = write_data(serBuffer);
if (status != Drv::ByteStreamStatus::OP_OK) {
connection_status = ConnectionStatus::DISCONNECTED;
}
return status;
}

void StreamDriver ::schedIn_handler(const FwIndexType portNum, U32 context) {
//If the connection was previously disconnected but is now available, re-configure
if ((connection_status == ConnectionStatus::DISCONNECTED) && Serial) {
connection_status = ConnectionStatus::CONNECTED;
configure(&Serial);
}
if (not reinterpret_cast<Stream*>(m_port_pointer)->available()) {
return;
}
Expand Down
7 changes: 7 additions & 0 deletions Arduino/Drv/StreamDriver/StreamDriver.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -61,10 +61,17 @@ class StreamDriver : public StreamDriverComponentBase {
U32 context /*!< The call order*/
);

enum ConnectionStatus {
DISCONNECTED,
CONNECTED
};

//! Port number to open
FwIndexType m_port_number;
//! Stores the open stream port, POINTER_CAST so Linux and Ardunio may use different types
void* m_port_pointer;
//! Stores the current connection status
ConnectionStatus connection_status;
};

} // end namespace Arduino
Expand Down