Skip to content

Commit

Permalink
v0.2 (#9)
Browse files Browse the repository at this point in the history
* VolatileStorage<>: Do not enforce std::is_trivial_v<Container>
* Add optional support for legacy app descriptors
* Add Bootloader::getNumberOfNodes()
* Promote CRC64 to public API
* Add kocherga::can::TxQueue<>
* CANAcceptanceFilterConfig::makePromiscuous(): do not construct {0,0} to enhance compatibility
* Improve logging messages
* Drop the last log report because it is usually not transmitted: the app is booted before the message can be sent
  • Loading branch information
pavel-kirienko authored Sep 20, 2021
1 parent 667d7ba commit 3116920
Show file tree
Hide file tree
Showing 11 changed files with 343 additions and 59 deletions.
2 changes: 2 additions & 0 deletions .clang-tidy
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,8 @@ Checks: >-
-cert-msc30-c,
-cert-msc50-cpp,
-*-easily-swappable-parameters,
-*-owning-memory,
-*-malloc,
WarningsAsErrors: '*'
HeaderFilterRegex: '.*'
AnalyzeTemporaryDtors: false
Expand Down
63 changes: 47 additions & 16 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@

Technical support is provided on the [UAVCAN Forum](https://forum.uavcan.org/).

A standard-compliant implementation of the firmware update server is provided in
A standard-compliant implementation of the software update server is provided in
[Yakut](https://github.com/UAVCAN/yakut#updating-node-software).

## Features
Expand Down Expand Up @@ -38,6 +38,9 @@ separate header file named `kocherga_*.hpp`. Kochergá does not have any compila
To integrate Kochergá into your application, just include this repository as a git subtree/submodule, or simply
copy-paste the required header files into your source tree.

For reference, a typical implementation on an ARM Cortex M4 MCU supporting
UAVCAN/serial (USB+UART) and UAVCAN/CAN (v1+v0) would set you back by about ~32K of flash.

### Application signature

The bootloader looks for an instance of the `AppInfo` structure located in the ROM image of the application at every
Expand Down Expand Up @@ -110,7 +113,7 @@ The integration test application available under `/tests/integration/bootloader/
The ROM backend abstracts the specifics of reading and writing your ROM (usually this is the on-chip flash memory).

```c++
class MyROMBackend : public kocherga::IROMBackend
class MyROMBackend final : public kocherga::IROMBackend
{
auto write(const std::size_t offset, const std::byte* const data, const std::size_t size) override
-> std::optional<std::size_t>
Expand All @@ -136,7 +139,7 @@ Transport implementations --- UAVCAN/CAN, UAVCAN/serial, etc., depending on whic
are interfaced with your hardware as follows.

```c++
class MySerialPort : public kocherga::serial::ISerialPort
class MySerialPort final : public kocherga::serial::ISerialPort
{
auto receive() -> std::optional<std::uint8_t> override
{
Expand All @@ -152,12 +155,13 @@ class MySerialPort : public kocherga::serial::ISerialPort
```

```c++
class MyCANDriver : public kocherga::can::ICANDriver
class MyCANDriver final : public kocherga::can::ICANDriver
{
auto configure(const Bitrate& bitrate,
const bool silent,
const kocherga::can::CANAcceptanceFilterConfig& filter) -> std::optional<Mode> override
{
tx_queue_.clear();
CAN_CONFIGURE(bitrate, silent, filter);
return Mode::FD; // Or Mode::Classic if CAN FD is not supported by the CAN controller.
}
Expand All @@ -167,20 +171,37 @@ class MyCANDriver : public kocherga::can::ICANDriver
const std::uint8_t payload_size,
const void* const payload) -> bool override
{
if (force_classic_can)
{
return CAN_PUSH_CLASSIC(extended_can_id, payload_size, payload); // No DLE, no BRS -- Classic only.
}
else
{
return CAN_PUSH_FD(extended_can_id, payload_size, payload);
}
const std::chrono::microseconds now = GET_TIME_SINCE_BOOT();
// You can use tx_queue_.size() to limit maximum depth of the queue.
const bool ok = tx_queue_.push(now, force_classic_can, extended_can_id, payload_size, payload);
pollTxQueue(now);
return ok;
}

auto pop(PayloadBuffer& payload_buffer) -> std::optional<std::pair<std::uint32_t, std::uint8_t>> override
{
pollTxQueue(); // Check if the HW TX mailboxes are ready to accept the next frame from the SW queue.
return CAN_POP(payload_buffer.data()); // The return value is optional(can_id, payload_size).
}

void pollTxQueue(const std::chrono::microseconds now)
{
if (const auto* const item = tx_queue_.peek()) // Take the top frame from the prioritized queue.
{
const bool expired = now > (item->timestamp + kocherga::can::SendTimeout); // Drop expired frames.
if (expired || CAN_PUSH(item->force_classic_can, // force_classic_can means no DLE, no BRS.
item->extended_can_id,
item->payload_size,
item->payload))
{
tx_queue_.pop(); // Enqueued into the HW TX mailbox or expired -- remove from the SW queue.
}
}
}

// Some CAN drivers come with built-in queue (e.g., SocketCAN), in which case this will not be needed.
// The recommended heap is https://github.com/pavel-kirienko/o1heap.
kocherga::can::TxQueue<void*(*)(std::size_t), void(*)(void*)> tx_queue_(&MY_MALLOC, &MY_FREE);
};
```
Expand Down Expand Up @@ -234,6 +255,9 @@ int main()
MyROMBackend rom_backend;
kocherga::SystemInfo system_info = GET_SYSTEM_INFO();
kocherga::Bootloader boot(rom_backend, system_info, MaxAppSize, args && args->linger);
// It's a good idea to check if the app is valid and safe to boot before adding the nodes.
// This way you can skip the potentially slow or disturbing interface initialization on the happy path.
// You can do it by calling poll() here once.

// Add a UAVCAN/serial node to the bootloader instance.
MySerialPort serial_port;
Expand All @@ -245,9 +269,9 @@ int main()
boot.addNode(&serial_node);

// Add a UAVCAN/CAN node to the bootloader instance.
std::optional<kocherga::ICANDriver::Bitrate> can_bitrate;
std::optional<std::uint8_t> uavcan_can_version;
std::optional<kocherga::NodeID> uavcan_can_node_id;
std::optional<kocherga::can::ICANDriver::Bitrate> can_bitrate;
std::optional<std::uint8_t> uavcan_can_version;
std::optional<kocherga::NodeID> uavcan_can_node_id;
if (args)
{
if (args->uavcan_can_bitrate.first > 0)
Expand Down Expand Up @@ -350,10 +374,17 @@ Note that the application does not need to depend on the Kochergá library.
It is recommended to copy-paste relevant pieces from Kochergá instead; specifically:

- `kocherga::VolatileStorage<>`
- `kocherga::detail::CRC64`
- `kocherga::CRC64`

## Revisions

### v0.2

- Add helper `kocherga::can::TxQueue`.
- Promote `kocherga::CRC64` to public API.
- Add optional support for legacy app descriptors to simplify integration into existing projects.
- Minor doc and API enhancements.

### v0.1

The first revision to go public.
81 changes: 50 additions & 31 deletions kocherga/kocherga.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@
#include <type_traits>

#define KOCHERGA_VERSION_MAJOR 0 // NOLINT
#define KOCHERGA_VERSION_MINOR 1 // NOLINT
#define KOCHERGA_VERSION_MINOR 2 // NOLINT

namespace kocherga
{
Expand Down Expand Up @@ -226,13 +226,6 @@ class IROMBackend

// --------------------------------------------------------------------------------------------------------------------

/// Internal use only.
namespace detail
{
static constexpr auto BitsPerByte = 8U;

static constexpr std::chrono::microseconds DefaultTransferIDTimeout{2'000'000}; ///< Default taken from Specification.

/// This is used to verify integrity of the application and other data.
/// Note that the firmware CRC verification is a computationally expensive process that needs to be completed
/// in a limited time interval, which should be minimized. This class has been carefully manually optimized to
Expand Down Expand Up @@ -278,7 +271,7 @@ class CRC64
for (auto it = std::rbegin(out); it != rend; ++it)
{
*it = static_cast<std::uint8_t>(x);
x >>= BitsPerByte;
x >>= 8U;
}
return out;
}
Expand All @@ -297,6 +290,15 @@ class CRC64
std::uint64_t crc_ = Xor;
};

// --------------------------------------------------------------------------------------------------------------------

/// Internal use only.
namespace detail
{
static constexpr auto BitsPerByte = 8U;

static constexpr std::chrono::microseconds DefaultTransferIDTimeout{2'000'000}; ///< Default taken from Specification.

/// Detects the application in the ROM, verifies its integrity, and retrieves the information about it.
class AppLocator final
{
Expand All @@ -306,17 +308,18 @@ class AppLocator final
{}

/// Returns the AppInfo if the app is found and its integrity is intact. Otherwise, returns an empty option.
[[nodiscard]] auto identifyApplication() const -> std::optional<AppInfo>
/// If the allow_legacy parameter is set, legacy app descriptors will be accepted, too.
[[nodiscard]] auto identifyApplication(const bool allow_legacy = false) const -> std::optional<AppInfo>
{
for (std::size_t offset = 0; offset < max_app_size_; offset += AppDescriptor::MagicSize)
{
AppDescriptor desc{};
if (sizeof(desc) == backend_.read(offset, reinterpret_cast<std::byte*>(&desc), sizeof(desc)))
{
if (desc.isValid(max_app_size_) &&
validateImageCRC(offset + AppDescriptor::CRCOffset,
static_cast<std::size_t>(desc.getAppInfo().image_size),
desc.getAppInfo().image_crc))
const bool match = desc.isValid(max_app_size_) || (allow_legacy && desc.isValidLegacy(max_app_size_));
if (match && validateImageCRC(offset + AppDescriptor::CRCOffset,
static_cast<std::size_t>(desc.getAppInfo().image_size),
desc.getAppInfo().image_crc))
{
return desc.getAppInfo();
}
Expand Down Expand Up @@ -345,6 +348,14 @@ class AppLocator final
((app_info.image_size % MagicSize) == 0);
}

[[nodiscard]] auto isValidLegacy(const std::size_t max_app_size) const -> bool
{
static constexpr auto SizeAlignmentRequirement = 4U; ///< Relaxed requirement to enhance compatibility.
return std::equal(signature.begin(), signature.end(), ReferenceSignature.begin()) &&
(app_info.image_size > 0) && (app_info.image_size <= max_app_size) &&
((app_info.image_size % SizeAlignmentRequirement) == 0);
}

[[nodiscard]] auto getAppInfo() const -> const AppInfo& { return app_info; }

private:
Expand Down Expand Up @@ -542,6 +553,8 @@ class Presenter final : public IReactor
return false;
}

[[nodiscard]] auto getNumberOfNodes() const -> std::uint8_t { return num_nodes_; }

[[nodiscard]] auto trigger(const INode* const node,
const NodeID file_server_node_id,
const std::size_t app_image_file_path_length,
Expand Down Expand Up @@ -988,23 +1001,33 @@ class Bootloader : public detail::IController
/// sit idle until instructed otherwise, or if the application itself commands the bootloader to begin the update.
/// The flag affects only the initial verification and has no effect on all subsequent checks; for example,
/// after the application is updated and validated, it will be booted after BootDelay regardless of this flag.
///
/// If the allow_legacy_app_descriptors option is set, the bootloader will also accept legacy descriptors alongside
/// the new format. This option should be set only if the bootloader is introduced to a product that was using
/// the old app descriptor format in the past; refer to the PX4 Brickproof Bootloader for details. If you are not
/// sure, leave the default value.
Bootloader(IROMBackend& rom_backend,
const SystemInfo& system_info,
const std::size_t max_app_size,
const bool linger,
const std::chrono::seconds boot_delay = std::chrono::seconds(0)) :
const std::chrono::seconds boot_delay = std::chrono::seconds(0),
const bool allow_legacy_app_descriptors = false) :
max_app_size_(max_app_size),
boot_delay_(boot_delay),
backend_(rom_backend),
presentation_(system_info, *this),
linger_(linger)
linger_(linger),
allow_legacy_app_descriptors_(allow_legacy_app_descriptors)
{}

/// Nodes shall be registered using this method after the instance is constructed.
/// The return value is true on success, false if there are too many nodes already or this node is already
/// registered (no effect in this case).
[[nodiscard]] auto addNode(INode* const node) -> bool { return presentation_.addNode(node); }

/// The number of nodes added with addNode(). Zero by default (obviously).
[[nodiscard]] auto getNumberOfNodes() const -> std::uint8_t { return presentation_.getNumberOfNodes(); }

/// Non-blocking periodic state update.
/// The outer logic should invoke this method after any hardware event (for example, if WFE/WFI is used on an
/// ARM platform), and periodically at least once per second. Typically, it would be invoked from the main loop.
Expand Down Expand Up @@ -1089,7 +1112,7 @@ class Bootloader : public detail::IController
{
backend_.endWrite();
}
app_info_ = detail::AppLocator(backend_, max_app_size_).identifyApplication();
app_info_ = detail::AppLocator(backend_, max_app_size_).identifyApplication(allow_legacy_app_descriptors_);
final_.reset();
if (app_info_)
{
Expand Down Expand Up @@ -1121,11 +1144,11 @@ class Bootloader : public detail::IController
if (State::AppUpdateInProgress == state_)
{
backend_.endWrite(); // Cycle the state to re-init ROM if needed.
pending_log_ = {detail::dsdl::Diagnostic::Severity::Warning, "Ongoing update process restarted"};
pending_log_ = {detail::dsdl::Diagnostic::Severity::Warning, "Ongoing software update restarted"};
}
else
{
pending_log_ = {detail::dsdl::Diagnostic::Severity::Notice, "Update started"};
pending_log_ = {detail::dsdl::Diagnostic::Severity::Notice, "Software update started"};
}
state_ = State::AppUpdateInProgress;
rom_offset_ = 0;
Expand All @@ -1139,7 +1162,8 @@ class Bootloader : public detail::IController
{
if (!response)
{
pending_log_ = {detail::dsdl::Diagnostic::Severity::Critical, "File request timeout or remote error"};
pending_log_ = {detail::dsdl::Diagnostic::Severity::Critical,
"Software image file request timeout or file server error"};
reset(false);
}
else
Expand All @@ -1153,11 +1177,7 @@ class Bootloader : public detail::IController
}
else
{
if (ok)
{
pending_log_ = {detail::dsdl::Diagnostic::Severity::Notice, "File transfer completed"};
}
else
if (!ok)
{
pending_log_ = {detail::dsdl::Diagnostic::Severity::Critical, "ROM write failure"};
}
Expand All @@ -1172,6 +1192,7 @@ class Bootloader : public detail::IController
IROMBackend& backend_;
detail::Presenter presentation_;
const bool linger_;
const bool allow_legacy_app_descriptors_;

std::chrono::microseconds uptime_{};
bool inited_ = false;
Expand Down Expand Up @@ -1226,15 +1247,15 @@ class VolatileStorage
{
public:
/// The amount of memory required to store the data. This is the size of the container plus 8 bytes for the CRC.
static constexpr auto StorageSize = sizeof(Container) + detail::CRC64::Size;
static constexpr auto StorageSize = sizeof(Container) + CRC64::Size; // NOLINT

explicit VolatileStorage(std::uint8_t* const location) : ptr_(location) {}

/// Checks if the data is available and reads it, then erases the storage to prevent deja-vu.
/// Returns an empty option if no data is available (in that case the storage is not erased).
[[nodiscard]] auto take() -> std::optional<Container>
{
detail::CRC64 crc;
CRC64 crc;
crc.update(ptr_, StorageSize);
if (crc.isResidueCorrect())
{
Expand All @@ -1250,15 +1271,13 @@ class VolatileStorage
void store(const Container& data)
{
(void) std::memmove(ptr_, &data, sizeof(Container));
detail::CRC64 crc;
CRC64 crc;
crc.update(ptr_, sizeof(Container));
const auto crc_ptr = ptr_ + sizeof(Container); // NOLINT NOSONAR pointer arithmetic
(void) std::memmove(crc_ptr, crc.getBytes().data(), detail::CRC64::Size);
(void) std::memmove(crc_ptr, crc.getBytes().data(), CRC64::Size);
}

protected:
static_assert(std::is_trivial_v<Container>, "Container shall be a trivial type.");

static constexpr std::uint8_t EraseFillValue = 0xCA;

std::uint8_t* const ptr_;
Expand Down
Loading

0 comments on commit 3116920

Please sign in to comment.