From 61e80cf6ffcff9a4dda827af531836d7b7513e3a Mon Sep 17 00:00:00 2001 From: Alexander Entinger Date: Wed, 11 Jan 2023 06:45:13 +0100 Subject: [PATCH] Upgrade examples OpenCyphal-Service-Server/Client to use latest DSDL for ExecuteCommand. --- .../OpenCyphal-Service-Client.ino | 16 ++++++++-------- .../OpenCyphal-Service-Server.ino | 16 ++++++++-------- 2 files changed, 16 insertions(+), 16 deletions(-) diff --git a/examples/OpenCyphal-Service-Client/OpenCyphal-Service-Client.ino b/examples/OpenCyphal-Service-Client/OpenCyphal-Service-Client.ino index d2642df2..8552787f 100644 --- a/examples/OpenCyphal-Service-Client/OpenCyphal-Service-Client.ino +++ b/examples/OpenCyphal-Service-Client/OpenCyphal-Service-Client.ino @@ -35,7 +35,7 @@ static int const MKRCAN_MCP2515_INT_PIN = 7; **************************************************************************************/ void onReceiveBufferFull(CanardFrame const &); -void onExecuteCommand_1_0_Response_Received(ExecuteCommand_1_0::Response<> const & rsp); +void onExecuteCommand_1_1_Response_Received(ExecuteCommand_1_1::Response<> const & rsp); /************************************************************************************** * GLOBAL VARIABLES @@ -51,10 +51,10 @@ ArduinoMCP2515 mcp2515([]() { digitalWrite(MKRCAN_MCP2515_CS_PIN, LOW); }, Node::Heap node_heap; Node node_hdl(node_heap.data(), node_heap.size(), micros); -ServiceClient> srv_client = node_hdl.create_service_client, ExecuteCommand_1_0::Response<>>( - ExecuteCommand_1_0::Request<>::PORT_ID, +ServiceClient> srv_client = node_hdl.create_service_client, ExecuteCommand_1_1::Response<>>( + ExecuteCommand_1_1::Request<>::PORT_ID, 2*1000*1000UL, - onExecuteCommand_1_0_Response_Received); + onExecuteCommand_1_1_Response_Received); /************************************************************************************** * SETUP/LOOP @@ -81,9 +81,9 @@ void setup() /* Request some coffee. */ char const cmd_param[] = "I want a double espresso with cream!"; - ExecuteCommand_1_0::Request<> req; + ExecuteCommand_1_1::Request<> req; req.data.command = 0xCAFE; - req.data.parameter.count = std::min(strlen(cmd_param), (size_t)uavcan_node_ExecuteCommand_Request_1_0_parameter_ARRAY_CAPACITY_); + req.data.parameter.count = std::min(strlen(cmd_param), (size_t)uavcan_node_ExecuteCommand_Request_1_1_parameter_ARRAY_CAPACITY_); std::copy(cmd_param, cmd_param + req.data.parameter.count, req.data.parameter.elements); @@ -111,9 +111,9 @@ void onReceiveBufferFull(CanardFrame const & frame) node_hdl.onCanFrameReceived(frame); } -void onExecuteCommand_1_0_Response_Received(ExecuteCommand_1_0::Response<> const & rsp) +void onExecuteCommand_1_1_Response_Received(ExecuteCommand_1_1::Response<> const & rsp) { - if (rsp.data.status == uavcan_node_ExecuteCommand_Response_1_0_STATUS_SUCCESS) + if (rsp.data.status == uavcan_node_ExecuteCommand_Response_1_1_STATUS_SUCCESS) Serial.println("Coffee successfully retrieved"); else Serial.println("Error when retrieving coffee"); diff --git a/examples/OpenCyphal-Service-Server/OpenCyphal-Service-Server.ino b/examples/OpenCyphal-Service-Server/OpenCyphal-Service-Server.ino index e1e27a76..32a0154b 100644 --- a/examples/OpenCyphal-Service-Server/OpenCyphal-Service-Server.ino +++ b/examples/OpenCyphal-Service-Server/OpenCyphal-Service-Server.ino @@ -35,7 +35,7 @@ static int const MKRCAN_MCP2515_INT_PIN = 7; **************************************************************************************/ void onReceiveBufferFull(CanardFrame const &); -ExecuteCommand_1_0::Response<> onExecuteCommand_1_0_Request_Received(ExecuteCommand_1_0::Request<> const &); +ExecuteCommand_1_1::Response<> onExecuteCommand_1_1_Request_Received(ExecuteCommand_1_1::Request<> const &); /************************************************************************************** * GLOBAL VARIABLES @@ -51,10 +51,10 @@ ArduinoMCP2515 mcp2515([]() { digitalWrite(MKRCAN_MCP2515_CS_PIN, LOW); }, Node::Heap node_heap; Node node_hdl(node_heap.data(), node_heap.size(), micros); -ServiceServer execute_command_srv = node_hdl.create_service_server, ExecuteCommand_1_0::Response<>>( - ExecuteCommand_1_0::Request<>::PORT_ID, +ServiceServer execute_command_srv = node_hdl.create_service_server, ExecuteCommand_1_1::Response<>>( + ExecuteCommand_1_1::Request<>::PORT_ID, 2*1000*1000UL, - onExecuteCommand_1_0_Request_Received); + onExecuteCommand_1_1_Request_Received); /************************************************************************************** * SETUP/LOOP @@ -99,14 +99,14 @@ void onReceiveBufferFull(CanardFrame const & frame) node_hdl.onCanFrameReceived(frame); } -ExecuteCommand_1_0::Response<> onExecuteCommand_1_0_Request_Received(ExecuteCommand_1_0::Request<> const & req) +ExecuteCommand_1_1::Response<> onExecuteCommand_1_1_Request_Received(ExecuteCommand_1_1::Request<> const & req) { - ExecuteCommand_1_0::Response<> rsp; + ExecuteCommand_1_1::Response<> rsp; if (req.data.command == 0xCAFE) - rsp.data.status = uavcan_node_ExecuteCommand_Response_1_0_STATUS_SUCCESS; + rsp.data.status = uavcan_node_ExecuteCommand_Response_1_1_STATUS_SUCCESS; else - rsp.data.status = uavcan_node_ExecuteCommand_Response_1_0_STATUS_NOT_AUTHORIZED; + rsp.data.status = uavcan_node_ExecuteCommand_Response_1_1_STATUS_NOT_AUTHORIZED; return rsp; }