mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-16 20:57:36 +08:00
Testing framework: added emulateSingleFrameBroadcastTransfer()
This commit is contained in:
@@ -103,3 +103,31 @@ struct BackgroundSpinner : uavcan::TimerBase
|
||||
spinning_node.spin(uavcan::MonotonicDuration::fromMSec(1));
|
||||
}
|
||||
};
|
||||
|
||||
template <typename MessageType>
|
||||
static inline void emulateSingleFrameBroadcastTransfer(CanDriverMock& can, uavcan::NodeID node_id,
|
||||
const MessageType& message, uavcan::TransferID tid)
|
||||
{
|
||||
uavcan::StaticTransferBuffer<100> buffer;
|
||||
uavcan::BitStream bitstream(buffer);
|
||||
uavcan::ScalarCodec codec(bitstream);
|
||||
|
||||
// Manual message publication
|
||||
ASSERT_LT(0, MessageType::encode(message, codec));
|
||||
ASSERT_GE(8, buffer.getMaxWritePos());
|
||||
|
||||
// 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);
|
||||
|
||||
ASSERT_EQ(buffer.getMaxWritePos(), frame.setPayload(buffer.getRawPtr(), buffer.getMaxWritePos()));
|
||||
|
||||
uavcan::CanFrame can_frame;
|
||||
ASSERT_TRUE(frame.compile(can_frame));
|
||||
|
||||
for (uint8_t i = 0; i < can.getNumIfaces(); i++)
|
||||
{
|
||||
can.ifaces.at(i).pushRx(can_frame);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -10,32 +10,10 @@
|
||||
static void publishNodeStatus(CanDriverMock& can, uavcan::NodeID node_id, uavcan::uint8_t status_code,
|
||||
uavcan::uint32_t uptime_sec, uavcan::TransferID tid)
|
||||
{
|
||||
uavcan::StaticTransferBuffer<100> buffer;
|
||||
uavcan::BitStream bitstream(buffer);
|
||||
uavcan::ScalarCodec codec(bitstream);
|
||||
|
||||
uavcan::protocol::NodeStatus msg;
|
||||
msg.status_code = status_code;
|
||||
msg.uptime_sec = uptime_sec;
|
||||
|
||||
// Manual message publication
|
||||
ASSERT_LT(0, uavcan::protocol::NodeStatus::encode(msg, codec));
|
||||
ASSERT_GE(8, buffer.getMaxWritePos());
|
||||
|
||||
// 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(uavcan::protocol::NodeStatus::DefaultDataTypeID, uavcan::TransferTypeMessageBroadcast,
|
||||
node_id, uavcan::NodeID::Broadcast, 0, tid, true);
|
||||
|
||||
ASSERT_EQ(buffer.getMaxWritePos(), frame.setPayload(buffer.getRawPtr(), buffer.getMaxWritePos()));
|
||||
|
||||
uavcan::CanFrame can_frame;
|
||||
ASSERT_TRUE(frame.compile(can_frame));
|
||||
|
||||
for (uint8_t i = 0; i < can.getNumIfaces(); i++)
|
||||
{
|
||||
can.ifaces.at(i).pushRx(can_frame);
|
||||
}
|
||||
emulateSingleFrameBroadcastTransfer(can, node_id, msg, tid);
|
||||
}
|
||||
|
||||
|
||||
|
||||
Reference in New Issue
Block a user