From dfad85a87c67544cc0ea6c5152da25e595b6eae4 Mon Sep 17 00:00:00 2001 From: DiegoLHendrix <119289719+DiegoLHendrix@users.noreply.github.com> Date: Thu, 31 Oct 2024 20:49:12 -0400 Subject: [PATCH 01/17] SDO Sample --- samples/canopen/CMakeLists.txt | 1 + samples/canopen/canopen_rpdo/main.cpp | 11 +- samples/canopen/canopen_sdo/CMakeLists.txt | 4 + samples/canopen/canopen_sdo/SDOCanNode.cpp | 90 +++++++++++++ samples/canopen/canopen_sdo/SDOCanNode.hpp | 140 +++++++++++++++++++++ samples/canopen/canopen_sdo/main.cpp | 98 +++++++++++++++ samples/canopen/canopen_tpdo/main.cpp | 17 +-- 7 files changed, 350 insertions(+), 11 deletions(-) create mode 100644 samples/canopen/canopen_sdo/CMakeLists.txt create mode 100644 samples/canopen/canopen_sdo/SDOCanNode.cpp create mode 100644 samples/canopen/canopen_sdo/SDOCanNode.hpp create mode 100644 samples/canopen/canopen_sdo/main.cpp diff --git a/samples/canopen/CMakeLists.txt b/samples/canopen/CMakeLists.txt index 83f08ce6..c5cfae44 100644 --- a/samples/canopen/CMakeLists.txt +++ b/samples/canopen/CMakeLists.txt @@ -1,3 +1,4 @@ add_subdirectory(canopen_rpdo) add_subdirectory(canopen_sample) +add_subdirectory(canopen_sdo) add_subdirectory(canopen_tpdo) diff --git a/samples/canopen/canopen_rpdo/main.cpp b/samples/canopen/canopen_rpdo/main.cpp index fef46b7a..f2f08228 100644 --- a/samples/canopen/canopen_rpdo/main.cpp +++ b/samples/canopen/canopen_rpdo/main.cpp @@ -11,6 +11,7 @@ #include #include #include +#include #include @@ -19,6 +20,7 @@ namespace io = core::io; namespace dev = core::dev; namespace time = core::time; +namespace log = core::log; /////////////////////////////////////////////////////////////////////////////// // EVT-core CAN callback and CAN setup. This will include logic to set @@ -36,20 +38,19 @@ namespace time = core::time; * @param message[in] The passed in CAN message that was read. */ -io::UART& uart = io::getUART(9600); // create a can interrupt handler void canInterrupt(io::CANMessage& message, void* priv) { auto* queue = (core::types::FixedQueue*) priv; // print out raw received data - uart.printf("Got RAW message from %X of length %d with data: ", message.getId(), message.getDataLength()); + log::LOGGER.log(log::Logger::LogLevel::INFO, "Got RAW message from %X of length %d with data: ", message.getId(), message.getDataLength()); uint8_t* data = message.getPayload(); for (int i = 0; i < message.getDataLength(); i++) { - uart.printf("%X ", *data); + log::LOGGER.log(log::Logger::LogLevel::INFO, "%X ", *data); data++; } - uart.printf("\r\n"); + log::LOGGER.log(log::Logger::LogLevel::INFO, "\r\n"); if (queue != nullptr) queue->append(message); @@ -59,6 +60,8 @@ int main() { // Initialize system core::platform::init(); + io::UART& uart = io::getUART(9600); + // Initialize the timer dev::Timer& timer = dev::getTimer(100); diff --git a/samples/canopen/canopen_sdo/CMakeLists.txt b/samples/canopen/canopen_sdo/CMakeLists.txt new file mode 100644 index 00000000..a702b201 --- /dev/null +++ b/samples/canopen/canopen_sdo/CMakeLists.txt @@ -0,0 +1,4 @@ +include(../../../cmake/evt-core_build.cmake) + +set( SAMPLE_SOURCES main.cpp SDOCanNode.cpp) +make_exe(canopen_sdo "${SAMPLE_SOURCES}") \ No newline at end of file diff --git a/samples/canopen/canopen_sdo/SDOCanNode.cpp b/samples/canopen/canopen_sdo/SDOCanNode.cpp new file mode 100644 index 00000000..c7a8237d --- /dev/null +++ b/samples/canopen/canopen_sdo/SDOCanNode.cpp @@ -0,0 +1,90 @@ +#include "SDOCanNode.hpp" + +SDOCanNode::SDOCanNode() { + sampleDataA = 0; + sampleDataB = 0; +} + +void SDOCanNode::SDOTransfer(CO_NODE node) { + + CO_CSDO *csdo = COCSdoFind(&(node), 0); + CO_ERR err = COCSdoRequestDownload(csdo, CO_DEV(0x00,0x01), + &sampleDataA, 8, + AppCSdoFinishCb, 1000); + + if (err == CO_ERR_NONE) { + + /* Transfer is started successfully */ + log::LOGGER.log(log::Logger::LogLevel::INFO, "Value transferred: %lu", sampleDataA); + + /* Note: don't use the 'readValue' until transfer is finished! */ + + } else { + /* Unable to start the SDO transfer */ + log::LOGGER.log(log::Logger::LogLevel::INFO, "Download Error"); + + } +} + +void SDOCanNode::SDOReceive(CO_NODE node) { + CO_CSDO *csdo; + CO_ERR err; + + csdo = COCSdoFind(&(node), 0); + err = COCSdoRequestUpload(csdo, CO_DEV(0x00,0x02), + &sampleDataB, 8, + AppCSdoFinishCb, 1000); + + if (err == CO_ERR_NONE) { + + /* Transfer is started successfully */ + log::LOGGER.log(log::Logger::LogLevel::INFO, "Value : %lu", sampleDataB); + + /* Note: don't use the 'readValue' until transfer is finished! */ + + } else { + /* Unable to start the SDO transfer */ + log::LOGGER.log(log::Logger::LogLevel::INFO, "Upload Error"); + + } +} + +uint8_t SDOCanNode::getSampleDataA() { + return sampleDataA; +} + +uint16_t SDOCanNode::getSampleDataB() { + return sampleDataB; +} + +void SDOCanNode::update() { + sampleDataA++; + if (sampleDataA % 20 == 0) { + sampleDataB *= 3; + } +} + +CO_OBJ_T* SDOCanNode::getObjectDictionary() { + return &objectDictionary[0]; +} + +uint8_t SDOCanNode::getNumElements() { + return OBJECT_DICTIONARY_SIZE; +} + +uint8_t SDOCanNode::getNodeID() { + return NODE_ID; +} + +/* The application specific SDO transfer finalization callback */ +void AppCSdoFinishCb(CO_CSDO *csdo, uint16_t index, uint8_t sub, uint32_t code) +{ + if (code == 0) { + /* read data is available in 'readValue' */ + + } + else { + /* a timeout or abort is detected during SDO transfer */ + } + +} \ No newline at end of file diff --git a/samples/canopen/canopen_sdo/SDOCanNode.hpp b/samples/canopen/canopen_sdo/SDOCanNode.hpp new file mode 100644 index 00000000..57d35ca4 --- /dev/null +++ b/samples/canopen/canopen_sdo/SDOCanNode.hpp @@ -0,0 +1,140 @@ +#include +#include + +#include +#include +#include +#include + +/** + * Representation of the CAN node. Handles constructing the object + * dictionary and other baseline settings. The idea is that each "board" + * will have a specific object dictionary associated with it. The object + * dictionary itself will also need to have information on "data of interest". + * For example, a temperature management system may to expose water pump + * flow rate in the object dictionary. + */ + +namespace log = core::log; + +class SDOCanNode : public CANDevice { +public: + SDOCanNode(); + + /** + * Update Object Dictionary entry + * + * @param newValue[in] The value to set sample data to + */ + void SDOTransfer(CO_NODE node); + + /** + * Read Object Dictionary entry + * + * @param newValue[in] The value to set sample data to + */ + void SDOReceive(CO_NODE node); + + /** + * Get the contained sample data + * + * @return The value of the sample data + */ + uint8_t getSampleDataA(); + uint16_t getSampleDataB(); + + /** + * increments counters up + */ + void update(); + + /** + * Get a pointer to the start of the object dictionary + * + * @return Pointer to the start of the object dictionary + */ + CO_OBJ_T* getObjectDictionary() override; + + /** + * Get the number of elements in the object dictionary. + * + * @return The number of elements in the object dictionary + */ + uint8_t getNumElements() override; + + /** + * Get the device's node ID + * + * @return The node ID of the can device. + */ + uint8_t getNodeID() override; + + /** + * Get the device's node ID + * + * @return The node ID of the can device. + */ + static constexpr uint8_t NODE_ID = 2; + +private: + /** + * This sample data will be exposed over CAN through the object + * dictionary. The address of the variable will be included in the + * object dictionary and can be updated via SDO via a CANopen client. + * This device will then broadcast the value via a triggered PDO. + */ + uint8_t sampleDataA; + uint8_t sampleDataB; + + /** + * Have to know the size of the object dictionary for initialization + * process. + */ + static constexpr uint8_t OBJECT_DICTIONARY_SIZE = 24; + + /** + * The object dictionary itself. Will be populated by this object during + * construction. + * + * The plus one is for the special "end of dictionary" marker. + */ + CO_OBJ_T objectDictionary[OBJECT_DICTIONARY_SIZE + 1] = { + MANDATORY_IDENTIFICATION_ENTRIES_1000_1014, + HEARTBEAT_PRODUCER_1017(2000), + IDENTITY_OBJECT_1018, + SDO_CONFIGURATION_1200, + + { + /* Communication Object SDO Server */ + .Key = CO_KEY(0x1280, 0x00, CO_OBJ_D___R_), + .Type = CO_TUNSIGNED32, + .Data = (CO_DATA) 0x03, + }, + { + /* SDO Server Request COBID */ + .Key = CO_KEY(0x1280, 0x01, CO_OBJ_D___R_), + .Type = CO_TUNSIGNED32, + .Data = (CO_DATA) CO_COBID_SDO_REQUEST(), + }, + { /* SDO Server Response COBID */ + .Key = CO_KEY(0x1280, 0x02, CO_OBJ_D___R_), + .Type = CO_TUNSIGNED32, + .Data = (CO_DATA) CO_COBID_SDO_RESPONSE(), + }, + { + .Key = CO_KEY(0x1280, 0x03, CO_OBJ_D___R_), + .Type = CO_TUNSIGNED8, + .Data = (CO_DATA) 1, + }, + + // User defined data, this will be where we put elements that can be + // accessed via SDO and depending on configuration PDO + DATA_LINK_START_KEY_21XX(0, 0x02), + DATA_LINK_21XX(0x00, 0x01, CO_TUNSIGNED8, &sampleDataA), + DATA_LINK_21XX(0x00, 0x02, CO_TUNSIGNED8, &sampleDataB), + + // End of dictionary marker + CO_OBJ_DICT_ENDMARK, + }; +}; +void AppCSdoFinishCb(CO_CSDO *csdo, uint16_t index, uint8_t sub, uint32_t code); \ No newline at end of file diff --git a/samples/canopen/canopen_sdo/main.cpp b/samples/canopen/canopen_sdo/main.cpp new file mode 100644 index 00000000..2750ac40 --- /dev/null +++ b/samples/canopen/canopen_sdo/main.cpp @@ -0,0 +1,98 @@ +/** +* This sample shows off CANopen support from EVT-core. This will +* setup a CANopen node and attempt to make back and forth communication. +*/ + +#include +#include +#include +#include +#include +#include + +#include + +#include "SDOCanNode.hpp" + + +namespace io = core::io; +namespace dev = core::dev; +namespace time = core::time; + + +int main() { + // Initialize system + core::platform::init(); + + io::UART& uart = io::getUART(9600); + log::LOGGER.setUART(&uart); + log::LOGGER.setLogLevel(log::Logger::LogLevel::INFO); + + // create the SDO node + SDOCanNode testCanNode; + + dev::Timer& timer = dev::getTimer(100); + + /////////////////////////////////////////////////////////////////////////// + // Setup CAN configuration, this handles making drivers, applying settings. + // And generally creating the CANopen stack node which is the interface + // between the application (the code we write) and the physical CAN network + /////////////////////////////////////////////////////////////////////////// + + // Will store CANopen messages that will be populated by the EVT-core CAN + // interrupt + core::types::FixedQueue canOpenQueue; + + // Initialize CAN, add an IRQ which will add messages to the queue above + io::CAN& can = io::getCAN(); + + // Reserved memory for CANopen stack usage + uint8_t sdoBuffer[CO_SSDO_N * CO_SDO_BUF_BYTE]; + CO_TMR_MEM appTmrMem[16]; + + // Reserve driver variables + CO_IF_DRV canStackDriver; + + CO_IF_CAN_DRV canDriver; + CO_IF_TIMER_DRV timerDriver; + CO_IF_NVM_DRV nvmDriver; + + CO_NODE canNode; + + // Attempt to join the CAN network + io::CAN::CANStatus result = can.connect(); + + // test that the board is connected to the can network + if (result != io::CAN::CANStatus::OK) { + uart.printf("Failed to connect to CAN network\r\n"); + return 1; + } + + // Initialize all the CANOpen drivers. + io::initializeCANopenDriver(&canOpenQueue, &can, &timer, &canStackDriver, &nvmDriver, &timerDriver, &canDriver); + + // Initialize the CANOpen node we are using. + io::initializeCANopenNode(&canNode, &testCanNode, &canStackDriver, sdoBuffer, appTmrMem); + + // Set the node to operational mode + CONmtSetMode(&canNode.Nmt, CO_OPERATIONAL); + + time::wait(500); + + // print any CANopen errors + uart.printf("Error: %d\r\n", CONodeGetErr(&canNode)); + + /////////////////////////////////////////////////////////////////////////// + // Main loop + /////////////////////////////////////////////////////////////////////////// + + while (1) { + testCanNode.SDOTransfer(canNode); + +// testCanNode.SDOReceive(canNode); + + io::processCANopenNode(&canNode); + // Wait for new data to come in + time::wait(500); + } +} \ No newline at end of file diff --git a/samples/canopen/canopen_tpdo/main.cpp b/samples/canopen/canopen_tpdo/main.cpp index 1806f25b..9b112cfd 100644 --- a/samples/canopen/canopen_tpdo/main.cpp +++ b/samples/canopen/canopen_tpdo/main.cpp @@ -9,6 +9,7 @@ #include #include #include +#include #include @@ -17,6 +18,7 @@ namespace io = core::io; namespace dev = core::dev; namespace time = core::time; +namespace log = core::log; /////////////////////////////////////////////////////////////////////////////// // EVT-core CAN callback and CAN setup. This will include logic to set @@ -34,20 +36,19 @@ namespace time = core::time; * @param message[in] The passed in CAN message that was read. */ -io::UART& uart = io::getUART(9600); // create a can interrupt handler void canInterrupt(io::CANMessage& message, void* priv) { auto* queue = (core::types::FixedQueue*) priv; // print out raw received data - uart.printf("Got RAW message from %X of length %d with data: ", message.getId(), message.getDataLength()); + log::LOGGER.log(log::Logger::LogLevel::INFO, "Got RAW message from %X of length %d with data: ", message.getId(), message.getDataLength()); uint8_t* data = message.getPayload(); for (int i = 0; i < message.getDataLength(); i++) { - uart.printf("%X ", *data); + log::LOGGER.log(log::Logger::LogLevel::INFO, "%X ", *data); data++; } - uart.printf("\r\n"); + log::LOGGER.log(log::Logger::LogLevel::INFO, "\r\n"); if (queue != nullptr) queue->append(message); @@ -55,19 +56,21 @@ void canInterrupt(io::CANMessage& message, void* priv) { // setup a TPDO event handler to print the raw TPDO message when sending extern "C" void COPdoTransmit(CO_IF_FRM* frm) { - uart.printf("Sending PDO as 0x%X with length %d and data: ", frm->Identifier, frm->DLC); + log::LOGGER.log(log::Logger::LogLevel::INFO, "Sending PDO as 0x%X with length %d and data: ", frm->Identifier, frm->DLC); uint8_t* data = frm->Data; for (int i = 0; i < frm->DLC; i++) { - uart.printf("%X ", *data); + log::LOGGER.log(log::Logger::LogLevel::INFO, "%X ", *data); data++; } - uart.printf("\r\n"); + log::LOGGER.log(log::Logger::LogLevel::INFO, "\r\n"); } int main() { // Initialize system core::platform::init(); + io::UART& uart = io::getUART(9600); + // create the TPDO node TPDOCanNode testCanNode; From 35424c881294d7e17a7258da4c4d34af98d04a7a Mon Sep 17 00:00:00 2001 From: DiegoLHendrix <119289719+DiegoLHendrix@users.noreply.github.com> Date: Mon, 4 Nov 2024 21:27:11 -0500 Subject: [PATCH 02/17] This SDO no worky --- samples/canopen/canopen_sdo/SDOCanNode.cpp | 22 ++++++++++++---------- samples/canopen/canopen_sdo/SDOCanNode.hpp | 5 +++-- samples/canopen/canopen_sdo/main.cpp | 21 +++++++++++++++++++-- 3 files changed, 34 insertions(+), 14 deletions(-) diff --git a/samples/canopen/canopen_sdo/SDOCanNode.cpp b/samples/canopen/canopen_sdo/SDOCanNode.cpp index c7a8237d..3fee7e96 100644 --- a/samples/canopen/canopen_sdo/SDOCanNode.cpp +++ b/samples/canopen/canopen_sdo/SDOCanNode.cpp @@ -1,27 +1,27 @@ #include "SDOCanNode.hpp" SDOCanNode::SDOCanNode() { - sampleDataA = 0; + sampleDataA = 6; sampleDataB = 0; } void SDOCanNode::SDOTransfer(CO_NODE node) { CO_CSDO *csdo = COCSdoFind(&(node), 0); - CO_ERR err = COCSdoRequestDownload(csdo, CO_DEV(0x00,0x01), - &sampleDataA, 8, + CO_ERR err = COCSdoRequestDownload(csdo, CO_DEV(0x2100,0x01), + &sampleDataA, 1, AppCSdoFinishCb, 1000); if (err == CO_ERR_NONE) { /* Transfer is started successfully */ - log::LOGGER.log(log::Logger::LogLevel::INFO, "Value transferred: %lu", sampleDataA); +// log::LOGGER.log(log::Logger::LogLevel::INFO, "Value Transferred: %lu", sampleDataA); /* Note: don't use the 'readValue' until transfer is finished! */ } else { /* Unable to start the SDO transfer */ - log::LOGGER.log(log::Logger::LogLevel::INFO, "Download Error"); + log::LOGGER.log(log::Logger::LogLevel::WARNING, "Transfer Error"); } } @@ -30,21 +30,21 @@ void SDOCanNode::SDOReceive(CO_NODE node) { CO_CSDO *csdo; CO_ERR err; + csdo = COCSdoFind(&(node), 0); - err = COCSdoRequestUpload(csdo, CO_DEV(0x00,0x02), - &sampleDataB, 8, + err = COCSdoRequestUpload(csdo, CO_DEV(0x2100,0x02), + sampleDataArray, 2, AppCSdoFinishCb, 1000); if (err == CO_ERR_NONE) { /* Transfer is started successfully */ - log::LOGGER.log(log::Logger::LogLevel::INFO, "Value : %lu", sampleDataB); /* Note: don't use the 'readValue' until transfer is finished! */ } else { /* Unable to start the SDO transfer */ - log::LOGGER.log(log::Logger::LogLevel::INFO, "Upload Error"); + log::LOGGER.log(log::Logger::LogLevel::WARNING, "Receive Error"); } } @@ -81,10 +81,12 @@ void AppCSdoFinishCb(CO_CSDO *csdo, uint16_t index, uint8_t sub, uint32_t code) { if (code == 0) { /* read data is available in 'readValue' */ - +// sampleDataB = (sampleDataArray[0] << 8) | sampleDataArray[1]; + log::LOGGER.log(log::Logger::LogLevel::WARNING, "Value transferred"); } else { /* a timeout or abort is detected during SDO transfer */ + log::LOGGER.log(log::Logger::LogLevel::WARNING, "SDO callback don goofed 0x%x", code); } } \ No newline at end of file diff --git a/samples/canopen/canopen_sdo/SDOCanNode.hpp b/samples/canopen/canopen_sdo/SDOCanNode.hpp index 57d35ca4..ad343ef3 100644 --- a/samples/canopen/canopen_sdo/SDOCanNode.hpp +++ b/samples/canopen/canopen_sdo/SDOCanNode.hpp @@ -84,7 +84,8 @@ class SDOCanNode : public CANDevice { * This device will then broadcast the value via a triggered PDO. */ uint8_t sampleDataA; - uint8_t sampleDataB; + uint16_t sampleDataB; + uint8_t sampleDataArray[2]; /** * Have to know the size of the object dictionary for initialization @@ -131,7 +132,7 @@ class SDOCanNode : public CANDevice { // accessed via SDO and depending on configuration PDO DATA_LINK_START_KEY_21XX(0, 0x02), DATA_LINK_21XX(0x00, 0x01, CO_TUNSIGNED8, &sampleDataA), - DATA_LINK_21XX(0x00, 0x02, CO_TUNSIGNED8, &sampleDataB), + DATA_LINK_21XX(0x00, 0x02, CO_TUNSIGNED16, &sampleDataB), // End of dictionary marker CO_OBJ_DICT_ENDMARK, diff --git a/samples/canopen/canopen_sdo/main.cpp b/samples/canopen/canopen_sdo/main.cpp index 2750ac40..de2aabcd 100644 --- a/samples/canopen/canopen_sdo/main.cpp +++ b/samples/canopen/canopen_sdo/main.cpp @@ -19,6 +19,22 @@ namespace io = core::io; namespace dev = core::dev; namespace time = core::time; +// create a can interrupt handler +void canInterrupt(io::CANMessage& message, void* priv) { + auto* queue = (core::types::FixedQueue*) priv; + + // print out raw received data + log::LOGGER.log(log::Logger::LogLevel::INFO, "Got RAW message from %X of length %d with data: ", message.getId(), message.getDataLength()); + uint8_t* data = message.getPayload(); + for (int i = 0; i < message.getDataLength(); i++) { + log::LOGGER.log(log::Logger::LogLevel::INFO, "%X ", *data); + data++; + } + log::LOGGER.log(log::Logger::LogLevel::INFO, "\r\n"); + + if (queue != nullptr) + queue->append(message); +} int main() { // Initialize system @@ -45,6 +61,7 @@ int main() { // Initialize CAN, add an IRQ which will add messages to the queue above io::CAN& can = io::getCAN(); + can.addIRQHandler(canInterrupt, reinterpret_cast(&canOpenQueue)); // Reserved memory for CANopen stack usage uint8_t sdoBuffer[CO_SSDO_N * CO_SDO_BUF_BYTE]; @@ -87,9 +104,9 @@ int main() { /////////////////////////////////////////////////////////////////////////// while (1) { - testCanNode.SDOTransfer(canNode); +// testCanNode.SDOTransfer(canNode); -// testCanNode.SDOReceive(canNode); + testCanNode.SDOReceive(canNode); io::processCANopenNode(&canNode); // Wait for new data to come in From c00d7906b24cb5be3d610414430a03320ba03056 Mon Sep 17 00:00:00 2001 From: DiegoLHendrix <119289719+DiegoLHendrix@users.noreply.github.com> Date: Sat, 9 Nov 2024 15:57:47 -0500 Subject: [PATCH 03/17] idk anymore --- samples/canopen/canopen_sdo/SDOCanNode.cpp | 8 ++++---- samples/canopen/canopen_sdo/main.cpp | 1 + 2 files changed, 5 insertions(+), 4 deletions(-) diff --git a/samples/canopen/canopen_sdo/SDOCanNode.cpp b/samples/canopen/canopen_sdo/SDOCanNode.cpp index 3fee7e96..e4706df5 100644 --- a/samples/canopen/canopen_sdo/SDOCanNode.cpp +++ b/samples/canopen/canopen_sdo/SDOCanNode.cpp @@ -21,7 +21,7 @@ void SDOCanNode::SDOTransfer(CO_NODE node) { } else { /* Unable to start the SDO transfer */ - log::LOGGER.log(log::Logger::LogLevel::WARNING, "Transfer Error"); + log::LOGGER.log(log::Logger::LogLevel::ERROR, "Transfer Error"); } } @@ -44,7 +44,7 @@ void SDOCanNode::SDOReceive(CO_NODE node) { } else { /* Unable to start the SDO transfer */ - log::LOGGER.log(log::Logger::LogLevel::WARNING, "Receive Error"); + log::LOGGER.log(log::Logger::LogLevel::ERROR, "Receive Error"); } } @@ -82,11 +82,11 @@ void AppCSdoFinishCb(CO_CSDO *csdo, uint16_t index, uint8_t sub, uint32_t code) if (code == 0) { /* read data is available in 'readValue' */ // sampleDataB = (sampleDataArray[0] << 8) | sampleDataArray[1]; - log::LOGGER.log(log::Logger::LogLevel::WARNING, "Value transferred"); + log::LOGGER.log(log::Logger::LogLevel::INFO, "Value transferred"); } else { /* a timeout or abort is detected during SDO transfer */ - log::LOGGER.log(log::Logger::LogLevel::WARNING, "SDO callback don goofed 0x%x", code); + log::LOGGER.log(log::Logger::LogLevel::ERROR, "SDO callback don goofed 0x%x", code); } } \ No newline at end of file diff --git a/samples/canopen/canopen_sdo/main.cpp b/samples/canopen/canopen_sdo/main.cpp index de2aabcd..34302f59 100644 --- a/samples/canopen/canopen_sdo/main.cpp +++ b/samples/canopen/canopen_sdo/main.cpp @@ -63,6 +63,7 @@ int main() { io::CAN& can = io::getCAN(); can.addIRQHandler(canInterrupt, reinterpret_cast(&canOpenQueue)); + // Reserved memory for CANopen stack usage uint8_t sdoBuffer[CO_SSDO_N * CO_SDO_BUF_BYTE]; CO_TMR_MEM appTmrMem[16]; From 4451a8be39049f19fee5c748712ebfc249e738f2 Mon Sep 17 00:00:00 2001 From: DiegoLHendrix <119289719+DiegoLHendrix@users.noreply.github.com> Date: Mon, 18 Nov 2024 12:58:35 -0500 Subject: [PATCH 04/17] The voices are getting louder --- include/core/io/CANOpenMacros.hpp | 4 +-- samples/canopen/canopen_sdo/SDOCanNode.cpp | 8 +++--- samples/canopen/canopen_sdo/main.cpp | 30 ++++++++++++++-------- 3 files changed, 25 insertions(+), 17 deletions(-) diff --git a/include/core/io/CANOpenMacros.hpp b/include/core/io/CANOpenMacros.hpp index a741aed8..bb0db231 100644 --- a/include/core/io/CANOpenMacros.hpp +++ b/include/core/io/CANOpenMacros.hpp @@ -121,12 +121,12 @@ }, \ { \ /* SDO Server Request COBID */ \ - .Key = CO_KEY(0x1200, 0x01, CO_OBJ__N__R_), \ + .Key = CO_KEY(0x1200, 0x01, CO_OBJ_DN__R_), \ .Type = CO_TUNSIGNED32, \ .Data = (CO_DATA) CO_COBID_SDO_REQUEST(), \ }, \ { /* SDO Server Response COBID */ \ - .Key = CO_KEY(0x1200, 0x02, CO_OBJ__N__R_), \ + .Key = CO_KEY(0x1200, 0x02, CO_OBJ_DN__R_), \ .Type = CO_TUNSIGNED32, \ .Data = (CO_DATA) CO_COBID_SDO_RESPONSE(), \ } diff --git a/samples/canopen/canopen_sdo/SDOCanNode.cpp b/samples/canopen/canopen_sdo/SDOCanNode.cpp index e4706df5..9d603d3e 100644 --- a/samples/canopen/canopen_sdo/SDOCanNode.cpp +++ b/samples/canopen/canopen_sdo/SDOCanNode.cpp @@ -30,21 +30,21 @@ void SDOCanNode::SDOReceive(CO_NODE node) { CO_CSDO *csdo; CO_ERR err; - csdo = COCSdoFind(&(node), 0); err = COCSdoRequestUpload(csdo, CO_DEV(0x2100,0x02), sampleDataArray, 2, - AppCSdoFinishCb, 1000); + AppCSdoFinishCb, 5000); if (err == CO_ERR_NONE) { /* Transfer is started successfully */ + log::LOGGER.log(log::Logger::LogLevel::INFO, "Sent Request"); /* Note: don't use the 'readValue' until transfer is finished! */ } else { /* Unable to start the SDO transfer */ - log::LOGGER.log(log::Logger::LogLevel::ERROR, "Receive Error"); + log::LOGGER.log(log::Logger::LogLevel::ERROR, "Request Error"); } } @@ -86,7 +86,7 @@ void AppCSdoFinishCb(CO_CSDO *csdo, uint16_t index, uint8_t sub, uint32_t code) } else { /* a timeout or abort is detected during SDO transfer */ - log::LOGGER.log(log::Logger::LogLevel::ERROR, "SDO callback don goofed 0x%x", code); + log::LOGGER.log(log::Logger::LogLevel::ERROR, "SDO callback don goofed 0x%x\r\n", code); } } \ No newline at end of file diff --git a/samples/canopen/canopen_sdo/main.cpp b/samples/canopen/canopen_sdo/main.cpp index 34302f59..b6991c98 100644 --- a/samples/canopen/canopen_sdo/main.cpp +++ b/samples/canopen/canopen_sdo/main.cpp @@ -11,6 +11,7 @@ #include #include +#include #include "SDOCanNode.hpp" @@ -23,17 +24,18 @@ namespace time = core::time; void canInterrupt(io::CANMessage& message, void* priv) { auto* queue = (core::types::FixedQueue*) priv; - // print out raw received data - log::LOGGER.log(log::Logger::LogLevel::INFO, "Got RAW message from %X of length %d with data: ", message.getId(), message.getDataLength()); uint8_t* data = message.getPayload(); - for (int i = 0; i < message.getDataLength(); i++) { - log::LOGGER.log(log::Logger::LogLevel::INFO, "%X ", *data); - data++; - } - log::LOGGER.log(log::Logger::LogLevel::INFO, "\r\n"); - if (queue != nullptr) queue->append(message); + char messageString[50]; + for (int i = 0; i < message.getDataLength(); i++) { + snprintf(&messageString[i * 5], 6, "0x%02X ", data[i]); + } + log::LOGGER.log(log::Logger::LogLevel::DEBUG, + "[CAN1] Got RAW message from %X of length %d with data: \r\n\t%s\r\n", + message.getId(), + message.getDataLength(), + messageString); } int main() { @@ -42,7 +44,7 @@ int main() { io::UART& uart = io::getUART(9600); log::LOGGER.setUART(&uart); - log::LOGGER.setLogLevel(log::Logger::LogLevel::INFO); + log::LOGGER.setLogLevel(log::Logger::LogLevel::DEBUG); // create the SDO node SDOCanNode testCanNode; @@ -103,14 +105,20 @@ int main() { /////////////////////////////////////////////////////////////////////////// // Main loop /////////////////////////////////////////////////////////////////////////// + uint32_t last_update = HAL_GetTick(); while (1) { // testCanNode.SDOTransfer(canNode); - testCanNode.SDOReceive(canNode); + + if((HAL_GetTick() - last_update) >= 1000 ){ // If 1000ms have passed Receive CAN message. + testCanNode.SDOReceive(canNode); + last_update = HAL_GetTick(); // Set to current time. + } io::processCANopenNode(&canNode); + // Wait for new data to come in - time::wait(500); + time::wait(1); } } \ No newline at end of file From ae64dc7dc2c2f00be2d2338e664a4b6a2716d8f0 Mon Sep 17 00:00:00 2001 From: DiegoLHendrix <119289719+DiegoLHendrix@users.noreply.github.com> Date: Fri, 22 Nov 2024 12:44:20 -0500 Subject: [PATCH 05/17] I Start Drinking On mondays at 8:15 am --- samples/canopen/canopen_sdo/SDOCanNode.cpp | 1 + samples/canopen/canopen_sdo/main.cpp | 1 - 2 files changed, 1 insertion(+), 1 deletion(-) diff --git a/samples/canopen/canopen_sdo/SDOCanNode.cpp b/samples/canopen/canopen_sdo/SDOCanNode.cpp index 9d603d3e..38a197eb 100644 --- a/samples/canopen/canopen_sdo/SDOCanNode.cpp +++ b/samples/canopen/canopen_sdo/SDOCanNode.cpp @@ -47,6 +47,7 @@ void SDOCanNode::SDOReceive(CO_NODE node) { log::LOGGER.log(log::Logger::LogLevel::ERROR, "Request Error"); } + } uint8_t SDOCanNode::getSampleDataA() { diff --git a/samples/canopen/canopen_sdo/main.cpp b/samples/canopen/canopen_sdo/main.cpp index b6991c98..1bb7437e 100644 --- a/samples/canopen/canopen_sdo/main.cpp +++ b/samples/canopen/canopen_sdo/main.cpp @@ -110,7 +110,6 @@ int main() { while (1) { // testCanNode.SDOTransfer(canNode); - if((HAL_GetTick() - last_update) >= 1000 ){ // If 1000ms have passed Receive CAN message. testCanNode.SDOReceive(canNode); last_update = HAL_GetTick(); // Set to current time. From 028f0307e413c6a132324c8cf5bb8a23d425633f Mon Sep 17 00:00:00 2001 From: DiegoLHendrix <119289719+DiegoLHendrix@users.noreply.github.com> Date: Sat, 23 Nov 2024 13:37:53 -0500 Subject: [PATCH 06/17] Start Drinking On comapny time --- samples/canopen/canopen_sdo/SDOCanNode.cpp | 6 +++--- samples/canopen/canopen_sdo/SDOCanNode.hpp | 2 +- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/samples/canopen/canopen_sdo/SDOCanNode.cpp b/samples/canopen/canopen_sdo/SDOCanNode.cpp index 38a197eb..10c024a2 100644 --- a/samples/canopen/canopen_sdo/SDOCanNode.cpp +++ b/samples/canopen/canopen_sdo/SDOCanNode.cpp @@ -26,14 +26,14 @@ void SDOCanNode::SDOTransfer(CO_NODE node) { } } -void SDOCanNode::SDOReceive(CO_NODE node) { +void SDOCanNode::SDOReceive(CO_NODE &node) { CO_CSDO *csdo; CO_ERR err; csdo = COCSdoFind(&(node), 0); err = COCSdoRequestUpload(csdo, CO_DEV(0x2100,0x02), sampleDataArray, 2, - AppCSdoFinishCb, 5000); + AppCSdoFinishCb, 1000); if (err == CO_ERR_NONE) { @@ -83,7 +83,7 @@ void AppCSdoFinishCb(CO_CSDO *csdo, uint16_t index, uint8_t sub, uint32_t code) if (code == 0) { /* read data is available in 'readValue' */ // sampleDataB = (sampleDataArray[0] << 8) | sampleDataArray[1]; - log::LOGGER.log(log::Logger::LogLevel::INFO, "Value transferred"); + log::LOGGER.log(log::Logger::LogLevel::INFO, "Value transferred %x, %x", csdo->Tfer.Buf[0], csdo->Tfer.Buf[1]); } else { /* a timeout or abort is detected during SDO transfer */ diff --git a/samples/canopen/canopen_sdo/SDOCanNode.hpp b/samples/canopen/canopen_sdo/SDOCanNode.hpp index ad343ef3..b5f72b2f 100644 --- a/samples/canopen/canopen_sdo/SDOCanNode.hpp +++ b/samples/canopen/canopen_sdo/SDOCanNode.hpp @@ -33,7 +33,7 @@ class SDOCanNode : public CANDevice { * * @param newValue[in] The value to set sample data to */ - void SDOReceive(CO_NODE node); + void SDOReceive(CO_NODE &node); /** * Get the contained sample data From 9169c959d05a7bf197d38a642b0bd33d3dcb7f56 Mon Sep 17 00:00:00 2001 From: DiegoLHendrix <119289719+DiegoLHendrix@users.noreply.github.com> Date: Mon, 2 Dec 2024 20:48:29 -0500 Subject: [PATCH 07/17] Good heavens I have arrived! --- include/core/io/CANopen.hpp | 20 ++++++++++ samples/canopen/canopen_sdo/SDOCanNode.cpp | 43 +++++---------------- samples/canopen/canopen_sdo/SDOCanNode.hpp | 10 ++--- samples/canopen/canopen_sdo/main.cpp | 15 +++++--- src/core/io/CANopen.cpp | 45 ++++++++++++++++++++++ 5 files changed, 89 insertions(+), 44 deletions(-) diff --git a/include/core/io/CANopen.hpp b/include/core/io/CANopen.hpp index f85b10b3..cf9b8d9c 100644 --- a/include/core/io/CANopen.hpp +++ b/include/core/io/CANopen.hpp @@ -14,11 +14,13 @@ #include #include #include +#include // Allows for resizable CANOpen queue if needed #ifndef CANOPEN_QUEUE_SIZE #define CANOPEN_QUEUE_SIZE 150 #endif +namespace log = core::log; namespace core::io { @@ -94,6 +96,24 @@ void initializeCANopenNode(CO_NODE* canNode, CANDevice* canDevice, CO_IF_DRV* ca */ void processCANopenNode(CO_NODE* canNode); +/** + * Update Object Dictionary entry + * + * @param node[in] The SDO node + * @param sampleDataArray[in] The value to set sample data to + */ +CO_ERR SDOTransfer(CO_NODE &node, uint8_t *data, uint8_t size, uint32_t entry); + +/** + * Read Object Dictionary entry + * + * @param node[in] The SDO node + * @param sampleDataArray[in] The value to set sample data to + */ +CO_ERR SDOReceive(CO_NODE &node, uint8_t *data, uint8_t size, uint32_t entry); + +void AppCSdoTransferCb(CO_CSDO *csdo, uint16_t index, uint8_t sub, uint32_t code); +void AppCSdoReceiveCb(CO_CSDO *csdo, uint16_t index, uint8_t sub, uint32_t code); } // namespace core::io #endif diff --git a/samples/canopen/canopen_sdo/SDOCanNode.cpp b/samples/canopen/canopen_sdo/SDOCanNode.cpp index 10c024a2..bb8da199 100644 --- a/samples/canopen/canopen_sdo/SDOCanNode.cpp +++ b/samples/canopen/canopen_sdo/SDOCanNode.cpp @@ -5,49 +5,41 @@ SDOCanNode::SDOCanNode() { sampleDataB = 0; } -void SDOCanNode::SDOTransfer(CO_NODE node) { +void SDOCanNode::SDO_Transfer(CO_NODE &node) { + sampleDataArray[0]++; + sampleDataArray[1]=sampleDataArray[0]*2; - CO_CSDO *csdo = COCSdoFind(&(node), 0); - CO_ERR err = COCSdoRequestDownload(csdo, CO_DEV(0x2100,0x01), - &sampleDataA, 1, - AppCSdoFinishCb, 1000); + CO_ERR err = core::io::SDOTransfer(node, sampleDataArray, 2, CO_DEV(0x2100,0x02)); if (err == CO_ERR_NONE) { /* Transfer is started successfully */ -// log::LOGGER.log(log::Logger::LogLevel::INFO, "Value Transferred: %lu", sampleDataA); + log::LOGGER.log(log::Logger::LogLevel::INFO, "SDOTransfer Sent Request"); /* Note: don't use the 'readValue' until transfer is finished! */ } else { /* Unable to start the SDO transfer */ - log::LOGGER.log(log::Logger::LogLevel::ERROR, "Transfer Error"); + log::LOGGER.log(log::Logger::LogLevel::ERROR, "SDOTransfer Request Error"); } } -void SDOCanNode::SDOReceive(CO_NODE &node) { - CO_CSDO *csdo; - CO_ERR err; - - csdo = COCSdoFind(&(node), 0); - err = COCSdoRequestUpload(csdo, CO_DEV(0x2100,0x02), - sampleDataArray, 2, - AppCSdoFinishCb, 1000); +void SDOCanNode::SDO_Receive(CO_NODE &node) { + CO_ERR err = core::io::SDOReceive(node, sampleDataArray, 1, CO_DEV(0x2100,0x01)); if (err == CO_ERR_NONE) { /* Transfer is started successfully */ - log::LOGGER.log(log::Logger::LogLevel::INFO, "Sent Request"); + log::LOGGER.log(log::Logger::LogLevel::INFO, "SDOReceive Sent Request"); /* Note: don't use the 'readValue' until transfer is finished! */ } else { /* Unable to start the SDO transfer */ - log::LOGGER.log(log::Logger::LogLevel::ERROR, "Request Error"); + log::LOGGER.log(log::Logger::LogLevel::ERROR, "SDOReceive Request Error"); } - } uint8_t SDOCanNode::getSampleDataA() { @@ -75,19 +67,4 @@ uint8_t SDOCanNode::getNumElements() { uint8_t SDOCanNode::getNodeID() { return NODE_ID; -} - -/* The application specific SDO transfer finalization callback */ -void AppCSdoFinishCb(CO_CSDO *csdo, uint16_t index, uint8_t sub, uint32_t code) -{ - if (code == 0) { - /* read data is available in 'readValue' */ -// sampleDataB = (sampleDataArray[0] << 8) | sampleDataArray[1]; - log::LOGGER.log(log::Logger::LogLevel::INFO, "Value transferred %x, %x", csdo->Tfer.Buf[0], csdo->Tfer.Buf[1]); - } - else { - /* a timeout or abort is detected during SDO transfer */ - log::LOGGER.log(log::Logger::LogLevel::ERROR, "SDO callback don goofed 0x%x\r\n", code); - } - } \ No newline at end of file diff --git a/samples/canopen/canopen_sdo/SDOCanNode.hpp b/samples/canopen/canopen_sdo/SDOCanNode.hpp index b5f72b2f..e820cd3a 100644 --- a/samples/canopen/canopen_sdo/SDOCanNode.hpp +++ b/samples/canopen/canopen_sdo/SDOCanNode.hpp @@ -5,6 +5,7 @@ #include #include #include +#include /** * Representation of the CAN node. Handles constructing the object @@ -26,14 +27,14 @@ class SDOCanNode : public CANDevice { * * @param newValue[in] The value to set sample data to */ - void SDOTransfer(CO_NODE node); + void SDO_Transfer(CO_NODE &node); /** * Read Object Dictionary entry * * @param newValue[in] The value to set sample data to */ - void SDOReceive(CO_NODE &node); + void SDO_Receive(CO_NODE &node); /** * Get the contained sample data @@ -85,7 +86,7 @@ class SDOCanNode : public CANDevice { */ uint8_t sampleDataA; uint16_t sampleDataB; - uint8_t sampleDataArray[2]; + uint8_t sampleDataArray[2] = {0, 0}; /** * Have to know the size of the object dictionary for initialization @@ -137,5 +138,4 @@ class SDOCanNode : public CANDevice { // End of dictionary marker CO_OBJ_DICT_ENDMARK, }; -}; -void AppCSdoFinishCb(CO_CSDO *csdo, uint16_t index, uint8_t sub, uint32_t code); \ No newline at end of file +}; \ No newline at end of file diff --git a/samples/canopen/canopen_sdo/main.cpp b/samples/canopen/canopen_sdo/main.cpp index 1bb7437e..43b404b6 100644 --- a/samples/canopen/canopen_sdo/main.cpp +++ b/samples/canopen/canopen_sdo/main.cpp @@ -105,14 +105,17 @@ int main() { /////////////////////////////////////////////////////////////////////////// // Main loop /////////////////////////////////////////////////////////////////////////// - uint32_t last_update = HAL_GetTick(); + uint32_t last_update_1 = HAL_GetTick(); + uint32_t last_update_2 = HAL_GetTick(); while (1) { -// testCanNode.SDOTransfer(canNode); - - if((HAL_GetTick() - last_update) >= 1000 ){ // If 1000ms have passed Receive CAN message. - testCanNode.SDOReceive(canNode); - last_update = HAL_GetTick(); // Set to current time. + if((HAL_GetTick() - last_update_1) >= 1000 ){ // If 1000ms have passed Receive CAN message. + testCanNode.SDO_Receive(canNode); + last_update_1 = HAL_GetTick(); // Set to current time. + } + else if((HAL_GetTick() - last_update_2) >= 5000 ){ // If 5000ms have passed Write CAN message. + testCanNode.SDO_Transfer(canNode); + last_update_2 = HAL_GetTick(); // Set to current time. } io::processCANopenNode(&canNode); diff --git a/src/core/io/CANopen.cpp b/src/core/io/CANopen.cpp index d6bfcfa8..8a7ebd90 100644 --- a/src/core/io/CANopen.cpp +++ b/src/core/io/CANopen.cpp @@ -131,6 +131,51 @@ void processCANopenNode(CO_NODE* canNode) { COTmrProcess(&canNode->Tmr); } +CO_ERR SDOTransfer(CO_NODE &node, uint8_t *data, uint8_t size, uint32_t entry) { + + CO_CSDO *csdo = COCSdoFind(&(node), 0); + CO_ERR err = COCSdoRequestDownload(csdo, entry, + data, size, + AppCSdoTransferCb, 1000); + return err; +} + +CO_ERR SDOReceive(CO_NODE &node, uint8_t *data, uint8_t size, uint32_t entry) { + CO_CSDO *csdo = COCSdoFind(&(node), 0); + CO_ERR err = COCSdoRequestUpload(csdo, entry, + data, size, + AppCSdoReceiveCb, 1000); + return err; +} + +/* The application specific SDO transfer finalization callback */ +void AppCSdoTransferCb(CO_CSDO *csdo, uint16_t index, uint8_t sub, uint32_t code) +{ + if (code == 0) { + /* read data is available in 'readValue' */ + log::LOGGER.log(log::Logger::LogLevel::INFO, "Value transferred %x, %x\r\n", csdo->Tfer.Buf[0], csdo->Tfer.Buf[1]); + } + else { + /* a timeout or abort is detected during SDO transfer */ + log::LOGGER.log(log::Logger::LogLevel::ERROR, "SDO callback don goofed 0x%x\r\n", code); + } + +} + +/* The application specific SDO receive finalization callback */ +void AppCSdoReceiveCb(CO_CSDO *csdo, uint16_t index, uint8_t sub, uint32_t code) +{ + if (code == 0) { + /* read data is available in 'readValue' */ + log::LOGGER.log(log::Logger::LogLevel::INFO, "Value received %x, %x\r\n", csdo->Tfer.Buf[0], csdo->Tfer.Buf[1]); + } + else { + /* a timeout or abort is detected during SDO transfer */ + + log::LOGGER.log(log::Logger::LogLevel::ERROR, "SDO callback don goofed 0x%x\r\n", code); + } + +} } // namespace core::io /////////////////////////////////////////////////////////////////////////////// From 4c750e491a9ddca764c31e3889ebe887dc830b8a Mon Sep 17 00:00:00 2001 From: DiegoLHendrix <119289719+DiegoLHendrix@users.noreply.github.com> Date: Tue, 3 Dec 2024 08:56:30 -0500 Subject: [PATCH 08/17] Added comments --- include/core/io/CANopen.hpp | 15 ++++++++ samples/canopen/canopen_sdo/SDOCanNode.cpp | 16 +++++---- samples/canopen/canopen_sdo/SDOCanNode.hpp | 4 +-- samples/canopen/canopen_sdo/main.cpp | 6 ++-- src/core/io/CANopen.cpp | 41 +++++++++++++++++++--- 5 files changed, 66 insertions(+), 16 deletions(-) diff --git a/include/core/io/CANopen.hpp b/include/core/io/CANopen.hpp index cf9b8d9c..5a8b6c71 100644 --- a/include/core/io/CANopen.hpp +++ b/include/core/io/CANopen.hpp @@ -112,7 +112,22 @@ CO_ERR SDOTransfer(CO_NODE &node, uint8_t *data, uint8_t size, uint32_t entry); */ CO_ERR SDOReceive(CO_NODE &node, uint8_t *data, uint8_t size, uint32_t entry); +/** + * The application-specific callback function for finalizing an SDO transfer operation. + * @param csdo[in] is the client-SDO object. + * @param index[in] is the object dictionary index. + * @param sub[in] is the object dictionary subindex. + * @param code[in] indicates the completion status of the operation (0 for success, error code otherwise). + */ void AppCSdoTransferCb(CO_CSDO *csdo, uint16_t index, uint8_t sub, uint32_t code); + +/** + * The application-specific callback function for finalizing an SDO receive operation. + * @param csdo[in] is the client-SDO object. + * @param index[in] is the object dictionary index. + * @param sub[in] is the object dictionary subindex. + * @param code[in] indicates the completion status of the operation (0 for success, error code otherwise). + */ void AppCSdoReceiveCb(CO_CSDO *csdo, uint16_t index, uint8_t sub, uint32_t code); } // namespace core::io diff --git a/samples/canopen/canopen_sdo/SDOCanNode.cpp b/samples/canopen/canopen_sdo/SDOCanNode.cpp index bb8da199..6221ac65 100644 --- a/samples/canopen/canopen_sdo/SDOCanNode.cpp +++ b/samples/canopen/canopen_sdo/SDOCanNode.cpp @@ -6,39 +6,41 @@ SDOCanNode::SDOCanNode() { } void SDOCanNode::SDO_Transfer(CO_NODE &node) { + /* Increment the first element of sampleDataArray by 1. */ sampleDataArray[0]++; - sampleDataArray[1]=sampleDataArray[0]*2; + /* Set the second element of sampleDataArray to twice the new value of the first element. */ + sampleDataArray[1] = sampleDataArray[0] * 2; + /* Initiate an SDO transfer using the specified node and sampleDataArray, + * targeting object dictionary entry 0x2100:02. */ CO_ERR err = core::io::SDOTransfer(node, sampleDataArray, 2, CO_DEV(0x2100,0x02)); + /* Check if the SDO transfer was successfully started. */ if (err == CO_ERR_NONE) { - /* Transfer is started successfully */ log::LOGGER.log(log::Logger::LogLevel::INFO, "SDOTransfer Sent Request"); /* Note: don't use the 'readValue' until transfer is finished! */ - } else { /* Unable to start the SDO transfer */ log::LOGGER.log(log::Logger::LogLevel::ERROR, "SDOTransfer Request Error"); - } } void SDOCanNode::SDO_Receive(CO_NODE &node) { + /* Initiate an SDO receive operation, reading data into sampleDataArray + * from object dictionary entry 0x2100:01. */ CO_ERR err = core::io::SDOReceive(node, sampleDataArray, 1, CO_DEV(0x2100,0x01)); + /* Check if the SDO receive operation was successfully started. */ if (err == CO_ERR_NONE) { - /* Transfer is started successfully */ log::LOGGER.log(log::Logger::LogLevel::INFO, "SDOReceive Sent Request"); /* Note: don't use the 'readValue' until transfer is finished! */ - } else { /* Unable to start the SDO transfer */ log::LOGGER.log(log::Logger::LogLevel::ERROR, "SDOReceive Request Error"); - } } diff --git a/samples/canopen/canopen_sdo/SDOCanNode.hpp b/samples/canopen/canopen_sdo/SDOCanNode.hpp index e820cd3a..8387bb27 100644 --- a/samples/canopen/canopen_sdo/SDOCanNode.hpp +++ b/samples/canopen/canopen_sdo/SDOCanNode.hpp @@ -25,14 +25,14 @@ class SDOCanNode : public CANDevice { /** * Update Object Dictionary entry * - * @param newValue[in] The value to set sample data to + * @param node[in] The canopen node to write to */ void SDO_Transfer(CO_NODE &node); /** * Read Object Dictionary entry * - * @param newValue[in] The value to set sample data to + * @param node[in] The canopen node to read from */ void SDO_Receive(CO_NODE &node); diff --git a/samples/canopen/canopen_sdo/main.cpp b/samples/canopen/canopen_sdo/main.cpp index 43b404b6..f146edbf 100644 --- a/samples/canopen/canopen_sdo/main.cpp +++ b/samples/canopen/canopen_sdo/main.cpp @@ -109,17 +109,17 @@ int main() { uint32_t last_update_2 = HAL_GetTick(); while (1) { - if((HAL_GetTick() - last_update_1) >= 1000 ){ // If 1000ms have passed Receive CAN message. + + if((HAL_GetTick() - last_update_1) >= 1000 ){ // If 1000ms have passed receive CAN message. testCanNode.SDO_Receive(canNode); last_update_1 = HAL_GetTick(); // Set to current time. } - else if((HAL_GetTick() - last_update_2) >= 5000 ){ // If 5000ms have passed Write CAN message. + else if((HAL_GetTick() - last_update_2) >= 5000 ){ // If 5000ms have passed write CAN message. testCanNode.SDO_Transfer(canNode); last_update_2 = HAL_GetTick(); // Set to current time. } io::processCANopenNode(&canNode); - // Wait for new data to come in time::wait(1); } diff --git a/src/core/io/CANopen.cpp b/src/core/io/CANopen.cpp index 8a7ebd90..f842b364 100644 --- a/src/core/io/CANopen.cpp +++ b/src/core/io/CANopen.cpp @@ -132,19 +132,54 @@ void processCANopenNode(CO_NODE* canNode) { } CO_ERR SDOTransfer(CO_NODE &node, uint8_t *data, uint8_t size, uint32_t entry) { - + /** + * Find the Client-SDO (CO_CSDO) object for the specified node. + * @param node[in] is the CANopen node to operate on. + * @return csdo[out] is the client-SDO object used to manage SDO communication. + */ CO_CSDO *csdo = COCSdoFind(&(node), 0); + + /** + * Initiate an SDO download request. + * @param csdo[in] is the client-SDO object. + * @param entry[in] specifies the object dictionary entry (index and subindex). + * @param data[in] is the pointer to the data to be sent. + * @param size[in] is the size of the data to be sent. + * @param AppCSdoTransferCb[in] is the callback function to be called upon transfer completion. + * @param 1000[in] is the timeout for the operation in milliseconds. + * @return err[out] indicates the result of the operation (success or error code). + */ CO_ERR err = COCSdoRequestDownload(csdo, entry, data, size, AppCSdoTransferCb, 1000); + + /* Return the result of the SDO transfer operation. */ return err; } CO_ERR SDOReceive(CO_NODE &node, uint8_t *data, uint8_t size, uint32_t entry) { + /** + * Find the Client-SDO (CO_CSDO) object for the specified node. + * @param node[in] is the CANopen node to operate on. + * @return csdo[out] is the client-SDO object used to manage SDO communication. + */ CO_CSDO *csdo = COCSdoFind(&(node), 0); - CO_ERR err = COCSdoRequestUpload(csdo, entry, + + /** + * Initiate an SDO upload request. + * @param csdo[in] is the client-SDO object. + * @param entry[in] specifies the object dictionary entry (index and subindex). + * @param data[out] is the pointer to store the received data. + * @param size[in] is the size of the data buffer. + * @param AppCSdoReceiveCb[in] is the callback function to be called upon reception completion. + * @param 1000[in] is the timeout for the operation in milliseconds. + * @return err[out] indicates the result of the operation (success or error code). + */ + CO_ERR err = COCSdoRequestUpload(csdo, entry, data, size, AppCSdoReceiveCb, 1000); + + /* Return the result of the SDO receive operation. */ return err; } @@ -171,10 +206,8 @@ void AppCSdoReceiveCb(CO_CSDO *csdo, uint16_t index, uint8_t sub, uint32_t code) } else { /* a timeout or abort is detected during SDO transfer */ - log::LOGGER.log(log::Logger::LogLevel::ERROR, "SDO callback don goofed 0x%x\r\n", code); } - } } // namespace core::io From 580dbfa855bdcb3008dd9b7c39b2d0af1caf6658 Mon Sep 17 00:00:00 2001 From: DiegoLHendrix <119289719+DiegoLHendrix@users.noreply.github.com> Date: Thu, 5 Dec 2024 19:23:18 -0500 Subject: [PATCH 09/17] CANopen is my sleep paralysis demon --- samples/canopen/canopen_rpdo/main.cpp | 1 - samples/canopen/canopen_sdo/main.cpp | 1 - 2 files changed, 2 deletions(-) diff --git a/samples/canopen/canopen_rpdo/main.cpp b/samples/canopen/canopen_rpdo/main.cpp index f2f08228..e721d014 100644 --- a/samples/canopen/canopen_rpdo/main.cpp +++ b/samples/canopen/canopen_rpdo/main.cpp @@ -38,7 +38,6 @@ namespace log = core::log; * @param message[in] The passed in CAN message that was read. */ - // create a can interrupt handler void canInterrupt(io::CANMessage& message, void* priv) { auto* queue = (core::types::FixedQueue*) priv; diff --git a/samples/canopen/canopen_sdo/main.cpp b/samples/canopen/canopen_sdo/main.cpp index f146edbf..dc5f9f5f 100644 --- a/samples/canopen/canopen_sdo/main.cpp +++ b/samples/canopen/canopen_sdo/main.cpp @@ -15,7 +15,6 @@ #include "SDOCanNode.hpp" - namespace io = core::io; namespace dev = core::dev; namespace time = core::time; From ffc84953f4846520d46749d894e8a2cbbbbc394c Mon Sep 17 00:00:00 2001 From: DiegoLHendrix <119289719+DiegoLHendrix@users.noreply.github.com> Date: Fri, 6 Dec 2024 09:41:48 -0500 Subject: [PATCH 10/17] please work cmake --- samples/canopen/canopen_sdo/main.cpp | 1 - src/core/io/CANopen.cpp | 1 - 2 files changed, 2 deletions(-) diff --git a/samples/canopen/canopen_sdo/main.cpp b/samples/canopen/canopen_sdo/main.cpp index dc5f9f5f..bfe9c58b 100644 --- a/samples/canopen/canopen_sdo/main.cpp +++ b/samples/canopen/canopen_sdo/main.cpp @@ -64,7 +64,6 @@ int main() { io::CAN& can = io::getCAN(); can.addIRQHandler(canInterrupt, reinterpret_cast(&canOpenQueue)); - // Reserved memory for CANopen stack usage uint8_t sdoBuffer[CO_SSDO_N * CO_SDO_BUF_BYTE]; CO_TMR_MEM appTmrMem[16]; diff --git a/src/core/io/CANopen.cpp b/src/core/io/CANopen.cpp index f842b364..2992cb03 100644 --- a/src/core/io/CANopen.cpp +++ b/src/core/io/CANopen.cpp @@ -194,7 +194,6 @@ void AppCSdoTransferCb(CO_CSDO *csdo, uint16_t index, uint8_t sub, uint32_t code /* a timeout or abort is detected during SDO transfer */ log::LOGGER.log(log::Logger::LogLevel::ERROR, "SDO callback don goofed 0x%x\r\n", code); } - } /* The application specific SDO receive finalization callback */ From 9301881cf55acbf7385e373105080ad6ae66e1f5 Mon Sep 17 00:00:00 2001 From: DiegoLHendrix <119289719+DiegoLHendrix@users.noreply.github.com> Date: Mon, 16 Dec 2024 15:47:35 -0500 Subject: [PATCH 11/17] Beetlejuice Beetlejuice Beetlejuice --- include/core/io/CANopen.hpp | 22 +++------ samples/canopen/canopen_sdo/SDOCanNode.cpp | 56 ++++++++++++---------- samples/canopen/canopen_sdo/SDOCanNode.hpp | 18 +------ samples/canopen/canopen_sdo/main.cpp | 16 +++---- samples/canopen/canopen_tpdo/main.cpp | 16 ++++--- src/core/io/CANopen.cpp | 42 ++++++---------- 6 files changed, 73 insertions(+), 97 deletions(-) diff --git a/include/core/io/CANopen.hpp b/include/core/io/CANopen.hpp index defe4803..104b7d14 100644 --- a/include/core/io/CANopen.hpp +++ b/include/core/io/CANopen.hpp @@ -110,25 +110,15 @@ CO_ERR SDOTransfer(CO_NODE &node, uint8_t *data, uint8_t size, uint32_t entry); * @param node[in] The SDO node * @param sampleDataArray[in] The value to set sample data to */ -CO_ERR SDOReceive(CO_NODE &node, uint8_t *data, uint8_t size, uint32_t entry); +CO_ERR SDOReceive(CO_NODE &node, uint8_t *data, uint8_t size, uint32_t entry, void (*AppCallback)(CO_NODE &node)); /** - * The application-specific callback function for finalizing an SDO transfer operation. - * @param csdo[in] is the client-SDO object. - * @param index[in] is the object dictionary index. - * @param sub[in] is the object dictionary subindex. - * @param code[in] indicates the completion status of the operation (0 for success, error code otherwise). - */ -void AppCSdoTransferCb(CO_CSDO *csdo, uint16_t index, uint8_t sub, uint32_t code); - -/** - * The application-specific callback function for finalizing an SDO receive operation. - * @param csdo[in] is the client-SDO object. - * @param index[in] is the object dictionary index. - * @param sub[in] is the object dictionary subindex. - * @param code[in] indicates the completion status of the operation (0 for success, error code otherwise). + * Register a callback method for sdo + * + * @param AppCallback[in] The SDO callback method that will be registered. See AppCSdoCallback method for explanation of parameters + * @param context[in] The context of the application */ -void AppCSdoReceiveCb(CO_CSDO *csdo, uint16_t index, uint8_t sub, uint32_t code); +void registerCallBack(void (*AppCallback)(CO_CSDO *csdo, uint16_t index, uint8_t size, uint32_t entry)); } // namespace core::io #endif diff --git a/samples/canopen/canopen_sdo/SDOCanNode.cpp b/samples/canopen/canopen_sdo/SDOCanNode.cpp index 6221ac65..38f4caf4 100644 --- a/samples/canopen/canopen_sdo/SDOCanNode.cpp +++ b/samples/canopen/canopen_sdo/SDOCanNode.cpp @@ -1,19 +1,40 @@ #include "SDOCanNode.hpp" +#include SDOCanNode::SDOCanNode() { - sampleDataA = 6; + sampleDataA = 0; sampleDataB = 0; + transferBuffArray[0] = 0; + transferBuffArray[1] = 0; +} + +/** + * The application-specific callback function for finalizing an SDO transfer/receive operation. + * @param csdo[in] is the client-SDO object. + * @param index[in] is the object dictionary index. + * @param sub[in] is the object dictionary subindex. + * @param code[in] indicates the completion status of the operation (0 for success, error code otherwise). + */ +void AppCSdoCallback(CO_CSDO *csdo, uint16_t index, uint8_t sub, uint32_t code) { + if (code == 0) { + /* read data is available in 'readValue' */ + log::LOGGER.log(log::Logger::LogLevel::INFO, "Value transferred %x, %x\r\n", csdo->Tfer.Buf[0], csdo->Tfer.Buf[1]); + } + else { + /* a timeout or abort is detected during SDO transfer */ + log::LOGGER.log(log::Logger::LogLevel::ERROR, "SDO callback don goofed 0x%x\r\n", code); + } } void SDOCanNode::SDO_Transfer(CO_NODE &node) { - /* Increment the first element of sampleDataArray by 1. */ - sampleDataArray[0]++; - /* Set the second element of sampleDataArray to twice the new value of the first element. */ - sampleDataArray[1] = sampleDataArray[0] * 2; + /* Increment the first element of transferBuffArray by 1. */ + transferBuffArray[0]++; + /* Set the second element of transferBuffArray to twice the new value of the first element. */ + transferBuffArray[1] = transferBuffArray[0] * 2; - /* Initiate an SDO transfer using the specified node and sampleDataArray, + /* Initiate an SDO transfer using the specified node and transferBuffArray, * targeting object dictionary entry 0x2100:02. */ - CO_ERR err = core::io::SDOTransfer(node, sampleDataArray, 2, CO_DEV(0x2100,0x02)); + CO_ERR err = core::io::SDOTransfer(node, transferBuffArray, 2, CO_DEV(0x2100,0x02)); /* Check if the SDO transfer was successfully started. */ if (err == CO_ERR_NONE) { @@ -28,9 +49,11 @@ void SDOCanNode::SDO_Transfer(CO_NODE &node) { } void SDOCanNode::SDO_Receive(CO_NODE &node) { - /* Initiate an SDO receive operation, reading data into sampleDataArray + static uint8_t receiveBuffArray[1]; + + /* Initiate an SDO receive operation, reading data into sampleDataA address * from object dictionary entry 0x2100:01. */ - CO_ERR err = core::io::SDOReceive(node, sampleDataArray, 1, CO_DEV(0x2100,0x01)); + CO_ERR err = core::io::SDOReceive(node, receiveBuffArray, 1, CO_DEV(0x2100,0x01), AppCSdoCallback() ); /* Check if the SDO receive operation was successfully started. */ if (err == CO_ERR_NONE) { @@ -44,21 +67,6 @@ void SDOCanNode::SDO_Receive(CO_NODE &node) { } } -uint8_t SDOCanNode::getSampleDataA() { - return sampleDataA; -} - -uint16_t SDOCanNode::getSampleDataB() { - return sampleDataB; -} - -void SDOCanNode::update() { - sampleDataA++; - if (sampleDataA % 20 == 0) { - sampleDataB *= 3; - } -} - CO_OBJ_T* SDOCanNode::getObjectDictionary() { return &objectDictionary[0]; } diff --git a/samples/canopen/canopen_sdo/SDOCanNode.hpp b/samples/canopen/canopen_sdo/SDOCanNode.hpp index 8387bb27..9ba78fad 100644 --- a/samples/canopen/canopen_sdo/SDOCanNode.hpp +++ b/samples/canopen/canopen_sdo/SDOCanNode.hpp @@ -2,10 +2,8 @@ #include #include -#include #include #include -#include /** * Representation of the CAN node. Handles constructing the object @@ -36,19 +34,6 @@ class SDOCanNode : public CANDevice { */ void SDO_Receive(CO_NODE &node); - /** - * Get the contained sample data - * - * @return The value of the sample data - */ - uint8_t getSampleDataA(); - uint16_t getSampleDataB(); - - /** - * increments counters up - */ - void update(); - /** * Get a pointer to the start of the object dictionary * @@ -86,7 +71,8 @@ class SDOCanNode : public CANDevice { */ uint8_t sampleDataA; uint16_t sampleDataB; - uint8_t sampleDataArray[2] = {0, 0}; + + uint8_t transferBuffArray[2]{}; /** * Have to know the size of the object dictionary for initialization diff --git a/samples/canopen/canopen_sdo/main.cpp b/samples/canopen/canopen_sdo/main.cpp index bfe9c58b..234d5456 100644 --- a/samples/canopen/canopen_sdo/main.cpp +++ b/samples/canopen/canopen_sdo/main.cpp @@ -103,19 +103,19 @@ int main() { /////////////////////////////////////////////////////////////////////////// // Main loop /////////////////////////////////////////////////////////////////////////// - uint32_t last_update_1 = HAL_GetTick(); - uint32_t last_update_2 = HAL_GetTick(); + uint32_t lastUpdate1 = HAL_GetTick(); + uint32_t lastUpdate2 = HAL_GetTick(); while (1) { - if((HAL_GetTick() - last_update_1) >= 1000 ){ // If 1000ms have passed receive CAN message. + if((HAL_GetTick() - lastUpdate1) >= 1000 ){ // If 1000ms have passed receive CAN message. testCanNode.SDO_Receive(canNode); - last_update_1 = HAL_GetTick(); // Set to current time. - } - else if((HAL_GetTick() - last_update_2) >= 5000 ){ // If 5000ms have passed write CAN message. - testCanNode.SDO_Transfer(canNode); - last_update_2 = HAL_GetTick(); // Set to current time. + lastUpdate1 = HAL_GetTick(); // Set to current time. } + // else if((HAL_GetTick() - lastUpdate2) >= 5000 ){ // If 5000ms have passed write CAN message. + // testCanNode.SDO_Transfer(canNode); + // lastUpdate2 = HAL_GetTick(); // Set to current time. + // } io::processCANopenNode(&canNode); // Wait for new data to come in diff --git a/samples/canopen/canopen_tpdo/main.cpp b/samples/canopen/canopen_tpdo/main.cpp index 9b112cfd..a54e80bb 100644 --- a/samples/canopen/canopen_tpdo/main.cpp +++ b/samples/canopen/canopen_tpdo/main.cpp @@ -3,6 +3,7 @@ * setup a CANopen node and attempt to make back and forth communication. */ +#include #include #include #include @@ -40,15 +41,16 @@ namespace log = core::log; // create a can interrupt handler void canInterrupt(io::CANMessage& message, void* priv) { auto* queue = (core::types::FixedQueue*) priv; + char messageString[50]; // print out raw received data - log::LOGGER.log(log::Logger::LogLevel::INFO, "Got RAW message from %X of length %d with data: ", message.getId(), message.getDataLength()); + snprintf(&messageString[5], 6, "Got RAW message from %X of length %d with data: ", message.getId(), message.getDataLength()); uint8_t* data = message.getPayload(); for (int i = 0; i < message.getDataLength(); i++) { - log::LOGGER.log(log::Logger::LogLevel::INFO, "%X ", *data); + snprintf(&messageString[i * 5], 1, "%X ", *data); data++; } - log::LOGGER.log(log::Logger::LogLevel::INFO, "\r\n"); + log::LOGGER.log(log::Logger::LogLevel::INFO,"\r\n\t%s\r\n", messageString); if (queue != nullptr) queue->append(message); @@ -56,13 +58,15 @@ void canInterrupt(io::CANMessage& message, void* priv) { // setup a TPDO event handler to print the raw TPDO message when sending extern "C" void COPdoTransmit(CO_IF_FRM* frm) { - log::LOGGER.log(log::Logger::LogLevel::INFO, "Sending PDO as 0x%X with length %d and data: ", frm->Identifier, frm->DLC); + char messageString[50]; + snprintf(&messageString[5], 6, "Sending PDO as 0x%X with length %d and data: ", frm->Identifier, frm->DLC); + uint8_t* data = frm->Data; for (int i = 0; i < frm->DLC; i++) { - log::LOGGER.log(log::Logger::LogLevel::INFO, "%X ", *data); + snprintf(&messageString[i * 5], 1, "%X ", *data); data++; } - log::LOGGER.log(log::Logger::LogLevel::INFO, "\r\n"); + log::LOGGER.log(log::Logger::LogLevel::INFO,"\r\n\t%s\r\n", messageString); } int main() { diff --git a/src/core/io/CANopen.cpp b/src/core/io/CANopen.cpp index 2992cb03..b80957f9 100644 --- a/src/core/io/CANopen.cpp +++ b/src/core/io/CANopen.cpp @@ -1,6 +1,7 @@ #include #include #include +#include #include @@ -31,6 +32,11 @@ uint8_t testerStorage[MAX_SIZE]; // Queue that stores the CAN messages to send to the CANopen parser core::types::FixedQueue* canQueue; + +// SDO variables +void* callBackContext; +void (*callback)(CO_CSDO *csdo, uint16_t index, uint8_t sub, uint32_t code); + } // namespace /////////////////////////////////////////////////////////////////////////////// @@ -151,13 +157,13 @@ CO_ERR SDOTransfer(CO_NODE &node, uint8_t *data, uint8_t size, uint32_t entry) { */ CO_ERR err = COCSdoRequestDownload(csdo, entry, data, size, - AppCSdoTransferCb, 1000); + callback, 1000); /* Return the result of the SDO transfer operation. */ return err; } -CO_ERR SDOReceive(CO_NODE &node, uint8_t *data, uint8_t size, uint32_t entry) { +CO_ERR SDOReceive(CO_NODE &node, uint8_t *data, uint8_t size, uint32_t entry, void (*AppCallback)(CO_CSDO *csdo, uint16_t index, uint8_t size, uint32_t entry)){ /** * Find the Client-SDO (CO_CSDO) object for the specified node. * @param node[in] is the CANopen node to operate on. @@ -165,6 +171,8 @@ CO_ERR SDOReceive(CO_NODE &node, uint8_t *data, uint8_t size, uint32_t entry) { */ CO_CSDO *csdo = COCSdoFind(&(node), 0); + core::io::registerCallBack(AppCallback); + /** * Initiate an SDO upload request. * @param csdo[in] is the client-SDO object. @@ -177,36 +185,16 @@ CO_ERR SDOReceive(CO_NODE &node, uint8_t *data, uint8_t size, uint32_t entry) { */ CO_ERR err = COCSdoRequestUpload(csdo, entry, data, size, - AppCSdoReceiveCb, 1000); + callback, 1000); /* Return the result of the SDO receive operation. */ return err; } -/* The application specific SDO transfer finalization callback */ -void AppCSdoTransferCb(CO_CSDO *csdo, uint16_t index, uint8_t sub, uint32_t code) -{ - if (code == 0) { - /* read data is available in 'readValue' */ - log::LOGGER.log(log::Logger::LogLevel::INFO, "Value transferred %x, %x\r\n", csdo->Tfer.Buf[0], csdo->Tfer.Buf[1]); - } - else { - /* a timeout or abort is detected during SDO transfer */ - log::LOGGER.log(log::Logger::LogLevel::ERROR, "SDO callback don goofed 0x%x\r\n", code); - } -} - -/* The application specific SDO receive finalization callback */ -void AppCSdoReceiveCb(CO_CSDO *csdo, uint16_t index, uint8_t sub, uint32_t code) -{ - if (code == 0) { - /* read data is available in 'readValue' */ - log::LOGGER.log(log::Logger::LogLevel::INFO, "Value received %x, %x\r\n", csdo->Tfer.Buf[0], csdo->Tfer.Buf[1]); - } - else { - /* a timeout or abort is detected during SDO transfer */ - log::LOGGER.log(log::Logger::LogLevel::ERROR, "SDO callback don goofed 0x%x\r\n", code); - } +void registerCallBack(void (*AppCallback)(CO_CSDO *csdo, uint16_t index, uint8_t size, uint32_t entry)) { + // Assign parameter AppCallback to callback. + callback = AppCallback; + // callBackContext = context; } } // namespace core::io From 8a9b880e66f32e71e48bd7f68a79047bc4716cc3 Mon Sep 17 00:00:00 2001 From: DiegoLHendrix <119289719+DiegoLHendrix@users.noreply.github.com> Date: Tue, 17 Dec 2024 16:20:42 -0500 Subject: [PATCH 12/17] I am the Oppenheimer of CAN --- include/core/io/CANopen.hpp | 39 ++++++++++------- samples/canopen/canopen_sdo/SDOCanNode.cpp | 49 +++++++++++++++------- samples/canopen/canopen_sdo/SDOCanNode.hpp | 18 ++++++++ samples/canopen/canopen_sdo/main.cpp | 8 ++-- src/core/io/CANopen.cpp | 13 +++--- 5 files changed, 88 insertions(+), 39 deletions(-) diff --git a/include/core/io/CANopen.hpp b/include/core/io/CANopen.hpp index 104b7d14..183388d6 100644 --- a/include/core/io/CANopen.hpp +++ b/include/core/io/CANopen.hpp @@ -97,28 +97,39 @@ void initializeCANopenNode(CO_NODE* canNode, CANDevice* canDevice, CO_IF_DRV* ca void processCANopenNode(CO_NODE* canNode); /** - * Update Object Dictionary entry + * This function sets up and starts an SDO download (write) request to transfer data + * to the specified object dictionary entry on the target CANopen node. * - * @param node[in] The SDO node - * @param sampleDataArray[in] The value to set sample data to + * @param node[in] Reference to the CANopen node object + * @param data[in] Pointer to the data buffer that holds the data to send + * @param size[in] Size of the data to transfer in bytes + * @param entry[in] Object dictionary entry (index + subindex) to write to + * @param AppCallback[in] Callback function when the transfer completes + * @return CO_ERR[out] Returns the result of the transfer operation */ -CO_ERR SDOTransfer(CO_NODE &node, uint8_t *data, uint8_t size, uint32_t entry); +CO_ERR SDOTransfer(CO_NODE &node, uint8_t *data, uint8_t size, uint32_t entry, void (*AppCallback)(CO_CSDO *csdo, uint16_t index, uint8_t size, uint32_t entry)); /** - * Read Object Dictionary entry - * - * @param node[in] The SDO node - * @param sampleDataArray[in] The value to set sample data to - */ -CO_ERR SDOReceive(CO_NODE &node, uint8_t *data, uint8_t size, uint32_t entry, void (*AppCallback)(CO_NODE &node)); +* This function starts an SDO upload (read) request to fetch data from the specified +* object dictionary entry on the target CANopen node +* +* @param node[in] Reference to the CANopen node object +* @param data[in] Pointer to the buffer where received data will be stored +* @param size[in] Size of the buffer provided to receive data +* @param entry[in] Object dictionary entry (index + subindex) to read from +* @param AppCallback[in] Callback function when the receive completes +* @return CO_ERR[out] Returns the result of the receive operation +*/ +CO_ERR SDOReceive(CO_NODE &node, uint8_t *data, uint8_t size, uint32_t entry, void (*AppCallback)(CO_CSDO *csdo, uint16_t index, uint8_t size, uint32_t entry)); /** - * Register a callback method for sdo + * This function assigns the user-provided callback function and AppContext to be + * used when an SDO operation completes * - * @param AppCallback[in] The SDO callback method that will be registered. See AppCSdoCallback method for explanation of parameters - * @param context[in] The context of the application + * @param AppCallback[in] Pointer to the callback function to register + * @param AppContext[in] Context to be passed to the callback */ -void registerCallBack(void (*AppCallback)(CO_CSDO *csdo, uint16_t index, uint8_t size, uint32_t entry)); +void registerCallBack(void (*AppCallback)(CO_CSDO *csdo, uint16_t index, uint8_t size, uint32_t entry), void* AppContext); } // namespace core::io #endif diff --git a/samples/canopen/canopen_sdo/SDOCanNode.cpp b/samples/canopen/canopen_sdo/SDOCanNode.cpp index 38f4caf4..9b27ec0a 100644 --- a/samples/canopen/canopen_sdo/SDOCanNode.cpp +++ b/samples/canopen/canopen_sdo/SDOCanNode.cpp @@ -1,5 +1,6 @@ #include "SDOCanNode.hpp" #include +#include SDOCanNode::SDOCanNode() { sampleDataA = 0; @@ -8,22 +9,36 @@ SDOCanNode::SDOCanNode() { transferBuffArray[1] = 0; } -/** - * The application-specific callback function for finalizing an SDO transfer/receive operation. - * @param csdo[in] is the client-SDO object. - * @param index[in] is the object dictionary index. - * @param sub[in] is the object dictionary subindex. - * @param code[in] indicates the completion status of the operation (0 for success, error code otherwise). - */ -void AppCSdoCallback(CO_CSDO *csdo, uint16_t index, uint8_t sub, uint32_t code) { +void SDOCanNode::SdoReceiveCallback(CO_CSDO *csdo, uint16_t index, uint8_t sub, uint32_t code) { + char messageString[50]; if (code == 0) { /* read data is available in 'readValue' */ - log::LOGGER.log(log::Logger::LogLevel::INFO, "Value transferred %x, %x\r\n", csdo->Tfer.Buf[0], csdo->Tfer.Buf[1]); + snprintf(&messageString[0], 25, "Value received %x, %x\r\n", csdo->Tfer.Buf[0], csdo->Tfer.Buf[1]); } else { /* a timeout or abort is detected during SDO transfer */ - log::LOGGER.log(log::Logger::LogLevel::ERROR, "SDO callback don goofed 0x%x\r\n", code); + snprintf(&messageString[0], 25, "SDO receive callback don goofed 0x%x\r\n", code); } + + log::LOGGER.log(log::Logger::LogLevel::DEBUG, + "SDO Receive Operation: \r\n\t%s\r\n", + messageString); +} + +void SDOCanNode::SdoTransferCallback(CO_CSDO *csdo, uint16_t index, uint8_t sub, uint32_t code) { + char messageString[50]; + if (code == 0) { + /* read data is available in 'readValue' */ + snprintf(&messageString[0], 25, "Value transferred %x, %x\r\n", csdo->Tfer.Buf[0], csdo->Tfer.Buf[1]); + } + else { + /* a timeout or abort is detected during SDO transfer */ + snprintf(&messageString[0], 25, "SDO transfer callback don goofed 0x%x\r\n", code); + } + + log::LOGGER.log(log::Logger::LogLevel::DEBUG, + "SDO Transfer Operation: \r\n\t%s\r\n", + messageString); } void SDOCanNode::SDO_Transfer(CO_NODE &node) { @@ -33,8 +48,10 @@ void SDOCanNode::SDO_Transfer(CO_NODE &node) { transferBuffArray[1] = transferBuffArray[0] * 2; /* Initiate an SDO transfer using the specified node and transferBuffArray, - * targeting object dictionary entry 0x2100:02. */ - CO_ERR err = core::io::SDOTransfer(node, transferBuffArray, 2, CO_DEV(0x2100,0x02)); + * targeting object dictionary entry 0x2100:02. + * Pass in the SDOTransfer operation callback function. + */ + CO_ERR err = core::io::SDOTransfer(node, transferBuffArray, 2, CO_DEV(0x2100,0x02), SdoTransferCallback); /* Check if the SDO transfer was successfully started. */ if (err == CO_ERR_NONE) { @@ -51,9 +68,11 @@ void SDOCanNode::SDO_Transfer(CO_NODE &node) { void SDOCanNode::SDO_Receive(CO_NODE &node) { static uint8_t receiveBuffArray[1]; - /* Initiate an SDO receive operation, reading data into sampleDataA address - * from object dictionary entry 0x2100:01. */ - CO_ERR err = core::io::SDOReceive(node, receiveBuffArray, 1, CO_DEV(0x2100,0x01), AppCSdoCallback() ); + /* Initiate an SDO receive operation, reading data into receiveBuffArray address + * from object dictionary entry 0x2100:01. + * Pass in the SDOReceive operation callback function. + */ + CO_ERR err = core::io::SDOReceive(node, receiveBuffArray, 1, CO_DEV(0x2100, 0x01), SdoReceiveCallback); /* Check if the SDO receive operation was successfully started. */ if (err == CO_ERR_NONE) { diff --git a/samples/canopen/canopen_sdo/SDOCanNode.hpp b/samples/canopen/canopen_sdo/SDOCanNode.hpp index 9ba78fad..7e08089d 100644 --- a/samples/canopen/canopen_sdo/SDOCanNode.hpp +++ b/samples/canopen/canopen_sdo/SDOCanNode.hpp @@ -20,6 +20,24 @@ class SDOCanNode : public CANDevice { public: SDOCanNode(); + /** + * The application-specific callback function for finalizing an SDO receive operation. + * @param csdo[in] is the client-SDO object. + * @param index[in] is the object dictionary index. + * @param sub[in] is the object dictionary subindex. + * @param code[in] indicates the completion status of the operation (0 for success, error code otherwise). + */ + static void SdoReceiveCallback(CO_CSDO *csdo, uint16_t index, uint8_t sub, uint32_t code); + + /** + * The application-specific callback function for finalizing an SDO transfer operation. + * @param csdo[in] is the client-SDO object. + * @param index[in] is the object dictionary index. + * @param sub[in] is the object dictionary subindex. + * @param code[in] indicates the completion status of the operation (0 for success, error code otherwise). + */ + static void SdoTransferCallback(CO_CSDO *csdo, uint16_t index, uint8_t sub, uint32_t code); + /** * Update Object Dictionary entry * diff --git a/samples/canopen/canopen_sdo/main.cpp b/samples/canopen/canopen_sdo/main.cpp index 234d5456..4799f0f3 100644 --- a/samples/canopen/canopen_sdo/main.cpp +++ b/samples/canopen/canopen_sdo/main.cpp @@ -112,10 +112,10 @@ int main() { testCanNode.SDO_Receive(canNode); lastUpdate1 = HAL_GetTick(); // Set to current time. } - // else if((HAL_GetTick() - lastUpdate2) >= 5000 ){ // If 5000ms have passed write CAN message. - // testCanNode.SDO_Transfer(canNode); - // lastUpdate2 = HAL_GetTick(); // Set to current time. - // } + else if((HAL_GetTick() - lastUpdate2) >= 5000 ){ // If 5000ms have passed write CAN message. + testCanNode.SDO_Transfer(canNode); + lastUpdate2 = HAL_GetTick(); // Set to current time. + } io::processCANopenNode(&canNode); // Wait for new data to come in diff --git a/src/core/io/CANopen.cpp b/src/core/io/CANopen.cpp index b80957f9..0012c4c2 100644 --- a/src/core/io/CANopen.cpp +++ b/src/core/io/CANopen.cpp @@ -34,7 +34,7 @@ uint8_t testerStorage[MAX_SIZE]; core::types::FixedQueue* canQueue; // SDO variables -void* callBackContext; +void* context; void (*callback)(CO_CSDO *csdo, uint16_t index, uint8_t sub, uint32_t code); } // namespace @@ -137,7 +137,7 @@ void processCANopenNode(CO_NODE* canNode) { COTmrProcess(&canNode->Tmr); } -CO_ERR SDOTransfer(CO_NODE &node, uint8_t *data, uint8_t size, uint32_t entry) { +CO_ERR SDOTransfer(CO_NODE &node, uint8_t *data, uint8_t size, uint32_t entry, void (*AppCallback)(CO_CSDO *csdo, uint16_t index, uint8_t size, uint32_t entry)) { /** * Find the Client-SDO (CO_CSDO) object for the specified node. * @param node[in] is the CANopen node to operate on. @@ -145,6 +145,8 @@ CO_ERR SDOTransfer(CO_NODE &node, uint8_t *data, uint8_t size, uint32_t entry) { */ CO_CSDO *csdo = COCSdoFind(&(node), 0); + core::io::registerCallBack(AppCallback, reinterpret_cast(csdo)); // Register callback function + /** * Initiate an SDO download request. * @param csdo[in] is the client-SDO object. @@ -171,7 +173,7 @@ CO_ERR SDOReceive(CO_NODE &node, uint8_t *data, uint8_t size, uint32_t entry, vo */ CO_CSDO *csdo = COCSdoFind(&(node), 0); - core::io::registerCallBack(AppCallback); + core::io::registerCallBack(AppCallback, reinterpret_cast(csdo)); // Register callback function /** * Initiate an SDO upload request. @@ -191,10 +193,9 @@ CO_ERR SDOReceive(CO_NODE &node, uint8_t *data, uint8_t size, uint32_t entry, vo return err; } -void registerCallBack(void (*AppCallback)(CO_CSDO *csdo, uint16_t index, uint8_t size, uint32_t entry)) { - // Assign parameter AppCallback to callback. +void registerCallBack(void (*AppCallback)(CO_CSDO *csdo, uint16_t index, uint8_t size, uint32_t entry), void* AppContext) { callback = AppCallback; - // callBackContext = context; + context = AppContext; } } // namespace core::io From ff170433333f64313d8bc48c174b797b0c938be5 Mon Sep 17 00:00:00 2001 From: GitHub Build Date: Tue, 17 Dec 2024 21:31:31 +0000 Subject: [PATCH 13/17] Applied Formatting Changes During GitHub Build --- include/core/io/CANopen.hpp | 31 +++---- samples/canopen/canopen_rpdo/main.cpp | 7 +- samples/canopen/canopen_sdo/SDOCanNode.cpp | 28 +++---- samples/canopen/canopen_sdo/SDOCanNode.hpp | 13 +-- samples/canopen/canopen_sdo/main.cpp | 17 ++-- samples/canopen/canopen_tpdo/main.cpp | 15 ++-- src/core/io/CANopen.cpp | 95 +++++++++++----------- 7 files changed, 104 insertions(+), 102 deletions(-) diff --git a/include/core/io/CANopen.hpp b/include/core/io/CANopen.hpp index 183388d6..ae897b8e 100644 --- a/include/core/io/CANopen.hpp +++ b/include/core/io/CANopen.hpp @@ -13,8 +13,8 @@ #include #include #include -#include #include +#include // Allows for resizable CANOpen queue if needed #ifndef CANOPEN_QUEUE_SIZE @@ -107,20 +107,22 @@ void processCANopenNode(CO_NODE* canNode); * @param AppCallback[in] Callback function when the transfer completes * @return CO_ERR[out] Returns the result of the transfer operation */ -CO_ERR SDOTransfer(CO_NODE &node, uint8_t *data, uint8_t size, uint32_t entry, void (*AppCallback)(CO_CSDO *csdo, uint16_t index, uint8_t size, uint32_t entry)); +CO_ERR SDOTransfer(CO_NODE& node, uint8_t* data, uint8_t size, uint32_t entry, + void (*AppCallback)(CO_CSDO* csdo, uint16_t index, uint8_t size, uint32_t entry)); /** -* This function starts an SDO upload (read) request to fetch data from the specified -* object dictionary entry on the target CANopen node -* -* @param node[in] Reference to the CANopen node object -* @param data[in] Pointer to the buffer where received data will be stored -* @param size[in] Size of the buffer provided to receive data -* @param entry[in] Object dictionary entry (index + subindex) to read from -* @param AppCallback[in] Callback function when the receive completes -* @return CO_ERR[out] Returns the result of the receive operation -*/ -CO_ERR SDOReceive(CO_NODE &node, uint8_t *data, uint8_t size, uint32_t entry, void (*AppCallback)(CO_CSDO *csdo, uint16_t index, uint8_t size, uint32_t entry)); + * This function starts an SDO upload (read) request to fetch data from the specified + * object dictionary entry on the target CANopen node + * + * @param node[in] Reference to the CANopen node object + * @param data[in] Pointer to the buffer where received data will be stored + * @param size[in] Size of the buffer provided to receive data + * @param entry[in] Object dictionary entry (index + subindex) to read from + * @param AppCallback[in] Callback function when the receive completes + * @return CO_ERR[out] Returns the result of the receive operation + */ +CO_ERR SDOReceive(CO_NODE& node, uint8_t* data, uint8_t size, uint32_t entry, + void (*AppCallback)(CO_CSDO* csdo, uint16_t index, uint8_t size, uint32_t entry)); /** * This function assigns the user-provided callback function and AppContext to be @@ -129,7 +131,8 @@ CO_ERR SDOReceive(CO_NODE &node, uint8_t *data, uint8_t size, uint32_t entry, vo * @param AppCallback[in] Pointer to the callback function to register * @param AppContext[in] Context to be passed to the callback */ -void registerCallBack(void (*AppCallback)(CO_CSDO *csdo, uint16_t index, uint8_t size, uint32_t entry), void* AppContext); +void registerCallBack(void (*AppCallback)(CO_CSDO* csdo, uint16_t index, uint8_t size, uint32_t entry), + void* AppContext); } // namespace core::io #endif diff --git a/samples/canopen/canopen_rpdo/main.cpp b/samples/canopen/canopen_rpdo/main.cpp index e721d014..2c38fd64 100644 --- a/samples/canopen/canopen_rpdo/main.cpp +++ b/samples/canopen/canopen_rpdo/main.cpp @@ -9,9 +9,9 @@ #include #include #include +#include #include #include -#include #include @@ -43,7 +43,10 @@ void canInterrupt(io::CANMessage& message, void* priv) { auto* queue = (core::types::FixedQueue*) priv; // print out raw received data - log::LOGGER.log(log::Logger::LogLevel::INFO, "Got RAW message from %X of length %d with data: ", message.getId(), message.getDataLength()); + log::LOGGER.log(log::Logger::LogLevel::INFO, + "Got RAW message from %X of length %d with data: ", + message.getId(), + message.getDataLength()); uint8_t* data = message.getPayload(); for (int i = 0; i < message.getDataLength(); i++) { log::LOGGER.log(log::Logger::LogLevel::INFO, "%X ", *data); diff --git a/samples/canopen/canopen_sdo/SDOCanNode.cpp b/samples/canopen/canopen_sdo/SDOCanNode.cpp index 9b27ec0a..865379bc 100644 --- a/samples/canopen/canopen_sdo/SDOCanNode.cpp +++ b/samples/canopen/canopen_sdo/SDOCanNode.cpp @@ -3,45 +3,39 @@ #include SDOCanNode::SDOCanNode() { - sampleDataA = 0; - sampleDataB = 0; + sampleDataA = 0; + sampleDataB = 0; transferBuffArray[0] = 0; transferBuffArray[1] = 0; } -void SDOCanNode::SdoReceiveCallback(CO_CSDO *csdo, uint16_t index, uint8_t sub, uint32_t code) { +void SDOCanNode::SdoReceiveCallback(CO_CSDO* csdo, uint16_t index, uint8_t sub, uint32_t code) { char messageString[50]; if (code == 0) { /* read data is available in 'readValue' */ snprintf(&messageString[0], 25, "Value received %x, %x\r\n", csdo->Tfer.Buf[0], csdo->Tfer.Buf[1]); - } - else { + } else { /* a timeout or abort is detected during SDO transfer */ snprintf(&messageString[0], 25, "SDO receive callback don goofed 0x%x\r\n", code); } - log::LOGGER.log(log::Logger::LogLevel::DEBUG, - "SDO Receive Operation: \r\n\t%s\r\n", - messageString); + log::LOGGER.log(log::Logger::LogLevel::DEBUG, "SDO Receive Operation: \r\n\t%s\r\n", messageString); } -void SDOCanNode::SdoTransferCallback(CO_CSDO *csdo, uint16_t index, uint8_t sub, uint32_t code) { +void SDOCanNode::SdoTransferCallback(CO_CSDO* csdo, uint16_t index, uint8_t sub, uint32_t code) { char messageString[50]; if (code == 0) { /* read data is available in 'readValue' */ snprintf(&messageString[0], 25, "Value transferred %x, %x\r\n", csdo->Tfer.Buf[0], csdo->Tfer.Buf[1]); - } - else { + } else { /* a timeout or abort is detected during SDO transfer */ snprintf(&messageString[0], 25, "SDO transfer callback don goofed 0x%x\r\n", code); } - log::LOGGER.log(log::Logger::LogLevel::DEBUG, - "SDO Transfer Operation: \r\n\t%s\r\n", - messageString); + log::LOGGER.log(log::Logger::LogLevel::DEBUG, "SDO Transfer Operation: \r\n\t%s\r\n", messageString); } -void SDOCanNode::SDO_Transfer(CO_NODE &node) { +void SDOCanNode::SDO_Transfer(CO_NODE& node) { /* Increment the first element of transferBuffArray by 1. */ transferBuffArray[0]++; /* Set the second element of transferBuffArray to twice the new value of the first element. */ @@ -51,7 +45,7 @@ void SDOCanNode::SDO_Transfer(CO_NODE &node) { * targeting object dictionary entry 0x2100:02. * Pass in the SDOTransfer operation callback function. */ - CO_ERR err = core::io::SDOTransfer(node, transferBuffArray, 2, CO_DEV(0x2100,0x02), SdoTransferCallback); + CO_ERR err = core::io::SDOTransfer(node, transferBuffArray, 2, CO_DEV(0x2100, 0x02), SdoTransferCallback); /* Check if the SDO transfer was successfully started. */ if (err == CO_ERR_NONE) { @@ -65,7 +59,7 @@ void SDOCanNode::SDO_Transfer(CO_NODE &node) { } } -void SDOCanNode::SDO_Receive(CO_NODE &node) { +void SDOCanNode::SDO_Receive(CO_NODE& node) { static uint8_t receiveBuffArray[1]; /* Initiate an SDO receive operation, reading data into receiveBuffArray address diff --git a/samples/canopen/canopen_sdo/SDOCanNode.hpp b/samples/canopen/canopen_sdo/SDOCanNode.hpp index 7e08089d..89dd9156 100644 --- a/samples/canopen/canopen_sdo/SDOCanNode.hpp +++ b/samples/canopen/canopen_sdo/SDOCanNode.hpp @@ -1,5 +1,5 @@ -#include #include +#include #include #include @@ -27,7 +27,7 @@ class SDOCanNode : public CANDevice { * @param sub[in] is the object dictionary subindex. * @param code[in] indicates the completion status of the operation (0 for success, error code otherwise). */ - static void SdoReceiveCallback(CO_CSDO *csdo, uint16_t index, uint8_t sub, uint32_t code); + static void SdoReceiveCallback(CO_CSDO* csdo, uint16_t index, uint8_t sub, uint32_t code); /** * The application-specific callback function for finalizing an SDO transfer operation. @@ -36,21 +36,21 @@ class SDOCanNode : public CANDevice { * @param sub[in] is the object dictionary subindex. * @param code[in] indicates the completion status of the operation (0 for success, error code otherwise). */ - static void SdoTransferCallback(CO_CSDO *csdo, uint16_t index, uint8_t sub, uint32_t code); + static void SdoTransferCallback(CO_CSDO* csdo, uint16_t index, uint8_t sub, uint32_t code); /** * Update Object Dictionary entry * * @param node[in] The canopen node to write to */ - void SDO_Transfer(CO_NODE &node); + void SDO_Transfer(CO_NODE& node); /** * Read Object Dictionary entry * * @param node[in] The canopen node to read from */ - void SDO_Receive(CO_NODE &node); + void SDO_Receive(CO_NODE& node); /** * Get a pointer to the start of the object dictionary @@ -122,7 +122,8 @@ class SDOCanNode : public CANDevice { .Type = CO_TUNSIGNED32, .Data = (CO_DATA) CO_COBID_SDO_REQUEST(), }, - { /* SDO Server Response COBID */ + { + /* SDO Server Response COBID */ .Key = CO_KEY(0x1280, 0x02, CO_OBJ_D___R_), .Type = CO_TUNSIGNED32, .Data = (CO_DATA) CO_COBID_SDO_RESPONSE(), diff --git a/samples/canopen/canopen_sdo/main.cpp b/samples/canopen/canopen_sdo/main.cpp index 4799f0f3..6f69fef2 100644 --- a/samples/canopen/canopen_sdo/main.cpp +++ b/samples/canopen/canopen_sdo/main.cpp @@ -1,7 +1,7 @@ /** -* This sample shows off CANopen support from EVT-core. This will -* setup a CANopen node and attempt to make back and forth communication. -*/ + * This sample shows off CANopen support from EVT-core. This will + * setup a CANopen node and attempt to make back and forth communication. + */ #include #include @@ -108,14 +108,13 @@ int main() { while (1) { - if((HAL_GetTick() - lastUpdate1) >= 1000 ){ // If 1000ms have passed receive CAN message. + if ((HAL_GetTick() - lastUpdate1) >= 1000) { // If 1000ms have passed receive CAN message. testCanNode.SDO_Receive(canNode); - lastUpdate1 = HAL_GetTick(); // Set to current time. + lastUpdate1 = HAL_GetTick(); // Set to current time. + } else if ((HAL_GetTick() - lastUpdate2) >= 5000) { // If 5000ms have passed write CAN message. + testCanNode.SDO_Transfer(canNode); + lastUpdate2 = HAL_GetTick(); // Set to current time. } - else if((HAL_GetTick() - lastUpdate2) >= 5000 ){ // If 5000ms have passed write CAN message. - testCanNode.SDO_Transfer(canNode); - lastUpdate2 = HAL_GetTick(); // Set to current time. - } io::processCANopenNode(&canNode); // Wait for new data to come in diff --git a/samples/canopen/canopen_tpdo/main.cpp b/samples/canopen/canopen_tpdo/main.cpp index a54e80bb..855c02f5 100644 --- a/samples/canopen/canopen_tpdo/main.cpp +++ b/samples/canopen/canopen_tpdo/main.cpp @@ -3,14 +3,14 @@ * setup a CANopen node and attempt to make back and forth communication. */ -#include #include #include #include #include +#include #include #include -#include +#include #include @@ -37,20 +37,23 @@ namespace log = core::log; * @param message[in] The passed in CAN message that was read. */ - // create a can interrupt handler void canInterrupt(io::CANMessage& message, void* priv) { auto* queue = (core::types::FixedQueue*) priv; char messageString[50]; // print out raw received data - snprintf(&messageString[5], 6, "Got RAW message from %X of length %d with data: ", message.getId(), message.getDataLength()); + snprintf(&messageString[5], + 6, + "Got RAW message from %X of length %d with data: ", + message.getId(), + message.getDataLength()); uint8_t* data = message.getPayload(); for (int i = 0; i < message.getDataLength(); i++) { snprintf(&messageString[i * 5], 1, "%X ", *data); data++; } - log::LOGGER.log(log::Logger::LogLevel::INFO,"\r\n\t%s\r\n", messageString); + log::LOGGER.log(log::Logger::LogLevel::INFO, "\r\n\t%s\r\n", messageString); if (queue != nullptr) queue->append(message); @@ -66,7 +69,7 @@ extern "C" void COPdoTransmit(CO_IF_FRM* frm) { snprintf(&messageString[i * 5], 1, "%X ", *data); data++; } - log::LOGGER.log(log::Logger::LogLevel::INFO,"\r\n\t%s\r\n", messageString); + log::LOGGER.log(log::Logger::LogLevel::INFO, "\r\n\t%s\r\n", messageString); } int main() { diff --git a/src/core/io/CANopen.cpp b/src/core/io/CANopen.cpp index 0012c4c2..ab91898e 100644 --- a/src/core/io/CANopen.cpp +++ b/src/core/io/CANopen.cpp @@ -1,7 +1,7 @@ +#include #include #include #include -#include #include @@ -35,7 +35,7 @@ core::types::FixedQueue* canQueue; // SDO variables void* context; -void (*callback)(CO_CSDO *csdo, uint16_t index, uint8_t sub, uint32_t code); +void (*callback)(CO_CSDO* csdo, uint16_t index, uint8_t sub, uint32_t code); } // namespace @@ -137,65 +137,64 @@ void processCANopenNode(CO_NODE* canNode) { COTmrProcess(&canNode->Tmr); } -CO_ERR SDOTransfer(CO_NODE &node, uint8_t *data, uint8_t size, uint32_t entry, void (*AppCallback)(CO_CSDO *csdo, uint16_t index, uint8_t size, uint32_t entry)) { - /** - * Find the Client-SDO (CO_CSDO) object for the specified node. - * @param node[in] is the CANopen node to operate on. - * @return csdo[out] is the client-SDO object used to manage SDO communication. - */ - CO_CSDO *csdo = COCSdoFind(&(node), 0); +CO_ERR SDOTransfer(CO_NODE& node, uint8_t* data, uint8_t size, uint32_t entry, + void (*AppCallback)(CO_CSDO* csdo, uint16_t index, uint8_t size, uint32_t entry)) { + /** + * Find the Client-SDO (CO_CSDO) object for the specified node. + * @param node[in] is the CANopen node to operate on. + * @return csdo[out] is the client-SDO object used to manage SDO communication. + */ + CO_CSDO* csdo = COCSdoFind(&(node), 0); core::io::registerCallBack(AppCallback, reinterpret_cast(csdo)); // Register callback function - /** - * Initiate an SDO download request. - * @param csdo[in] is the client-SDO object. - * @param entry[in] specifies the object dictionary entry (index and subindex). - * @param data[in] is the pointer to the data to be sent. - * @param size[in] is the size of the data to be sent. - * @param AppCSdoTransferCb[in] is the callback function to be called upon transfer completion. - * @param 1000[in] is the timeout for the operation in milliseconds. - * @return err[out] indicates the result of the operation (success or error code). - */ - CO_ERR err = COCSdoRequestDownload(csdo, entry, - data, size, - callback, 1000); - - /* Return the result of the SDO transfer operation. */ + /** + * Initiate an SDO download request. + * @param csdo[in] is the client-SDO object. + * @param entry[in] specifies the object dictionary entry (index and subindex). + * @param data[in] is the pointer to the data to be sent. + * @param size[in] is the size of the data to be sent. + * @param AppCSdoTransferCb[in] is the callback function to be called upon transfer completion. + * @param 1000[in] is the timeout for the operation in milliseconds. + * @return err[out] indicates the result of the operation (success or error code). + */ + CO_ERR err = COCSdoRequestDownload(csdo, entry, data, size, callback, 1000); + + /* Return the result of the SDO transfer operation. */ return err; } -CO_ERR SDOReceive(CO_NODE &node, uint8_t *data, uint8_t size, uint32_t entry, void (*AppCallback)(CO_CSDO *csdo, uint16_t index, uint8_t size, uint32_t entry)){ - /** - * Find the Client-SDO (CO_CSDO) object for the specified node. - * @param node[in] is the CANopen node to operate on. - * @return csdo[out] is the client-SDO object used to manage SDO communication. - */ - CO_CSDO *csdo = COCSdoFind(&(node), 0); +CO_ERR SDOReceive(CO_NODE& node, uint8_t* data, uint8_t size, uint32_t entry, + void (*AppCallback)(CO_CSDO* csdo, uint16_t index, uint8_t size, uint32_t entry)) { + /** + * Find the Client-SDO (CO_CSDO) object for the specified node. + * @param node[in] is the CANopen node to operate on. + * @return csdo[out] is the client-SDO object used to manage SDO communication. + */ + CO_CSDO* csdo = COCSdoFind(&(node), 0); core::io::registerCallBack(AppCallback, reinterpret_cast(csdo)); // Register callback function - /** - * Initiate an SDO upload request. - * @param csdo[in] is the client-SDO object. - * @param entry[in] specifies the object dictionary entry (index and subindex). - * @param data[out] is the pointer to store the received data. - * @param size[in] is the size of the data buffer. - * @param AppCSdoReceiveCb[in] is the callback function to be called upon reception completion. - * @param 1000[in] is the timeout for the operation in milliseconds. - * @return err[out] indicates the result of the operation (success or error code). - */ - CO_ERR err = COCSdoRequestUpload(csdo, entry, - data, size, - callback, 1000); - - /* Return the result of the SDO receive operation. */ + /** + * Initiate an SDO upload request. + * @param csdo[in] is the client-SDO object. + * @param entry[in] specifies the object dictionary entry (index and subindex). + * @param data[out] is the pointer to store the received data. + * @param size[in] is the size of the data buffer. + * @param AppCSdoReceiveCb[in] is the callback function to be called upon reception completion. + * @param 1000[in] is the timeout for the operation in milliseconds. + * @return err[out] indicates the result of the operation (success or error code). + */ + CO_ERR err = COCSdoRequestUpload(csdo, entry, data, size, callback, 1000); + + /* Return the result of the SDO receive operation. */ return err; } -void registerCallBack(void (*AppCallback)(CO_CSDO *csdo, uint16_t index, uint8_t size, uint32_t entry), void* AppContext) { +void registerCallBack(void (*AppCallback)(CO_CSDO* csdo, uint16_t index, uint8_t size, uint32_t entry), + void* AppContext) { callback = AppCallback; - context = AppContext; + context = AppContext; } } // namespace core::io From 359df6644c41d8e99cdc596317f70892ec098731 Mon Sep 17 00:00:00 2001 From: DiegoLHendrix Date: Sat, 21 Dec 2024 13:06:50 -0500 Subject: [PATCH 14/17] Get me out of PR review hell --- samples/canopen/canopen_sdo/SDOCanNode.cpp | 18 ++++++++++-------- samples/canopen/canopen_sdo/SDOCanNode.hpp | 6 +++--- samples/canopen/canopen_sdo/main.cpp | 9 ++++----- 3 files changed, 17 insertions(+), 16 deletions(-) diff --git a/samples/canopen/canopen_sdo/SDOCanNode.cpp b/samples/canopen/canopen_sdo/SDOCanNode.cpp index 865379bc..b435468c 100644 --- a/samples/canopen/canopen_sdo/SDOCanNode.cpp +++ b/samples/canopen/canopen_sdo/SDOCanNode.cpp @@ -35,15 +35,16 @@ void SDOCanNode::SdoTransferCallback(CO_CSDO* csdo, uint16_t index, uint8_t sub, log::LOGGER.log(log::Logger::LogLevel::DEBUG, "SDO Transfer Operation: \r\n\t%s\r\n", messageString); } -void SDOCanNode::SDO_Transfer(CO_NODE& node) { +void SDOCanNode::transferData(CO_NODE& node) { /* Increment the first element of transferBuffArray by 1. */ transferBuffArray[0]++; /* Set the second element of transferBuffArray to twice the new value of the first element. */ transferBuffArray[1] = transferBuffArray[0] * 2; - /* Initiate an SDO transfer using the specified node and transferBuffArray, - * targeting object dictionary entry 0x2100:02. - * Pass in the SDOTransfer operation callback function. + /* + * Initiates an SDO transfer for the specified node using the provided + * transfer buffer array. Targets the object dictionary entry at index 0x2100, + * sub-index 0x02. Registers and executes the SDOTransferCallback function upon completion. */ CO_ERR err = core::io::SDOTransfer(node, transferBuffArray, 2, CO_DEV(0x2100, 0x02), SdoTransferCallback); @@ -59,12 +60,13 @@ void SDOCanNode::SDO_Transfer(CO_NODE& node) { } } -void SDOCanNode::SDO_Receive(CO_NODE& node) { +void SDOCanNode::receiveData(CO_NODE& node) { static uint8_t receiveBuffArray[1]; - /* Initiate an SDO receive operation, reading data into receiveBuffArray address - * from object dictionary entry 0x2100:01. - * Pass in the SDOReceive operation callback function. + /* + * Initiates an SDO receive operation for the specified node, reading data into + * the provided receive buffer array. Targets the object dictionary entry at + * index 0x2100, sub-index 0x01. Registers and executes the SDOReceiveCallback function upon completion. */ CO_ERR err = core::io::SDOReceive(node, receiveBuffArray, 1, CO_DEV(0x2100, 0x01), SdoReceiveCallback); diff --git a/samples/canopen/canopen_sdo/SDOCanNode.hpp b/samples/canopen/canopen_sdo/SDOCanNode.hpp index 89dd9156..017e6d3e 100644 --- a/samples/canopen/canopen_sdo/SDOCanNode.hpp +++ b/samples/canopen/canopen_sdo/SDOCanNode.hpp @@ -43,14 +43,14 @@ class SDOCanNode : public CANDevice { * * @param node[in] The canopen node to write to */ - void SDO_Transfer(CO_NODE& node); + void transferData(CO_NODE& node); /** * Read Object Dictionary entry * * @param node[in] The canopen node to read from */ - void SDO_Receive(CO_NODE& node); + void receiveData(CO_NODE& node); /** * Get a pointer to the start of the object dictionary @@ -128,7 +128,7 @@ class SDOCanNode : public CANDevice { .Type = CO_TUNSIGNED32, .Data = (CO_DATA) CO_COBID_SDO_RESPONSE(), }, - { + { /* Node ID of Server */ .Key = CO_KEY(0x1280, 0x03, CO_OBJ_D___R_), .Type = CO_TUNSIGNED8, .Data = (CO_DATA) 1, diff --git a/samples/canopen/canopen_sdo/main.cpp b/samples/canopen/canopen_sdo/main.cpp index 6f69fef2..43475cfe 100644 --- a/samples/canopen/canopen_sdo/main.cpp +++ b/samples/canopen/canopen_sdo/main.cpp @@ -107,13 +107,12 @@ int main() { uint32_t lastUpdate2 = HAL_GetTick(); while (1) { - - if ((HAL_GetTick() - lastUpdate1) >= 1000) { // If 1000ms have passed receive CAN message. - testCanNode.SDO_Receive(canNode); + if ((HAL_GetTick() - lastUpdate1) >= 1000) { // If 1000ms have passed receive CAN message. + testCanNode.receiveData(canNode); // Receive data from server lastUpdate1 = HAL_GetTick(); // Set to current time. } else if ((HAL_GetTick() - lastUpdate2) >= 5000) { // If 5000ms have passed write CAN message. - testCanNode.SDO_Transfer(canNode); - lastUpdate2 = HAL_GetTick(); // Set to current time. + testCanNode.transferData(canNode); // Send data to server + lastUpdate2 = HAL_GetTick(); // Set to current time. } io::processCANopenNode(&canNode); From 056309716caf1ac994a3e73012ec92d3c4df71b8 Mon Sep 17 00:00:00 2001 From: GitHub Build Date: Sat, 21 Dec 2024 18:08:34 +0000 Subject: [PATCH 15/17] Applied Formatting Changes During GitHub Build --- samples/canopen/canopen_sdo/SDOCanNode.hpp | 3 ++- samples/canopen/canopen_sdo/main.cpp | 4 ++-- 2 files changed, 4 insertions(+), 3 deletions(-) diff --git a/samples/canopen/canopen_sdo/SDOCanNode.hpp b/samples/canopen/canopen_sdo/SDOCanNode.hpp index 017e6d3e..59cf7a08 100644 --- a/samples/canopen/canopen_sdo/SDOCanNode.hpp +++ b/samples/canopen/canopen_sdo/SDOCanNode.hpp @@ -128,7 +128,8 @@ class SDOCanNode : public CANDevice { .Type = CO_TUNSIGNED32, .Data = (CO_DATA) CO_COBID_SDO_RESPONSE(), }, - { /* Node ID of Server */ + { + /* Node ID of Server */ .Key = CO_KEY(0x1280, 0x03, CO_OBJ_D___R_), .Type = CO_TUNSIGNED8, .Data = (CO_DATA) 1, diff --git a/samples/canopen/canopen_sdo/main.cpp b/samples/canopen/canopen_sdo/main.cpp index 43475cfe..5b044afb 100644 --- a/samples/canopen/canopen_sdo/main.cpp +++ b/samples/canopen/canopen_sdo/main.cpp @@ -108,10 +108,10 @@ int main() { while (1) { if ((HAL_GetTick() - lastUpdate1) >= 1000) { // If 1000ms have passed receive CAN message. - testCanNode.receiveData(canNode); // Receive data from server + testCanNode.receiveData(canNode); // Receive data from server lastUpdate1 = HAL_GetTick(); // Set to current time. } else if ((HAL_GetTick() - lastUpdate2) >= 5000) { // If 5000ms have passed write CAN message. - testCanNode.transferData(canNode); // Send data to server + testCanNode.transferData(canNode); // Send data to server lastUpdate2 = HAL_GetTick(); // Set to current time. } From 7ee46dac17672fc5d2a983e2cb514f68a0080ca3 Mon Sep 17 00:00:00 2001 From: DiegoLHendrix Date: Thu, 2 Jan 2025 23:20:39 -0500 Subject: [PATCH 16/17] I am Tyler Durden --- include/core/io/CANopen.hpp | 2 +- src/core/io/CANopen.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/include/core/io/CANopen.hpp b/include/core/io/CANopen.hpp index ae897b8e..e0984115 100644 --- a/include/core/io/CANopen.hpp +++ b/include/core/io/CANopen.hpp @@ -131,7 +131,7 @@ CO_ERR SDOReceive(CO_NODE& node, uint8_t* data, uint8_t size, uint32_t entry, * @param AppCallback[in] Pointer to the callback function to register * @param AppContext[in] Context to be passed to the callback */ -void registerCallBack(void (*AppCallback)(CO_CSDO* csdo, uint16_t index, uint8_t size, uint32_t entry), +void registerCallBack(void (*AppCallback)(CO_CSDO* csdo, uint16_t index, uint8_t sub, uint32_t code), void* AppContext); } // namespace core::io diff --git a/src/core/io/CANopen.cpp b/src/core/io/CANopen.cpp index ab91898e..9233a550 100644 --- a/src/core/io/CANopen.cpp +++ b/src/core/io/CANopen.cpp @@ -191,7 +191,7 @@ CO_ERR SDOReceive(CO_NODE& node, uint8_t* data, uint8_t size, uint32_t entry, return err; } -void registerCallBack(void (*AppCallback)(CO_CSDO* csdo, uint16_t index, uint8_t size, uint32_t entry), +void registerCallBack(void (*AppCallback)(CO_CSDO* csdo, uint16_t index, uint8_t sub, uint32_t code), void* AppContext) { callback = AppCallback; context = AppContext; From 92d8cc70a667bbc17ce81e531722a2d016147bc8 Mon Sep 17 00:00:00 2001 From: GitHub Build Date: Fri, 3 Jan 2025 04:23:25 +0000 Subject: [PATCH 17/17] Applied Formatting Changes During GitHub Build --- include/core/io/CANopen.hpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/include/core/io/CANopen.hpp b/include/core/io/CANopen.hpp index e0984115..44442977 100644 --- a/include/core/io/CANopen.hpp +++ b/include/core/io/CANopen.hpp @@ -131,8 +131,7 @@ CO_ERR SDOReceive(CO_NODE& node, uint8_t* data, uint8_t size, uint32_t entry, * @param AppCallback[in] Pointer to the callback function to register * @param AppContext[in] Context to be passed to the callback */ -void registerCallBack(void (*AppCallback)(CO_CSDO* csdo, uint16_t index, uint8_t sub, uint32_t code), - void* AppContext); +void registerCallBack(void (*AppCallback)(CO_CSDO* csdo, uint16_t index, uint8_t sub, uint32_t code), void* AppContext); } // namespace core::io #endif