All unit tests compile, but crash. This is the most horrifying commit I've ever made.

This commit is contained in:
Pavel Kirienko
2015-07-01 14:55:24 +03:00
parent feb7600f17
commit 8a2e22046e
42 changed files with 421 additions and 587 deletions
@@ -85,13 +85,6 @@ struct UAVCAN_EXPORT ${t.cpp_type_name}
${':' if idx == 0 else ','} ${a.name}()
% endfor
{
enum { MaxByteLen = ::uavcan::BitLenToByteLen<MaxBitLen>::Result };
% if (t.kind == t.KIND_MESSAGE) and (t.has_default_dtid):
::uavcan::StaticAssert<int(MaxByteLen) <= int(::uavcan::MaxMessageBroadcastTransferPayloadLen)>::check();
% else:
::uavcan::StaticAssert<int(MaxByteLen) <= int(::uavcan::MaxServiceTransferPayloadLen)>::check();
% endif
::uavcan::StaticAssert<_tmpl == 0>::check(); // Usage check
#if UAVCAN_DEBUG
+1 -3
View File
@@ -56,9 +56,7 @@ public:
DataTypeID(uint16_t id) // Implicit
: value_(id)
{
UAVCAN_ASSERT(id <= MaxPossibleDataTypeIDValue);
}
{ }
static DataTypeID getMaxValueForDataTypeKind(const DataTypeKind dtkind);
@@ -41,7 +41,7 @@ class UAVCAN_EXPORT DataTypeInfoProvider : Noncopyable
}
void handleComputeAggregateTypeSignatureRequest(const protocol::ComputeAggregateTypeSignature::Request& request,
protocol::ComputeAggregateTypeSignature::Response& response)
protocol::ComputeAggregateTypeSignature::Response&)
{
const DataTypeKind kind = DataTypeKind(request.kind.value); // No mapping needed
if (!isValidDataTypeKind(kind))
@@ -51,6 +51,7 @@ class UAVCAN_EXPORT DataTypeInfoProvider : Noncopyable
return;
}
#if 0 /* TODO FIXME */
UAVCAN_TRACE("DataTypeInfoProvider", "ComputeAggregateTypeSignature request for dtk=%d, len(known_ids)=%d",
int(request.kind.value), int(request.known_ids.size()));
@@ -61,6 +62,7 @@ class UAVCAN_EXPORT DataTypeInfoProvider : Noncopyable
response.aggregate_signature =
GlobalDataTypeRegistry::instance().computeAggregateSignature(kind, response.mutually_known_ids).get();
#endif
}
void handleGetDataTypeInfoRequest(const protocol::GetDataTypeInfo::Request& request,
@@ -65,7 +65,7 @@ public:
*/
int start(const protocol::HardwareVersion& hardware_version,
const NodeID preferred_node_id = NodeID::Broadcast,
const TransferPriority transfer_priority = TransferPriorityNormal);
const TransferPriority transfer_priority = TransferPriority::OneHigherThanLowest);
/**
* Use this method to determine when allocation is complete.
@@ -237,15 +237,15 @@ public:
, allocation_pub_(node)
{ }
int init()
int init(const TransferPriority priority)
{
int res = allocation_pub_.init();
if (res < 0)
{
return res;
}
(void)allocation_pub_.setPriority(TransferPriorityLow);
allocation_pub_.setTxTimeout(MonotonicDuration::fromMSec(Allocation::DEFAULT_REQUEST_PERIOD_MS));
allocation_pub_.setPriority(priority);
allocation_pub_.setTxTimeout(MonotonicDuration::fromMSec(1000 /* TODO FIXME ALLOCATION RANDOMIZATION */));
res = allocation_sub_.start(AllocationCallback(this, &AllocationRequestManager::handleAllocation));
if (res < 0)
@@ -135,7 +135,8 @@ public:
, storage_(storage)
{ }
int init(const UniqueID& own_unique_id)
int init(const UniqueID& own_unique_id,
const TransferPriority priority = TransferPriority::OneHigherThanLowest)
{
/*
* Initializing storage first, because the next step requires it to be loaded
@@ -173,13 +174,13 @@ public:
/*
* Misc
*/
res = allocation_request_manager_.init();
res = allocation_request_manager_.init(priority);
if (res < 0)
{
return res;
}
res = node_discoverer_.init();
res = node_discoverer_.init(priority);
if (res < 0)
{
return res;
@@ -207,7 +207,7 @@ public:
* storage backend using key 'cluster_size'.
* Returns negative error code.
*/
int init(uint8_t init_cluster_size = ClusterSizeUnknown)
int init(const uint8_t init_cluster_size, const TransferPriority priority)
{
/*
* Figuring out the cluster size
@@ -263,7 +263,7 @@ public:
{
return res;
}
(void)discovery_pub_.setPriority(TransferPriorityLow);
discovery_pub_.setPriority(priority);
res = discovery_sub_.start(DiscoveryCallback(this, &ClusterManager::handleDiscovery));
if (res < 0)
@@ -727,7 +727,7 @@ public:
* value from the persistent storage will be used. If not set and there's no such key
* in the persistent storage, initialization will fail.
*/
int init(uint8_t cluster_size = ClusterManager::ClusterSizeUnknown)
int init(const uint8_t cluster_size, const TransferPriority priority)
{
/*
* Initializing state variables
@@ -748,7 +748,7 @@ public:
return res;
}
res = cluster_.init(cluster_size);
res = cluster_.init(cluster_size, priority);
if (res < 0)
{
return res;
@@ -246,12 +246,14 @@ public:
, node_discoverer_(node, tracer, *this)
{ }
int init(const UniqueID& own_unique_id, const uint8_t cluster_size = ClusterManager::ClusterSizeUnknown)
int init(const UniqueID& own_unique_id,
const uint8_t cluster_size = ClusterManager::ClusterSizeUnknown,
const TransferPriority priority = TransferPriority::OneHigherThanLowest)
{
/*
* Initializing Raft core first, because the next step requires Log to be loaded
*/
int res = raft_core_.init(cluster_size);
int res = raft_core_.init(cluster_size, priority);
if (res < 0)
{
return res;
@@ -276,13 +278,13 @@ public:
/*
* Misc
*/
res = allocation_request_manager_.init();
res = allocation_request_manager_.init(priority);
if (res < 0)
{
return res;
}
res = node_discoverer_.init();
res = node_discoverer_.init(priority);
if (res < 0)
{
return res;
@@ -309,8 +309,10 @@ public:
, node_status_sub_(node)
{ }
int init()
int init(const TransferPriority priority)
{
// TODO FIXME set priority
(void)priority;
int res = get_node_info_client_.init();
if (res < 0)
{
@@ -46,14 +46,14 @@ class UAVCAN_EXPORT GlobalTimeSyncMaster : protected LoopbackFrameListenerBase
UAVCAN_ASSERT(iface_index < MaxCanIfaces);
}
int init()
int init(TransferPriority priority = TransferPriority::OneLowerThanHighest)
{
const int res = pub_.init();
if (res >= 0)
{
pub_.getTransferSender().setIfaceMask(uint8_t(1 << iface_index_));
pub_.getTransferSender().setCanIOFlags(CanIOFlagLoopback);
pub_.setPriority(TransferPriorityHigh); // Fixed priority
pub_.setPriority(priority);
}
return res;
}
@@ -109,7 +109,7 @@ class UAVCAN_EXPORT GlobalTimeSyncMaster : protected LoopbackFrameListenerBase
{
if (frame.getDataTypeID() == dtid_ &&
frame.getTransferType() == TransferTypeMessageBroadcast &&
frame.isLast() && frame.isFirst() &&
frame.isStartOfTransfer() && frame.isEndOfTransfer() &&
frame.getSrcNodeID() == node_.getNodeID())
{
iface_masters_[iface]->setTxTimestamp(frame.getUtcTimestamp());
+2 -2
View File
@@ -94,14 +94,14 @@ public:
* Must be called once before use.
* Returns negative error code.
*/
int init()
int init(TransferPriority priority = TransferPriority::OneHigherThanLowest)
{
const int res = logmsg_pub_.init();
if (res < 0)
{
return res;
}
logmsg_pub_.setPriority(TransferPriorityLow); // Fixed priority
logmsg_pub_.setPriority(priority); // Fixed priority
return 0;
}
@@ -118,6 +118,7 @@ class UAVCAN_EXPORT NetworkCompatibilityChecker : Noncopyable
last_cats_request_ok_ = resp.isSuccessful();
if (last_cats_request_ok_)
{
#if 0 /* TODO FIXME */
const DataTypeSignature sign = GlobalDataTypeRegistry::instance().
computeAggregateSignature(checking_dtkind_, resp.getResponse().mutually_known_ids);
@@ -129,6 +130,7 @@ class UAVCAN_EXPORT NetworkCompatibilityChecker : Noncopyable
{
result_.conflicting_node = resp.getCallID().server_node_id;
}
#endif
}
}
@@ -143,7 +145,8 @@ class UAVCAN_EXPORT NetworkCompatibilityChecker : Noncopyable
checking_dtkind_ = kind;
protocol::ComputeAggregateTypeSignature::Request request;
request.kind.value = kind;
GlobalDataTypeRegistry::instance().getDataTypeIDMask(kind, request.known_ids);
// TODO FIXME
// GlobalDataTypeRegistry::instance().getDataTypeIDMask(kind, request.known_ids);
int res = cats_cln_.call(nid, request);
if (res < 0)
@@ -7,6 +7,7 @@
#include <cassert>
#include <uavcan/build_config.hpp>
#include <uavcan/util/templates.hpp>
#include <uavcan/std.hpp>
namespace uavcan
@@ -29,7 +30,13 @@ class UAVCAN_EXPORT TransferPriority
public:
static const uint8_t BitLen = 5U;
static const uint8_t NumericallyMax = (1U << BitLen) - 1;
static const uint8_t NumericallyMin = 0;
/// This priority is used by default
static const TransferPriority Default;
static const TransferPriority OneHigherThanLowest;
static const TransferPriority OneLowerThanHighest;
TransferPriority() : value_(0xFF) { }
@@ -39,6 +46,16 @@ public:
UAVCAN_ASSERT(isValid());
}
template <uint8_t Percent>
static TransferPriority fromPercent()
{
StaticAssert<(Percent <= 100)>::check();
enum { Result = ((100U - Percent) * NumericallyMax) / 100U };
StaticAssert<(Result <= NumericallyMax)>::check();
StaticAssert<(Result >= NumericallyMin)>::check();
return TransferPriority(Result);
}
uint8_t get() const { return value_; }
bool isValid() const { return value_ < (1U << BitLen); }
@@ -169,7 +169,7 @@ int DynamicNodeIDClient::start(const protocol::HardwareVersion& hardware_version
}
dnida_sub_.allowAnonymousTransfers();
startPeriodic(MonotonicDuration::fromMSec(protocol::dynamic_node_id::Allocation::DEFAULT_REQUEST_PERIOD_MS));
startPeriodic(MonotonicDuration::fromMSec(1000 /* TODO FIXME */));
return 0;
}
+1 -3
View File
@@ -165,7 +165,6 @@ void Dispatcher::handleFrame(const CanRxFrame& can_frame)
switch (frame.getTransferType())
{
case TransferTypeMessageBroadcast:
case TransferTypeMessageUnicast:
{
lmsg_.handleFrame(frame);
break;
@@ -364,8 +363,7 @@ bool Dispatcher::hasSubscriber(DataTypeID dtid) const
bool Dispatcher::hasPublisher(DataTypeID dtid) const
{
return outgoing_transfer_reg_.exists(dtid, TransferTypeMessageBroadcast) ||
outgoing_transfer_reg_.exists(dtid, TransferTypeMessageUnicast);
return outgoing_transfer_reg_.exists(dtid, TransferTypeMessageBroadcast);
}
bool Dispatcher::hasServer(DataTypeID dtid) const
+5
View File
@@ -12,7 +12,12 @@ namespace uavcan
* TransferPriority
*/
const uint8_t TransferPriority::BitLen;
const uint8_t TransferPriority::NumericallyMax;
const uint8_t TransferPriority::NumericallyMin;
const TransferPriority TransferPriority::Default((1U << BitLen) / 2);
const TransferPriority TransferPriority::OneHigherThanLowest(NumericallyMax - 1);
const TransferPriority TransferPriority::OneLowerThanHighest(NumericallyMin + 1);
/**
* TransferID
@@ -65,7 +65,7 @@ MultiFrameIncomingTransfer::MultiFrameIncomingTransfer(MonotonicTime ts_mono, Ut
, buf_acc_(tba)
{
UAVCAN_ASSERT(last_frame.isValid());
UAVCAN_ASSERT(last_frame.isLast());
UAVCAN_ASSERT(last_frame.isEndOfTransfer());
}
int MultiFrameIncomingTransfer::read(unsigned offset, uint8_t* data, unsigned len) const
@@ -202,7 +202,7 @@ void TransferListenerBase::handleFrame(const RxFrame& frame)
TransferReceiver* recv = receivers_.access(key);
if (recv == NULL)
{
if (!frame.isFirst())
if (!frame.isStartOfTransfer())
{
return;
}
@@ -219,8 +219,8 @@ void TransferListenerBase::handleFrame(const RxFrame& frame)
handleReception(*recv, frame, tba);
}
else if (frame.getSrcNodeID().isBroadcast() &&
frame.isFirst() &&
frame.isLast() &&
frame.isStartOfTransfer() &&
frame.isEndOfTransfer() &&
frame.getDstNodeID().isBroadcast()) // Anonymous transfer
{
handleAnonymousTransferReception(frame);
@@ -7,7 +7,6 @@
#include <uavcan/helpers/ostream.hpp>
#include <uavcan/Timestamp.hpp>
#include <uavcan/mavlink/Message.hpp>
#include <uavcan/protocol/ComputeAggregateTypeSignature.hpp>
#include <uavcan/protocol/GetTransportStats.hpp>
#include <uavcan/protocol/Panic.hpp>
@@ -19,7 +18,6 @@
#include <uavcan/protocol/NodeStatus.hpp>
#include <uavcan/protocol/GetNodeInfo.hpp>
#include <uavcan/protocol/debug/LogMessage.hpp>
#include <uavcan/protocol/debug/StartHILSimulation.hpp>
#include <uavcan/protocol/debug/KeyValue.hpp>
#include <root_ns_a/Deep.hpp>
@@ -29,14 +27,6 @@ TEST(Dsdl, Streaming)
{
std::ostringstream os;
uavcan::mavlink::Message mavlink;
os << mavlink << std::endl << "==========" << std::endl;
mavlink.compid = 12;
mavlink.seq = 42;
mavlink.payload = "Here\tgoes\npayload";
os << mavlink << std::endl << "==========" << std::endl;
uavcan::protocol::GetNodeInfo::Response get_node_info_rsp;
os << get_node_info_rsp << std::endl << "==========" << std::endl;
@@ -45,18 +35,6 @@ TEST(Dsdl, Streaming)
os << ps << std::endl << "==========" << std::endl;
static const std::string Reference =
"seq: 0\n"
"sysid: 0\n"
"compid: 0\n"
"msgid: 0\n"
"payload: \"\"\n"
"==========\n"
"seq: 42\n"
"sysid: 0\n"
"compid: 12\n"
"msgid: 0\n"
"payload: \"Here\\x09goes\\x0Apayload\"\n"
"==========\n"
"status: \n"
" uptime_sec: 0\n"
" status_code: 0\n"
@@ -0,0 +1,10 @@
#
# This thing is only needed for testing
#
uint8 seq
uint8 sysid
uint8 compid
uint8 msgid
uint8[<256] payload
+16 -35
View File
@@ -4,7 +4,7 @@
#include <gtest/gtest.h>
#include <uavcan/node/publisher.hpp>
#include <uavcan/mavlink/Message.hpp>
#include <root_ns_a/MavlinkMessage.hpp>
#include "../clock.hpp"
#include "../transport/can/can.hpp"
#include "test_node.hpp"
@@ -16,17 +16,17 @@ TEST(Publisher, Basic)
CanDriverMock can_driver(2, clock_mock);
TestNode node(can_driver, clock_mock, 1);
uavcan::Publisher<uavcan::mavlink::Message> publisher(node);
uavcan::Publisher<root_ns_a::MavlinkMessage> publisher(node);
ASSERT_FALSE(publisher.getTransferSender().isInitialized());
std::cout <<
"sizeof(uavcan::Publisher<uavcan::mavlink::Message>): " <<
sizeof(uavcan::Publisher<uavcan::mavlink::Message>) << std::endl;
"sizeof(uavcan::Publisher<root_ns_a::MavlinkMessage>): " <<
sizeof(uavcan::Publisher<root_ns_a::MavlinkMessage>) << std::endl;
// Manual type registration - we can't rely on the GDTR state
uavcan::GlobalDataTypeRegistry::instance().reset();
uavcan::DefaultDataTypeRegistrator<uavcan::mavlink::Message> _registrator;
uavcan::DefaultDataTypeRegistrator<root_ns_a::MavlinkMessage> _registrator;
/*
* Message layout:
@@ -36,7 +36,7 @@ TEST(Publisher, Basic)
* uint8 msgid
* uint8[<256] payload
*/
uavcan::mavlink::Message msg;
root_ns_a::MavlinkMessage msg;
msg.seq = 0x42;
msg.sysid = 0x72;
msg.compid = 0x08;
@@ -54,9 +54,11 @@ TEST(Publisher, Basic)
// uint_fast16_t data_type_id, TransferType transfer_type, NodeID src_node_id, NodeID dst_node_id,
// uint_fast8_t frame_index, TransferID transfer_id, bool last_frame = false
uavcan::Frame expected_frame(uavcan::mavlink::Message::DefaultDataTypeID, uavcan::TransferTypeMessageBroadcast,
node.getNodeID(), uavcan::NodeID::Broadcast, 0, 0, true);
uavcan::Frame expected_frame(root_ns_a::MavlinkMessage::DefaultDataTypeID, uavcan::TransferTypeMessageBroadcast,
node.getNodeID(), uavcan::NodeID::Broadcast, 0);
expected_frame.setPayload(expected_transfer_payload, 7);
expected_frame.setStartOfTransfer(true);
expected_frame.setEndOfTransfer(true);
uavcan::CanFrame expected_can_frame;
ASSERT_TRUE(expected_frame.compile(expected_can_frame));
@@ -67,14 +69,16 @@ TEST(Publisher, Basic)
ASSERT_TRUE(can_driver.ifaces[1].tx.empty());
// Second shot - checking the transfer ID
publisher.setPriority(uavcan::TransferPriorityLow);
publisher.setPriority(10);
ASSERT_LT(0, publisher.broadcast(msg));
expected_frame = uavcan::Frame(uavcan::mavlink::Message::DefaultDataTypeID,
expected_frame = uavcan::Frame(root_ns_a::MavlinkMessage::DefaultDataTypeID,
uavcan::TransferTypeMessageBroadcast,
node.getNodeID(), uavcan::NodeID::Broadcast, 0, 1, true);
node.getNodeID(), uavcan::NodeID::Broadcast, 1);
expected_frame.setStartOfTransfer(true);
expected_frame.setEndOfTransfer(true);
expected_frame.setPayload(expected_transfer_payload, 7);
expected_frame.setPriority(uavcan::TransferPriorityLow);
expected_frame.setPriority(10);
ASSERT_TRUE(expected_frame.compile(expected_can_frame));
ASSERT_TRUE(can_driver.ifaces[0].matchAndPopTx(expected_can_frame, tx_timeout_usec + 100));
@@ -85,29 +89,6 @@ TEST(Publisher, Basic)
clock_mock.advance(1000);
/*
* Unicast
*/
{
publisher.setPriority(uavcan::TransferPriorityHigh);
ASSERT_LT(0, publisher.unicast(msg, 0x44));
// uint_fast16_t data_type_id, TransferType transfer_type, NodeID src_node_id, NodeID dst_node_id,
// uint_fast8_t frame_index, TransferID transfer_id, bool last_frame = false
uavcan::Frame expected_frame(uavcan::mavlink::Message::DefaultDataTypeID, uavcan::TransferTypeMessageUnicast,
node.getNodeID(), uavcan::NodeID(0x44), 0, 0, true);
expected_frame.setPayload(expected_transfer_payload, 7);
expected_frame.setPriority(uavcan::TransferPriorityHigh);
uavcan::CanFrame expected_can_frame;
ASSERT_TRUE(expected_frame.compile(expected_can_frame));
ASSERT_TRUE(can_driver.ifaces[0].matchAndPopTx(expected_can_frame, tx_timeout_usec + 100 + 1000));
ASSERT_TRUE(can_driver.ifaces[1].matchAndPopTx(expected_can_frame, tx_timeout_usec + 100 + 1000));
ASSERT_TRUE(can_driver.ifaces[0].tx.empty());
ASSERT_TRUE(can_driver.ifaces[1].tx.empty());
}
/*
* Misc
*/
+1 -1
View File
@@ -79,7 +79,7 @@ TEST(ServiceServer, Basic)
// uint_fast16_t data_type_id, TransferType transfer_type, NodeID src_node_id, NodeID dst_node_id,
// uint_fast8_t frame_index, TransferID transfer_id, bool last_frame
uavcan::Frame frame(root_ns_a::StringService::DefaultDataTypeID, uavcan::TransferTypeServiceRequest,
uavcan::NodeID(uint8_t(i + 0x10)), 1, 0, i, true);
uavcan::NodeID(uint8_t(i + 0x10)), 1, i);
const uint8_t req[] = {'r', 'e', 'q', uint8_t(i + '0')};
frame.setPayload(req, sizeof(req));
+25 -19
View File
@@ -5,8 +5,8 @@
#include <gtest/gtest.h>
#include <uavcan/node/subscriber.hpp>
#include <uavcan/util/method_binder.hpp>
#include <uavcan/mavlink/Message.hpp>
#include <root_ns_a/EmptyMessage.hpp>
#include <root_ns_a/MavlinkMessage.hpp>
#include "../clock.hpp"
#include "../transport/can/can.hpp"
#include "test_node.hpp"
@@ -64,22 +64,22 @@ TEST(Subscriber, Basic)
{
// Manual type registration - we can't rely on the GDTR state
uavcan::GlobalDataTypeRegistry::instance().reset();
uavcan::DefaultDataTypeRegistrator<uavcan::mavlink::Message> _registrator;
uavcan::DefaultDataTypeRegistrator<root_ns_a::MavlinkMessage> _registrator;
SystemClockDriver clock_driver;
CanDriverMock can_driver(2, clock_driver);
TestNode node(can_driver, clock_driver, 1);
typedef SubscriptionListener<uavcan::mavlink::Message> Listener;
typedef SubscriptionListener<root_ns_a::MavlinkMessage> Listener;
uavcan::Subscriber<uavcan::mavlink::Message, Listener::ExtendedBinder> sub_extended(node);
uavcan::Subscriber<uavcan::mavlink::Message, Listener::ExtendedBinder> sub_extended2(node); // Not used
uavcan::Subscriber<uavcan::mavlink::Message, Listener::SimpleBinder> sub_simple(node);
uavcan::Subscriber<uavcan::mavlink::Message, Listener::SimpleBinder> sub_simple2(node); // Not used
uavcan::Subscriber<root_ns_a::MavlinkMessage, Listener::ExtendedBinder> sub_extended(node);
uavcan::Subscriber<root_ns_a::MavlinkMessage, Listener::ExtendedBinder> sub_extended2(node); // Not used
uavcan::Subscriber<root_ns_a::MavlinkMessage, Listener::SimpleBinder> sub_simple(node);
uavcan::Subscriber<root_ns_a::MavlinkMessage, Listener::SimpleBinder> sub_simple2(node); // Not used
std::cout <<
"sizeof(uavcan::Subscriber<uavcan::mavlink::Message, Listener::ExtendedBinder>): " <<
sizeof(uavcan::Subscriber<uavcan::mavlink::Message, Listener::ExtendedBinder>) << std::endl;
"sizeof(uavcan::Subscriber<root_ns_a::MavlinkMessage, Listener::ExtendedBinder>): " <<
sizeof(uavcan::Subscriber<root_ns_a::MavlinkMessage, Listener::ExtendedBinder>) << std::endl;
// Null binder - will fail
ASSERT_EQ(-uavcan::ErrInvalidParam, sub_extended.start(Listener::ExtendedBinder(NULL, NULL)));
@@ -94,7 +94,7 @@ TEST(Subscriber, Basic)
* uint8 msgid
* uint8[<256] payload
*/
uavcan::mavlink::Message expected_msg;
root_ns_a::MavlinkMessage expected_msg;
expected_msg.seq = 0x42;
expected_msg.sysid = 0x72;
expected_msg.compid = 0x08;
@@ -109,13 +109,15 @@ TEST(Subscriber, Basic)
std::vector<uavcan::RxFrame> rx_frames;
for (uint8_t i = 0; i < 4; i++)
{
uavcan::TransferType tt = (i & 1) ? uavcan::TransferTypeMessageUnicast : uavcan::TransferTypeMessageBroadcast;
uavcan::TransferType tt = uavcan::TransferTypeMessageBroadcast;
uavcan::NodeID dni = (tt == uavcan::TransferTypeMessageBroadcast) ?
uavcan::NodeID::Broadcast : node.getDispatcher().getNodeID();
// uint_fast16_t data_type_id, TransferType transfer_type, NodeID src_node_id, NodeID dst_node_id,
// uint_fast8_t frame_index, TransferID transfer_id, bool last_frame
uavcan::Frame frame(uavcan::mavlink::Message::DefaultDataTypeID, tt, uavcan::NodeID(uint8_t(i + 100)),
dni, 0, i, true);
uavcan::Frame frame(root_ns_a::MavlinkMessage::DefaultDataTypeID, tt, uavcan::NodeID(uint8_t(i + 100)),
dni, i);
frame.setStartOfTransfer(true);
frame.setEndOfTransfer(true);
frame.setPayload(transfer_payload, 7);
uavcan::RxFrame rx_frame(frame, clock_driver.getMonotonic(), clock_driver.getUtc(), 0);
rx_frames.push_back(rx_frame);
@@ -184,7 +186,7 @@ TEST(Subscriber, Basic)
}
static void panickingSink(const uavcan::ReceivedDataStructure<uavcan::mavlink::Message>&)
static void panickingSink(const uavcan::ReceivedDataStructure<root_ns_a::MavlinkMessage>&)
{
FAIL() << "I just went mad";
}
@@ -194,14 +196,14 @@ TEST(Subscriber, FailureCount)
{
// Manual type registration - we can't rely on the GDTR state
uavcan::GlobalDataTypeRegistry::instance().reset();
uavcan::DefaultDataTypeRegistrator<uavcan::mavlink::Message> _registrator;
uavcan::DefaultDataTypeRegistrator<root_ns_a::MavlinkMessage> _registrator;
SystemClockDriver clock_driver;
CanDriverMock can_driver(2, clock_driver);
TestNode node(can_driver, clock_driver, 1);
{
uavcan::Subscriber<uavcan::mavlink::Message> sub(node);
uavcan::Subscriber<root_ns_a::MavlinkMessage> sub(node);
ASSERT_EQ(0, node.getDispatcher().getNumMessageListeners());
sub.start(panickingSink);
ASSERT_EQ(1, node.getDispatcher().getNumMessageListeners());
@@ -212,8 +214,10 @@ TEST(Subscriber, FailureCount)
{
// uint_fast16_t data_type_id, TransferType transfer_type, NodeID src_node_id, NodeID dst_node_id,
// uint_fast8_t frame_index, TransferID transfer_id, bool last_frame
uavcan::Frame frame(uavcan::mavlink::Message::DefaultDataTypeID, uavcan::TransferTypeMessageBroadcast,
uavcan::NodeID(uint8_t(i + 100)), uavcan::NodeID::Broadcast, 0, i, true);
uavcan::Frame frame(root_ns_a::MavlinkMessage::DefaultDataTypeID, uavcan::TransferTypeMessageBroadcast,
uavcan::NodeID(uint8_t(i + 100)), uavcan::NodeID::Broadcast, i);
frame.setStartOfTransfer(true);
frame.setEndOfTransfer(true);
// No payload - broken transfer
uavcan::RxFrame rx_frame(frame, clock_driver.getMonotonic(), clock_driver.getUtc(), 0);
can_driver.ifaces[0].pushRx(rx_frame);
@@ -257,7 +261,9 @@ TEST(Subscriber, SingleFrameTransfer)
// uint_fast16_t data_type_id, TransferType transfer_type, NodeID src_node_id, NodeID dst_node_id,
// uint_fast8_t frame_index, TransferID transfer_id, bool last_frame
uavcan::Frame frame(root_ns_a::EmptyMessage::DefaultDataTypeID, uavcan::TransferTypeMessageBroadcast,
uavcan::NodeID(uint8_t(i + 100)), uavcan::NodeID::Broadcast, 0, i, true);
uavcan::NodeID(uint8_t(i + 100)), uavcan::NodeID::Broadcast, i);
frame.setStartOfTransfer(true);
frame.setEndOfTransfer(true);
// No payload - message is empty
uavcan::RxFrame rx_frame(frame, clock_driver.getMonotonic(), clock_driver.getUtc(), 0);
can_driver.ifaces[0].pushRx(rx_frame);
@@ -62,6 +62,8 @@ static bool validateDataTypeInfoResponse(const std::auto_ptr<ServiceCallResultCo
return true;
}
// TODO FIXME NEW IMPLEMENTATION
#if 0
TEST(DataTypeInfoProvider, Basic)
{
@@ -225,3 +227,5 @@ TEST(DataTypeInfoProvider, Basic)
ASSERT_EQ(0, cats_cln.collector.result->getResponse().aggregate_signature);
ASSERT_FALSE(cats_cln.collector.result->getResponse().mutually_known_ids.any());
}
#endif
@@ -95,7 +95,7 @@ TEST(dynamic_node_id_server_AllocationRequestManager, Basic)
AllocationRequestManager manager(nodes.a, tracer, handler);
ASSERT_LE(0, manager.init());
ASSERT_LE(0, manager.init(uavcan::TransferPriority::OneHigherThanLowest));
/*
* Allocation
@@ -8,7 +8,6 @@
#include "../../helpers.hpp"
#include "../memory_storage_backend.hpp"
TEST(dynamic_node_id_server_ClusterManager, Initialization)
{
using namespace uavcan::dynamic_node_id_server::distributed;
@@ -32,11 +31,11 @@ TEST(dynamic_node_id_server_ClusterManager, Initialization)
ClusterManager mgr(nodes.a, storage, log, tracer);
// Too big
ASSERT_GT(0, mgr.init(MaxClusterSize + 1));
ASSERT_GT(0, mgr.init(MaxClusterSize + 1, uavcan::TransferPriority::OneHigherThanLowest));
ASSERT_EQ(0, storage.getNumKeys());
// OK
ASSERT_LE(0, mgr.init(5));
ASSERT_LE(0, mgr.init(5, uavcan::TransferPriority::OneHigherThanLowest));
ASSERT_EQ(1, storage.getNumKeys());
ASSERT_EQ("5", storage.get("cluster_size"));
@@ -57,12 +56,12 @@ TEST(dynamic_node_id_server_ClusterManager, Initialization)
ClusterManager mgr(nodes.a, storage, log, tracer);
// Not configured
ASSERT_GT(0, mgr.init());
ASSERT_GT(0, mgr.init(0, uavcan::TransferPriority::OneHigherThanLowest));
ASSERT_EQ(0, storage.getNumKeys());
// OK
storage.set("cluster_size", "5");
ASSERT_LE(0, mgr.init());
ASSERT_LE(0, mgr.init(0, uavcan::TransferPriority::OneHigherThanLowest));
ASSERT_EQ(1, storage.getNumKeys());
}
}
@@ -94,7 +93,7 @@ TEST(dynamic_node_id_server_ClusterManager, OneServer)
/*
* Starting
*/
ASSERT_LE(0, mgr.init(1));
ASSERT_LE(0, mgr.init(1, uavcan::TransferPriority::OneHigherThanLowest));
ASSERT_EQ(0, mgr.getNumKnownServers());
ASSERT_TRUE(mgr.isClusterDiscovered());
@@ -171,7 +170,7 @@ TEST(dynamic_node_id_server_ClusterManager, ThreeServers)
/*
* Starting
*/
ASSERT_LE(0, mgr.init(3));
ASSERT_LE(0, mgr.init(3, uavcan::TransferPriority::OneHigherThanLowest));
ASSERT_EQ(0, mgr.getNumKnownServers());
ASSERT_FALSE(mgr.isClusterDiscovered());
@@ -62,8 +62,8 @@ TEST(dynamic_node_id_server_RaftCore, Basic)
/*
* Initialization
*/
ASSERT_LE(0, raft_a->init(2));
ASSERT_LE(0, raft_b->init(2));
ASSERT_LE(0, raft_a->init(2, uavcan::TransferPriority::OneHigherThanLowest));
ASSERT_LE(0, raft_b->init(2, uavcan::TransferPriority::OneHigherThanLowest));
/*
* Running and trying not to fall
@@ -102,7 +102,7 @@ TEST(dynamic_node_id_server_RaftCore, Basic)
storage_a.reset();
raft_a.reset(new RaftCore(nodes.a, storage_a, tracer_a, commit_handler_a));
ASSERT_LE(0, raft_a->init(2));
ASSERT_LE(0, raft_a->init(2, uavcan::TransferPriority::OneHigherThanLowest));
ASSERT_EQ(0, raft_a->getCommitIndex());
nodes.spinBoth(uavcan::MonotonicDuration::fromMSec(9000));
@@ -104,7 +104,7 @@ TEST(dynamic_node_id_server_NodeDiscoverer, Basic)
/*
* Initialization
*/
ASSERT_LE(0, disc.init());
ASSERT_LE(0, disc.init(uavcan::TransferPriority::OneHigherThanLowest));
ASSERT_FALSE(disc.hasUnknownNodes());
@@ -208,7 +208,7 @@ TEST(dynamic_node_id_server_NodeDiscoverer, RestartAndMaxAttempts)
/*
* Initialization
*/
ASSERT_LE(0, disc.init());
ASSERT_LE(0, disc.init(uavcan::TransferPriority::OneHigherThanLowest));
ASSERT_FALSE(disc.hasUnknownNodes());
@@ -172,7 +172,9 @@ TEST(GlobalTimeSyncSlave, Basic)
static uavcan::Frame makeSyncMsg(uavcan::uint64_t usec, uavcan::NodeID snid, uavcan::TransferID tid)
{
uavcan::Frame frame(uavcan::protocol::GlobalTimeSync::DefaultDataTypeID, uavcan::TransferTypeMessageBroadcast,
snid, uavcan::NodeID::Broadcast, 0, tid, true);
snid, uavcan::NodeID::Broadcast, tid);
frame.setStartOfTransfer(true);
frame.setEndOfTransfer(true);
EXPECT_EQ(8, frame.setPayload(reinterpret_cast<uint8_t*>(&usec), 8)); // Assuming little endian
return frame;
}
+3 -1
View File
@@ -148,7 +148,9 @@ static inline void emulateSingleFrameBroadcastTransfer(CanDriver& can, uavcan::N
// DataTypeID data_type_id, TransferType transfer_type, NodeID src_node_id, NodeID dst_node_id,
// uint_fast8_t frame_index, TransferID transfer_id, bool last_frame
uavcan::Frame frame(MessageType::DefaultDataTypeID, uavcan::TransferTypeMessageBroadcast,
node_id, uavcan::NodeID::Broadcast, 0, tid, true);
node_id, uavcan::NodeID::Broadcast, tid);
frame.setStartOfTransfer(true);
frame.setEndOfTransfer(true);
ASSERT_EQ(buffer.getMaxWritePos(), frame.setPayload(buffer.getRawPtr(), buffer.getMaxWritePos()));
@@ -55,7 +55,9 @@ TEST(TransportStatsProvider, Basic)
* Sending a malformed frame, it must be registered as tranfer error
*/
uavcan::Frame frame(uavcan::protocol::GetTransportStats::DefaultDataTypeID, uavcan::TransferTypeServiceRequest,
2, 1, 0, 0, true);
2, 1, 0);
frame.setStartOfTransfer(true);
frame.setEndOfTransfer(true);
uavcan::CanFrame can_frame;
ASSERT_TRUE(frame.compile(can_frame));
nodes.can_a.read_queue.push(can_frame);
+18 -17
View File
@@ -101,15 +101,17 @@ TEST(Dispatcher, Reception)
static const std::string DATA[6] =
{
"Yes, man is mortal, but that would be only half the trouble. ",
"Yes, man is mortal, but that would be only half the trouble. "
"The worst of it is that he's sometimes unexpectedly mortal - there's the trick!",
"In fact, I'm beginning to fear that this confusion will go on for a long time. ",
"In fact, I'm beginning to fear that this confusion will go on for a long time. "
"And all because he writes down what I said incorrectly.",
"I had the pleasure of meeting that young man at the Patriarch's Ponds. ",
"I had the pleasure of meeting that young man at the Patriarch's Ponds. "
"He almost drove me mad myself, proving to me that I don't exist. But you do believe that it is really I?",
"He was a dreamer, a thinker, a speculative philosopher... or, as his wife would have it, an idiot.",
// This one is too long to use in message transfers
"The only way to get ideas for stories is to drink way too much coffee and buy a desk that doesn't "
"collapse when you beat your head against it",
@@ -121,18 +123,17 @@ TEST(Dispatcher, Reception)
std::cout << "Size of test data chunk " << i << ": " << DATA[i].length() << std::endl;
}
const Transfer transfers[9] =
const Transfer transfers[8] =
{
emulator.makeTransfer(uavcan::TransferPriorityNormal, uavcan::TransferTypeMessageBroadcast, 10, DATA[0], TYPES[0]),
emulator.makeTransfer(uavcan::TransferPriorityNormal, uavcan::TransferTypeMessageUnicast, 11, DATA[1], TYPES[1]),
emulator.makeTransfer(uavcan::TransferPriorityService, uavcan::TransferTypeServiceRequest, 12, DATA[2], TYPES[2]),
emulator.makeTransfer(uavcan::TransferPriorityService, uavcan::TransferTypeServiceResponse, 13, DATA[4], TYPES[3]),
emulator.makeTransfer(uavcan::TransferPriorityNormal, uavcan::TransferTypeMessageUnicast, 14, DATA[3], TYPES[0]),
emulator.makeTransfer(uavcan::TransferPriorityNormal, uavcan::TransferTypeMessageBroadcast, 15, DATA[5], TYPES[1]),
emulator.makeTransfer(0, uavcan::TransferTypeMessageBroadcast, 10, DATA[0], TYPES[0]),
emulator.makeTransfer(5, uavcan::TransferTypeMessageBroadcast, 11, DATA[1], TYPES[1]),
emulator.makeTransfer(10, uavcan::TransferTypeServiceRequest, 12, DATA[2], TYPES[2]),
emulator.makeTransfer(15, uavcan::TransferTypeServiceResponse, 13, DATA[4], TYPES[3]),
emulator.makeTransfer(20, uavcan::TransferTypeMessageBroadcast, 14, DATA[3], TYPES[0]),
emulator.makeTransfer(25, uavcan::TransferTypeMessageBroadcast, 15, DATA[5], TYPES[1]),
// Wrongly addressed:
emulator.makeTransfer(uavcan::TransferPriorityService, uavcan::TransferTypeServiceResponse, 10, DATA[0], TYPES[3], 100),
emulator.makeTransfer(uavcan::TransferPriorityService, uavcan::TransferTypeServiceRequest, 11, DATA[4], TYPES[2], 101),
emulator.makeTransfer(uavcan::TransferPriorityNormal, uavcan::TransferTypeMessageUnicast, 12, DATA[2], TYPES[1], 102)
emulator.makeTransfer(29, uavcan::TransferTypeServiceResponse, 10, DATA[0], TYPES[3], 100),
emulator.makeTransfer(31, uavcan::TransferTypeServiceRequest, 11, DATA[4], TYPES[2], 101)
};
/*
@@ -280,12 +281,12 @@ TEST(Dispatcher, Transmission)
// uint_fast16_t data_type_id, TransferType transfer_type, NodeID src_node_id, NodeID dst_node_id,
// uint_fast8_t frame_index, TransferID transfer_id, bool last_frame = false
uavcan::Frame frame(123, uavcan::TransferTypeMessageUnicast, SELF_NODE_ID, 2, 0, 0, true);
uavcan::Frame frame(123, uavcan::TransferTypeServiceRequest, SELF_NODE_ID, 2, 0);
frame.setPayload(reinterpret_cast<const uint8_t*>("123"), 3);
ASSERT_FALSE(dispatcher.hasPublisher(123));
ASSERT_FALSE(dispatcher.hasPublisher(456));
const uavcan::OutgoingTransferRegistryKey otr_key(123, uavcan::TransferTypeMessageUnicast, 2);
const uavcan::OutgoingTransferRegistryKey otr_key(123, uavcan::TransferTypeServiceRequest, 2);
ASSERT_TRUE(out_trans_reg.accessOrCreate(otr_key, uavcan::MonotonicTime::fromMSec(1000000)));
ASSERT_TRUE(dispatcher.hasPublisher(123));
ASSERT_FALSE(dispatcher.hasPublisher(456));
@@ -384,7 +385,7 @@ TEST(Dispatcher, Loopback)
// uint_fast16_t data_type_id, TransferType transfer_type, NodeID src_node_id, NodeID dst_node_id,
// uint_fast8_t frame_index, TransferID transfer_id, bool last_frame = false
uavcan::Frame frame(123, uavcan::TransferTypeMessageUnicast, SELF_NODE_ID, 2, 0, 0, true);
uavcan::Frame frame(123, uavcan::TransferTypeServiceResponse, SELF_NODE_ID, 2, 0);
frame.setPayload(reinterpret_cast<const uint8_t*>("123"), 3);
ASSERT_TRUE(listener.last_frame == uavcan::RxFrame());
+81 -190
View File
@@ -5,6 +5,7 @@
#include <string>
#include <gtest/gtest.h>
#include <uavcan/transport/transfer.hpp>
#include <uavcan/transport/crc.hpp>
#include "../clock.hpp"
#include "can/can.hpp"
@@ -19,24 +20,18 @@ TEST(Frame, MessageParseCompile)
Frame frame;
/*
* Priority (LOW, NORMAL, HIGH)
* Priority
* Message Type ID
* Service Not Message
* Source Node ID
* BroadcastNotUnicast
* Frame Index
* Last Frame
* Transfer ID
*/
const uint32_t can_id =
(1 << 27) | // Priority
(2000 << 16) | // Message Type ID
(42 << 9) | // Source Node ID
(1 << 8) | // BroadcastNotUnicast
(11 << 4) | // Frame Index
(1 << 3) | // Last Frame
(2 << 0); // Transfer ID
(16 << 24) | // Priority
(20000 << 8) | // Message Type ID
(0 << 7) | // Service Not Message
(42 << 0); // Source Node ID
const std::string payload_string = "hello";
const std::string payload_string = "hello\xD4"; // SET = 110, TID = 20
/*
* Parse
@@ -48,14 +43,15 @@ TEST(Frame, MessageParseCompile)
// Valid
ASSERT_TRUE(frame.parse(makeCanFrame(can_id, payload_string, EXT)));
EXPECT_EQ(TransferID(2), frame.getTransferID());
EXPECT_TRUE(frame.isLast());
EXPECT_EQ(11, frame.getIndex());
EXPECT_EQ(TransferID(20), frame.getTransferID());
EXPECT_TRUE(frame.isStartOfTransfer());
EXPECT_TRUE(frame.isEndOfTransfer());
EXPECT_FALSE(frame.getToggle());
EXPECT_EQ(uavcan::NodeID(42), frame.getSrcNodeID());
EXPECT_TRUE(frame.getDstNodeID().isBroadcast());
EXPECT_EQ(uavcan::TransferTypeMessageBroadcast, frame.getTransferType());
EXPECT_EQ(2000, frame.getDataTypeID().get());
EXPECT_EQ(uavcan::TransferPriorityNormal, frame.getPriority());
EXPECT_EQ(16, frame.getPriority().get());
EXPECT_EQ(payload_string.length(), frame.getPayloadLen());
EXPECT_TRUE(std::equal(frame.getPayloadPtr(), frame.getPayloadPtr() + frame.getPayloadLen(),
@@ -96,24 +92,22 @@ TEST(Frame, ServiceParseCompile)
Frame frame;
/*
* Priority = SERVICE
* RequestNotResponse
* Priority
* Service Type ID
* Request Not Response
* Destination Node ID
* Service Not Message
* Source Node ID
* Frame Index
* Last Frame
* Transfer ID
*/
const uint32_t can_id =
(2 << 27) | // Priority (Service)
(1 << 26) | // RequestNotResponse
(500 << 17) | // Service Type ID
(42 << 10) | // Source Node ID
(60 << 4) | // Frame Index
(1 << 3) | // Last Frame
(5 << 0); // Transfer ID
(31 << 24) | // Priority
(200 << 16) | // Service Type ID
(1 << 15) | // Request Not Response
(0x42 << 8) | // Destination Node ID
(1 << 7) | // Service Not Message
(42 << 0); // Source Node ID
const std::string payload_string = "\x42hello"; // dst = 0x42
const std::string payload_string = "hello\x6a"; // SET = 011, TID = 10
/*
* Parse
@@ -126,13 +120,14 @@ TEST(Frame, ServiceParseCompile)
ASSERT_TRUE(frame.parse(makeCanFrame(can_id, payload_string, EXT)));
EXPECT_EQ(TransferID(5), frame.getTransferID());
EXPECT_TRUE(frame.isLast());
EXPECT_EQ(60, frame.getIndex());
EXPECT_FALSE(frame.isStartOfTransfer());
EXPECT_TRUE(frame.isEndOfTransfer());
EXPECT_TRUE(frame.getToggle());
EXPECT_EQ(uavcan::NodeID(42), frame.getSrcNodeID());
EXPECT_EQ(uavcan::NodeID(0x42), frame.getDstNodeID());
EXPECT_EQ(uavcan::TransferTypeServiceRequest, frame.getTransferType());
EXPECT_EQ(500, frame.getDataTypeID().get());
EXPECT_EQ(uavcan::TransferPriorityService, frame.getPriority());
EXPECT_EQ(31, frame.getPriority().get());
EXPECT_EQ(payload_string.length(), frame.getPayloadLen() + 1);
EXPECT_TRUE(std::equal(frame.getPayloadPtr(), frame.getPayloadPtr() + frame.getPayloadLen(),
@@ -173,25 +168,20 @@ TEST(Frame, AnonymousParseCompile)
Frame frame;
/*
* Priority (LOW, NORMAL, HIGH)
* Priority
* Discriminator
* Message Type ID
* Service Not Message
* Source Node ID
* BroadcastNotUnicast
* Frame Index
* Last Frame
* Transfer ID
*/
const uint32_t can_id =
(0 << 27) | // Priority (high)
(2000 << 16) | // Message Type ID
(0 << 9) | // Source Node ID
(1 << 8) | // BroadcastNotUnicast
(11 << 4) | // Frame Index (will be ignored)
(1 << 3) | // Last Frame (will be ignored)
(2 << 0); // Transfer ID (will be ignored)
(16383 << 10) | // Discriminator
(1 << 8); // Message Type ID
const std::string payload_string = "\x01\x02\x03\x04";
const uint8_t payload_sum = 1 + 2 + 3 + 4;
const std::string payload_string = "hello\x94"; // SET = 100, TID = 20
uavcan::TransferCRC payload_crc;
payload_crc.add(reinterpret_cast<const uint8_t*>(payload_string.c_str()), unsigned(payload_string.length()));
/*
* Parse
@@ -199,13 +189,14 @@ TEST(Frame, AnonymousParseCompile)
ASSERT_TRUE(frame.parse(makeCanFrame(can_id, payload_string, EXT)));
EXPECT_EQ(TransferID(0), frame.getTransferID());
EXPECT_TRUE(frame.isLast());
EXPECT_EQ(0, frame.getIndex());
EXPECT_TRUE(frame.isStartOfTransfer());
EXPECT_FALSE(frame.isEndOfTransfer());
EXPECT_FALSE(frame.getToggle());
EXPECT_TRUE(frame.getSrcNodeID().isBroadcast());
EXPECT_TRUE(frame.getDstNodeID().isBroadcast());
EXPECT_EQ(uavcan::TransferTypeMessageBroadcast, frame.getTransferType());
EXPECT_EQ(2000, frame.getDataTypeID().get());
EXPECT_EQ(uavcan::TransferPriorityHigh, frame.getPriority());
EXPECT_EQ(1, frame.getDataTypeID().get());
EXPECT_EQ(0, frame.getPriority().get());
EXPECT_EQ(payload_string.length(), frame.getPayloadLen());
EXPECT_TRUE(std::equal(frame.getPayloadPtr(), frame.getPayloadPtr() + frame.getPayloadLen(),
@@ -216,17 +207,20 @@ TEST(Frame, AnonymousParseCompile)
/*
* Compile
*/
const uint32_t DiscriminatorMask = 0x00FFFC00;
const uint32_t NoDiscriminatorMask = 0xFF0003FF;
CanFrame can_frame;
ASSERT_TRUE(frame.parse(makeCanFrame(can_id, payload_string, EXT)));
ASSERT_TRUE(frame.compile(can_frame));
ASSERT_EQ(can_id & 0xFFFFFF00 & uavcan::CanFrame::MaskExtID,
can_frame.id & 0xFFFFFF00 & uavcan::CanFrame::MaskExtID);
ASSERT_EQ(can_id & NoDiscriminatorMask & uavcan::CanFrame::MaskExtID,
can_frame.id & NoDiscriminatorMask & uavcan::CanFrame::MaskExtID);
EXPECT_EQ(payload_string.length(), can_frame.dlc);
EXPECT_TRUE(std::equal(can_frame.data, can_frame.data + can_frame.dlc, payload_string.begin()));
ASSERT_EQ(payload_sum, can_frame.id & 0xFF);
EXPECT_EQ((can_frame.id & DiscriminatorMask & uavcan::CanFrame::MaskExtID) >> 10, payload_crc.get() & 16383);
/*
* Comparison
@@ -257,145 +251,44 @@ TEST(Frame, FrameParsing)
/*
* Message CAN ID fields and offsets:
* 27 Priority (LOW=3, NORMAL=1, HIGH=0)
* 16 Message Type ID
* 9 Source Node ID
* 8 BroadcastNotUnicast
* 4 Frame Index
* 3 Last Frame
* 0 Transfer ID
* 24 Priority
* 8 Message Type ID
* 7 Service Not Message (0)
* 0 Source Node ID
*
* Service CAN ID fields and offsets:
* 27 Priority (SERVICE=2)
* 26 RequestNotResponse
* 17 Service Type ID
* 10 Source Node ID
* 4 Frame Index
* 3 Last Frame
* 0 Transfer ID
* 24 Priority
* 16 Service Type ID
* 15 Request Not Response
* 8 Destination Node ID
* 7 Service Not Message (1)
* 0 Source Node ID
*/
/*
* SFT message broadcast
*/
can.id = CanFrame::FlagEFF |
(2 << 0) |
(1 << 3) |
(0 << 4) |
(1 << 8) |
(42 << 9) |
(456 << 16) |
(1 << 27);
(2 << 24) |
(456 << 8) |
(0 << 7) |
(42 << 0);
can.data[7] = 0xc0; // SET=110, TID=0
ASSERT_TRUE(frame.parse(can));
ASSERT_TRUE(frame.isFirst());
ASSERT_TRUE(frame.isLast());
ASSERT_EQ(uavcan::TransferPriorityNormal, frame.getPriority());
ASSERT_EQ(0, frame.getIndex());
EXPECT_TRUE(frame.isStartOfTransfer());
EXPECT_TRUE(frame.isEndOfTransfer());
EXPECT_FALSE(frame.getToggle());
ASSERT_EQ(2, frame.getPriority().get());
ASSERT_EQ(NodeID(42), frame.getSrcNodeID());
ASSERT_EQ(NodeID::Broadcast, frame.getDstNodeID());
ASSERT_EQ(456, frame.getDataTypeID().get());
ASSERT_EQ(TransferID(2), frame.getTransferID());
ASSERT_EQ(uavcan::TransferTypeMessageBroadcast, frame.getTransferType());
ASSERT_EQ(sizeof(CanFrame::data), frame.getMaxPayloadLen());
/*
* SFT message unicast
*/
can.id = CanFrame::FlagEFF |
(2 << 0) |
(1 << 3) | // Last Frame
(0 << 4) | // Frame Index
(0 << 8) |
(42 << 9) |
(456 << 16) |
(0 << 27);
ASSERT_FALSE(frame.parse(can)); // No payload - failure
can.dlc = 1;
can.data[0] = 0xFF;
ASSERT_FALSE(frame.parse(can)); // Invalid first byte - failure
can.data[0] = 127;
ASSERT_TRUE(frame.parse(can));
ASSERT_TRUE(frame.isFirst());
ASSERT_TRUE(frame.isLast());
ASSERT_EQ(uavcan::TransferPriorityHigh, frame.getPriority());
ASSERT_EQ(0, frame.getIndex());
ASSERT_EQ(NodeID(42), frame.getSrcNodeID());
ASSERT_EQ(NodeID(127), frame.getDstNodeID());
ASSERT_EQ(456, frame.getDataTypeID().get());
ASSERT_EQ(TransferID(2), frame.getTransferID());
ASSERT_EQ(uavcan::TransferTypeMessageUnicast, frame.getTransferType());
ASSERT_EQ(sizeof(CanFrame::data) - 1, frame.getMaxPayloadLen());
/*
* MFT message unicast
* Invalid - unterminated transfer
*/
can.id = CanFrame::FlagEFF |
(2 << 0) |
(0 << 3) |
(15 << 4) |
(0 << 8) |
(42 << 9) |
(456 << 16) |
(0 << 27);
ASSERT_FALSE(frame.parse(can));
/*
* MFT service request
* Invalid frame index
*/
can.id = CanFrame::FlagEFF |
(2 << 27) | // Priority (Service)
(1 << 26) | // RequestNotResponse
(500 << 17) | // Service Type ID
(42 << 10) | // Source Node ID
(63 << 4) | // Frame Index
(1 << 3) | // Last Frame
(5 << 0); // Transfer ID
ASSERT_FALSE(frame.parse(can));
/*
* Malformed frames
*/
can.id = CanFrame::FlagEFF |
(2 << 0) |
(1 << 3) |
(15 << 4) |
(0 << 8) |
(42 << 9) |
(456 << 16) |
(3 << 27);
can.dlc = 3;
can.data[0] = 42;
ASSERT_FALSE(frame.parse(can)); // Src == Dst Node ID
can.data[0] = 41;
ASSERT_TRUE(frame.parse(can));
ASSERT_EQ(uavcan::TransferPriorityLow, frame.getPriority());
/*
* Broadcast SNID exceptions
* Note that last 3 fields are ignored
*/
can.id = CanFrame::FlagEFF |
(2 << 27) | // Priority
(2000 << 16) | // Message Type ID
(0 << 9) | // Source Node ID
(1 << 8); // BroadcastNotUnicast
ASSERT_FALSE(frame.parse(can)); // Invalid priority
can.id = CanFrame::FlagEFF |
(1 << 27) | // Priority
(2000 << 16) | // Message Type ID
(0 << 9) | // Source Node ID
(1 << 8); // BroadcastNotUnicast
ASSERT_TRUE(frame.parse(can));
// TODO: test service frames
// TODO: test malformed frames
}
@@ -415,13 +308,10 @@ TEST(Frame, RxFrameParse)
// Valid
can_rx_frame.ts_mono = uavcan::MonotonicTime::fromUSec(1); // Zero is not allowed
can_rx_frame.id = CanFrame::FlagEFF |
(2 << 0) |
(1 << 3) |
(0 << 4) |
(1 << 8) |
(42 << 9) |
(456 << 16) |
(1 << 27);
(2 << 24) |
(456 << 8) |
(0 << 7) |
(42 << 0);
ASSERT_TRUE(rx_frame.parse(can_rx_frame));
ASSERT_EQ(1, rx_frame.getMonotonicTimestamp().toUSec());
@@ -430,7 +320,7 @@ TEST(Frame, RxFrameParse)
can_rx_frame.ts_mono = tsMono(123);
can_rx_frame.iface_index = 2;
Frame frame(456, uavcan::TransferTypeMessageBroadcast, 1, uavcan::NodeID::Broadcast, 0, 0);
Frame frame(456, uavcan::TransferTypeMessageBroadcast, 1, uavcan::NodeID::Broadcast, 0);
ASSERT_TRUE(frame.compile(can_rx_frame));
ASSERT_TRUE(rx_frame.parse(can_rx_frame));
@@ -448,14 +338,13 @@ TEST(Frame, FrameToString)
// RX frame default
RxFrame rx_frame;
EXPECT_EQ("prio=4 dtid=65535 tt=4 snid=255 dnid=255 idx=0 last=0 tid=0 payload=[] ts_m=0.000000 ts_utc=0.000000 iface=0",
EXPECT_EQ("prio=255 dtid=65535 tt=3 snid=255 dnid=255 sot=0 eot=0 togl=0 tid=0 payload=[] ts_m=0.000000 ts_utc=0.000000 iface=0",
rx_frame.toString());
// RX frame max len
rx_frame = RxFrame(Frame(uavcan::DataTypeID::MaxPossibleDataTypeIDValue, uavcan::TransferTypeMessageUnicast,
rx_frame = RxFrame(Frame(uavcan::DataTypeID::MaxPossibleDataTypeIDValue, uavcan::TransferTypeMessageBroadcast,
uavcan::NodeID::Max, uavcan::NodeID::Max - 1,
Frame::getMaxIndexForTransferType(uavcan::TransferTypeMessageUnicast),
uavcan::TransferID::Max, true),
uavcan::TransferID::Max),
uavcan::MonotonicTime::getMax(), uavcan::UtcTime::getMax(), 3);
uint8_t data[8];
@@ -465,7 +354,9 @@ TEST(Frame, FrameToString)
}
rx_frame.setPayload(data, sizeof(data));
EXPECT_EQ("prio=1 dtid=2047 tt=3 snid=127 dnid=126 idx=15 last=1 tid=7 payload=[00 01 02 03 04 05 06] "
rx_frame.setPriority(uavcan::TransferPriority::NumericallyMax);
EXPECT_EQ("prio=31 dtid=65535 tt=2 snid=127 dnid=126 sot=0 eot=0 togl=0 tid=0 payload=[00 01 02 03 04 05 06] "
"ts_m=18446744073709.551615 ts_utc=18446744073709.551615 iface=3",
rx_frame.toString());
@@ -12,7 +12,7 @@
static uavcan::RxFrame makeFrame()
{
uavcan::RxFrame frame(
uavcan::Frame(123, uavcan::TransferTypeMessageBroadcast, 1, uavcan::NodeID::Broadcast, 0, 1, true),
uavcan::Frame(123, uavcan::TransferTypeMessageBroadcast, 1, uavcan::NodeID::Broadcast, 0),
tsMono(123), tsUtc(456), 0);
uint8_t data[8];
for (uint8_t i = 0; i < sizeof(data); i++)
@@ -20,10 +20,10 @@ TEST(OutgoingTransferRegistry, Basic)
static const int NUM_KEYS = 5;
const OutgoingTransferRegistryKey keys[NUM_KEYS] =
{
OutgoingTransferRegistryKey(123, uavcan::TransferTypeMessageUnicast, 42),
OutgoingTransferRegistryKey(123, uavcan::TransferTypeServiceResponse, 42),
OutgoingTransferRegistryKey(321, uavcan::TransferTypeMessageBroadcast, 0),
OutgoingTransferRegistryKey(213, uavcan::TransferTypeServiceRequest, 2),
OutgoingTransferRegistryKey(312, uavcan::TransferTypeMessageUnicast, 4),
OutgoingTransferRegistryKey(312, uavcan::TransferTypeServiceResponse, 4),
OutgoingTransferRegistryKey(456, uavcan::TransferTypeServiceRequest, 2)
};
+3 -3
View File
@@ -236,14 +236,14 @@ TEST(TransferBufferManager, Basic)
std::auto_ptr<TransferBufferManagerType> mgr(new TransferBufferManagerType(pool));
// Empty
ASSERT_FALSE(mgr->access(TransferBufferManagerKey(0, uavcan::TransferTypeMessageUnicast)));
ASSERT_FALSE(mgr->access(TransferBufferManagerKey(127, uavcan::TransferTypeMessageUnicast)));
ASSERT_FALSE(mgr->access(TransferBufferManagerKey(0, uavcan::TransferTypeMessageBroadcast)));
ASSERT_FALSE(mgr->access(TransferBufferManagerKey(127, uavcan::TransferTypeServiceRequest)));
ITransferBuffer* tbb = NULL;
const TransferBufferManagerKey keys[5] =
{
TransferBufferManagerKey(0, uavcan::TransferTypeMessageUnicast),
TransferBufferManagerKey(0, uavcan::TransferTypeServiceRequest),
TransferBufferManagerKey(1, uavcan::TransferTypeMessageBroadcast),
TransferBufferManagerKey(2, uavcan::TransferTypeServiceRequest),
TransferBufferManagerKey(127, uavcan::TransferTypeServiceResponse),
+22 -53
View File
@@ -45,7 +45,6 @@ TEST(TransferListener, BasicMFT)
*/
static const std::string DATA[] =
{
// Too long for unicast messages
"Build a man a fire, and he'll be warm for a day. "
"Set a man on fire, and he'll be warm for the rest of his life.",
@@ -53,7 +52,6 @@ TEST(TransferListener, BasicMFT)
"In the beginning there was nothing, which exploded.",
// Too long for message transfers
"The USSR, which they'd begun to renovate and improve at about the time when Tatarsky decided to "
"change his profession, improved so much that it ceased to exist",
@@ -68,11 +66,11 @@ TEST(TransferListener, BasicMFT)
TransferListenerEmulator emulator(subscriber, type);
const Transfer transfers[] =
{
emulator.makeTransfer(uavcan::TransferPriorityNormal, uavcan::TransferTypeMessageBroadcast, 1, DATA[0]),
emulator.makeTransfer(uavcan::TransferPriorityNormal, uavcan::TransferTypeMessageUnicast, 1, DATA[1]), // Same NID
emulator.makeTransfer(uavcan::TransferPriorityNormal, uavcan::TransferTypeMessageUnicast, 2, DATA[2]),
emulator.makeTransfer(uavcan::TransferPriorityService, uavcan::TransferTypeServiceRequest, 3, DATA[3]),
emulator.makeTransfer(uavcan::TransferPriorityService, uavcan::TransferTypeServiceResponse, 4, DATA[4]),
emulator.makeTransfer(16, uavcan::TransferTypeMessageBroadcast, 1, DATA[0]),
emulator.makeTransfer(16, uavcan::TransferTypeMessageBroadcast, 1, DATA[1]), // Same NID
emulator.makeTransfer(16, uavcan::TransferTypeMessageBroadcast, 2, DATA[2]),
emulator.makeTransfer(16, uavcan::TransferTypeServiceRequest, 3, DATA[3]),
emulator.makeTransfer(16, uavcan::TransferTypeServiceResponse, 4, DATA[4]),
};
/*
@@ -103,8 +101,8 @@ TEST(TransferListener, CrcFailure)
* Generating transfers with damaged payload (CRC is not valid)
*/
TransferListenerEmulator emulator(subscriber, type);
const Transfer tr_mft = emulator.makeTransfer(uavcan::TransferPriorityNormal, uavcan::TransferTypeMessageBroadcast, 42, "123456789abcdefghik");
const Transfer tr_sft = emulator.makeTransfer(uavcan::TransferPriorityNormal, uavcan::TransferTypeMessageUnicast, 11, "abcd");
const Transfer tr_mft = emulator.makeTransfer(16, uavcan::TransferTypeMessageBroadcast, 42, "123456789abcdefghik");
const Transfer tr_sft = emulator.makeTransfer(16, uavcan::TransferTypeMessageBroadcast, 11, "abcd");
std::vector<uavcan::RxFrame> ser_mft = serializeTransfer(tr_mft);
std::vector<uavcan::RxFrame> ser_sft = serializeTransfer(tr_sft);
@@ -145,15 +143,15 @@ TEST(TransferListener, BasicSFT)
TransferListenerEmulator emulator(subscriber, type);
const Transfer transfers[] =
{
emulator.makeTransfer(uavcan::TransferPriorityNormal, uavcan::TransferTypeMessageBroadcast, 1, "123"),
emulator.makeTransfer(uavcan::TransferPriorityNormal, uavcan::TransferTypeMessageUnicast, 1, "456"), // Same NID
emulator.makeTransfer(uavcan::TransferPriorityNormal, uavcan::TransferTypeMessageUnicast, 2, ""),
emulator.makeTransfer(uavcan::TransferPriorityService, uavcan::TransferTypeServiceRequest, 3, "abc"),
emulator.makeTransfer(uavcan::TransferPriorityService, uavcan::TransferTypeServiceResponse, 4, ""),
emulator.makeTransfer(uavcan::TransferPriorityService, uavcan::TransferTypeServiceResponse, 2, ""), // New TT, ignored due to OOM
emulator.makeTransfer(uavcan::TransferPriorityNormal, uavcan::TransferTypeMessageUnicast, 2, "foo"), // Same as 2, not ignored
emulator.makeTransfer(uavcan::TransferPriorityNormal, uavcan::TransferTypeMessageUnicast, 2, "123456789abc"), // Same as 2, not SFT - ignore
emulator.makeTransfer(uavcan::TransferPriorityNormal, uavcan::TransferTypeMessageUnicast, 2, "bar"), // Same as 2, not ignored
emulator.makeTransfer(16, uavcan::TransferTypeMessageBroadcast, 1, "123"),
emulator.makeTransfer(16, uavcan::TransferTypeServiceRequest, 1, "456"), // Same NID
emulator.makeTransfer(16, uavcan::TransferTypeServiceRequest, 2, ""),
emulator.makeTransfer(16, uavcan::TransferTypeServiceRequest, 3, "abc"),
emulator.makeTransfer(16, uavcan::TransferTypeServiceResponse, 4, ""),
emulator.makeTransfer(16, uavcan::TransferTypeServiceResponse, 2, ""), // New TT, ignored due to OOM
emulator.makeTransfer(16, uavcan::TransferTypeServiceRequest, 2, "foo"), // Same as 2, not ignored
emulator.makeTransfer(16, uavcan::TransferTypeServiceRequest, 2, "123456789abc"), // Same as 2, not SFT - ignore
emulator.makeTransfer(16, uavcan::TransferTypeServiceRequest, 2, "bar"), // Same as 2, not ignored
};
emulator.send(transfers);
@@ -182,8 +180,8 @@ TEST(TransferListener, Cleanup)
* Generating transfers
*/
TransferListenerEmulator emulator(subscriber, type);
const Transfer tr_mft = emulator.makeTransfer(uavcan::TransferPriorityNormal, uavcan::TransferTypeMessageBroadcast, 42, "123456789abcdefghik");
const Transfer tr_sft = emulator.makeTransfer(uavcan::TransferPriorityNormal, uavcan::TransferTypeMessageUnicast, 11, "abcd");
const Transfer tr_mft = emulator.makeTransfer(16, uavcan::TransferTypeMessageBroadcast, 42, "123456789abcdefghik");
const Transfer tr_sft = emulator.makeTransfer(16, uavcan::TransferTypeServiceResponse, 11, "abcd");
const std::vector<uavcan::RxFrame> ser_mft = serializeTransfer(tr_mft);
const std::vector<uavcan::RxFrame> ser_sft = serializeTransfer(tr_sft);
@@ -225,35 +223,6 @@ TEST(TransferListener, Cleanup)
}
TEST(TransferListener, MaximumTransferLength)
{
const uavcan::DataTypeDescriptor type(uavcan::DataTypeKindMessage, 123, uavcan::DataTypeSignature(123456789), "A");
NullAllocator poolmgr;
uavcan::TransferPerfCounter perf;
TestListener<uavcan::MaxPossibleTransferPayloadLen * 2, 3, 3> subscriber(perf, type, poolmgr);
TransferListenerEmulator emulator(subscriber, type);
const Transfer transfers[] =
{
emulator.makeTransfer(uavcan::TransferPriorityService, uavcan::TransferTypeServiceRequest, 1,
std::string(uavcan::MaxServiceTransferPayloadLen, 'z')), // Longer
emulator.makeTransfer(uavcan::TransferPriorityNormal, uavcan::TransferTypeMessageUnicast, 2,
std::string(uavcan::MaxMessageUnicastTransferPayloadLen, 'z')), // Shorter
emulator.makeTransfer(uavcan::TransferPriorityNormal, uavcan::TransferTypeMessageBroadcast, 3,
std::string(uavcan::MaxMessageBroadcastTransferPayloadLen, 'z')) // Same as above
};
emulator.send(transfers);
ASSERT_TRUE(subscriber.matchAndPop(transfers[1]));
ASSERT_TRUE(subscriber.matchAndPop(transfers[2]));
ASSERT_TRUE(subscriber.matchAndPop(transfers[0])); // Service takes more frames
ASSERT_TRUE(subscriber.isEmpty());
}
TEST(TransferListener, AnonymousTransfers)
{
const uavcan::DataTypeDescriptor type(uavcan::DataTypeKindMessage, 123, uavcan::DataTypeSignature(123456789), "A");
@@ -265,10 +234,10 @@ TEST(TransferListener, AnonymousTransfers)
TransferListenerEmulator emulator(subscriber, type);
const Transfer transfers[] =
{
emulator.makeTransfer(uavcan::TransferPriorityNormal, uavcan::TransferTypeMessageUnicast, 0, "12345678"), // Invalid - not broadcast
emulator.makeTransfer(uavcan::TransferPriorityNormal, uavcan::TransferTypeMessageBroadcast, 0, "12345678"), // Valid
emulator.makeTransfer(uavcan::TransferPriorityNormal, uavcan::TransferTypeMessageBroadcast, 0, "123456789"), // Invalid - not SFT
emulator.makeTransfer(uavcan::TransferPriorityNormal, uavcan::TransferTypeMessageBroadcast, 0, "") // Valid
emulator.makeTransfer(16, uavcan::TransferTypeServiceRequest, 0, "1234567"), // Invalid - not broadcast
emulator.makeTransfer(16, uavcan::TransferTypeMessageBroadcast, 0, "1234567"), // Valid
emulator.makeTransfer(16, uavcan::TransferTypeMessageBroadcast, 0, "12345678"), // Invalid - not SFT
emulator.makeTransfer(16, uavcan::TransferTypeMessageBroadcast, 0, "") // Valid
};
emulator.send(transfers);
+116 -119
View File
@@ -13,6 +13,18 @@
* The code you're about to look at desperately needs some cleaning.
*/
enum SotEotToggle
{
SET000 = 0,
SET001 = 1,
SET010 = 2,
SET011 = 3,
SET100 = 4,
SET101 = 5, // Illegal
SET110 = 6,
SET111 = 7 // Illegal
};
struct RxFrameGenerator
{
static const uavcan::TransferBufferManagerKey DEFAULT_KEY;
@@ -26,7 +38,8 @@ struct RxFrameGenerator
, bufmgr_key(bufmgr_key)
{ }
uavcan::RxFrame operator()(uint8_t iface_index, const std::string& data, uint8_t frame_index, bool last,
/// iface_index, data, set, transfer_id, ts_monotonic [, ts_utc]
uavcan::RxFrame operator()(uint8_t iface_index, const std::string& data, SotEotToggle set,
uint8_t transfer_id, uint64_t ts_monotonic, uint64_t ts_utc = 0)
{
const uavcan::NodeID dst_nid =
@@ -34,7 +47,15 @@ struct RxFrameGenerator
uavcan::NodeID::Broadcast : TARGET_NODE_ID;
uavcan::Frame frame(data_type_id, bufmgr_key.getTransferType(), bufmgr_key.getNodeID(),
dst_nid, frame_index, transfer_id, last);
dst_nid, transfer_id);
frame.setStartOfTransfer((set & (1 << 2)) != 0);
frame.setEndOfTransfer((set & (1 << 1)) != 0);
if ((set & (1 << 0)) != 0)
{
frame.flipToggle();
}
EXPECT_EQ(data.length(),
frame.setPayload(reinterpret_cast<const uint8_t*>(data.c_str()), unsigned(data.length())));
@@ -113,16 +134,16 @@ TEST(TransferReceiver, Basic)
/*
* Single frame transfer with zero ts, must be ignored
*/
CHECK_NOT_COMPLETE(rcv.addFrame(gen(0, "Foo", 0, true, 0, 0), bk));
CHECK_NOT_COMPLETE(rcv.addFrame(gen(0, "Foo", SET110, 0, 0), bk));
ASSERT_EQ(TransferReceiver::getDefaultTransferInterval(), rcv.getInterval());
ASSERT_EQ(0, rcv.getLastTransferTimestampMonotonic().toUSec());
/*
* Valid compound transfer
* Args: iface_index, data, frame_index, last, transfer_id, timestamp
* Args: iface_index, data, set, transfer_id, ts_monotonic
*/
CHECK_NOT_COMPLETE(rcv.addFrame(gen(0, "\x34\x12" "345678", 0, false, 0, 100), bk));
CHECK_COMPLETE(rcv.addFrame(gen(0, "foo", 1, true, 0, 200), bk));
CHECK_NOT_COMPLETE(rcv.addFrame(gen(0, "\x34\x12" "345678", SET100, 0, 100), bk));
CHECK_COMPLETE( rcv.addFrame(gen(0, "foo", SET011, 0, 200), bk));
ASSERT_TRUE(matchBufferContent(bufmgr.access(gen.bufmgr_key), "345678foo"));
ASSERT_EQ(0x1234, rcv.getLastTransferCrc());
@@ -131,16 +152,18 @@ TEST(TransferReceiver, Basic)
/*
* Compound transfer mixed with invalid frames; buffer was not released explicitly
* Args: iface_index, data, set, transfer_id, ts_monotonic
*/
CHECK_NOT_COMPLETE(rcv.addFrame(gen(0, "qwe", 0, false, 0, 300), bk)); // Previous TID, rejected
CHECK_NOT_COMPLETE(rcv.addFrame(gen(1, "rty", 0, false, 0, 300), bk)); // Previous TID, wrong iface
CHECK_NOT_COMPLETE(rcv.addFrame(gen(0, "\x9a\x78" "345678", 0, false, 1, 1000), bk));
CHECK_NOT_COMPLETE(rcv.addFrame(gen(0, "qwertyui", 0, false, 1, 1100), bk)); // Old FI
CHECK_NOT_COMPLETE(rcv.addFrame(gen(0, "abcdefgh", 1, false, 1, 1200), bk));
CHECK_NOT_COMPLETE(rcv.addFrame(gen(0, "45678910", 1, false, 2, 1300), bk)); // Next TID, but FI > 0
CHECK_NOT_COMPLETE(rcv.addFrame(gen(1, "", 2, true, 1, 1300), bk)); // Wrong iface
CHECK_NOT_COMPLETE(rcv.addFrame(gen(0, "", 11, true, 1, 1300), bk)); // Unexpected FI
CHECK_COMPLETE( rcv.addFrame(gen(0, "", 2, true, 1, 1300), bk));
CHECK_NOT_COMPLETE(rcv.addFrame(gen(0, "qwe", SET100, 0, 300), bk)); // Previous TID, rejected
CHECK_NOT_COMPLETE(rcv.addFrame(gen(1, "rty", SET100, 0, 300), bk)); // Previous TID, wrong iface
CHECK_NOT_COMPLETE(rcv.addFrame(gen(0, "\x9a\x78" "345678", SET100, 1, 1000), bk));
CHECK_NOT_COMPLETE(rcv.addFrame(gen(0, "qwertyui", SET100, 1, 1100), bk)); // Old toggle
CHECK_NOT_COMPLETE(rcv.addFrame(gen(0, "qwertyui", SET000, 1, 1100), bk)); // Old toggle
CHECK_NOT_COMPLETE(rcv.addFrame(gen(0, "abcdefgh", SET001, 1, 1200), bk));
CHECK_NOT_COMPLETE(rcv.addFrame(gen(0, "45678910", SET001, 2, 1300), bk)); // Next TID, but not SOT
CHECK_NOT_COMPLETE(rcv.addFrame(gen(1, "", SET010, 1, 1300), bk)); // Wrong iface
CHECK_NOT_COMPLETE(rcv.addFrame(gen(0, "", SET000, 1, 1300), bk)); // Unexpected toggle
CHECK_COMPLETE( rcv.addFrame(gen(0, "", SET010, 1, 1300), bk));
ASSERT_TRUE(matchBufferContent(bufmgr.access(gen.bufmgr_key), "345678abcdefgh"));
ASSERT_EQ(0x789A, rcv.getLastTransferCrc());
@@ -153,25 +176,26 @@ TEST(TransferReceiver, Basic)
/*
* Single-frame transfers
* Args: iface_index, data, set, transfer_id, ts_monotonic
*/
CHECK_NOT_COMPLETE(rcv.addFrame(gen(0, "qwe", 0, true, 1, 2000), bk)); // Previous TID
CHECK_NOT_COMPLETE(rcv.addFrame(gen(1, "qwe", 0, true, 2, 2100), bk)); // Wrong iface
CHECK_SINGLE_FRAME(rcv.addFrame(gen(0, "qwe", 0, true, 2, 2200), bk));
CHECK_NOT_COMPLETE(rcv.addFrame(gen(0, "qwe", SET110, 1, 2000), bk)); // Previous TID
CHECK_NOT_COMPLETE(rcv.addFrame(gen(1, "qwe", SET110, 2, 2100), bk)); // Wrong iface
CHECK_SINGLE_FRAME(rcv.addFrame(gen(0, "qwe", SET110, 2, 2200), bk));
ASSERT_FALSE(bufmgr.access(gen.bufmgr_key)); // Buffer must be removed
ASSERT_GT(TransferReceiver::getDefaultTransferInterval(), rcv.getInterval());
ASSERT_EQ(2200, rcv.getLastTransferTimestampMonotonic().toUSec());
CHECK_SINGLE_FRAME(rcv.addFrame(gen(0, "", 0, true, 3, 2500), bk));
CHECK_SINGLE_FRAME(rcv.addFrame(gen(0, "", SET110, 3, 2500), bk));
ASSERT_EQ(2500, rcv.getLastTransferTimestampMonotonic().toUSec());
CHECK_NOT_COMPLETE(rcv.addFrame(gen(0, "", 0, true, 0, 3000), bk)); // Old TID
CHECK_NOT_COMPLETE(rcv.addFrame(gen(0, "", 0, true, 1, 3100), bk)); // Old TID
CHECK_NOT_COMPLETE(rcv.addFrame(gen(0, "", 0, true, 3, 3200), bk)); // Old TID
CHECK_NOT_COMPLETE(rcv.addFrame(gen(1, "", 0, true, 0, 3300), bk)); // Old TID, wrong iface
CHECK_NOT_COMPLETE(rcv.addFrame(gen(1, "", 0, true, 2, 3400), bk)); // Old TID, wrong iface
CHECK_NOT_COMPLETE(rcv.addFrame(gen(1, "", 0, true, 3, 3500), bk)); // Old TID, wrong iface
CHECK_SINGLE_FRAME(rcv.addFrame(gen(0, "", 0, true, 4, 3600), bk));
CHECK_NOT_COMPLETE(rcv.addFrame(gen(0, "", SET110, 0, 3000), bk)); // Old TID
CHECK_NOT_COMPLETE(rcv.addFrame(gen(0, "", SET110, 1, 3100), bk)); // Old TID
CHECK_NOT_COMPLETE(rcv.addFrame(gen(0, "", SET110, 3, 3200), bk)); // Old TID
CHECK_NOT_COMPLETE(rcv.addFrame(gen(1, "", SET110, 0, 3300), bk)); // Old TID, wrong iface
CHECK_NOT_COMPLETE(rcv.addFrame(gen(1, "", SET110, 2, 3400), bk)); // Old TID, wrong iface
CHECK_NOT_COMPLETE(rcv.addFrame(gen(1, "", SET110, 3, 3500), bk)); // Old TID, wrong iface
CHECK_SINGLE_FRAME(rcv.addFrame(gen(0, "", SET110, 4, 3600), bk));
ASSERT_EQ(3600, rcv.getLastTransferTimestampMonotonic().toUSec());
std::cout << "Interval: " << rcv.getInterval().toString() << std::endl;
@@ -179,34 +203,34 @@ TEST(TransferReceiver, Basic)
/*
* Timeouts
*/
CHECK_NOT_COMPLETE(rcv.addFrame(gen(1, "qwe", 0, true, 1, 5000), bk)); // Wrong iface - ignored
CHECK_SINGLE_FRAME(rcv.addFrame(gen(1, "qwe", 0, true, 6, 1500000), bk)); // Accepted due to iface timeout
CHECK_NOT_COMPLETE(rcv.addFrame(gen(1, "qwe", SET110, 1, 5000), bk)); // Wrong iface - ignored
CHECK_SINGLE_FRAME(rcv.addFrame(gen(1, "qwe", SET110, 6, 1500000), bk)); // Accepted due to iface timeout
ASSERT_EQ(1500000, rcv.getLastTransferTimestampMonotonic().toUSec());
std::cout << "Interval: " << rcv.getInterval().toString() << std::endl;
CHECK_NOT_COMPLETE(rcv.addFrame(gen(0, "qwe", 0, true, 7, 1500100), bk)); // Ignored - old iface 0
CHECK_SINGLE_FRAME(rcv.addFrame(gen(1, "qwe", 0, true, 7, 1500100), bk));
CHECK_NOT_COMPLETE(rcv.addFrame(gen(0, "qwe", SET110, 7, 1500100), bk)); // Ignored - old iface 0
CHECK_SINGLE_FRAME(rcv.addFrame(gen(1, "qwe", SET110, 7, 1500100), bk));
ASSERT_EQ(1500100, rcv.getLastTransferTimestampMonotonic().toUSec());
std::cout << "Interval: " << rcv.getInterval().toString() << std::endl;
CHECK_NOT_COMPLETE(rcv.addFrame(gen(1, "qwe", 0, true, 7, 1500100), bk)); // Old TID
CHECK_SINGLE_FRAME(rcv.addFrame(gen(0, "qwe", 0, true, 7, 100000000), bk)); // Accepted - global timeout
CHECK_NOT_COMPLETE(rcv.addFrame(gen(1, "qwe", SET110, 7, 1500100), bk)); // Old TID
CHECK_SINGLE_FRAME(rcv.addFrame(gen(0, "qwe", SET110, 7, 100000000), bk)); // Accepted - global timeout
ASSERT_EQ(100000000, rcv.getLastTransferTimestampMonotonic().toUSec());
std::cout << "Interval: " << rcv.getInterval().toString() << std::endl;
CHECK_SINGLE_FRAME(rcv.addFrame(gen(0, "qwe", 0, true, 0, 100000100), bk));
CHECK_SINGLE_FRAME(rcv.addFrame(gen(0, "qwe", SET110, 0, 100000100), bk));
ASSERT_EQ(100000100, rcv.getLastTransferTimestampMonotonic().toUSec());
std::cout << "Interval: " << rcv.getInterval().toString() << std::endl;
ASSERT_TRUE(rcv.isTimedOut(tsMono(900000000)));
CHECK_NOT_COMPLETE(rcv.addFrame(gen(1, "\x78\x56" "345678", 0, false, 0, 900000000), bk)); // Global timeout
CHECK_NOT_COMPLETE(rcv.addFrame(gen(0, "12345678", 0, false, 0, 900000100), bk)); // Wrong iface
CHECK_NOT_COMPLETE(rcv.addFrame(gen(0, "qwe", 1, true, 0, 900000200), bk)); // Wrong iface
CHECK_COMPLETE( rcv.addFrame(gen(1, "qwe", 1, true, 0, 900000200), bk));
CHECK_NOT_COMPLETE(rcv.addFrame(gen(1, "\x78\x56" "345678", SET100, 0, 900000000), bk)); // Global timeout
CHECK_NOT_COMPLETE(rcv.addFrame(gen(0, "12345678", SET100, 0, 900000100), bk)); // Wrong iface
CHECK_NOT_COMPLETE(rcv.addFrame(gen(0, "qwe", SET011, 0, 900000200), bk)); // Wrong iface
CHECK_COMPLETE( rcv.addFrame(gen(1, "qwe", SET011, 0, 900000200), bk));
ASSERT_EQ(900000000, rcv.getLastTransferTimestampMonotonic().toUSec());
std::cout << "Interval: " << rcv.getInterval().toString() << std::endl;
@@ -241,11 +265,11 @@ TEST(TransferReceiver, OutOfBufferSpace_32bytes)
/*
* Simple transfer, maximum buffer length
*/
CHECK_NOT_COMPLETE(rcv.addFrame(gen(1, "12345678", 0, false, 1, 100000000), bk)); // 6
CHECK_NOT_COMPLETE(rcv.addFrame(gen(1, "12345678", 1, false, 1, 100000100), bk)); // 14
CHECK_NOT_COMPLETE(rcv.addFrame(gen(1, "12345678", 2, false, 1, 100000200), bk)); // 22
CHECK_NOT_COMPLETE(rcv.addFrame(gen(1, "12345678", 3, false, 1, 100000300), bk)); // 30
CHECK_COMPLETE( rcv.addFrame(gen(1, "12", 4, true, 1, 100000400), bk)); // 32
CHECK_NOT_COMPLETE(rcv.addFrame(gen(1, "12345678", SET100, 1, 100000000), bk)); // 6
CHECK_NOT_COMPLETE(rcv.addFrame(gen(1, "12345678", SET001, 1, 100000100), bk)); // 14
CHECK_NOT_COMPLETE(rcv.addFrame(gen(1, "12345678", SET000, 1, 100000200), bk)); // 22
CHECK_NOT_COMPLETE(rcv.addFrame(gen(1, "12345678", SET001, 1, 100000300), bk)); // 30
CHECK_COMPLETE( rcv.addFrame(gen(1, "12", SET010, 1, 100000400), bk)); // 32
ASSERT_EQ(100000000, rcv.getLastTransferTimestampMonotonic().toUSec());
ASSERT_TRUE(matchBufferContent(bufmgr.access(gen.bufmgr_key), "34567812345678123456781234567812"));
@@ -254,11 +278,11 @@ TEST(TransferReceiver, OutOfBufferSpace_32bytes)
/*
* Transfer longer than available buffer space
*/
CHECK_NOT_COMPLETE(rcv.addFrame(gen(1, "12345678", 0, false, 2, 100001000), bk)); // 6
CHECK_NOT_COMPLETE(rcv.addFrame(gen(1, "12345678", 1, false, 2, 100001100), bk)); // 14
CHECK_NOT_COMPLETE(rcv.addFrame(gen(1, "12345678", 2, false, 2, 100001200), bk)); // 22
CHECK_NOT_COMPLETE(rcv.addFrame(gen(1, "12345678", 3, false, 2, 100001200), bk)); // 30
CHECK_NOT_COMPLETE(rcv.addFrame(gen(1, "12345678", 4, true, 2, 100001300), bk)); // 38 // EOT, ignored - lost sync
CHECK_NOT_COMPLETE(rcv.addFrame(gen(1, "12345678", SET100, 2, 100001000), bk)); // 6
CHECK_NOT_COMPLETE(rcv.addFrame(gen(1, "12345678", SET001, 2, 100001100), bk)); // 14
CHECK_NOT_COMPLETE(rcv.addFrame(gen(1, "12345678", SET000, 2, 100001200), bk)); // 22
CHECK_NOT_COMPLETE(rcv.addFrame(gen(1, "12345678", SET001, 2, 100001200), bk)); // 30
CHECK_NOT_COMPLETE(rcv.addFrame(gen(1, "12345678", SET010, 2, 100001300), bk)); // 38 // EOT, ignored - lost sync
ASSERT_EQ(100000000, rcv.getLastTransferTimestampMonotonic().toUSec()); // Timestamp will not be overriden
ASSERT_FALSE(bufmgr.access(gen.bufmgr_key)); // Buffer should be removed
@@ -268,32 +292,6 @@ TEST(TransferReceiver, OutOfBufferSpace_32bytes)
}
TEST(TransferReceiver, UnterminatedTransfer)
{
Context<512> context;
RxFrameGenerator gen(789);
uavcan::TransferReceiver& rcv = context.receiver;
uavcan::ITransferBufferManager& bufmgr = context.bufmgr;
uavcan::TransferBufferAccessor bk(context.bufmgr, RxFrameGenerator::DEFAULT_KEY);
const uint8_t MaxIndex = uavcan::Frame::getMaxIndexForTransferType(RxFrameGenerator::DEFAULT_KEY.getTransferType());
std::string content;
for (uint8_t i = 0; i <= MaxIndex; i++)
{
CHECK_NOT_COMPLETE(rcv.addFrame(gen(1, "12345678", i, false, 0, 1000U + i), bk)); // Last one will be dropped
content += "12345678";
}
CHECK_COMPLETE(rcv.addFrame(gen(1, "12345678", MaxIndex, true, 0, 1100), bk));
ASSERT_EQ(1000, rcv.getLastTransferTimestampMonotonic().toUSec());
ASSERT_TRUE(matchBufferContent(bufmgr.access(gen.bufmgr_key), std::string(content, 2)));
ASSERT_EQ(0x3231, rcv.getLastTransferCrc());
ASSERT_EQ(1, rcv.yieldErrorCount());
ASSERT_EQ(0, rcv.yieldErrorCount());
}
TEST(TransferReceiver, OutOfOrderFrames)
{
Context<32> context;
@@ -302,12 +300,12 @@ TEST(TransferReceiver, OutOfOrderFrames)
uavcan::ITransferBufferManager& bufmgr = context.bufmgr;
uavcan::TransferBufferAccessor bk(context.bufmgr, RxFrameGenerator::DEFAULT_KEY);
CHECK_NOT_COMPLETE(rcv.addFrame(gen(1, "12345678", 0, false, 7, 100000000), bk));
CHECK_NOT_COMPLETE(rcv.addFrame(gen(1, "--------", 3, false, 7, 100000100), bk)); // Out of order
CHECK_NOT_COMPLETE(rcv.addFrame(gen(1, "--------", 2, true, 7, 100000200), bk)); // Out of order
CHECK_NOT_COMPLETE(rcv.addFrame(gen(1, "qwertyui", 1, false, 7, 100000300), bk));
CHECK_NOT_COMPLETE(rcv.addFrame(gen(1, "--------", 4, true, 7, 100000200), bk)); // Out of order
CHECK_COMPLETE( rcv.addFrame(gen(1, "abcd", 2, true, 7, 100000400), bk));
CHECK_NOT_COMPLETE(rcv.addFrame(gen(1, "12345678", SET100, 7, 100000000), bk));
CHECK_NOT_COMPLETE(rcv.addFrame(gen(1, "--------", SET001, 7, 100000100), bk)); // Out of order
CHECK_NOT_COMPLETE(rcv.addFrame(gen(1, "--------", SET010, 7, 100000200), bk)); // Out of order
CHECK_NOT_COMPLETE(rcv.addFrame(gen(1, "qwertyui", SET001, 7, 100000300), bk));
CHECK_NOT_COMPLETE(rcv.addFrame(gen(1, "--------", SET010, 7, 100000200), bk)); // Out of order
CHECK_COMPLETE( rcv.addFrame(gen(1, "abcd", SET010, 7, 100000400), bk));
ASSERT_EQ(100000000, rcv.getLastTransferTimestampMonotonic().toUSec());
ASSERT_TRUE(matchBufferContent(bufmgr.access(gen.bufmgr_key), "345678qwertyuiabcd"));
@@ -332,9 +330,9 @@ TEST(TransferReceiver, IntervalMeasurement)
for (int i = 0; i < 1000; i++)
{
CHECK_NOT_COMPLETE(rcv.addFrame(gen(1, "12345678", 0, false, tid.get(), timestamp), bk));
CHECK_NOT_COMPLETE(rcv.addFrame(gen(1, "qwertyui", 1, false, tid.get(), timestamp), bk));
CHECK_COMPLETE( rcv.addFrame(gen(1, "abcd", 2, true, tid.get(), timestamp), bk));
CHECK_NOT_COMPLETE(rcv.addFrame(gen(1, "12345678", SET100, tid.get(), timestamp), bk));
CHECK_NOT_COMPLETE(rcv.addFrame(gen(1, "qwertyui", SET001, tid.get(), timestamp), bk));
CHECK_COMPLETE( rcv.addFrame(gen(1, "abcd", SET010, tid.get(), timestamp), bk));
ASSERT_TRUE(matchBufferContent(bufmgr.access(gen.bufmgr_key), "345678qwertyuiabcd"));
ASSERT_EQ(0x3231, rcv.getLastTransferCrc());
@@ -359,16 +357,16 @@ TEST(TransferReceiver, Restart)
/*
* This transfer looks complete, but must be ignored because of large delay after the first frame
*/
CHECK_NOT_COMPLETE(rcv.addFrame(gen(0, "--------", 0, false, 0, 100), bk)); // Begin
CHECK_NOT_COMPLETE(rcv.addFrame(gen(0, "--------", 1, false, 0, 10000100), bk)); // Continue 10 sec later, expired
CHECK_NOT_COMPLETE(rcv.addFrame(gen(0, "--------", 2, true, 0, 10000200), bk)); // Ignored
CHECK_NOT_COMPLETE(rcv.addFrame(gen(0, "--------", SET100, 0, 100), bk)); // Begin
CHECK_NOT_COMPLETE(rcv.addFrame(gen(0, "--------", SET001, 0, 10000100), bk)); // Continue 10 sec later, expired
CHECK_NOT_COMPLETE(rcv.addFrame(gen(0, "--------", SET010, 0, 10000200), bk)); // Ignored
/*
* Begins immediately after, gets an iface timeout but completes OK
*/
CHECK_NOT_COMPLETE(rcv.addFrame(gen(1, "12345678", 0, false, 0, 10000300), bk)); // Begin
CHECK_NOT_COMPLETE(rcv.addFrame(gen(1, "12345678", 1, false, 0, 12000300), bk)); // 2 sec later, iface timeout
CHECK_COMPLETE( rcv.addFrame(gen(1, "12345678", 2, true, 0, 12000400), bk)); // OK nevertheless
CHECK_NOT_COMPLETE(rcv.addFrame(gen(1, "12345678", SET100, 0, 10000300), bk)); // Begin
CHECK_NOT_COMPLETE(rcv.addFrame(gen(1, "12345678", SET001, 0, 12000300), bk)); // 2 sec later, iface timeout
CHECK_COMPLETE( rcv.addFrame(gen(1, "12345678", SET010, 0, 12000400), bk)); // OK nevertheless
ASSERT_TRUE(matchBufferContent(bufmgr.access(gen.bufmgr_key), "3456781234567812345678"));
ASSERT_EQ(0x3231, rcv.getLastTransferCrc());
@@ -376,14 +374,14 @@ TEST(TransferReceiver, Restart)
/*
* Begins OK, gets an iface timeout, switches to another iface
*/
CHECK_NOT_COMPLETE(rcv.addFrame(gen(1, "--------", 0, false, 1, 13000500), bk)); // Begin
CHECK_NOT_COMPLETE(rcv.addFrame(gen(1, "--------", 1, false, 1, 16000500), bk)); // 3 sec later, iface timeout
CHECK_NOT_COMPLETE(rcv.addFrame(gen(0, "--------", 1, false, 1, 16000600), bk)); // Same TID, another iface - ignore
CHECK_NOT_COMPLETE(rcv.addFrame(gen(0, "--------", 1, false, 2, 16000700), bk)); // Not first frame - ignore
CHECK_NOT_COMPLETE(rcv.addFrame(gen(0, "12345678", 0, false, 2, 16000800), bk)); // First, another iface - restart
CHECK_NOT_COMPLETE(rcv.addFrame(gen(1, "--------", 2, true, 1, 16000600), bk)); // Old iface - ignore
CHECK_NOT_COMPLETE(rcv.addFrame(gen(0, "12345678", 1, false, 2, 16000900), bk)); // Continuing
CHECK_COMPLETE( rcv.addFrame(gen(0, "12345678", 2, true, 2, 16000910), bk)); // Done
CHECK_NOT_COMPLETE(rcv.addFrame(gen(1, "--------", SET100, 1, 13000500), bk)); // Begin
CHECK_NOT_COMPLETE(rcv.addFrame(gen(1, "--------", SET001, 1, 16000500), bk)); // 3 sec later, iface timeout
CHECK_NOT_COMPLETE(rcv.addFrame(gen(0, "--------", SET001, 1, 16000600), bk)); // Same TID, another iface - ignore
CHECK_NOT_COMPLETE(rcv.addFrame(gen(0, "--------", SET001, 2, 16000700), bk)); // Not first frame - ignore
CHECK_NOT_COMPLETE(rcv.addFrame(gen(0, "12345678", SET100, 2, 16000800), bk)); // First, another iface - restart
CHECK_NOT_COMPLETE(rcv.addFrame(gen(1, "--------", SET010, 1, 16000600), bk)); // Old iface - ignore
CHECK_NOT_COMPLETE(rcv.addFrame(gen(0, "12345678", SET001, 2, 16000900), bk)); // Continuing
CHECK_COMPLETE( rcv.addFrame(gen(0, "12345678", SET010, 2, 16000910), bk)); // Done
ASSERT_TRUE(matchBufferContent(bufmgr.access(gen.bufmgr_key), "3456781234567812345678"));
ASSERT_EQ(0x3231, rcv.getLastTransferCrc());
@@ -404,9 +402,9 @@ TEST(TransferReceiver, UtcTransferTimestamping)
/*
* Zero UTC timestamp must be preserved
*/
CHECK_NOT_COMPLETE(rcv.addFrame(gen(1, "12345678", 0, false, 0, 1, 0), bk));
CHECK_NOT_COMPLETE(rcv.addFrame(gen(1, "qwertyui", 1, false, 0, 2, 0), bk));
CHECK_COMPLETE( rcv.addFrame(gen(1, "abcd", 2, true, 0, 3, 0), bk));
CHECK_NOT_COMPLETE(rcv.addFrame(gen(1, "12345678", SET100, 0, 1, 0), bk));
CHECK_NOT_COMPLETE(rcv.addFrame(gen(1, "qwertyui", SET001, 0, 2, 0), bk));
CHECK_COMPLETE( rcv.addFrame(gen(1, "abcd", SET010, 0, 3, 0), bk));
ASSERT_TRUE(matchBufferContent(bufmgr.access(gen.bufmgr_key), "345678qwertyuiabcd"));
ASSERT_EQ(1, rcv.getLastTransferTimestampMonotonic().toUSec());
@@ -415,9 +413,9 @@ TEST(TransferReceiver, UtcTransferTimestamping)
/*
* Non-zero UTC timestamp
*/
CHECK_NOT_COMPLETE(rcv.addFrame(gen(1, "12345678", 0, false, 1, 4, 123), bk)); // This UTC is going to be preserved
CHECK_NOT_COMPLETE(rcv.addFrame(gen(1, "qwertyui", 1, false, 1, 5, 0), bk)); // Following are ignored
CHECK_COMPLETE( rcv.addFrame(gen(1, "abcd", 2, true, 1, 6, 42), bk));
CHECK_NOT_COMPLETE(rcv.addFrame(gen(1, "12345678", SET100, 1, 4, 123), bk)); // This UTC is going to be preserved
CHECK_NOT_COMPLETE(rcv.addFrame(gen(1, "qwertyui", SET001, 1, 5, 0), bk)); // Following are ignored
CHECK_COMPLETE( rcv.addFrame(gen(1, "abcd", SET010, 1, 6, 42), bk));
ASSERT_TRUE(matchBufferContent(bufmgr.access(gen.bufmgr_key), "345678qwertyuiabcd"));
ASSERT_EQ(4, rcv.getLastTransferTimestampMonotonic().toUSec());
@@ -425,17 +423,18 @@ TEST(TransferReceiver, UtcTransferTimestamping)
/*
* Single-frame transfers
* iface_index, data, set, transfer_id, ts_monotonic
*/
CHECK_SINGLE_FRAME(rcv.addFrame(gen(1, "abc", 0, true, 2, 10, 100000000), bk)); // Exact value is irrelevant
CHECK_SINGLE_FRAME(rcv.addFrame(gen(1, "abc", SET100, 2, 10, 100000000), bk)); // Exact value is irrelevant
ASSERT_EQ(10, rcv.getLastTransferTimestampMonotonic().toUSec());
ASSERT_EQ(100000000, rcv.getLastTransferTimestampUtc().toUSec());
/*
* Restart recovery
*/
CHECK_NOT_COMPLETE(rcv.addFrame(gen(0, "12345678", 0, false, 1, 100000000, 800000000), bk));
CHECK_NOT_COMPLETE(rcv.addFrame(gen(0, "qwertyui", 1, false, 1, 100000001, 300000000), bk));
CHECK_COMPLETE( rcv.addFrame(gen(0, "abcd", 2, true, 1, 100000002, 900000000), bk));
CHECK_NOT_COMPLETE(rcv.addFrame(gen(0, "12345678", SET100, 1, 100000000, 800000000), bk));
CHECK_NOT_COMPLETE(rcv.addFrame(gen(0, "qwertyui", SET001, 1, 100000001, 300000000), bk));
CHECK_COMPLETE( rcv.addFrame(gen(0, "abcd", SET010, 1, 100000002, 900000000), bk));
ASSERT_TRUE(matchBufferContent(bufmgr.access(gen.bufmgr_key), "345678qwertyuiabcd"));
ASSERT_EQ(100000000, rcv.getLastTransferTimestampMonotonic().toUSec());
@@ -450,9 +449,8 @@ TEST(TransferReceiver, HeaderParsing)
uavcan::TransferReceiver& rcv = context.receiver;
uavcan::ITransferBufferManager& bufmgr = context.bufmgr;
static const uavcan::TransferType ADDRESSED_TRANSFER_TYPES[3] =
static const uavcan::TransferType ADDRESSED_TRANSFER_TYPES[2] =
{
uavcan::TransferTypeMessageUnicast,
uavcan::TransferTypeServiceRequest,
uavcan::TransferTypeServiceResponse
};
@@ -467,8 +465,8 @@ TEST(TransferReceiver, HeaderParsing)
uavcan::TransferBufferManagerKey(gen.bufmgr_key.getNodeID(), uavcan::TransferTypeMessageBroadcast);
uavcan::TransferBufferAccessor bk1(context.bufmgr, gen.bufmgr_key);
CHECK_NOT_COMPLETE(rcv.addFrame(gen(0, "12345678", 0, false, tid.get(), 1), bk1));
CHECK_COMPLETE( rcv.addFrame(gen(0, "abcd", 1, true, tid.get(), 2), bk1));
CHECK_NOT_COMPLETE(rcv.addFrame(gen(0, "12345678", SET100, tid.get(), 1), bk1));
CHECK_COMPLETE( rcv.addFrame(gen(0, "abcd", SET011, tid.get(), 2), bk1));
ASSERT_TRUE(matchBufferContent(bufmgr.access(gen.bufmgr_key), "345678abcd"));
ASSERT_EQ(0x3231, rcv.getLastTransferCrc());
@@ -478,7 +476,7 @@ TEST(TransferReceiver, HeaderParsing)
}
/*
* MFT, message unicast, service request/response
* MFT, service request/response
*/
for (unsigned i = 0; i < (sizeof(ADDRESSED_TRANSFER_TYPES) / sizeof(ADDRESSED_TRANSFER_TYPES[0])); i++)
{
@@ -488,8 +486,8 @@ TEST(TransferReceiver, HeaderParsing)
const uint64_t ts_monotonic = i + 10;
CHECK_NOT_COMPLETE(rcv.addFrame(gen(0, "1234567", 0, false, tid.get(), ts_monotonic), bk2));
CHECK_COMPLETE( rcv.addFrame(gen(0, "abcd", 1, true, tid.get(), ts_monotonic), bk2));
CHECK_NOT_COMPLETE(rcv.addFrame(gen(0, "1234567", SET100, tid.get(), ts_monotonic), bk2));
CHECK_COMPLETE( rcv.addFrame(gen(0, "abcd", SET011, tid.get(), ts_monotonic), bk2));
ASSERT_TRUE(matchBufferContent(bufmgr.access(gen.bufmgr_key), "34567abcd"));
ASSERT_EQ(0x3231, rcv.getLastTransferCrc());
@@ -501,21 +499,20 @@ TEST(TransferReceiver, HeaderParsing)
/*
* SFT, message broadcasting
*/
static const std::string SFT_PAYLOAD_BROADCAST = "12345678";
static const std::string SFT_PAYLOAD_UNICAST = "1234567";
static const std::string SFT_PAYLOAD = "1234567";
{
gen.bufmgr_key =
uavcan::TransferBufferManagerKey(gen.bufmgr_key.getNodeID(), uavcan::TransferTypeMessageBroadcast);
uavcan::TransferBufferAccessor bk(context.bufmgr, gen.bufmgr_key);
const uavcan::RxFrame frame = gen(0, SFT_PAYLOAD_BROADCAST, 0, true, tid.get(), 1000);
const uavcan::RxFrame frame = gen(0, SFT_PAYLOAD, SET110, tid.get(), 1000);
CHECK_SINGLE_FRAME(rcv.addFrame(frame, bk));
ASSERT_EQ(0x0000, rcv.getLastTransferCrc()); // Default value - zero
// All bytes are payload, zero overhead
ASSERT_TRUE(std::equal(SFT_PAYLOAD_BROADCAST.begin(), SFT_PAYLOAD_BROADCAST.end(), frame.getPayloadPtr()));
ASSERT_TRUE(std::equal(SFT_PAYLOAD.begin(), SFT_PAYLOAD.end(), frame.getPayloadPtr()));
tid.increment();
}
@@ -529,13 +526,13 @@ TEST(TransferReceiver, HeaderParsing)
uavcan::TransferBufferManagerKey(gen.bufmgr_key.getNodeID(), ADDRESSED_TRANSFER_TYPES[i]);
uavcan::TransferBufferAccessor bk(context.bufmgr, gen.bufmgr_key);
const uavcan::RxFrame frame = gen(0, SFT_PAYLOAD_UNICAST, 0, true, tid.get(), i + 10000U);
const uavcan::RxFrame frame = gen(0, SFT_PAYLOAD, SET110, tid.get(), i + 10000U);
CHECK_SINGLE_FRAME(rcv.addFrame(frame, bk));
ASSERT_EQ(0x0000, rcv.getLastTransferCrc()); // Default value - zero
// First byte must be ignored
ASSERT_TRUE(std::equal(SFT_PAYLOAD_UNICAST.begin(), SFT_PAYLOAD_UNICAST.end(), frame.getPayloadPtr()));
ASSERT_TRUE(std::equal(SFT_PAYLOAD.begin(), SFT_PAYLOAD.end(), frame.getPayloadPtr()));
tid.increment();
}
+16 -16
View File
@@ -74,16 +74,16 @@ TEST(TransferSender, Basic)
*/
static const uint64_t TX_DEADLINE = 1000000;
// Normal priority
sendOne(senders[0], DATA[0], TX_DEADLINE, 0, uavcan::TransferTypeMessageBroadcast, 0);
// Low priority
senders[0].setPriority(uavcan::TransferPriorityLow);
sendOne(senders[0], DATA[1], TX_DEADLINE, 0, uavcan::TransferTypeMessageUnicast, RX_NODE_ID);
senders[0].setPriority(20);
sendOne(senders[0], DATA[0], TX_DEADLINE, 0, uavcan::TransferTypeMessageBroadcast, 0);
sendOne(senders[0], DATA[1], TX_DEADLINE, 0, uavcan::TransferTypeMessageBroadcast, 0);
// High priority
senders[0].setPriority(uavcan::TransferPriorityHigh);
senders[0].setPriority(10);
sendOne(senders[0], "123", TX_DEADLINE, 0, uavcan::TransferTypeMessageBroadcast, 0);
sendOne(senders[0], "456", TX_DEADLINE, 0, uavcan::TransferTypeMessageUnicast, RX_NODE_ID);
sendOne(senders[0], "456", TX_DEADLINE, 0, uavcan::TransferTypeMessageBroadcast, 0);
senders[1].setPriority(15);
sendOne(senders[1], DATA[2], TX_DEADLINE, 0, uavcan::TransferTypeServiceRequest, RX_NODE_ID);
sendOne(senders[1], DATA[3], TX_DEADLINE, 0, uavcan::TransferTypeServiceResponse, RX_NODE_ID, 1);
sendOne(senders[1], "", TX_DEADLINE, 0, uavcan::TransferTypeServiceRequest, RX_NODE_ID);
@@ -92,15 +92,15 @@ TEST(TransferSender, Basic)
using namespace uavcan;
static const Transfer TRANSFERS[8] =
{
Transfer(TX_DEADLINE, 0, TransferPriorityNormal, TransferTypeMessageBroadcast, 0, TX_NODE_ID, 0, DATA[0], TYPES[0]),
Transfer(TX_DEADLINE, 0, TransferPriorityLow, TransferTypeMessageUnicast, 0, TX_NODE_ID, RX_NODE_ID, DATA[1], TYPES[0]),
Transfer(TX_DEADLINE, 0, TransferPriorityHigh, TransferTypeMessageBroadcast, 1, TX_NODE_ID, 0, "123", TYPES[0]),
Transfer(TX_DEADLINE, 0, TransferPriorityHigh, TransferTypeMessageUnicast, 1, TX_NODE_ID, RX_NODE_ID, "456", TYPES[0]),
Transfer(TX_DEADLINE, 0, 20, TransferTypeMessageBroadcast, 0, TX_NODE_ID, 0, DATA[0], TYPES[0]),
Transfer(TX_DEADLINE, 0, 20, TransferTypeMessageBroadcast, 0, TX_NODE_ID, 0, DATA[1], TYPES[0]),
Transfer(TX_DEADLINE, 0, 10, TransferTypeMessageBroadcast, 1, TX_NODE_ID, 0, "123", TYPES[0]),
Transfer(TX_DEADLINE, 0, 10, TransferTypeMessageBroadcast, 1, TX_NODE_ID, 0, "456", TYPES[0]),
Transfer(TX_DEADLINE, 0, TransferPriorityService, TransferTypeServiceRequest, 0, TX_NODE_ID, RX_NODE_ID, DATA[2], TYPES[1]),
Transfer(TX_DEADLINE, 0, TransferPriorityService, TransferTypeServiceResponse, 1, TX_NODE_ID, RX_NODE_ID, DATA[3], TYPES[1]),
Transfer(TX_DEADLINE, 0, TransferPriorityService, TransferTypeServiceRequest, 1, TX_NODE_ID, RX_NODE_ID, "", TYPES[1]),
Transfer(TX_DEADLINE, 0, TransferPriorityService, TransferTypeServiceResponse, 2, TX_NODE_ID, RX_NODE_ID, "", TYPES[1])
Transfer(TX_DEADLINE, 0, 15, TransferTypeServiceRequest, 0, TX_NODE_ID, RX_NODE_ID, DATA[2], TYPES[1]),
Transfer(TX_DEADLINE, 0, 15, TransferTypeServiceResponse, 1, TX_NODE_ID, RX_NODE_ID, DATA[3], TYPES[1]),
Transfer(TX_DEADLINE, 0, 15, TransferTypeServiceRequest, 1, TX_NODE_ID, RX_NODE_ID, "", TYPES[1]),
Transfer(TX_DEADLINE, 0, 15, TransferTypeServiceResponse, 2, TX_NODE_ID, RX_NODE_ID, "", TYPES[1])
};
/*
@@ -217,7 +217,7 @@ TEST(TransferSender, Loopback)
ASSERT_EQ(1, listener.last_frame.getIfaceIndex());
ASSERT_EQ(3, listener.last_frame.getPayloadLen());
ASSERT_TRUE(TX_NODE_ID == listener.last_frame.getSrcNodeID());
ASSERT_TRUE(listener.last_frame.isLast());
ASSERT_TRUE(listener.last_frame.isEndOfTransfer());
EXPECT_EQ(0, dispatcher.getTransferPerfCounter().getErrorCount());
EXPECT_EQ(1, dispatcher.getTransferPerfCounter().getTxTransferCount());
@@ -255,7 +255,7 @@ TEST(TransferSender, PassiveMode)
// ...but not unicast or anything else
ASSERT_EQ(-uavcan::ErrPassiveMode,
sender.send(Payload, sizeof(Payload), tsMono(1000), uavcan::MonotonicTime(),
uavcan::TransferTypeMessageUnicast, uavcan::NodeID(42)));
uavcan::TransferTypeServiceRequest, uavcan::NodeID(42)));
EXPECT_EQ(0, dispatcher.getTransferPerfCounter().getErrorCount());
EXPECT_EQ(1, dispatcher.getTransferPerfCounter().getTxTransferCount());
@@ -12,9 +12,9 @@ TEST(TransferTestHelpers, Transfer)
uavcan::PoolAllocator<uavcan::MemPoolBlockSize * 8, uavcan::MemPoolBlockSize> pool;
uavcan::TransferBufferManager<128, 1> mgr(pool);
uavcan::TransferBufferAccessor tba(mgr, uavcan::TransferBufferManagerKey(0, uavcan::TransferTypeMessageUnicast));
uavcan::TransferBufferAccessor tba(mgr, uavcan::TransferBufferManagerKey(0, uavcan::TransferTypeMessageBroadcast));
uavcan::RxFrame frame(uavcan::Frame(123, uavcan::TransferTypeMessageBroadcast, 1, 0, 0, 0, true),
uavcan::RxFrame frame(uavcan::Frame(123, uavcan::TransferTypeMessageBroadcast, 1, 0, 0),
uavcan::MonotonicTime(), uavcan::UtcTime(), 0);
uavcan::MultiFrameIncomingTransfer mfit(tsMono(10), tsUtc(1000), frame, tba);
@@ -35,8 +35,8 @@ TEST(TransferTestHelpers, MFTSerialization)
uavcan::DataTypeDescriptor type(uavcan::DataTypeKindMessage, 123, uavcan::DataTypeSignature(123456789), "Foo");
static const std::string DATA = "To go wrong in one's own way is better than to go right in someone else's.";
const Transfer transfer(1, 100000, uavcan::TransferPriorityNormal,
uavcan::TransferTypeMessageUnicast, 2, 42, 127, DATA, type);
const Transfer transfer(1, 100000, 10,
uavcan::TransferTypeServiceRequest, 2, 42, 127, DATA, type);
const std::vector<uavcan::RxFrame> ser = serializeTransfer(transfer);
@@ -69,28 +69,28 @@ TEST(TransferTestHelpers, SFTSerialization)
uavcan::DataTypeDescriptor type(uavcan::DataTypeKindMessage, 123, uavcan::DataTypeSignature(123456789), "Foo");
{
const Transfer transfer(1, 100000, uavcan::TransferPriorityNormal,
uavcan::TransferTypeMessageBroadcast, 7, 42, 0, "Nvrfrget", type);
const Transfer transfer(1, 100000, 10,
uavcan::TransferTypeMessageBroadcast, 7, 42, 0, "Nvrfrgt", type);
const std::vector<uavcan::RxFrame> ser = serializeTransfer(transfer);
ASSERT_EQ(1, ser.size());
std::cout << "Serialized transfer:\n\t" << ser[0].toString() << "\n";
}
{
const Transfer transfer(1, 100000, uavcan::TransferPriorityService,
const Transfer transfer(1, 100000, 11,
uavcan::TransferTypeServiceRequest, 7, 42, 127, "7-chars", type);
const std::vector<uavcan::RxFrame> ser = serializeTransfer(transfer);
ASSERT_EQ(1, ser.size());
std::cout << "Serialized transfer:\n\t" << ser[0].toString() << "\n";
}
{
const Transfer transfer(1, 100000, uavcan::TransferPriorityNormal,
const Transfer transfer(1, 100000, 12,
uavcan::TransferTypeMessageBroadcast, 7, 42, 0, "", type);
const std::vector<uavcan::RxFrame> ser = serializeTransfer(transfer);
ASSERT_EQ(1, ser.size());
std::cout << "Serialized transfer:\n\t" << ser[0].toString() << "\n";
}
{
const Transfer transfer(1, 100000, uavcan::TransferPriorityService,
const Transfer transfer(1, 100000, 13,
uavcan::TransferTypeServiceResponse, 7, 42, 127, "", type);
const std::vector<uavcan::RxFrame> ser = serializeTransfer(transfer);
ASSERT_EQ(1, ser.size());
@@ -99,9 +99,9 @@ struct Transfer
std::string toString() const
{
std::ostringstream os;
os << "ts_m=" << ts_monotonic
os << "ts_m=" << ts_monotonic
<< " ts_utc=" << ts_utc
<< " prio=" << priority
<< " prio=" << int(priority.get())
<< " tt=" << transfer_type
<< " tid=" << int(transfer_id.get())
<< " snid=" << int(src_node_id.get())
@@ -176,25 +176,7 @@ namespace
std::vector<uavcan::RxFrame> serializeTransfer(const Transfer& transfer)
{
bool need_crc = false;
switch (transfer.transfer_type)
{
case uavcan::TransferTypeMessageBroadcast:
{
need_crc = transfer.payload.length() > sizeof(uavcan::CanFrame::data);
break;
}
case uavcan::TransferTypeServiceResponse:
case uavcan::TransferTypeServiceRequest:
case uavcan::TransferTypeMessageUnicast:
{
need_crc = transfer.payload.length() > (sizeof(uavcan::CanFrame::data) - 1);
break;
}
default:
std::cerr << "X_X" << std::endl;
std::exit(1);
}
const bool need_crc = transfer.payload.length() > (sizeof(uavcan::CanFrame::data) - 1);
std::vector<uint8_t> raw_payload;
if (need_crc)
@@ -208,7 +190,6 @@ std::vector<uavcan::RxFrame> serializeTransfer(const Transfer& transfer)
raw_payload.insert(raw_payload.end(), transfer.payload.begin(), transfer.payload.end());
std::vector<uavcan::RxFrame> output;
uint8_t frame_index = 0;
unsigned offset = 0;
uavcan::MonotonicTime ts_monotonic = transfer.ts_monotonic;
uavcan::UtcTime ts_utc = transfer.ts_utc;
@@ -219,7 +200,10 @@ std::vector<uavcan::RxFrame> serializeTransfer(const Transfer& transfer)
EXPECT_TRUE(bytes_left >= 0);
uavcan::Frame frm(transfer.data_type.getID(), transfer.transfer_type, transfer.src_node_id,
transfer.dst_node_id, frame_index, transfer.transfer_id);
transfer.dst_node_id, transfer.transfer_id);
frm.setStartOfTransfer(true);
const int spres = frm.setPayload(&*(raw_payload.begin() + offset), unsigned(bytes_left));
if (spres < 0)
{
@@ -228,22 +212,23 @@ std::vector<uavcan::RxFrame> serializeTransfer(const Transfer& transfer)
}
if (spres == bytes_left)
{
frm.makeLast();
frm.setEndOfTransfer(true);
}
offset += unsigned(spres);
EXPECT_GE(uavcan::Frame::getMaxIndexForTransferType(transfer.transfer_type), frame_index);
frame_index++;
const uavcan::RxFrame rxfrm(frm, ts_monotonic, ts_utc, 0);
ts_monotonic += uavcan::MonotonicDuration::fromUSec(1);
ts_utc += uavcan::UtcDuration::fromUSec(1);
output.push_back(rxfrm);
if (frm.isLast())
if (frm.isEndOfTransfer())
{
break;
}
frm.setStartOfTransfer(false);
frm.flipToggle();
}
return output;
}
@@ -282,14 +282,7 @@ const std::map<std::string,
uavcan::equipment::hardpoint::Command msg;
msg.command = std::stoi(args.at(0));
auto pub = node->makePublisher<uavcan::equipment::hardpoint::Command>();
if (node_id.isBroadcast())
{
(void)pub->broadcast(msg);
}
else
{
(void)pub->unicast(msg, node_id);
}
(void)pub->broadcast(msg);
}
}
},
@@ -305,14 +298,7 @@ const std::map<std::string,
msg.timeout_sec = (args.size() > 1) ? std::stoi(args.at(1)) : 60;
std::cout << msg << std::endl;
auto pub = node->makePublisher<uavcan::protocol::EnumerationRequest>();
if (node_id.isBroadcast())
{
(void)pub->broadcast(msg);
}
else
{
(void)pub->unicast(msg, node_id); // Unicasting an enumeration request - what a nonsense
}
(void)pub->broadcast(msg);
}
}
}