Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Implement a ROS2 style API Service Client. #196

Merged
merged 4 commits into from
Jan 9, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
20 changes: 12 additions & 8 deletions examples/OpenCyphal-Service-Client/OpenCyphal-Service-Client.ino
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@ static int const MKRCAN_MCP2515_INT_PIN = 7;
**************************************************************************************/

void onReceiveBufferFull(CanardFrame const &);
void onExecuteCommand_1_0_Response_Received(CanardRxTransfer const &, Node &);
void onExecuteCommand_1_0_Response_Received(ExecuteCommand_1_0::Response<> const & rsp);

/**************************************************************************************
* GLOBAL VARIABLES
Expand All @@ -52,6 +52,11 @@ Node::Heap<Node::DEFAULT_O1HEAP_SIZE> node_heap;
CircularBuffer<Node::TReceiveCircularBuffer>::Heap<Node::DEFAULT_RX_QUEUE_SIZE> node_rx_queue;
Node node_hdl(node_heap.data(), node_heap.size(), node_rx_queue.data(), node_rx_queue.size(), micros);

ServiceClient<ExecuteCommand_1_0::Request<>> srv_client = node_hdl.create_service_client<ExecuteCommand_1_0::Request<>, ExecuteCommand_1_0::Response<>>(
ExecuteCommand_1_0::Request<>::PORT_ID,
2*1000*1000UL,
onExecuteCommand_1_0_Response_Received);

/**************************************************************************************
* SETUP/LOOP
**************************************************************************************/
Expand All @@ -76,15 +81,16 @@ void setup()
mcp2515.setNormalMode();

/* Request some coffee. */
char const cmd_param[] = "I want a double espresso with cream";
char const cmd_param[] = "I want a double espresso with cream!";
ExecuteCommand_1_0::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_);
std::copy(cmd_param,
cmd_param + req.data.parameter.count,
req.data.parameter.elements);

node_hdl.request<ExecuteCommand_1_0::Request<>, ExecuteCommand_1_0::Response<>>(req, 27 /* remote node id */, onExecuteCommand_1_0_Response_Received);
if (!srv_client->request(27 /* remote node id */, req))
Serial.println("Coffee request failed.");
}

void loop()
Expand All @@ -106,12 +112,10 @@ void onReceiveBufferFull(CanardFrame const & frame)
node_hdl.onCanFrameReceived(frame, micros());
}

void onExecuteCommand_1_0_Response_Received(CanardRxTransfer const & transfer, Node & /* node_hdl */)
void onExecuteCommand_1_0_Response_Received(ExecuteCommand_1_0::Response<> const & rsp)
{
ExecuteCommand_1_0::Response<> const rsp = ExecuteCommand_1_0::Response<>::deserialize(transfer);

if (rsp.data.status == arduino::_107_::opencyphal::to_integer(ExecuteCommand_1_0::Response<>::Status::SUCCESS))
Serial.println("Coffee snode_hdlcessful retrieved");
if (rsp.data.status == uavcan_node_ExecuteCommand_Response_1_0_STATUS_SUCCESS)
Serial.println("Coffee successfully retrieved");
else
Serial.println("Error when retrieving coffee");
}
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,7 @@ Node::Heap<Node::DEFAULT_O1HEAP_SIZE> node_heap;
CircularBuffer<Node::TReceiveCircularBuffer>::Heap<Node::DEFAULT_RX_QUEUE_SIZE> node_rx_queue;
Node node_hdl(node_heap.data(), node_heap.size(), node_rx_queue.data(), node_rx_queue.size(), micros);

Service execute_command_srv = node_hdl.create_service<ExecuteCommand_1_0::Request<>, ExecuteCommand_1_0::Response<>>(
ServiceServer execute_command_srv = node_hdl.create_service_server<ExecuteCommand_1_0::Request<>, ExecuteCommand_1_0::Response<>>(
ExecuteCommand_1_0::Request<>::PORT_ID,
2*1000*1000UL,
onExecuteCommand_1_0_Request_Received);
Expand Down
3 changes: 2 additions & 1 deletion keywords.txt
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,8 @@ Node KEYWORD1
Heap KEYWORD1
Publisher KEYWORD1
Subscription KEYWORD1
Service KEYWORD1
ServiceServer KEYWORD1
ServiceClient KEYWORD1
Request KEYWORD1
Response KEYWORD1

Expand Down
3 changes: 2 additions & 1 deletion src/107-Arduino-Cyphal.h
Original file line number Diff line number Diff line change
Expand Up @@ -14,9 +14,10 @@

#include "Node.hpp"
#include "DSDL_Types.h"
#include "Service.hpp"
#include "Publisher.hpp"
#include "Subscription.hpp"
#include "ServiceClient.hpp"
#include "ServiceServer.hpp"
#include "nodeinfo/NodeInfo.h"
#include "register/RegisterList.h"

Expand Down
13 changes: 1 addition & 12 deletions src/Node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -117,23 +117,12 @@ void Node::processRxQueue()

if(result == 1)
{
/* Obtain the pointer to the subscribed object and in invoke its reception callback. */
impl::SubscriptionBase * sub_ptr = static_cast<impl::SubscriptionBase *>(rx_subscription->user_reference);
sub_ptr->onTransferReceived(transfer);

/* Free dynamically allocated memory after processing. */
_canard_hdl.memory_free(&_canard_hdl, transfer.payload);

/*
if (transfer.metadata.transfer_kind == CanardTransferKindResponse) {
if ((_tx_transfer_map.count(transfer.metadata.port_id) > 0) && (_tx_transfer_map[transfer.metadata.port_id] == transfer.metadata.transfer_id))
{
transfer_received_func(transfer, *this);
unsubscribe(CanardTransferKindResponse, transfer.metadata.port_id);
}
}
else
transfer_received_func(transfer, *this);
*/
}
}
}
Expand Down
14 changes: 10 additions & 4 deletions src/Node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,9 +21,10 @@
#include <memory>
#include <functional>

#include "Service.hpp"
#include "Publisher.hpp"
#include "Subscription.hpp"
#include "ServiceClient.hpp"
#include "ServiceServer.hpp"
#include "CircularBuffer.hpp"

#include "libo1heap/o1heap.h"
Expand Down Expand Up @@ -81,9 +82,14 @@ class Node
OnReceiveCb&& on_receive_cb);

template <typename T_REQ, typename T_RSP, typename OnRequestCb>
Service create_service(CanardPortID const port_id,
CanardMicrosecond const tx_timeout_usec,
OnRequestCb&& on_request_cb);
ServiceServer create_service_server(CanardPortID const port_id,
CanardMicrosecond const tx_timeout_usec,
OnRequestCb&& on_request_cb);

template <typename T_REQ, typename T_RSP, typename OnResponseCb>
ServiceClient<T_REQ> create_service_client(CanardPortID const port_id,
CanardMicrosecond const tx_timeout_usec,
OnResponseCb&& on_response_cb);

/* Must be called from the application to process
* all received CAN frames.
Expand Down
41 changes: 23 additions & 18 deletions src/Node.ipp
Original file line number Diff line number Diff line change
Expand Up @@ -44,11 +44,11 @@ Subscription Node::create_subscription(CanardPortID const port_id,
}

template <typename T_REQ, typename T_RSP, typename OnRequestCb>
Service Node::create_service(CanardPortID const port_id,
CanardMicrosecond const tx_timeout_usec,
OnRequestCb&& on_request_cb)
ServiceServer Node::create_service_server(CanardPortID const port_id,
CanardMicrosecond const tx_timeout_usec,
OnRequestCb&& on_request_cb)
{
auto srv = std::make_shared<impl::Service<T_REQ, T_RSP, OnRequestCb>>(
auto srv = std::make_shared<impl::ServiceServer<T_REQ, T_RSP, OnRequestCb>>(
*this,
port_id,
tx_timeout_usec,
Expand All @@ -67,21 +67,26 @@ Service Node::create_service(CanardPortID const port_id,
return srv;
}

/*
template <typename T_REQ, typename T_RSP>
bool Node::request(T_REQ const & req, CanardNodeID const remote_node_id, OnTransferReceivedFunc func)
template <typename T_REQ, typename T_RSP, typename OnResponseCb>
ServiceClient<T_REQ> Node::create_service_client(CanardPortID const port_id,
CanardMicrosecond const tx_timeout_usec,
OnResponseCb&& on_response_cb)
{
static_assert(T_REQ::TRANSFER_KIND == CanardTransferKindRequest, "Node::request<T_REQ, T_RSP> API - T_REQ != CanardTransferKindRequest");
static_assert(T_RSP::TRANSFER_KIND == CanardTransferKindResponse, "Node::request<T_REQ, T_RSP> API - T_RSP != CanardTransferKindResponse");

std::array<uint8_t, T_REQ::MAX_PAYLOAD_SIZE> payload_buf;
payload_buf.fill(0);
size_t const payload_size = req.serialize(payload_buf.data());
CanardTransferID const transfer_id = getNextTransferId(T_REQ::PORT_ID);
auto clt = std::make_shared<impl::ServiceClient<T_REQ, T_RSP, OnResponseCb>>(
*this,
port_id,
tx_timeout_usec,
std::forward<OnResponseCb>(on_response_cb)
);

if (!enqeueTransfer(remote_node_id, T_REQ::TRANSFER_KIND, T_REQ::PORT_ID, payload_size, payload_buf.data(), transfer_id))
return false;
int8_t const rc = canardRxSubscribe(&_canard_hdl,
CanardTransferKindResponse,
port_id,
T_RSP::MAX_PAYLOAD_SIZE,
CANARD_DEFAULT_TRANSFER_ID_TIMEOUT_USEC,
&(clt->canard_rx_subscription()));
if (rc < 0)
return nullptr;

return subscribe(T_RSP::TRANSFER_KIND, T_RSP::PORT_ID, T_RSP::MAX_PAYLOAD_SIZE, func);
return clt;
}
*/
92 changes: 92 additions & 0 deletions src/ServiceClient.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,92 @@
/**
* This software is distributed under the terms of the MIT License.
* Copyright (c) 2020-2023 LXRobotics.
* Author: Alexander Entinger <alexander.entinger@lxrobotics.com>
* Contributors: https://github.com/107-systems/107-Arduino-Cyphal/graphs/contributors.
*/

#ifndef INC_107_ARDUINO_CYPHAL_SERVICE_CLIENT_HPP
#define INC_107_ARDUINO_CYPHAL_SERVICE_CLIENT_HPP

/**************************************************************************************
* INCLUDE
**************************************************************************************/

#include <memory>

#include "SubscriptionBase.h"

#include "libcanard/canard.h"

/**************************************************************************************
* FORWARD DECLARATION
**************************************************************************************/

class Node;

/**************************************************************************************
* NAMESPACE
**************************************************************************************/

namespace impl
{

/**************************************************************************************
* CLASS DECLARATION
**************************************************************************************/

template <typename T_REQ>
class ServiceClientBase : public SubscriptionBase
{
public:
ServiceClientBase() : SubscriptionBase{CanardTransferKindResponse} { }
virtual ~ServiceClientBase() { }
virtual bool request(CanardNodeID const remote_node_id, T_REQ const & req) = 0;
};

template<typename T_REQ, typename T_RSP, typename OnResponseCb>
class ServiceClient : public ServiceClientBase<T_REQ>
{
public:
ServiceClient(Node & node_hdl, CanardPortID const port_id, CanardMicrosecond const tx_timeout_usec, OnResponseCb on_response_cb)
: _node_hdl{node_hdl}
, _port_id{port_id}
, _tx_timeout_usec{tx_timeout_usec}
, _on_response_cb{on_response_cb}
, _transfer_id{0}
{ }
virtual ~ServiceClient();


virtual bool request(CanardNodeID const remote_node_id, T_REQ const & req) override;
virtual bool onTransferReceived(CanardRxTransfer const & transfer) override;


private:
Node & _node_hdl;
CanardPortID const _port_id;
CanardMicrosecond const _tx_timeout_usec;
OnResponseCb _on_response_cb;
CanardTransferID _transfer_id;
};

/**************************************************************************************
* NAMESPACE
**************************************************************************************/

} /* impl */

/**************************************************************************************
* TYPEDEF
**************************************************************************************/

template <typename T_REQ>
using ServiceClient = std::shared_ptr<impl::ServiceClientBase<T_REQ>>;

/**************************************************************************************
* TEMPLATE IMPLEMENTATION
**************************************************************************************/

#include "ServiceClient.ipp"

#endif /* INC_107_ARDUINO_CYPHAL_SERVICE_CLIENT_HPP */
67 changes: 67 additions & 0 deletions src/ServiceClient.ipp
Original file line number Diff line number Diff line change
@@ -0,0 +1,67 @@
/**
* This software is distributed under the terms of the MIT License.
* Copyright (c) 2020-2023 LXRobotics.
* Author: Alexander Entinger <alexander.entinger@lxrobotics.com>
* Contributors: https://github.com/107-systems/107-Arduino-Cyphal/graphs/contributors.
*/

/**************************************************************************************
* NAMESPACE
**************************************************************************************/

namespace impl {

/**************************************************************************************
* CTOR/DTOR
**************************************************************************************/

template<typename T_REQ, typename T_RSP, typename OnResponseCb>
ServiceClient<T_REQ, T_RSP, OnResponseCb>::~ServiceClient()
{
_node_hdl.unsubscribe(_port_id, SubscriptionBase::canard_transfer_kind());
}

/**************************************************************************************
* PUBLIC MEMBER FUNCTIONS
**************************************************************************************/

template<typename T_REQ, typename T_RSP, typename OnResponseCb>
bool ServiceClient<T_REQ, T_RSP, OnResponseCb>::request(CanardNodeID const remote_node_id, T_REQ const & req)
{
CanardTransferMetadata const transfer_metadata =
{
.priority = CanardPriorityNominal,
.transfer_kind = CanardTransferKindRequest,
.port_id = _port_id,
.remote_node_id = remote_node_id,
.transfer_id = _transfer_id++,
};

/* Serialize message into payload buffer. */
std::array<uint8_t, T_REQ::MAX_PAYLOAD_SIZE> payload_buf{};
size_t const payload_buf_size = req.serialize(payload_buf.data());

/* Serialize transfer into a series of CAN frames. */
return _node_hdl.enqueue_transfer(_tx_timeout_usec,
&transfer_metadata,
payload_buf_size,
payload_buf.data());
}

template<typename T_REQ, typename T_RSP, typename OnResponseCb>
bool ServiceClient<T_REQ, T_RSP, OnResponseCb>::onTransferReceived(CanardRxTransfer const & transfer)
{
/* Deserialize the response message. */
T_RSP const rsp = T_RSP::deserialize(transfer);

/* Invoke the user registered callback. */
_on_response_cb(rsp);

return true;
}

/**************************************************************************************
* NAMESPACE
**************************************************************************************/

} /* impl */
Loading