From 56c74487ec121200ee8491e1fa0b5e508ed65fd6 Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Sun, 6 Apr 2014 00:00:30 +0400 Subject: [PATCH] STM32: Added notes on thread safety and driver usage. --- .../stm32/driver/include/uavcan_stm32/can.hpp | 5 +++- .../driver/include/uavcan_stm32/clock.hpp | 26 ++++++++++++++----- 2 files changed, 23 insertions(+), 8 deletions(-) diff --git a/libuavcan_drivers/stm32/driver/include/uavcan_stm32/can.hpp b/libuavcan_drivers/stm32/driver/include/uavcan_stm32/can.hpp index 8ddbc9e719..1117cf8f1d 100644 --- a/libuavcan_drivers/stm32/driver/include/uavcan_stm32/can.hpp +++ b/libuavcan_drivers/stm32/driver/include/uavcan_stm32/can.hpp @@ -28,7 +28,8 @@ namespace uavcan_stm32 { /** - * RX queue item + * RX queue item. + * The application shall not use this directly. */ struct CanRxItem { @@ -43,6 +44,7 @@ struct CanRxItem /** * Single CAN iface. + * The application shall not use this directly. */ class CanIface : public uavcan::ICanIface, uavcan::Noncopyable { @@ -167,6 +169,7 @@ public: /** * CAN driver, incorporates all available CAN ifaces. + * Please avoid direct usage, prefer @ref CanInitHelper instead. */ class CanDriver : public uavcan::ICanDriver, uavcan::Noncopyable { diff --git a/libuavcan_drivers/stm32/driver/include/uavcan_stm32/clock.hpp b/libuavcan_drivers/stm32/driver/include/uavcan_stm32/clock.hpp index b3e6a5c1b7..ebe934ff6d 100644 --- a/libuavcan_drivers/stm32/driver/include/uavcan_stm32/clock.hpp +++ b/libuavcan_drivers/stm32/driver/include/uavcan_stm32/clock.hpp @@ -18,45 +18,57 @@ namespace clock void init(); /** - * For general usage. + * Returns current monotonic time passed since the moment when clock::init() was called. + * This function is thread safe. */ uavcan::MonotonicTime getMonotonic(); + +/** + * Returns UTC time if it has been set, otherwise returns zero time. + * This function is thread safe. + */ uavcan::UtcTime getUtc(); /** * Performs UTC time adjustment. * The UTC time will be zero until first adjustment has been performed. + * This function is thread safe. */ void adjustUtc(uavcan::UtcDuration adjustment); /** * Clock speed error. - * Positive if the hardware timer is slower than reference time + * Positive if the hardware timer is slower than reference time. + * This function is thread safe. */ uavcan::int32_t getUtcSpeedCorrectionPPM(); /** * Number of non-gradual adjustments performed so far. * Ideally should be zero. + * This function is thread safe. */ uavcan::uint32_t getUtcAjdustmentJumpCount(); } /** - * Trivial system clock implementation; can be redefined by the application. - * Uses a simple 16-bit hardware timer for both UTC and monotonic clocks. + * Adapter for uavcan::ISystemClock. */ class SystemClock : public uavcan::ISystemClock, uavcan::Noncopyable { SystemClock() { } -public: - static SystemClock& instance(); - virtual uavcan::MonotonicTime getMonotonic() const { return clock::getMonotonic(); } virtual uavcan::UtcTime getUtc() const { return clock::getUtc(); } virtual void adjustUtc(uavcan::UtcDuration adjustment) { clock::adjustUtc(adjustment); } + +public: + /** + * Calls clock::init() as needed. + * This function is thread safe. + */ + static SystemClock& instance(); }; }