Merge branch 'dynamic_node_id_raft' of https://github.com/UAVCAN/uavcan into dynamic_node_id_raft

This commit is contained in:
David Sidrane 2015-05-29 18:00:08 -10:00
commit 81512cc2e7
24 changed files with 193 additions and 204 deletions

View File

@ -11,7 +11,6 @@ Path path
---
uint64 crc64 # Undefined for directories
uint32 size # Undefined for directories
uint40 size # Undefined for directories
Error error
EntryType entry_type

View File

@ -12,7 +12,7 @@
# will be returned, and data array will be empty.
#
uint32 offset
uint40 offset
Path path
---

View File

@ -15,9 +15,9 @@
# example by means of creating a staging area for uncompleted writes (like FTP servers do).
#
uint32 offset
uint40 offset
Path path
uint8[<=200] data
uint8[<=192] data
---

View File

@ -9,7 +9,6 @@
#include <uavcan/node/abstract_node.hpp>
#include <uavcan/data_type.hpp>
#include <uavcan/node/global_data_type_registry.hpp>
#include <uavcan/util/lazy_constructor.hpp>
#include <uavcan/debug.hpp>
#include <uavcan/transport/transfer_sender.hpp>
#include <uavcan/marshal/scalar_codec.hpp>
@ -20,15 +19,14 @@ namespace uavcan
class GenericPublisherBase : Noncopyable
{
const MonotonicDuration max_transfer_interval_; // TODO: memory usage can be reduced
TransferSender sender_;
MonotonicDuration tx_timeout_;
INode& node_;
LazyConstructor<TransferSender> sender_;
protected:
GenericPublisherBase(INode& node, MonotonicDuration tx_timeout,
MonotonicDuration max_transfer_interval)
: max_transfer_interval_(max_transfer_interval)
: sender_(node.getDispatcher(), max_transfer_interval)
, tx_timeout_(tx_timeout)
, node_(node)
{
@ -51,7 +49,8 @@ protected:
int genericPublish(const IMarshalBuffer& buffer, TransferType transfer_type, NodeID dst_node_id,
TransferID* tid, MonotonicTime blocking_deadline);
TransferSender* getTransferSender();
TransferSender& getTransferSender() { return sender_; }
const TransferSender& getTransferSender() const { return sender_; }
public:
static MonotonicDuration getMinTxTimeout() { return MonotonicDuration::fromUSec(200); }
@ -66,7 +65,7 @@ public:
*/
void allowAnonymousTransfers()
{
sender_->allowAnonymousTransfers();
sender_.allowAnonymousTransfers();
}
INode& getNode() const { return node_; }
@ -124,12 +123,6 @@ public:
{
return genericPublish(message, transfer_type, dst_node_id, &tid, blocking_deadline);
}
TransferSender* getTransferSender()
{
(void)checkInit();
return GenericPublisherBase::getTransferSender();
}
};
// ----------------------------------------------------------------------------

View File

@ -33,26 +33,27 @@ namespace uavcan
template <typename DataType_>
class UAVCAN_EXPORT ReceivedDataStructure : public DataType_
{
const IncomingTransfer* _transfer_; ///< Such weird name is necessary to avoid clashing with DataType fields
const IncomingTransfer* const _transfer_; ///< Such weird name is necessary to avoid clashing with DataType fields
template <typename Ret, Ret(IncomingTransfer::*Fun) () const>
Ret safeget() const
{
if (_transfer_ == NULL)
{
UAVCAN_ASSERT(0);
return Ret();
}
return (_transfer_->*Fun)();
}
protected:
ReceivedDataStructure() : _transfer_(NULL) { }
ReceivedDataStructure()
: _transfer_(NULL)
{ }
void setTransfer(const IncomingTransfer* arg_transfer)
ReceivedDataStructure(const IncomingTransfer* arg_transfer)
: _transfer_(arg_transfer)
{
UAVCAN_ASSERT(arg_transfer != NULL);
_transfer_ = arg_transfer;
}
public:
@ -139,7 +140,10 @@ public:
typedef TransferListenerTemplate<BufferSize, NumStaticBufs, NumStaticReceivers> Type;
};
/**
* Please note that the reference passed to the RX callback points to a stack-allocated object, which means
* that it gets invalidated shortly after the callback returns.
*/
template <typename DataSpec, typename DataStruct, typename TransferListenerType>
class UAVCAN_EXPORT GenericSubscriber : public GenericSubscriberBase
{
@ -162,23 +166,24 @@ class UAVCAN_EXPORT GenericSubscriber : public GenericSubscriberBase
{ }
};
struct ReceivedDataStructureSpec : public ReceivedDataStructure<DataStruct>
{
using ReceivedDataStructure<DataStruct>::setTransfer;
};
LazyConstructor<TransferForwarder> forwarder_;
ReceivedDataStructureSpec message_;
int checkInit();
bool decodeTransfer(IncomingTransfer& transfer);
void handleIncomingTransfer(IncomingTransfer& transfer);
int genericStart(bool (Dispatcher::*registration_method)(TransferListenerBase*));
protected:
struct ReceivedDataStructureSpec : public ReceivedDataStructure<DataStruct>
{
ReceivedDataStructureSpec() { }
ReceivedDataStructureSpec(const IncomingTransfer* arg_transfer)
: ReceivedDataStructure<DataStruct>(arg_transfer)
{ }
};
explicit GenericSubscriber(INode& node)
: GenericSubscriberBase(node)
{ }
@ -227,15 +232,6 @@ protected:
}
TransferListenerType* getTransferListener() { return forwarder_; }
/**
* Returns a reference to the temporary storage for decoded received messages.
* Reference to this storage is used as a parameter for subscription callbacks.
* This storage is guaranteed to stay intact after the last message was decoded, i.e.
* the application can use it to access the last received message object.
*/
ReceivedDataStructure<DataStruct>& getReceivedStructStorage() { return message_; }
const ReceivedDataStructure<DataStruct>& getReceivedStructStorage() const { return message_; }
};
// ----------------------------------------------------------------------------
@ -250,48 +246,51 @@ int GenericSubscriber<DataSpec, DataStruct, TransferListenerType>::checkInit()
{
return 0;
}
GlobalDataTypeRegistry::instance().freeze();
const DataTypeDescriptor* const descr =
GlobalDataTypeRegistry::instance().find(DataTypeKind(DataSpec::DataTypeKind), DataSpec::getDataTypeFullName());
if (!descr)
if (descr == NULL)
{
UAVCAN_TRACE("GenericSubscriber", "Type [%s] is not registered", DataSpec::getDataTypeFullName());
return -ErrUnknownDataType;
}
forwarder_.template construct<SelfType&, const DataTypeDescriptor&, IPoolAllocator&>
(*this, *descr, node_.getAllocator());
return 0;
}
template <typename DataSpec, typename DataStruct, typename TransferListenerType>
bool GenericSubscriber<DataSpec, DataStruct, TransferListenerType>::decodeTransfer(IncomingTransfer& transfer)
void GenericSubscriber<DataSpec, DataStruct, TransferListenerType>::handleIncomingTransfer(IncomingTransfer& transfer)
{
ReceivedDataStructureSpec rx_struct(&transfer);
/*
* Decoding into the temporary storage
*/
BitStream bitstream(transfer);
ScalarCodec codec(bitstream);
message_.setTransfer(&transfer);
const int decode_res = DataStruct::decode(rx_struct, codec);
const int decode_res = DataStruct::decode(message_, codec);
// We don't need the data anymore, the memory can be reused from the callback:
transfer.release();
if (decode_res <= 0)
{
UAVCAN_TRACE("GenericSubscriber", "Unable to decode the message [%i] [%s]",
decode_res, DataSpec::getDataTypeFullName());
failure_count_++;
node_.getDispatcher().getTransferPerfCounter().addError();
return false;
return;
}
return true;
}
template <typename DataSpec, typename DataStruct, typename TransferListenerType>
void GenericSubscriber<DataSpec, DataStruct, TransferListenerType>::handleIncomingTransfer(IncomingTransfer& transfer)
{
if (decodeTransfer(transfer))
{
handleReceivedDataStruct(message_);
}
/*
* Invoking the callback
*/
handleReceivedDataStruct(rx_struct);
}
template <typename DataSpec, typename DataStruct, typename TransferListenerType>

View File

@ -18,7 +18,7 @@ class UAVCAN_EXPORT IMarshalBuffer : public ITransferBuffer
{
public:
virtual const uint8_t* getDataPtr() const = 0;
virtual unsigned getDataLength() const = 0;
virtual unsigned getMaxWritePos() const = 0;
};
/**
@ -43,10 +43,8 @@ public:
/**
* Default implementation of marshal buffer provider.
* This implementation provides the buffer large enough to
* serialize any UAVCAN data structure.
*/
template <unsigned MaxSize_ = MaxPossibleTransferPayloadLen>
template <unsigned MaxSize_>
class UAVCAN_EXPORT MarshalBufferProvider : public IMarshalBufferProvider
{
class Buffer : public IMarshalBuffer
@ -65,7 +63,7 @@ class UAVCAN_EXPORT MarshalBufferProvider : public IMarshalBufferProvider
virtual const uint8_t* getDataPtr() const { return buf_.getRawPtr(); }
virtual unsigned getDataLength() const { return buf_.getMaxWritePos(); }
virtual unsigned getMaxWritePos() const { return buf_.getMaxWritePos(); }
public:
void reset() { buf_.reset(); }

View File

@ -47,20 +47,20 @@ namespace uavcan
* be allocated in the memory pool if needed.
* Default value is acceptable for any use case.
*
* @tparam OutgoingTransferMaxPayloadLen Maximum outgoing transfer payload length.
* It's pointless to make this value larger than
* @ref MaxTransferPayloadLen, which is default.
* Note that in tiny mode the default value is actually
* smaller than @ref MaxTransferPayloadLen (may cause
* run-time failures).
* @tparam MarshalBufferSize Size of the marshal buffer that is used to provide short-term temporary storage for
* serialized data for TX transfers. The buffer must be large enough to accommodate
* largest serialized TX transfer. The default value is guaranteed to be large enough,
* but it can be reduced if long TX transfers are not used to optimize memory use.
* If UAVCAN_TINY mode is enabled, this value defaults to the maximum length of a
* response transfer of uavcan.protocol.GetNodeInfo.
*/
template <std::size_t MemPoolSize_,
#if UAVCAN_TINY
unsigned OutgoingTransferRegistryStaticEntries = 0,
unsigned OutgoingTransferMaxPayloadLen = 264
unsigned MarshalBufferSize = BitLenToByteLen<protocol::GetNodeInfo::Response::MaxBitLen>::Result
#else
unsigned OutgoingTransferRegistryStaticEntries = 10,
unsigned OutgoingTransferMaxPayloadLen = MaxPossibleTransferPayloadLen
unsigned MarshalBufferSize = MaxPossibleTransferPayloadLen
#endif
>
class UAVCAN_EXPORT Node : public INode
@ -73,7 +73,7 @@ class UAVCAN_EXPORT Node : public INode
typedef PoolAllocator<MemPoolSize, MemPoolBlockSize> Allocator;
Allocator pool_allocator_;
MarshalBufferProvider<OutgoingTransferMaxPayloadLen> marsh_buf_;
MarshalBufferProvider<MarshalBufferSize> marsh_buf_;
OutgoingTransferRegistry<OutgoingTransferRegistryStaticEntries> outgoing_trans_reg_;
Scheduler scheduler_;
@ -265,9 +265,8 @@ public:
// ----------------------------------------------------------------------------
template <std::size_t MemPoolSize_, unsigned OutgoingTransferRegistryStaticEntries,
unsigned OutgoingTransferMaxPayloadLen>
int Node<MemPoolSize_, OutgoingTransferRegistryStaticEntries, OutgoingTransferMaxPayloadLen>::start(
template <std::size_t MemPoolSize_, unsigned OutgoingTransferRegistryStaticEntries, unsigned MarshalBufferSize>
int Node<MemPoolSize_, OutgoingTransferRegistryStaticEntries, MarshalBufferSize>::start(
const TransferPriority priority)
{
if (started_)
@ -313,9 +312,8 @@ fail:
#if !UAVCAN_TINY
template <std::size_t MemPoolSize_, unsigned OutgoingTransferRegistryStaticEntries,
unsigned OutgoingTransferMaxPayloadLen>
int Node<MemPoolSize_, OutgoingTransferRegistryStaticEntries, OutgoingTransferMaxPayloadLen>::
template <std::size_t MemPoolSize_, unsigned OutgoingTransferRegistryStaticEntries, unsigned MarshalBufferSize>
int Node<MemPoolSize_, OutgoingTransferRegistryStaticEntries, MarshalBufferSize>::
checkNetworkCompatibility(NetworkCompatibilityCheckResult& result)
{
if (!started_)

View File

@ -81,46 +81,20 @@ public:
/**
* Returns priority of outgoing transfers.
* TODO: Make const.
*/
TransferPriority getPriority()
TransferPriority getPriority() const
{
// TODO probably TransferSender must be transformed into regular field?
TransferSender* const ts = getTransferSender();
if (ts != NULL)
{
return ts->getPriority();
}
else
{
return TransferPriorityNormal; // This is default
}
return BaseType::getTransferSender().getPriority();
}
/**
* Allows to change the priority of outgoing transfers.
* Note that only High, Normal and Low priorities can be used; Service priority is not available for messages.
* Returns negative error code if priority cannot be set, non-negative on success.
* If the priority value is invalid, an assertion failure will be generated, and the value will not be updated.
*/
int setPriority(const TransferPriority prio)
void setPriority(const TransferPriority prio)
{
if (prio < NumTransferPriorities && prio != TransferPriorityService)
{
TransferSender* const ts = getTransferSender(); // TODO: Static TransferSender?
if (ts != NULL)
{
ts->setPriority(prio);
return 0;
}
else
{
return -ErrLogic;
}
}
else
{
return -ErrInvalidParam;
}
BaseType::getTransferSender().setPriority(prio);
}
static MonotonicDuration getDefaultTxTimeout() { return MonotonicDuration::fromMSec(10); }

View File

@ -59,9 +59,10 @@ struct ServiceCallID
/**
* Object of this type will be returned to the application as a result of service call.
* Note that application ALWAYS gets this result, even when it times out or fails because of some other reason.
* The class is made noncopyable because it keeps a reference to a stack-allocated object.
*/
template <typename DataType>
class UAVCAN_EXPORT ServiceCallResult
class UAVCAN_EXPORT ServiceCallResult : Noncopyable
{
public:
typedef ReceivedDataStructure<typename DataType::Response> ResponseFieldType;
@ -92,6 +93,9 @@ public:
ServiceCallID getCallID() const { return call_id_; }
/**
* Returned reference points to a stack-allocated object.
*/
const ResponseFieldType& getResponse() const { return response_; }
ResponseFieldType& getResponse() { return response_; }
};
@ -200,6 +204,10 @@ public:
* This class can manage multiple concurrent calls to the same or different remote servers. Number of concurrent
* calls is limited only by amount of available pool memory.
*
* Note that the reference passed to the callback points to a stack-allocated object, which means that the
* reference invalidates once the callback returns. If you want to use this object after the callback execution,
* you need to copy it somewhere.
*
* @tparam DataType_ Service data type.
*
* @tparam Callback_ Service response will be delivered through the callback of this type.
@ -257,8 +265,12 @@ private:
UAVCAN_TRACE("ServiceClient::TimeoutCallbackCaller", "Timeout from nid=%d, tid=%d, dtname=%s",
int(state.getCallID().server_node_id.get()), int(state.getCallID().transfer_id.get()),
DataType::getDataTypeFullName());
typename SubscriberType::ReceivedDataStructureSpec rx_struct; // Default-initialized
ServiceCallResultType result(ServiceCallResultType::ErrorTimeout, state.getCallID(),
owner.getReceivedStructStorage()); // Mutable!
rx_struct); // Mutable!
owner.invokeCallback(result);
}
}

View File

@ -64,6 +64,9 @@ public:
/**
* Use this class to implement UAVCAN service servers.
*
* Note that the references passed to the callback may point to stack-allocated objects, which means that the
* references get invalidated once the callback returns.
*
* @tparam DataType_ Service data type.
*
* @tparam Callback_ Service calls will be delivered through the callback of this type, and service
@ -117,26 +120,26 @@ private:
PublisherType publisher_;
Callback callback_;
uint32_t response_failure_count_;
ServiceResponseDataStructure<ResponseType> response_;
virtual void handleReceivedDataStruct(ReceivedDataStructure<RequestType>& request)
{
UAVCAN_ASSERT(request.getTransferType() == TransferTypeServiceRequest);
ServiceResponseDataStructure<ResponseType> response;
if (try_implicit_cast<bool>(callback_, true))
{
// The application needs newly initialized structure
response_ = ServiceResponseDataStructure<ResponseType>();
UAVCAN_ASSERT(response_.isResponseEnabled()); // Enabled by default
callback_(request, response_);
UAVCAN_ASSERT(response.isResponseEnabled()); // Enabled by default
callback_(request, response);
}
else
{
handleFatalError("Srv serv clbk");
}
if (response_.isResponseEnabled())
if (response.isResponseEnabled())
{
const int res = publisher_.publish(response_, TransferTypeServiceResponse, request.getSrcNodeID(),
const int res = publisher_.publish(response, TransferTypeServiceResponse, request.getSrcNodeID(),
request.getTransferID());
if (res < 0)
{

View File

@ -30,11 +30,6 @@ public:
typedef protocol::file::EntryType EntryType;
typedef protocol::file::Error Error;
/**
* Use this class to compute CRC64 for uavcan.protocol.file.GetInfo.
*/
typedef DataTypeSignatureCRC FileCRC;
/**
* All read operations must return this number of bytes, unless end of file is reached.
*/
@ -51,7 +46,7 @@ public:
* Implementation of this method is required.
* On success the method must return zero.
*/
virtual int16_t getInfo(const Path& path, uint64_t& out_crc64, uint32_t& out_size, EntryType& out_type) = 0;
virtual int16_t getInfo(const Path& path, uint64_t& out_size, EntryType& out_type) = 0;
/**
* Backend for uavcan.protocol.file.Read.
@ -60,7 +55,7 @@ public:
* if the end of file is reached.
* On success the method must return zero.
*/
virtual int16_t read(const Path& path, const uint32_t offset, uint8_t* out_buffer, uint16_t& inout_size) = 0;
virtual int16_t read(const Path& path, const uint64_t offset, uint8_t* out_buffer, uint16_t& inout_size) = 0;
// Methods below are optional.
@ -69,7 +64,7 @@ public:
* Implementation of this method is NOT required; by default it returns uavcan.protocol.file.Error.NOT_IMPLEMENTED.
* On success the method must return zero.
*/
virtual int16_t write(const Path& path, const uint32_t offset, const uint8_t* buffer, const uint16_t size)
virtual int16_t write(const Path& path, const uint64_t offset, const uint8_t* buffer, const uint16_t size)
{
(void)path;
(void)offset;
@ -129,7 +124,7 @@ class BasicFileServer
void handleGetInfo(const protocol::file::GetInfo::Request& req, protocol::file::GetInfo::Response& resp)
{
resp.error.value = backend_.getInfo(req.path.path, resp.crc64, resp.size, resp.entry_type);
resp.error.value = backend_.getInfo(req.path.path, resp.size, resp.entry_type);
}
void handleRead(const protocol::file::Read::Request& req, protocol::file::Read::Response& resp)

View File

@ -51,16 +51,9 @@ class UAVCAN_EXPORT GlobalTimeSyncMaster : protected LoopbackFrameListenerBase
const int res = pub_.init();
if (res >= 0)
{
TransferSender* const ts = pub_.getTransferSender();
UAVCAN_ASSERT(ts != NULL);
ts->setIfaceMask(uint8_t(1 << iface_index_));
ts->setCanIOFlags(CanIOFlagLoopback);
const int prio_res = pub_.setPriority(TransferPriorityHigh); // Fixed priority
if (prio_res < 0)
{
return prio_res;
}
pub_.getTransferSender().setIfaceMask(uint8_t(1 << iface_index_));
pub_.getTransferSender().setCanIOFlags(CanIOFlagLoopback);
pub_.setPriority(TransferPriorityHigh); // Fixed priority
}
return res;
}
@ -84,8 +77,8 @@ class UAVCAN_EXPORT GlobalTimeSyncMaster : protected LoopbackFrameListenerBase
int publish(TransferID tid, MonotonicTime current_time)
{
UAVCAN_ASSERT(pub_.getTransferSender()->getCanIOFlags() == CanIOFlagLoopback);
UAVCAN_ASSERT(pub_.getTransferSender()->getIfaceMask() == (1 << iface_index_));
UAVCAN_ASSERT(pub_.getTransferSender().getCanIOFlags() == CanIOFlagLoopback);
UAVCAN_ASSERT(pub_.getTransferSender().getIfaceMask() == (1 << iface_index_));
const MonotonicDuration since_prev_pub = current_time - iface_prev_pub_mono_;
iface_prev_pub_mono_ = current_time;

View File

@ -101,7 +101,8 @@ public:
{
return res;
}
return logmsg_pub_.setPriority(TransferPriorityLow); // Fixed priority
logmsg_pub_.setPriority(TransferPriorityLow); // Fixed priority
return 0;
}
/**

View File

@ -20,16 +20,17 @@ namespace uavcan
class UAVCAN_EXPORT TransferSender
{
const MonotonicDuration max_transfer_interval_;
const DataTypeDescriptor& data_type_;
Dispatcher& dispatcher_;
TransferPriority priority_;
const CanTxQueue::Qos qos_;
const TransferCRC crc_base_;
CanTxQueue::Qos qos_;
TransferCRC crc_base_;
DataTypeID data_type_id_;
CanIOFlags flags_;
uint8_t iface_mask_;
bool allow_anonymous_transfers_;
Dispatcher& dispatcher_;
void registerError() const;
public:
@ -43,16 +44,30 @@ public:
TransferSender(Dispatcher& dispatcher, const DataTypeDescriptor& data_type, CanTxQueue::Qos qos,
MonotonicDuration max_transfer_interval = getDefaultMaxTransferInterval())
: max_transfer_interval_(max_transfer_interval)
, data_type_(data_type)
, dispatcher_(dispatcher)
, priority_(TransferPriorityNormal)
, qos_(qos)
, crc_base_(data_type.getSignature().toTransferCRC())
, qos_(CanTxQueue::Qos())
, flags_(CanIOFlags(0))
, iface_mask_(AllIfacesMask)
, allow_anonymous_transfers_(false)
{
init(data_type, qos);
}
TransferSender(Dispatcher& dispatcher, MonotonicDuration max_transfer_interval = getDefaultMaxTransferInterval())
: max_transfer_interval_(max_transfer_interval)
, dispatcher_(dispatcher)
, priority_(TransferPriorityNormal)
, qos_(CanTxQueue::Qos())
, flags_(CanIOFlags(0))
, iface_mask_(AllIfacesMask)
, allow_anonymous_transfers_(false)
{ }
void init(const DataTypeDescriptor& dtid, CanTxQueue::Qos qos);
bool isInitialized() const { return data_type_id_ != DataTypeID(); }
CanIOFlags getCanIOFlags() const { return flags_; }
void setCanIOFlags(CanIOFlags flags) { flags_ = flags; }

View File

@ -9,7 +9,7 @@ namespace uavcan
bool GenericPublisherBase::isInited() const
{
return bool(sender_);
return sender_.isInitialized();
}
int GenericPublisherBase::doInit(DataTypeKind dtkind, const char* dtname, CanTxQueue::Qos qos)
@ -22,13 +22,14 @@ int GenericPublisherBase::doInit(DataTypeKind dtkind, const char* dtname, CanTxQ
GlobalDataTypeRegistry::instance().freeze();
const DataTypeDescriptor* const descr = GlobalDataTypeRegistry::instance().find(dtkind, dtname);
if (!descr)
if (descr == NULL)
{
UAVCAN_TRACE("GenericPublisher", "Type [%s] is not registered", dtname);
return -ErrUnknownDataType;
}
sender_.construct<Dispatcher&, const DataTypeDescriptor&, CanTxQueue::Qos, MonotonicDuration>
(node_.getDispatcher(), *descr, qos, max_transfer_interval_);
sender_.init(*descr, qos);
return 0;
}
@ -47,21 +48,16 @@ int GenericPublisherBase::genericPublish(const IMarshalBuffer& buffer, TransferT
{
if (tid)
{
return sender_->send(buffer.getDataPtr(), buffer.getDataLength(), getTxDeadline(),
blocking_deadline, transfer_type, dst_node_id, *tid);
return sender_.send(buffer.getDataPtr(), buffer.getMaxWritePos(), getTxDeadline(),
blocking_deadline, transfer_type, dst_node_id, *tid);
}
else
{
return sender_->send(buffer.getDataPtr(), buffer.getDataLength(), getTxDeadline(),
blocking_deadline, transfer_type, dst_node_id);
return sender_.send(buffer.getDataPtr(), buffer.getMaxWritePos(), getTxDeadline(),
blocking_deadline, transfer_type, dst_node_id);
}
}
TransferSender* GenericPublisherBase::getTransferSender()
{
return sender_.isConstructed() ? static_cast<TransferSender*>(sender_) : NULL;
}
void GenericPublisherBase::setTxTimeout(MonotonicDuration tx_timeout)
{
tx_timeout = max(tx_timeout, getMinTxTimeout());

View File

@ -160,11 +160,7 @@ int DynamicNodeIDClient::start(const protocol::HardwareVersion& hardware_version
return res;
}
dnida_pub_.allowAnonymousTransfers();
res = dnida_pub_.setPriority(transfer_priority);
if (res < 0)
{
return res;
}
dnida_pub_.setPriority(transfer_priority);
res = dnida_sub_.start(AllocationCallback(this, &DynamicNodeIDClient::handleAllocation));
if (res < 0)

View File

@ -71,11 +71,7 @@ int NodeStatusProvider::startAndPublish(TransferPriority priority)
int res = -1;
res = node_status_pub_.setPriority(priority);
if (res < 0)
{
goto fail;
}
node_status_pub_.setPriority(priority);
if (!getNode().isPassiveMode())
{

View File

@ -15,6 +15,15 @@ void TransferSender::registerError() const
dispatcher_.getTransferPerfCounter().addError();
}
void TransferSender::init(const DataTypeDescriptor& dtid, CanTxQueue::Qos qos)
{
UAVCAN_ASSERT(!isInitialized());
qos_ = qos;
data_type_id_ = dtid.getID();
crc_base_ = dtid.getSignature().toTransferCRC();
}
int TransferSender::send(const uint8_t* payload, unsigned payload_len, MonotonicTime tx_deadline,
MonotonicTime blocking_deadline, TransferType transfer_type, NodeID dst_node_id,
TransferID tid) const
@ -24,7 +33,7 @@ int TransferSender::send(const uint8_t* payload, unsigned payload_len, Monotonic
return -ErrTransferTooLong;
}
Frame frame(data_type_.getID(), transfer_type, dispatcher_.getNodeID(), dst_node_id, 0, tid);
Frame frame(data_type_id_, transfer_type, dispatcher_.getNodeID(), dst_node_id, 0, tid);
if (transfer_type == TransferTypeMessageBroadcast ||
transfer_type == TransferTypeMessageUnicast)
{
@ -143,7 +152,7 @@ int TransferSender::send(const uint8_t* payload, unsigned payload_len, Monotonic
/*
* TODO: TID is not needed for anonymous transfers, this part of the code can be skipped?
*/
const OutgoingTransferRegistryKey otr_key(data_type_.getID(), transfer_type, dst_node_id);
const OutgoingTransferRegistryKey otr_key(data_type_id_, transfer_type, dst_node_id);
UAVCAN_ASSERT(!tx_deadline.isZero());
const MonotonicTime otr_deadline = tx_deadline + max_transfer_interval_;
@ -151,8 +160,8 @@ int TransferSender::send(const uint8_t* payload, unsigned payload_len, Monotonic
TransferID* const tid = dispatcher_.getOutgoingTransferRegistry().accessOrCreate(otr_key, otr_deadline);
if (tid == NULL)
{
UAVCAN_TRACE("TransferSender", "OTR access failure, dtd=%s tt=%i",
data_type_.toString().c_str(), int(transfer_type));
UAVCAN_TRACE("TransferSender", "OTR access failure, dtid=%d tt=%i",
int(data_type_id_.get()), int(transfer_type));
return -ErrMemory;
}

View File

@ -18,6 +18,8 @@ TEST(Publisher, Basic)
uavcan::Publisher<uavcan::mavlink::Message> publisher(node);
ASSERT_FALSE(publisher.getTransferSender().isInitialized());
std::cout <<
"sizeof(uavcan::Publisher<uavcan::mavlink::Message>): " <<
sizeof(uavcan::Publisher<uavcan::mavlink::Message>) << std::endl;
@ -110,18 +112,5 @@ TEST(Publisher, Basic)
* Misc
*/
ASSERT_TRUE(uavcan::GlobalDataTypeRegistry::instance().isFrozen());
ASSERT_TRUE(publisher.getTransferSender());
}
TEST(Publisher, ImplicitInitialization)
{
SystemClockMock clock_mock(100);
CanDriverMock can_driver(2, clock_mock);
TestNode node(can_driver, clock_mock, 1);
uavcan::Publisher<uavcan::mavlink::Message> publisher(node);
// Will be initialized ad-hoc
ASSERT_TRUE(publisher.getTransferSender());
ASSERT_TRUE(publisher.getTransferSender().isInitialized());
}

View File

@ -178,8 +178,7 @@ TEST(ServiceClient, Basic)
ASSERT_EQ(0, nodes.b.getDispatcher().getNumServiceResponseListeners()); // Third has timed out :(
// Validating
// We use expected response instead of empty response because the last valid will be reused on fauilure
ASSERT_TRUE(handler.match(ResultType::ErrorTimeout, 99, expected_response));
ASSERT_TRUE(handler.match(ResultType::ErrorTimeout, 99, root_ns_a::StringService::Response()));
// Stray request
ASSERT_LT(0, client3.call(99, request)); // Will timeout!
@ -341,7 +340,7 @@ TEST(ServiceClient, ConcurrentCalls)
ASSERT_EQ(1, client.getNumPendingCalls()); // One dropped
ASSERT_EQ(1, nodes.b.getDispatcher().getNumServiceResponseListeners()); // Still listening
ASSERT_TRUE(handler.match(ResultType::ErrorTimeout, 88, last_response));
ASSERT_TRUE(handler.match(ResultType::ErrorTimeout, 88, root_ns_a::StringService::Response()));
/*
* Validating the 500 ms timeout
@ -352,7 +351,7 @@ TEST(ServiceClient, ConcurrentCalls)
ASSERT_EQ(0, client.getNumPendingCalls()); // All finished
ASSERT_EQ(0, nodes.b.getDispatcher().getNumServiceResponseListeners()); // Not listening
ASSERT_TRUE(handler.match(ResultType::ErrorTimeout, 99, last_response));
ASSERT_TRUE(handler.match(ResultType::ErrorTimeout, 99, root_ns_a::StringService::Response()));
}

View File

@ -20,7 +20,7 @@ struct TestNode : public uavcan::INode
{
uavcan::PoolAllocator<uavcan::MemPoolBlockSize * 100, uavcan::MemPoolBlockSize> pool;
uavcan::PoolManager<1> poolmgr;
uavcan::MarshalBufferProvider<> buffer_provider;
uavcan::MarshalBufferProvider<512> buffer_provider;
uavcan::OutgoingTransferRegistry<8> otr;
uavcan::Scheduler scheduler;
uint64_t internal_failure_count;

View File

@ -19,7 +19,8 @@ using uavcan::DefaultDataTypeRegistrator;
using uavcan::MonotonicDuration;
template <typename DataType>
static bool validateDataTypeInfoResponse(const std::auto_ptr<ServiceCallResult<GetDataTypeInfo> >& resp, unsigned mask)
static bool validateDataTypeInfoResponse(const std::auto_ptr<ServiceCallResultCollector<GetDataTypeInfo>::Result>& resp,
unsigned mask)
{
if (!resp.get())
{

View File

@ -13,15 +13,10 @@ public:
static const std::string file_name;
static const std::string file_data;
virtual int16_t getInfo(const Path& path, uint64_t& out_crc64, uint32_t& out_size, EntryType& out_type)
virtual int16_t getInfo(const Path& path, uint64_t& out_size, EntryType& out_type)
{
if (path == file_name)
{
{
FileCRC crc;
crc.add(reinterpret_cast<const uavcan::uint8_t*>(file_data.c_str()), unsigned(file_data.length()));
out_crc64 = crc.get();
}
out_size = uint16_t(file_data.length());
out_type.flags |= EntryType::FLAG_FILE;
out_type.flags |= EntryType::FLAG_READABLE;
@ -33,7 +28,7 @@ public:
}
}
virtual int16_t read(const Path& path, const uint32_t offset, uint8_t* out_buffer, uint16_t& inout_size)
virtual int16_t read(const Path& path, const uint64_t offset, uint8_t* out_buffer, uint16_t& inout_size)
{
if (path == file_name)
{
@ -90,7 +85,6 @@ TEST(BasicFileServer, Basic)
ASSERT_TRUE(get_info.collector.result.get());
ASSERT_TRUE(get_info.collector.result->isSuccessful());
ASSERT_EQ(0x62EC59E3F1A4F00A, get_info.collector.result->getResponse().crc64);
ASSERT_EQ(0, get_info.collector.result->getResponse().error.value);
ASSERT_EQ(9, get_info.collector.result->getResponse().size);
ASSERT_EQ(EntryType::FLAG_FILE | EntryType::FLAG_READABLE,

View File

@ -51,18 +51,47 @@ struct SubscriberWithCollector
template <typename DataType>
class ServiceCallResultCollector : uavcan::Noncopyable
{
typedef uavcan::ServiceCallResult<DataType> ResultType;
typedef uavcan::ServiceCallResult<DataType> ServiceCallResult;
void handler(const ResultType& result)
public:
class Result
{
this->result.reset(new ResultType(result));
const typename ServiceCallResult::Status status_;
uavcan::ServiceCallID call_id_;
typename DataType::Response response_;
public:
Result(typename ServiceCallResult::Status arg_status,
uavcan::ServiceCallID arg_call_id,
const typename DataType::Response& arg_response)
: status_(arg_status)
, call_id_(arg_call_id)
, response_(arg_response)
{ }
bool isSuccessful() const { return status_ == ServiceCallResult::Success; }
typename ServiceCallResult::Status getStatus() const { return status_; }
uavcan::ServiceCallID getCallID() const { return call_id_; }
const typename DataType::Response& getResponse() const { return response_; }
typename DataType::Response& getResponse() { return response_; }
};
private:
void handler(const uavcan::ServiceCallResult<DataType>& tmp_result)
{
std::cout << tmp_result << std::endl;
result.reset(new Result(tmp_result.getStatus(), tmp_result.getCallID(), tmp_result.getResponse()));
}
public:
std::auto_ptr<ResultType> result;
std::auto_ptr<Result> result;
typedef uavcan::MethodBinder<ServiceCallResultCollector*,
void (ServiceCallResultCollector::*)(const ResultType&)> Binder;
void (ServiceCallResultCollector::*)(const uavcan::ServiceCallResult<DataType>&)>
Binder;
Binder bind() { return Binder(this, &ServiceCallResultCollector::handler); }
};