From 1c7fb3a4e7366b09f1908639147a32bbc6380cc3 Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Fri, 21 Jul 2017 15:35:38 +0300 Subject: [PATCH 01/81] New link to coding conventions --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index 4e185554..a2bd1806 100644 --- a/README.md +++ b/README.md @@ -61,7 +61,7 @@ This section is intended only for library developers and contributors. The library design document can be found in [DESIGN.md](DESIGN.md) -Contributors, please follow the [Zubax Style Guide](https://github.com/Zubax/zubax_style_guide). +Contributors, please follow the [Zubax C++ Coding Conventions](https://kb.zubax.com/x/84Ah). ### Building and Running Tests From 799c9e6d710fcb311aa01bcf4dfb8b8e3ab141a9 Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Fri, 21 Jul 2017 15:42:56 +0300 Subject: [PATCH 02/81] Updated link in DESIGN.md --- DESIGN.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/DESIGN.md b/DESIGN.md index bad4e3c9..cbf1aa48 100644 --- a/DESIGN.md +++ b/DESIGN.md @@ -528,7 +528,7 @@ The suggested approach is to keep all of the library’s functions in just one C ## Coding style -Please refer to [the Zubax coding style](https://github.com/Zubax/zubax_style_guide). +Please refer to [the Zubax coding conventions](https://kb.zubax.com/x/84Ah). ## Testing From e49bdece231b261a7cf8d50e4998c091a3807e06 Mon Sep 17 00:00:00 2001 From: Manuel Odendahl Date: Tue, 23 Jan 2018 10:37:47 -0500 Subject: [PATCH 03/81] Make data_index a uint16_t to allow sending more than 256 bytes. --- canard.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/canard.c b/canard.c index 18aa4367..0faa39f8 100644 --- a/canard.c +++ b/canard.c @@ -898,7 +898,7 @@ CANARD_INTERNAL int enqueueTxFrames(CanardInstance* ins, } else // Multi frame transfer { - uint8_t data_index = 0; + uint16_t data_index = 0; uint8_t toggle = 0; uint8_t sot_eot = 0x80; From 636795f4bc395f56af8d2c61d3757b5e762bb9e5 Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Sat, 24 Feb 2018 15:46:52 +0200 Subject: [PATCH 04/81] STM32: better explanation of the STM32's bxCAN frame filtering logic; fixes #45 --- drivers/stm32/canard_stm32.c | 50 +++++++++++++++++++++++++++++++----- 1 file changed, 43 insertions(+), 7 deletions(-) diff --git a/drivers/stm32/canard_stm32.c b/drivers/stm32/canard_stm32.c index fa7d288c..85bc4401 100644 --- a/drivers/stm32/canard_stm32.c +++ b/drivers/stm32/canard_stm32.c @@ -472,7 +472,44 @@ int canardSTM32ConfigureAcceptanceFilters(const CanardSTM32AcceptanceFilterConfi * Converting the ID and the Mask into the representation that can be chewed by the hardware. * If Mask asks us to accept both STDID and EXTID, we need to use EXT mode on the filter, * otherwise it will reject all EXTID frames. This logic is not documented in the RM. - * True story. This is sacred knowledge! Don't tell the unworthy. + * + * The logic of the hardware acceptance filters can be described as follows: + * + * accepted = (received_id & filter_mask) == (filter_id & filter_mask) + * + * Where: + * - accepted - if true, the frame will be accepted by the filter. + * - received_id - the CAN ID of the received frame, either 11-bit or 29-bit, with extension bits + * marking extended frames, error frames, etc. + * - filter_id - the value of the filter ID register. + * - filter_mask - the value of the filter mask register. + * + * There are special bits that are not members of the CAN ID field: + * - EFF - set for extended frames (29-bit), cleared for standard frames (11-bit) + * - RTR - like above, indicates Remote Transmission Request frames. + * + * The following truth table summarizes the logic (where: FM - filter mask, FID - filter ID, RID - received + * frame ID, A - true if accepted, X - any state): + * + * FM FID RID A + * 0 X X 1 + * 1 0 0 1 + * 1 1 0 0 + * 1 0 1 0 + * 1 1 1 1 + * + * One would expect that for the purposes of hardware filtering, the special bits should be treated + * in the same way as the real ID bits. However, this is not the case with bxCAN. The following truth + * table has been determined empirically (this behavior was not documented as of 2017): + * + * FM FID RID A + * 0 0 0 1 + * 0 0 1 0 <-- frame rejected! + * 0 1 X 1 + * 1 0 0 1 + * 1 1 0 0 + * 1 0 1 0 + * 1 1 1 1 */ uint32_t id = 0; uint32_t mask = 0; @@ -481,15 +518,14 @@ int canardSTM32ConfigureAcceptanceFilters(const CanardSTM32AcceptanceFilterConfi if ((cfg->id & CANARD_CAN_FRAME_EFF) || !(cfg->mask & CANARD_CAN_FRAME_EFF)) { - // The application wants to trick us by requesting both ext and std frames! - id = (cfg->id & CANARD_CAN_EXT_ID_MASK) << 3; // Little they know, we can handle that correctly. - mask = (cfg->mask & CANARD_CAN_EXT_ID_MASK) << 3; // See? - id |= CANARD_STM32_CAN_RIR_IDE; // That's how we do this. Where's my sunglasses? + id = (cfg->id & CANARD_CAN_EXT_ID_MASK) << 3; + mask = (cfg->mask & CANARD_CAN_EXT_ID_MASK) << 3; + id |= CANARD_STM32_CAN_RIR_IDE; } else { - id = (cfg->id & CANARD_CAN_STD_ID_MASK) << 21; // Regular std frames, nothing fancy. - mask = (cfg->mask & CANARD_CAN_STD_ID_MASK) << 21; // Boring. + id = (cfg->id & CANARD_CAN_STD_ID_MASK) << 21; + mask = (cfg->mask & CANARD_CAN_STD_ID_MASK) << 21; } if (cfg->id & CANARD_CAN_FRAME_RTR) From e6ded1b05f48c5413bce677dc74c57a2b76ab7bf Mon Sep 17 00:00:00 2001 From: MitchKoch Date: Fri, 16 Mar 2018 15:49:22 -0700 Subject: [PATCH 05/81] Support for a node to forget its assigned nodeid Useful for battery packs that never get powered off and are dynamically added and removed from UAVCAN networks --- canard.c | 4 ++++ canard.h | 6 ++++++ 2 files changed, 10 insertions(+) diff --git a/canard.c b/canard.c index 18aa4367..12d9ac99 100644 --- a/canard.c +++ b/canard.c @@ -130,6 +130,10 @@ uint8_t canardGetLocalNodeID(const CanardInstance* ins) return ins->node_id; } +void canardForgetLocalNodeID(CanardInstance* ins) { + ins->node_id = CANARD_BROADCAST_NODE_ID; +} + int canardBroadcast(CanardInstance* ins, uint64_t data_type_signature, uint16_t data_type_id, diff --git a/canard.h b/canard.h index c779acae..24824ed6 100644 --- a/canard.h +++ b/canard.h @@ -323,6 +323,12 @@ void canardSetLocalNodeID(CanardInstance* ins, */ uint8_t canardGetLocalNodeID(const CanardInstance* ins); +/** + * Forgets the current node ID value so that a new Node ID can be assigned. + * This is useful for Battery Packs that are never power cycled, but need to be added and removed from networks regularly. + */ +void canardForgetLocalNodeID(CanardInstance* ins); + /** * Sends a broadcast transfer. * If the node is in passive mode, only single frame transfers will be allowed (they will be transmitted as anonymous). From 19df002601910bf9c43447230059f9ec99c83b4f Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Mon, 7 May 2018 12:48:12 +0300 Subject: [PATCH 06/81] Abort build if the platform is not supported --- canard.h | 14 ++++++++++++++ 1 file changed, 14 insertions(+) diff --git a/canard.h b/canard.h index c779acae..a480ecbc 100644 --- a/canard.h +++ b/canard.h @@ -45,6 +45,16 @@ extern "C" { # define CANARD_ASSERT(x) assert(x) #endif +/// By default this macro expands to static_assert if supported by the language (C11, C++14, or newer). +/// The user can redefine this if necessary. +#ifndef CANARD_STATIC_ASSERT +# if defined(static_assert) || (defined(__cplusplus) && (__cplusplus >= 201402L)) +# define CANARD_STATIC_ASSERT(...) static_assert(__VA_ARGS__) +# else +# define CANARD_STATIC_ASSERT(...) /* empty */ +# endif +#endif + /// Error code definitions; inverse of these values may be returned from API calls. #define CANARD_OK 0 // Value 1 is omitted intentionally, since -1 is often used in 3rd party code @@ -490,6 +500,10 @@ CanardPoolAllocatorStatistics canardGetPoolAllocatorStatistics(CanardInstance* i uint16_t canardConvertNativeFloatToFloat16(float value); float canardConvertFloat16ToNativeFloat(uint16_t value); +/// Abort the build if the current platform is not supported. +CANARD_STATIC_ASSERT(((uint32_t)CANARD_MULTIFRAME_RX_PAYLOAD_HEAD_SIZE) < 32, + "Platforms where sizeof(void*) > 4 are not supported. " + "On AMD64 use 32-bit mode (e.g. GCC flag -m32)."); #ifdef __cplusplus } From fa8f0a40a4d07f5787d8b71940b07d41c544e8c4 Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Mon, 7 May 2018 12:57:17 +0300 Subject: [PATCH 07/81] An attempt to combat warnings --- canard.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/canard.h b/canard.h index a480ecbc..2d91e2c0 100644 --- a/canard.h +++ b/canard.h @@ -51,7 +51,7 @@ extern "C" { # if defined(static_assert) || (defined(__cplusplus) && (__cplusplus >= 201402L)) # define CANARD_STATIC_ASSERT(...) static_assert(__VA_ARGS__) # else -# define CANARD_STATIC_ASSERT(...) /* empty */ +# define CANARD_STATIC_ASSERT(...) struct { char _dummy; } # endif #endif From ebdc822338e78cc2f8a4db063859ec50d38a8424 Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Mon, 7 May 2018 13:01:22 +0300 Subject: [PATCH 08/81] Indeed; how about this --- canard.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/canard.h b/canard.h index 2d91e2c0..c7067129 100644 --- a/canard.h +++ b/canard.h @@ -51,7 +51,7 @@ extern "C" { # if defined(static_assert) || (defined(__cplusplus) && (__cplusplus >= 201402L)) # define CANARD_STATIC_ASSERT(...) static_assert(__VA_ARGS__) # else -# define CANARD_STATIC_ASSERT(...) struct { char _dummy; } +# define CANARD_STATIC_ASSERT(x, ...) typedef char _static_assertion_##__LINE__[(x) ? 1 : -1] # endif #endif From 48b74477b3bb38ee3e5c0d61eec7e05fb71638e1 Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Mon, 7 May 2018 13:02:58 +0300 Subject: [PATCH 09/81] Checking against C++11 --- canard.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/canard.h b/canard.h index c7067129..67d8f1a3 100644 --- a/canard.h +++ b/canard.h @@ -45,10 +45,10 @@ extern "C" { # define CANARD_ASSERT(x) assert(x) #endif -/// By default this macro expands to static_assert if supported by the language (C11, C++14, or newer). +/// By default this macro expands to static_assert if supported by the language (C11, C++11, or newer). /// The user can redefine this if necessary. #ifndef CANARD_STATIC_ASSERT -# if defined(static_assert) || (defined(__cplusplus) && (__cplusplus >= 201402L)) +# if defined(static_assert) || (defined(__cplusplus) && (__cplusplus >= 201103L)) # define CANARD_STATIC_ASSERT(...) static_assert(__VA_ARGS__) # else # define CANARD_STATIC_ASSERT(x, ...) typedef char _static_assertion_##__LINE__[(x) ? 1 : -1] From 0f5527ec0674ee4ae2ace4947d518c9dadb1694d Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Mon, 7 May 2018 13:05:21 +0300 Subject: [PATCH 10/81] Checking the C language version explicitly to avoid warnings from Clang --- canard.h | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/canard.h b/canard.h index 67d8f1a3..fd2430e0 100644 --- a/canard.h +++ b/canard.h @@ -48,7 +48,8 @@ extern "C" { /// By default this macro expands to static_assert if supported by the language (C11, C++11, or newer). /// The user can redefine this if necessary. #ifndef CANARD_STATIC_ASSERT -# if defined(static_assert) || (defined(__cplusplus) && (__cplusplus >= 201103L)) +# if (defined(__STDC_VERSION__) && (__STDC_VERSION__ >= 201112L)) ||\ + (defined(__cplusplus) && (__cplusplus >= 201103L)) # define CANARD_STATIC_ASSERT(...) static_assert(__VA_ARGS__) # else # define CANARD_STATIC_ASSERT(x, ...) typedef char _static_assertion_##__LINE__[(x) ? 1 : -1] From 20b7b0a2b769032080e87d4ab4ae37fb2d7c54ef Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Mon, 7 May 2018 13:20:40 +0300 Subject: [PATCH 11/81] Using explicitly unsigned literals to squelch warnings from clang-tidy --- canard.h | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/canard.h b/canard.h index fd2430e0..8ce3eb83 100644 --- a/canard.h +++ b/canard.h @@ -94,9 +94,9 @@ extern "C" { /// Related to CanardCANFrame #define CANARD_CAN_EXT_ID_MASK 0x1FFFFFFFU #define CANARD_CAN_STD_ID_MASK 0x000007FFU -#define CANARD_CAN_FRAME_EFF (1UL << 31) ///< Extended frame format -#define CANARD_CAN_FRAME_RTR (1UL << 30) ///< Remote transmission (not used by UAVCAN) -#define CANARD_CAN_FRAME_ERR (1UL << 29) ///< Error frame (not used by UAVCAN) +#define CANARD_CAN_FRAME_EFF (1UL << 31U) ///< Extended frame format +#define CANARD_CAN_FRAME_RTR (1UL << 30U) ///< Remote transmission (not used by UAVCAN) +#define CANARD_CAN_FRAME_ERR (1UL << 29U) ///< Error frame (not used by UAVCAN) /** * This data type holds a standard CAN 2.0B data frame with 29-bit ID. From 80386734ea6ce6d44d29fd2861bd7e278ad67e1d Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Sun, 20 May 2018 21:43:36 +0300 Subject: [PATCH 12/81] More compiler warnings; fixed clang-tidy warnings --- canard.c | 165 ++++++++++++++++--------------- canard.h | 23 +++-- canard_internals.h | 4 +- drivers/stm32/canard_stm32.h | 8 +- tests/CMakeLists.txt | 12 +++ tests/demo.c | 16 +-- tests/stm32/test_can_timings.cpp | 12 +-- tests/test_float16.cpp | 12 +-- tests/test_scalar_encoding.cpp | 33 ++++--- 9 files changed, 156 insertions(+), 129 deletions(-) diff --git a/canard.c b/canard.c index 0faa39f8..3b76b16c 100644 --- a/canard.c +++ b/canard.c @@ -36,26 +36,27 @@ #define TRANSFER_TIMEOUT_USEC 2000000 -#define TRANSFER_ID_BIT_LEN 5 -#define ANON_MSG_DATA_TYPE_ID_BIT_LEN 2 +#define TRANSFER_ID_BIT_LEN 5U +#define ANON_MSG_DATA_TYPE_ID_BIT_LEN 2U -#define SOURCE_ID_FROM_ID(x) ((uint8_t) (((x) >> 0) & 0x7F)) -#define SERVICE_NOT_MSG_FROM_ID(x) ((bool) (((x) >> 7) & 0x1)) -#define REQUEST_NOT_RESPONSE_FROM_ID(x) ((bool) (((x) >> 15) & 0x1)) -#define DEST_ID_FROM_ID(x) ((uint8_t) (((x) >> 8) & 0x7F)) -#define PRIORITY_FROM_ID(x) ((uint8_t) (((x) >> 24) & 0x1F)) -#define MSG_TYPE_FROM_ID(x) ((uint16_t)(((x) >> 8) & 0xFFFF)) -#define SRV_TYPE_FROM_ID(x) ((uint8_t) (((x) >> 16) & 0xFF)) +#define SOURCE_ID_FROM_ID(x) ((uint8_t) (((x) >> 0U) & 0x7FU)) +#define SERVICE_NOT_MSG_FROM_ID(x) ((bool) (((x) >> 7U) & 0x1U)) +#define REQUEST_NOT_RESPONSE_FROM_ID(x) ((bool) (((x) >> 15U) & 0x1U)) +#define DEST_ID_FROM_ID(x) ((uint8_t) (((x) >> 8U) & 0x7FU)) +#define PRIORITY_FROM_ID(x) ((uint8_t) (((x) >> 24U) & 0x1FU)) +#define MSG_TYPE_FROM_ID(x) ((uint16_t)(((x) >> 8U) & 0xFFFFU)) +#define SRV_TYPE_FROM_ID(x) ((uint8_t) (((x) >> 16U) & 0xFFU)) #define MAKE_TRANSFER_DESCRIPTOR(data_type_id, transfer_type, src_node_id, dst_node_id) \ - (((uint32_t)data_type_id) | (((uint32_t)transfer_type) << 16) | \ - (((uint32_t)src_node_id) << 18) | (((uint32_t)dst_node_id) << 25)) + (((uint32_t)(data_type_id)) | (((uint32_t)(transfer_type)) << 16U) | \ + (((uint32_t)(src_node_id)) << 18U) | (((uint32_t)(dst_node_id)) << 25U)) -#define TRANSFER_ID_FROM_TAIL_BYTE(x) ((uint8_t)((x) & 0x1F)) +#define TRANSFER_ID_FROM_TAIL_BYTE(x) ((uint8_t)((x) & 0x1FU)) -#define IS_START_OF_TRANSFER(x) ((bool)(((x) >> 7) & 0x1)) -#define IS_END_OF_TRANSFER(x) ((bool)(((x) >> 6) & 0x1)) -#define TOGGLE_BIT(x) ((bool)(((x) >> 5) & 0x1)) +// The extra cast to unsigned is needed to squelch warnings from clang-tidy +#define IS_START_OF_TRANSFER(x) ((bool)(((unsigned)(x) >> 7U) & 0x1U)) +#define IS_END_OF_TRANSFER(x) ((bool)(((unsigned)(x) >> 6U) & 0x1U)) +#define TOGGLE_BIT(x) ((bool)(((unsigned)(x) >> 5U) & 0x1U)) struct CanardTxQueueItem @@ -166,12 +167,12 @@ int canardBroadcast(CanardInstance* ins, // anonymous transfer, random discriminator const uint16_t discriminator = (uint16_t)((crcAdd(0xFFFFU, payload, payload_len)) & 0x7FFEU); - can_id = ((uint32_t) priority << 24) | ((uint32_t) discriminator << 9) | - ((uint32_t) (data_type_id & DTIDMask) << 8) | (uint32_t) canardGetLocalNodeID(ins); + can_id = ((uint32_t) priority << 24U) | ((uint32_t) discriminator << 9U) | + ((uint32_t) (data_type_id & DTIDMask) << 8U) | (uint32_t) canardGetLocalNodeID(ins); } else { - can_id = ((uint32_t) priority << 24) | ((uint32_t) data_type_id << 8) | (uint32_t) canardGetLocalNodeID(ins); + can_id = ((uint32_t) priority << 24U) | ((uint32_t) data_type_id << 8U) | (uint32_t) canardGetLocalNodeID(ins); if (payload_len > 7) { @@ -210,9 +211,9 @@ int canardRequestOrRespond(CanardInstance* ins, return -CANARD_ERROR_NODE_ID_NOT_SET; } - const uint32_t can_id = ((uint32_t) priority << 24) | ((uint32_t) data_type_id << 16) | - ((uint32_t) kind << 15) | ((uint32_t) destination_node_id << 8) | - (1 << 7) | (uint32_t) canardGetLocalNodeID(ins); + const uint32_t can_id = ((uint32_t) priority << 24U) | ((uint32_t) data_type_id << 16U) | + ((uint32_t) kind << 15U) | ((uint32_t) destination_node_id << 8U) | + (1U << 7U) | (uint32_t) canardGetLocalNodeID(ins); uint16_t crc = 0xFFFFU; if (payload_len > 7) @@ -331,7 +332,7 @@ void canardHandleRxFrame(CanardInstance* ins, const CanardCANFrame* frame, uint6 releaseStatePayload(ins, rx_state); if (!IS_START_OF_TRANSFER(tail_byte)) // missed the first frame { - rx_state->transfer_id += 1; + rx_state->transfer_id++; return; } } @@ -383,7 +384,7 @@ void canardHandleRxFrame(CanardInstance* ins, const CanardCANFrame* frame, uint6 prepareForNextTransfer(rx_state); return; } - rx_state->payload_crc = ((uint16_t) frame->data[0]) | ((uint16_t) frame->data[1] << 8); + rx_state->payload_crc = (uint16_t)(((uint16_t) frame->data[0]) | (uint16_t)((uint16_t) frame->data[1] << 8U)); rx_state->calculated_crc = crcAdd((uint16_t)rx_state->calculated_crc, frame->data + 2, (uint8_t)(frame->data_len - 3)); } @@ -563,7 +564,7 @@ int canardDecodeScalar(const CanardRxTransfer* transfer, if ((bit_length % 8) != 0) { // coverity[overrun-local] - storage.bytes[bit_length / 8] = (uint8_t)(storage.bytes[bit_length / 8] >> ((8 - (bit_length % 8)) & 7)); + storage.bytes[bit_length / 8U] = (uint8_t)(storage.bytes[bit_length / 8U] >> ((8U - (bit_length % 8U)) & 7U)); } /* @@ -593,35 +594,36 @@ int canardDecodeScalar(const CanardRxTransfer* transfer, /* * Extending the sign bit if needed. I miss templates. + * Note that we operate on unsigned values in order to avoid undefined behaviors. */ if (value_is_signed && (std_byte_length * 8 != bit_length)) { if (bit_length <= 8) { - if ((storage.s8 & (1U << (bit_length - 1))) != 0) // If the sign bit is set... + if ((storage.u8 & (1U << (bit_length - 1U))) != 0) // If the sign bit is set... { - storage.s8 |= (uint8_t) 0xFFU & (uint8_t) ~((1U << bit_length) - 1U); // ...set all bits above it. + storage.u8 |= (uint8_t) 0xFFU & (uint8_t) ~((1U << bit_length) - 1U); // ...set all bits above it. } } else if (bit_length <= 16) { - if ((storage.s16 & (1U << (bit_length - 1))) != 0) + if ((storage.u16 & (1U << (bit_length - 1U))) != 0) { - storage.s16 |= (uint16_t) 0xFFFFU & (uint16_t) ~((1U << bit_length) - 1U); + storage.u16 |= (uint16_t) 0xFFFFU & (uint16_t) ~((1U << bit_length) - 1U); } } else if (bit_length <= 32) { - if ((storage.s32 & (((uint32_t) 1) << (bit_length - 1))) != 0) + if ((storage.u32 & (((uint32_t) 1) << (bit_length - 1U))) != 0) { - storage.s32 |= (uint32_t) 0xFFFFFFFFUL & (uint32_t) ~((((uint32_t) 1) << bit_length) - 1U); + storage.u32 |= (uint32_t) 0xFFFFFFFFUL & (uint32_t) ~((((uint32_t) 1) << bit_length) - 1U); } } else if (bit_length < 64) // Strictly less, this is not a typo { - if ((storage.s64 & (((uint64_t) 1) << (bit_length - 1))) != 0) + if ((storage.u64 & (((uint64_t) 1) << (bit_length - 1U))) != 0) { - storage.s64 |= (uint64_t) 0xFFFFFFFFFFFFFFFFULL & (uint64_t) ~((((uint64_t) 1) << bit_length) - 1U); + storage.u64 |= (uint64_t) 0xFFFFFFFFFFFFFFFFULL & (uint64_t) ~((((uint64_t) 1) << bit_length) - 1U); } } else @@ -735,7 +737,7 @@ void canardEncodeScalar(void* destination, if ((bit_length % 8) != 0) { // coverity[overrun-local] - storage.bytes[bit_length / 8] = (uint8_t)(storage.bytes[bit_length / 8] << ((8 - (bit_length % 8)) & 7)); + storage.bytes[bit_length / 8U] = (uint8_t)(storage.bytes[bit_length / 8U] << ((8U - (bit_length % 8U)) & 7U)); } /* @@ -774,11 +776,11 @@ uint16_t canardConvertNativeFloatToFloat16(float value) float f; }; - const union FP32 f32inf = { 255UL << 23 }; - const union FP32 f16inf = { 31UL << 23 }; - const union FP32 magic = { 15UL << 23 }; - const uint32_t sign_mask = 0x80000000U; - const uint32_t round_mask = ~0xFFFU; + const union FP32 f32inf = { 255UL << 23U }; + const union FP32 f16inf = { 31UL << 23U }; + const union FP32 magic = { 15UL << 23U }; + const uint32_t sign_mask = 0x80000000UL; + const uint32_t round_mask = ~0xFFFUL; union FP32 in; in.f = value; @@ -800,10 +802,10 @@ uint16_t canardConvertNativeFloatToFloat16(float value) { in.u = f16inf.u; } - out = (uint16_t)(in.u >> 13); + out = (uint16_t)(in.u >> 13U); } - out |= (uint16_t)(sign >> 16); + out |= (uint16_t)(sign >> 16U); return out; } @@ -818,17 +820,17 @@ float canardConvertFloat16ToNativeFloat(uint16_t value) float f; }; - const union FP32 magic = { (254UL - 15UL) << 23 }; - const union FP32 was_inf_nan = { (127UL + 16UL) << 23 }; + const union FP32 magic = { (254UL - 15UL) << 23U }; + const union FP32 was_inf_nan = { (127UL + 16UL) << 23U }; union FP32 out; - out.u = (value & 0x7FFFU) << 13; + out.u = (value & 0x7FFFU) << 13U; out.f *= magic.f; if (out.f >= was_inf_nan.f) { - out.u |= 255UL << 23; + out.u |= 255UL << 23U; } - out.u |= (value & 0x8000UL) << 16; + out.u |= (value & 0x8000UL) << 16U; return out.f; } @@ -836,12 +838,12 @@ float canardConvertFloat16ToNativeFloat(uint16_t value) /* * Internal (static functions) */ -CANARD_INTERNAL int computeTransferIDForwardDistance(uint8_t a, uint8_t b) +CANARD_INTERNAL int16_t computeTransferIDForwardDistance(uint8_t a, uint8_t b) { - int d = b - a; + int16_t d = (int16_t)(b - a); if (d < 0) { - d += 1 << TRANSFER_ID_BIT_LEN; + d = (int16_t)(d + (int16_t)(1U << TRANSFER_ID_BIT_LEN)); } return d; } @@ -850,7 +852,7 @@ CANARD_INTERNAL void incrementTransferID(uint8_t* transfer_id) { CANARD_ASSERT(transfer_id != NULL); - *transfer_id += 1; + (*transfer_id)++; if (*transfer_id >= 32) { *transfer_id = 0; @@ -890,7 +892,7 @@ CANARD_INTERNAL int enqueueTxFrames(CanardInstance* ins, memcpy(queue_item->frame.data, payload, payload_len); queue_item->frame.data_len = (uint8_t)(payload_len + 1); - queue_item->frame.data[payload_len] = (uint8_t)(0xC0 | (*transfer_id & 31)); + queue_item->frame.data[payload_len] = (uint8_t)(0xC0U | (*transfer_id & 31U)); queue_item->frame.id = can_id | CANARD_CAN_FRAME_EFF; pushTxQueue(ins, queue_item); @@ -917,7 +919,7 @@ CANARD_INTERNAL int enqueueTxFrames(CanardInstance* ins, { // add crc queue_item->frame.data[0] = (uint8_t) (crc); - queue_item->frame.data[1] = (uint8_t) (crc >> 8); + queue_item->frame.data[1] = (uint8_t) (crc >> 8U); i = 2; } else @@ -932,7 +934,7 @@ CANARD_INTERNAL int enqueueTxFrames(CanardInstance* ins, // tail byte sot_eot = (data_index == payload_len) ? (uint8_t)0x40 : sot_eot; - queue_item->frame.data[i] = (uint8_t)(sot_eot | (toggle << 5) | (*transfer_id & 31)); + queue_item->frame.data[i] = (uint8_t)(sot_eot | ((uint32_t)toggle << 5U) | ((uint32_t)*transfer_id & 31U)); queue_item->frame.id = can_id | CANARD_CAN_FRAME_EFF; queue_item->frame.data_len = (uint8_t)(i + 1); pushTxQueue(ins, queue_item); @@ -1024,8 +1026,8 @@ CANARD_INTERNAL bool isPriorityHigher(uint32_t rhs, uint32_t id) const bool rhs_ext = (rhs & CANARD_CAN_FRAME_EFF) != 0; if (ext != rhs_ext) { - uint32_t arb11 = ext ? (clean_id >> 18) : clean_id; - uint32_t rhs_arb11 = rhs_ext ? (rhs_clean_id >> 18) : rhs_clean_id; + uint32_t arb11 = ext ? (clean_id >> 18U) : clean_id; + uint32_t rhs_arb11 = rhs_ext ? (rhs_clean_id >> 18U) : rhs_clean_id; if (arb11 != rhs_arb11) { return arb11 < rhs_arb11; @@ -1058,7 +1060,7 @@ CANARD_INTERNAL bool isPriorityHigher(uint32_t rhs, uint32_t id) CANARD_INTERNAL void prepareForNextTransfer(CanardRxState* state) { CANARD_ASSERT(state->buffer_blocks == NULL); - state->transfer_id += 1; + state->transfer_id++; state->payload_len = 0; state->next_toggle = 0; } @@ -1227,13 +1229,14 @@ CANARD_INTERNAL int bufferBlockPushBytes(CanardPoolAllocator* allocator, } if (data_index >= data_len) { - state->payload_len += data_len; + state->payload_len = + (uint16_t)(state->payload_len + data_len) & ((1U << CANARD_TRANSFER_PAYLOAD_LEN_BITS) - 1U); return 1; } } // head is full. - uint8_t index_at_nth_block = - (((state->payload_len) - CANARD_MULTIFRAME_RX_PAYLOAD_HEAD_SIZE) % CANARD_BUFFER_BLOCK_DATA_SIZE); + uint16_t index_at_nth_block = + (uint16_t)(((state->payload_len) - CANARD_MULTIFRAME_RX_PAYLOAD_HEAD_SIZE) % CANARD_BUFFER_BLOCK_DATA_SIZE); // get to current block CanardBufferBlock* block = NULL; @@ -1253,7 +1256,7 @@ CANARD_INTERNAL int bufferBlockPushBytes(CanardPoolAllocator* allocator, } else { - uint8_t nth_block = 1; + uint16_t nth_block = 1; // get to block block = state->buffer_blocks; @@ -1263,8 +1266,9 @@ CANARD_INTERNAL int bufferBlockPushBytes(CanardPoolAllocator* allocator, block = block->next; } - const uint8_t num_buffer_blocks = (((state->payload_len + data_len) - CANARD_MULTIFRAME_RX_PAYLOAD_HEAD_SIZE) / - CANARD_BUFFER_BLOCK_DATA_SIZE) + 1; + const uint16_t num_buffer_blocks = + (uint16_t) (((((uint32_t)state->payload_len + data_len) - CANARD_MULTIFRAME_RX_PAYLOAD_HEAD_SIZE) / + CANARD_BUFFER_BLOCK_DATA_SIZE) + 1U); if (num_buffer_blocks > nth_block && index_at_nth_block == 0) { @@ -1299,7 +1303,7 @@ CANARD_INTERNAL int bufferBlockPushBytes(CanardPoolAllocator* allocator, } } - state->payload_len += data_len; + state->payload_len = (uint16_t)(state->payload_len + data_len) & ((1U << CANARD_TRANSFER_PAYLOAD_LEN_BITS) - 1U); return 1; } @@ -1324,11 +1328,11 @@ void copyBitArray(const uint8_t* src, uint32_t src_offset, uint32_t src_len, CANARD_ASSERT(src_len > 0U); // Normalizing inputs - src += src_offset / 8; - dst += dst_offset / 8; + src += src_offset / 8U; + dst += dst_offset / 8U; - src_offset %= 8; - dst_offset %= 8; + src_offset %= 8U; + dst_offset %= 8U; const size_t last_bit = src_offset + src_len; while (last_bit - src_offset) @@ -1340,9 +1344,10 @@ void copyBitArray(const uint8_t* src, uint32_t src_offset, uint32_t src_len, const uint32_t copy_bits = MIN(last_bit - src_offset, 8U - max_offset); const uint8_t write_mask = (uint8_t)((uint8_t)(0xFF00U >> copy_bits) >> dst_bit_offset); - const uint8_t src_data = (uint8_t)((src[src_offset / 8U] << src_bit_offset) >> dst_bit_offset); + const uint8_t src_data = (uint8_t)(((uint32_t)src[src_offset / 8U] << src_bit_offset) >> dst_bit_offset); - dst[dst_offset / 8U] = (uint8_t)((dst[dst_offset / 8U] & ~write_mask) | (src_data & write_mask)); + dst[dst_offset / 8U] = + (uint8_t)(((uint32_t)dst[dst_offset / 8U] & (uint32_t)~write_mask) | (uint32_t)(src_data & write_mask)); src_offset += copy_bits; dst_offset += copy_bits; @@ -1363,7 +1368,7 @@ CANARD_INTERNAL int descatterTransferPayload(const CanardRxTransfer* transfer, if (bit_offset + bit_length > transfer->payload_len * 8) { - bit_length = (uint8_t)(transfer->payload_len * 8 - bit_offset); + bit_length = (uint8_t)(transfer->payload_len * 8U - bit_offset); } CANARD_ASSERT(bit_length > 0); @@ -1382,14 +1387,14 @@ CANARD_INTERNAL int descatterTransferPayload(const CanardRxTransfer* transfer, // Reading head if (input_bit_offset < CANARD_MULTIFRAME_RX_PAYLOAD_HEAD_SIZE * 8) { - const uint8_t amount = MIN(remaining_bit_length, - CANARD_MULTIFRAME_RX_PAYLOAD_HEAD_SIZE * 8U - input_bit_offset); + const uint8_t amount = (uint8_t)MIN(remaining_bit_length, + CANARD_MULTIFRAME_RX_PAYLOAD_HEAD_SIZE * 8U - input_bit_offset); copyBitArray(&transfer->payload_head[0], input_bit_offset, amount, (uint8_t*) output, 0); input_bit_offset += amount; - output_bit_offset += amount; - remaining_bit_length -= amount; + output_bit_offset = (uint8_t)(output_bit_offset + amount); + remaining_bit_length = (uint8_t)(remaining_bit_length - amount); } // Reading middle @@ -1414,8 +1419,8 @@ CANARD_INTERNAL int descatterTransferPayload(const CanardRxTransfer* transfer, copyBitArray(&block->data[0], bit_offset_within_block, amount, (uint8_t*) output, output_bit_offset); input_bit_offset += amount; - output_bit_offset += amount; - remaining_bit_length -= amount; + output_bit_offset = (uint8_t)(output_bit_offset + amount); + remaining_bit_length = (uint8_t)(remaining_bit_length - amount); } CANARD_ASSERT(block_end_bit_offset > block_bit_offset); @@ -1436,7 +1441,7 @@ CANARD_INTERNAL int descatterTransferPayload(const CanardRxTransfer* transfer, output_bit_offset); input_bit_offset += remaining_bit_length; - output_bit_offset += remaining_bit_length; + output_bit_offset = (uint8_t)(output_bit_offset + remaining_bit_length); remaining_bit_length = 0; } @@ -1491,16 +1496,16 @@ CANARD_INTERNAL void swapByteOrder(void* data, unsigned size) */ CANARD_INTERNAL uint16_t crcAddByte(uint16_t crc_val, uint8_t byte) { - crc_val ^= (uint16_t) ((uint16_t) (byte) << 8); + crc_val ^= (uint16_t) ((uint16_t) (byte) << 8U); for (int j = 0; j < 8; j++) { if (crc_val & 0x8000U) { - crc_val = (uint16_t) ((uint16_t) (crc_val << 1) ^ 0x1021U); + crc_val = (uint16_t) ((uint16_t) (crc_val << 1U) ^ 0x1021U); } else { - crc_val = (uint16_t) (crc_val << 1); + crc_val = (uint16_t) (crc_val << 1U); } } return crc_val; @@ -1508,7 +1513,7 @@ CANARD_INTERNAL uint16_t crcAddByte(uint16_t crc_val, uint8_t byte) CANARD_INTERNAL uint16_t crcAddSignature(uint16_t crc_val, uint64_t data_type_signature) { - for (int shift_val = 0; shift_val < 64; shift_val += 8) + for (uint16_t shift_val = 0; shift_val < 64; shift_val = (uint16_t)(shift_val + 8U)) { crc_val = crcAddByte(crc_val, (uint8_t) (data_type_signature >> shift_val)); } diff --git a/canard.h b/canard.h index 8ce3eb83..137edf1d 100644 --- a/canard.h +++ b/canard.h @@ -38,13 +38,16 @@ extern "C" { /// Libcanard version. API will be backwards compatible within the same major version. #define CANARD_VERSION_MAJOR 0 -#define CANARD_VERSION_MINOR 1 +#define CANARD_VERSION_MINOR 2 /// By default this macro resolves to the standard assert(). The user can redefine this if necessary. #ifndef CANARD_ASSERT # define CANARD_ASSERT(x) assert(x) #endif +#define CANARD_GLUE(a, b) CANARD_GLUE_IMPL_(a, b) +#define CANARD_GLUE_IMPL_(a, b) a##b + /// By default this macro expands to static_assert if supported by the language (C11, C++11, or newer). /// The user can redefine this if necessary. #ifndef CANARD_STATIC_ASSERT @@ -52,7 +55,7 @@ extern "C" { (defined(__cplusplus) && (__cplusplus >= 201103L)) # define CANARD_STATIC_ASSERT(...) static_assert(__VA_ARGS__) # else -# define CANARD_STATIC_ASSERT(x, ...) typedef char _static_assertion_##__LINE__[(x) ? 1 : -1] +# define CANARD_STATIC_ASSERT(x, ...) typedef char CANARD_GLUE(_static_assertion_, __LINE__)[(x) ? 1 : -1] # endif #endif @@ -65,10 +68,10 @@ extern "C" { #define CANARD_ERROR_INTERNAL 9 /// The size of a memory block in bytes. -#define CANARD_MEM_BLOCK_SIZE 32 +#define CANARD_MEM_BLOCK_SIZE 32U /// This will be changed when the support for CAN FD is added -#define CANARD_CAN_FRAME_MAX_DATA_LEN 8 +#define CANARD_CAN_FRAME_MAX_DATA_LEN 8U /// Node ID values. Refer to the specification for more info. #define CANARD_BROADCAST_NODE_ID 0 @@ -98,6 +101,10 @@ extern "C" { #define CANARD_CAN_FRAME_RTR (1UL << 30U) ///< Remote transmission (not used by UAVCAN) #define CANARD_CAN_FRAME_ERR (1UL << 29U) ///< Error frame (not used by UAVCAN) +#define CANARD_TRANSFER_PAYLOAD_LEN_BITS 10U +#define CANARD_MAX_TRANSFER_PAYLOAD_LEN ((1U << CANARD_TRANSFER_PAYLOAD_LEN_BITS) - 1U) + + /** * This data type holds a standard CAN 2.0B data frame with 29-bit ID. */ @@ -218,16 +225,18 @@ struct CanardRxState const uint32_t dtid_tt_snid_dnid; - uint16_t payload_crc; - // We're using plain 'unsigned' here, because C99 doesn't permit explicit field type specification unsigned calculated_crc : 16; - unsigned payload_len : 10; + unsigned payload_len : CANARD_TRANSFER_PAYLOAD_LEN_BITS; unsigned transfer_id : 5; unsigned next_toggle : 1; // 16+10+5+1 = 32, aligned. + uint16_t payload_crc; + uint8_t buffer_head[]; }; +CANARD_STATIC_ASSERT(sizeof(CanardRxState) <= 28, "Invalid memory layout"); +CANARD_STATIC_ASSERT(CANARD_MULTIFRAME_RX_PAYLOAD_HEAD_SIZE >= 4, "Invalid memory layout"); /** * This is the core structure that keeps all of the states and allocated resources of the library instance. diff --git a/canard_internals.h b/canard_internals.h index b1f19df6..eba1cf50 100644 --- a/canard_internals.h +++ b/canard_internals.h @@ -77,8 +77,8 @@ CANARD_INTERNAL CanardTxQueueItem* createTxItem(CanardPoolAllocator* allocator); CANARD_INTERNAL void prepareForNextTransfer(CanardRxState* state); -CANARD_INTERNAL int computeTransferIDForwardDistance(uint8_t a, - uint8_t b); +CANARD_INTERNAL int16_t computeTransferIDForwardDistance(uint8_t a, + uint8_t b); CANARD_INTERNAL void incrementTransferID(uint8_t* transfer_id); diff --git a/drivers/stm32/canard_stm32.h b/drivers/stm32/canard_stm32.h index 1cee8bfe..a64f9b8a 100644 --- a/drivers/stm32/canard_stm32.h +++ b/drivers/stm32/canard_stm32.h @@ -238,7 +238,7 @@ int canardSTM32ComputeCANTimings(const uint32_t peripheral_clock_rate, */ uint8_t bs1_bs2_sum = (uint8_t)(max_quanta_per_bit - 1); - while ((prescaler_bs % (1 + bs1_bs2_sum)) != 0) + while ((prescaler_bs % (1U + bs1_bs2_sum)) != 0) { if (bs1_bs2_sum <= 2) { @@ -247,7 +247,7 @@ int canardSTM32ComputeCANTimings(const uint32_t peripheral_clock_rate, bs1_bs2_sum--; } - const uint32_t prescaler = prescaler_bs / (1 + bs1_bs2_sum); + const uint32_t prescaler = prescaler_bs / (1U + bs1_bs2_sum); if ((prescaler < 1U) || (prescaler > 1024U)) { return -CANARD_STM32_ERROR_UNSUPPORTED_BIT_RATE; // No solution @@ -277,7 +277,7 @@ int canardSTM32ComputeCANTimings(const uint32_t peripheral_clock_rate, CANARD_ASSERT(bs1_bs2_sum > bs1); { - const uint16_t sample_point_permill = (uint16_t)(1000 * (1 + bs1) / (1 + bs1 + bs2)); + const uint16_t sample_point_permill = (uint16_t)(1000U * (1U + bs1) / (1U + bs1 + bs2)); if (sample_point_permill > MaxSamplePointLocationPermill) // Strictly more! { @@ -296,7 +296,7 @@ int canardSTM32ComputeCANTimings(const uint32_t peripheral_clock_rate, * ts2,ts1,brp = (x>>20)&7, (x>>16)&15, x&511 * return (1+ts1+1)/(1+ts1+1+ts2+1) */ - if ((target_bitrate != (peripheral_clock_rate / (prescaler * (1 + bs1 + bs2)))) || + if ((target_bitrate != (peripheral_clock_rate / (prescaler * (1U + bs1 + bs2)))) || !valid) { // This actually means that the algorithm has a logic error, hence assert(0). diff --git a/tests/CMakeLists.txt b/tests/CMakeLists.txt index a1416b9f..0a3ce454 100644 --- a/tests/CMakeLists.txt +++ b/tests/CMakeLists.txt @@ -17,6 +17,18 @@ include_directories(../drivers/socketcan) set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11 -Wall -Wextra -Werror -m32") set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -std=c99 -Wall -Wextra -Werror -m32 -pedantic") +# C warnings +set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -Wdouble-promotion -Wswitch-enum -Wfloat-equal -Wundef") +set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -Wconversion -Wtype-limits") +set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -Wsign-conversion -Wcast-align -Wmissing-declarations") + +# C++ warnings +set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wdouble-promotion -Wswitch-enum -Wfloat-equal -Wundef") +set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wconversion -Wsign-promo") +set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wsign-conversion -Wcast-align -Wmissing-declarations") +set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wtype-limits -Wzero-as-null-pointer-constant -Wnon-virtual-dtor") +set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Woverloaded-virtual -Wsign-promo -Wold-style-cast") + # Expose internal API for unit testing set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -DCANARD_INTERNAL=''") set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -DCANARD_INTERNAL=''") diff --git a/tests/demo.c b/tests/demo.c index 0c5a66be..c765d2cb 100644 --- a/tests/demo.c +++ b/tests/demo.c @@ -74,7 +74,7 @@ static uint8_t node_health = UAVCAN_NODE_HEALTH_OK; static uint8_t node_mode = UAVCAN_NODE_MODE_INITIALIZATION; -uint64_t getMonotonicTimestampUSec(void) +static uint64_t getMonotonicTimestampUSec(void) { struct timespec ts; memset(&ts, 0, sizeof(ts)); @@ -82,14 +82,14 @@ uint64_t getMonotonicTimestampUSec(void) { abort(); } - return ts.tv_sec * 1000000ULL + ts.tv_nsec / 1000ULL; + return (uint64_t)(ts.tv_sec * 1000000LL + ts.tv_nsec / 1000LL); } /** * Returns a pseudo random float in the range [0, 1]. */ -float getRandomFloat(void) +static float getRandomFloat(void) { static bool initialized = false; if (!initialized) // This is not thread safe, but a race condition here is not harmful. @@ -105,7 +105,7 @@ float getRandomFloat(void) /** * This function uses a mock unique ID, this is not allowed in real applications! */ -void readUniqueID(uint8_t* out_uid) +static void readUniqueID(uint8_t* out_uid) { for (uint8_t i = 0; i < UNIQUE_ID_LENGTH_BYTES; i++) { @@ -114,7 +114,7 @@ void readUniqueID(uint8_t* out_uid) } -void makeNodeStatusMessage(uint8_t buffer[UAVCAN_NODE_STATUS_MESSAGE_SIZE]) +static void makeNodeStatusMessage(uint8_t buffer[UAVCAN_NODE_STATUS_MESSAGE_SIZE]) { memset(buffer, 0, UAVCAN_NODE_STATUS_MESSAGE_SIZE); @@ -306,7 +306,7 @@ static bool shouldAcceptTransfer(const CanardInstance* ins, /** * This function is called at 1 Hz rate from the main loop. */ -void process1HzTasks(uint64_t timestamp_usec) +static void process1HzTasks(uint64_t timestamp_usec) { /* * Purging transfers that are no longer transmitted. This will occasionally free up some memory. @@ -358,7 +358,7 @@ void process1HzTasks(uint64_t timestamp_usec) /** * Transmits all frames from the TX queue, receives up to one frame. */ -void processTxRxOnce(SocketCANInstance* socketcan, int timeout_msec) +static void processTxRxOnce(SocketCANInstance* socketcan, int timeout_msec) { // Transmitting for (const CanardCANFrame* txf = NULL; (txf = canardPeekTxQueue(&canard)) != NULL;) @@ -457,7 +457,7 @@ int main(int argc, char** argv) // Structure of the request is documented in the DSDL definition // See http://uavcan.org/Specification/6._Application_level_functions/#dynamic-node-id-allocation uint8_t allocation_request[CANARD_CAN_FRAME_MAX_DATA_LEN - 1]; - allocation_request[0] = PreferredNodeID << 1; + allocation_request[0] = (uint8_t)(PreferredNodeID << 1U); if (node_id_allocation_unique_id_offset == 0) { diff --git a/tests/stm32/test_can_timings.cpp b/tests/stm32/test_can_timings.cpp index d790380c..1c996682 100644 --- a/tests/stm32/test_can_timings.cpp +++ b/tests/stm32/test_can_timings.cpp @@ -36,13 +36,13 @@ static std::uint32_t computeBDTR(const std::uint32_t pclk1, const int res = canardSTM32ComputeCANTimings(pclk1, target_bitrate, &timings); - const std::uint16_t sample_point_permill = + const auto sample_point_permill = std::uint16_t((1000 * (1 + timings.bit_segment_1) / (1 + timings.bit_segment_1 + timings.bit_segment_2))); - const std::uint32_t bdtr = (((timings.max_resynchronization_jump_width - 1) & 3U) << 24) | - (((timings.bit_segment_1 - 1) & 15U) << 16) | - (((timings.bit_segment_2 - 1) & 7U) << 20) | - (((timings.bit_rate_prescaler - 1) & 1023U) << 0); + const std::uint32_t bdtr = (((timings.max_resynchronization_jump_width - 1U) & 3U) << 24U) | + (((timings.bit_segment_1 - 1U) & 15U) << 16U) | + (((timings.bit_segment_2 - 1U) & 7U) << 20U) | + (((timings.bit_rate_prescaler - 1U) & 1023U) << 0U); std::printf("PCLK %9u Target %9u %s (%d) Presc %4u BS %2u/%u %.1f%% BDTR 0x%08x\n", unsigned(pclk1), @@ -52,7 +52,7 @@ static std::uint32_t computeBDTR(const std::uint32_t pclk1, timings.bit_rate_prescaler, timings.bit_segment_1, timings.bit_segment_2, - sample_point_permill * 0.1F, + double(sample_point_permill) * 0.1, unsigned(bdtr)); if (res != 0) { diff --git a/tests/test_float16.cpp b/tests/test_float16.cpp index bee9994d..740d0155 100644 --- a/tests/test_float16.cpp +++ b/tests/test_float16.cpp @@ -23,7 +23,7 @@ */ #include -#include +#include #include "canard.h" @@ -35,7 +35,7 @@ TEST(Float16, FromNative) ASSERT_EQ(0b1100000000000000, canardConvertNativeFloatToFloat16(-2)); ASSERT_EQ(0b0111110000000000, canardConvertNativeFloatToFloat16(999999)); // +inf ASSERT_EQ(0b1111101111111111, canardConvertNativeFloatToFloat16(-65519)); // -max - ASSERT_EQ(0b0111111111111111, canardConvertNativeFloatToFloat16(nan(""))); // nan + ASSERT_EQ(0b0111111111111111, canardConvertNativeFloatToFloat16(std::nan(""))); // nan } @@ -48,16 +48,16 @@ TEST(Float16, ToNative) ASSERT_FLOAT_EQ(INFINITY, canardConvertFloat16ToNativeFloat(0b0111110000000000)); ASSERT_FLOAT_EQ(-65504, canardConvertFloat16ToNativeFloat(0b1111101111111111)); - ASSERT_TRUE((bool)isnan(canardConvertFloat16ToNativeFloat(0b0111111111111111))); + ASSERT_TRUE(bool(std::isnan(canardConvertFloat16ToNativeFloat(0b0111111111111111)))); } TEST(Float16, BackAndForth) { - float x = -1000; - while (x <= 1000) + float x = -1000.0F; + while (x <= 1000.0F) { ASSERT_FLOAT_EQ(x, canardConvertFloat16ToNativeFloat(canardConvertNativeFloatToFloat16(x))); - x += 0.5; + x += 0.5F; } } diff --git a/tests/test_scalar_encoding.cpp b/tests/test_scalar_encoding.cpp index bae36d06..f9b38045 100644 --- a/tests/test_scalar_encoding.cpp +++ b/tests/test_scalar_encoding.cpp @@ -38,15 +38,15 @@ TEST(BigEndian, Check) template -static inline T read(CanardRxTransfer* transfer, uint16_t bit_offset, uint8_t bit_length) +static inline T read(CanardRxTransfer* transfer, uint32_t bit_offset, uint8_t bit_length) { auto value = T(); - const int res = canardDecodeScalar(transfer, bit_offset, bit_length, std::is_signed::value, &value); + const int res = canardDecodeScalar(transfer, uint16_t(bit_offset), bit_length, std::is_signed::value, &value); if (res != bit_length) { throw std::runtime_error("Unexpected return value; expected " + - std::to_string(bit_length) + ", got " + std::to_string(res)); + std::to_string(unsigned(bit_length)) + ", got " + std::to_string(res)); } return value; @@ -55,7 +55,7 @@ static inline T read(CanardRxTransfer* transfer, uint16_t bit_offset, uint8_t bi TEST(ScalarDecode, SingleFrame) { - auto transfer = CanardRxTransfer(); + CanardRxTransfer transfer{}; static const uint8_t buf[7] = { @@ -118,7 +118,7 @@ TEST(ScalarDecode, MultiFrame) /* * Configuring the transfer object */ - auto transfer = CanardRxTransfer(); + CanardRxTransfer transfer{}; uint8_t head[CANARD_MULTIFRAME_RX_PAYLOAD_HEAD_SIZE]; for (auto& x : head) @@ -148,7 +148,8 @@ TEST(ScalarDecode, MultiFrame) transfer.payload_middle = middle_a; transfer.payload_tail = &tail[0]; - transfer.payload_len = CANARD_MULTIFRAME_RX_PAYLOAD_HEAD_SIZE + CANARD_BUFFER_BLOCK_DATA_SIZE * 2 + sizeof(tail); + transfer.payload_len = + uint16_t(CANARD_MULTIFRAME_RX_PAYLOAD_HEAD_SIZE + CANARD_BUFFER_BLOCK_DATA_SIZE * 2 + sizeof(tail)); std::cout << "Payload size: " << transfer.payload_len << std::endl; @@ -172,17 +173,17 @@ TEST(ScalarDecode, MultiFrame) // Last 64 ASSERT_EQ(0b0100010000110011001000100001000111001100110011001100110011001100ULL, - read(&transfer, transfer.payload_len * 8 - 64, 64)); + read(&transfer, transfer.payload_len * 8U - 64U, 64)); /* * Testing without the middle */ - transfer.payload_middle = NULL; - transfer.payload_len -= CANARD_BUFFER_BLOCK_DATA_SIZE * 2; + transfer.payload_middle = nullptr; + transfer.payload_len = uint16_t(transfer.payload_len - CANARD_BUFFER_BLOCK_DATA_SIZE * 2U); // Last 64 ASSERT_EQ(0b0100010000110011001000100001000110100101101001011010010110100101ULL, - read(&transfer, transfer.payload_len * 8 - 64, 64)); + read(&transfer, transfer.payload_len * 8U - 64U, 64)); } @@ -198,21 +199,21 @@ TEST(ScalarEncode, Basic) u8 = 0b1111; canardEncodeScalar(buffer, 5, 4, &u8); - ASSERT_EQ(123 | 0b111, buffer[0]); + ASSERT_EQ(123U | 0b111U, buffer[0]); ASSERT_EQ(0b10000000, buffer[1]); int16_t s16 = -1; canardEncodeScalar(buffer, 9, 15, &s16); - ASSERT_EQ(123 | 0b111, buffer[0]); + ASSERT_EQ(123U | 0b111U, buffer[0]); ASSERT_EQ(0b11111111, buffer[1]); ASSERT_EQ(0b11111111, buffer[2]); ASSERT_EQ(0b00000000, buffer[3]); - int64_t s64 = (int64_t) 0b0000000100100011101111000110011110001001101010111100110111101111L; + auto s64 = int64_t(0b0000000100100011101111000110011110001001101010111100110111101111L); canardEncodeScalar(buffer, 16, 60, &s64); - ASSERT_EQ(123 | 0b111, buffer[0]); // 0 - ASSERT_EQ(0b11111111, buffer[1]); // 8 - ASSERT_EQ(0b11101111, buffer[2]); // 16 + ASSERT_EQ(123U | 0b111U, buffer[0]); // 0 + ASSERT_EQ(0b11111111, buffer[1]); // 8 + ASSERT_EQ(0b11101111, buffer[2]); // 16 ASSERT_EQ(0b11001101, buffer[3]); ASSERT_EQ(0b10101011, buffer[4]); ASSERT_EQ(0b10001001, buffer[5]); From a2111383f1b08d0eae55f0de4f4e2a0f87b801b0 Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Sun, 20 May 2018 21:55:50 +0300 Subject: [PATCH 13/81] GCC 4.9 compat --- canard.c | 2 +- tests/test_scalar_encoding.cpp | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/canard.c b/canard.c index 3b76b16c..5c83c8d3 100644 --- a/canard.c +++ b/canard.c @@ -471,7 +471,7 @@ void canardHandleRxFrame(CanardInstance* ins, const CanardCANFrame* frame, uint6 return; } - rx_state->next_toggle ^= 1; + rx_state->next_toggle = rx_state->next_toggle ? 0 : 1; } void canardCleanupStaleTransfers(CanardInstance* ins, uint64_t current_time_usec) diff --git a/tests/test_scalar_encoding.cpp b/tests/test_scalar_encoding.cpp index f9b38045..1f3b98e5 100644 --- a/tests/test_scalar_encoding.cpp +++ b/tests/test_scalar_encoding.cpp @@ -55,7 +55,7 @@ static inline T read(CanardRxTransfer* transfer, uint32_t bit_offset, uint8_t bi TEST(ScalarDecode, SingleFrame) { - CanardRxTransfer transfer{}; + auto transfer = CanardRxTransfer(); static const uint8_t buf[7] = { @@ -118,7 +118,7 @@ TEST(ScalarDecode, MultiFrame) /* * Configuring the transfer object */ - CanardRxTransfer transfer{}; + auto transfer = CanardRxTransfer(); uint8_t head[CANARD_MULTIFRAME_RX_PAYLOAD_HEAD_SIZE]; for (auto& x : head) From 5e8a42bed3b62163039105c3793a8fc23f0c0fab Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Sun, 20 May 2018 21:58:52 +0300 Subject: [PATCH 14/81] Clang compat --- tests/CMakeLists.txt | 2 ++ 1 file changed, 2 insertions(+) diff --git a/tests/CMakeLists.txt b/tests/CMakeLists.txt index 0a3ce454..8f26a2c5 100644 --- a/tests/CMakeLists.txt +++ b/tests/CMakeLists.txt @@ -28,6 +28,8 @@ set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wconversion -Wsign-promo") set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wsign-conversion -Wcast-align -Wmissing-declarations") set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wtype-limits -Wzero-as-null-pointer-constant -Wnon-virtual-dtor") set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Woverloaded-virtual -Wsign-promo -Wold-style-cast") +# We allow the following warnings for compatibility with the C codebase: +set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wno-error=old-style-cast -Wno-error=zero-as-null-pointer-constant") # Expose internal API for unit testing set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -DCANARD_INTERNAL=''") From cc46b0106c4bd94ad3915fcdd90477823f62415d Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Sun, 20 May 2018 22:01:37 +0300 Subject: [PATCH 15/81] nan() --> nanf() --- tests/test_float16.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tests/test_float16.cpp b/tests/test_float16.cpp index 740d0155..c1fabb97 100644 --- a/tests/test_float16.cpp +++ b/tests/test_float16.cpp @@ -35,7 +35,7 @@ TEST(Float16, FromNative) ASSERT_EQ(0b1100000000000000, canardConvertNativeFloatToFloat16(-2)); ASSERT_EQ(0b0111110000000000, canardConvertNativeFloatToFloat16(999999)); // +inf ASSERT_EQ(0b1111101111111111, canardConvertNativeFloatToFloat16(-65519)); // -max - ASSERT_EQ(0b0111111111111111, canardConvertNativeFloatToFloat16(std::nan(""))); // nan + ASSERT_EQ(0b0111111111111111, canardConvertNativeFloatToFloat16(std::nanf(""))); // nan } From 786a8d4cc0debbedaeb5789d8b587fce0f4c14e3 Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Sun, 20 May 2018 22:26:42 +0300 Subject: [PATCH 16/81] Migrated to Catch; bye bye GTest --- .travis.yml | 9 +- tests/CMakeLists.txt | 9 +- tests/catch/catch.hpp | 12012 +++++++++++++++++++++++++++++ tests/catch/test_main.cpp | 28 + tests/stm32/test_can_timings.cpp | 28 +- tests/test_crc.cpp | 8 +- tests/test_float16.cpp | 34 +- tests/test_init.cpp | 6 +- tests/test_memory_allocator.cpp | 74 +- tests/test_scalar_encoding.cpp | 103 +- 10 files changed, 12174 insertions(+), 137 deletions(-) create mode 100644 tests/catch/catch.hpp create mode 100644 tests/catch/test_main.cpp diff --git a/.travis.yml b/.travis.yml index 5aca0a96..c8ee8b72 100644 --- a/.travis.yml +++ b/.travis.yml @@ -17,18 +17,11 @@ addons: env: - CFLAGS="-Werror" CXXFLAGS="-Werror" -before_install: - - mkdir gtest-build - - pushd gtest-build - - CXXFLAGS='-m32' CFLAGS='-m32' cmake /usr/src/gtest - - make - - popd - script: # Building and running unit tests - mkdir build - cd build - - CMAKE_LIBRARY_PATH=../gtest-build/ cmake ../tests + - cmake ../tests - make - ./run_tests - cd .. diff --git a/tests/CMakeLists.txt b/tests/CMakeLists.txt index 8f26a2c5..79392722 100644 --- a/tests/CMakeLists.txt +++ b/tests/CMakeLists.txt @@ -2,12 +2,11 @@ # Copyright (c) 2016-2017 UAVCAN Team # -cmake_minimum_required(VERSION 2.8) +cmake_minimum_required(VERSION 3.1) project(libcanard) -# GTest -find_package(GTest REQUIRED) -include_directories(${GTEST_INCLUDE_DIRS}) +# Catch library for unit testing +include_directories(catch) # Libcanard include_directories(..) @@ -39,13 +38,13 @@ set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -DCANARD_INTERNAL=''") file(GLOB tests_src RELATIVE "${CMAKE_SOURCE_DIR}" "*.cpp" + "catch/*.cpp" "stm32/*.cpp") message(STATUS "Unit test source files: ${tests_src}") add_executable(run_tests ${tests_src} ../canard.c) target_link_libraries(run_tests - ${GTEST_BOTH_LIBRARIES} pthread) # Demo application diff --git a/tests/catch/catch.hpp b/tests/catch/catch.hpp new file mode 100644 index 00000000..362f8693 --- /dev/null +++ b/tests/catch/catch.hpp @@ -0,0 +1,12012 @@ +/* + * Catch v2.0.1 + * Generated: 2017-11-03 11:53:39.642003 + * ---------------------------------------------------------- + * This file has been merged from multiple headers. Please don't edit it directly + * Copyright (c) 2017 Two Blue Cubes Ltd. All rights reserved. + * + * Distributed under the Boost Software License, Version 1.0. (See accompanying + * file LICENSE_1_0.txt or copy at http://www.boost.org/LICENSE_1_0.txt) + */ +#ifndef TWOBLUECUBES_SINGLE_INCLUDE_CATCH_HPP_INCLUDED +#define TWOBLUECUBES_SINGLE_INCLUDE_CATCH_HPP_INCLUDED +// start catch.hpp + + +#ifdef __clang__ +# pragma clang system_header +#elif defined __GNUC__ +# pragma GCC system_header +#endif + +// start catch_suppress_warnings.h + +#ifdef __clang__ +# ifdef __ICC // icpc defines the __clang__ macro +# pragma warning(push) +# pragma warning(disable: 161 1682) +# else // __ICC +# pragma clang diagnostic ignored "-Wglobal-constructors" +# pragma clang diagnostic ignored "-Wvariadic-macros" +# pragma clang diagnostic ignored "-Wc99-extensions" +# pragma clang diagnostic ignored "-Wunused-variable" +# pragma clang diagnostic push +# pragma clang diagnostic ignored "-Wpadded" +# pragma clang diagnostic ignored "-Wswitch-enum" +# pragma clang diagnostic ignored "-Wcovered-switch-default" +# endif +#elif defined __GNUC__ +# pragma GCC diagnostic ignored "-Wvariadic-macros" +# pragma GCC diagnostic ignored "-Wunused-variable" +# pragma GCC diagnostic ignored "-Wparentheses" + +# pragma GCC diagnostic push +# pragma GCC diagnostic ignored "-Wpadded" +#endif +// end catch_suppress_warnings.h +#if defined(CATCH_CONFIG_MAIN) || defined(CATCH_CONFIG_RUNNER) +# define CATCH_IMPL +# define CATCH_CONFIG_EXTERNAL_INTERFACES +# if defined(CATCH_CONFIG_DISABLE_MATCHERS) +# undef CATCH_CONFIG_DISABLE_MATCHERS +# endif +#endif + +// start catch_platform.h + +#ifdef __APPLE__ +# include +# if TARGET_OS_MAC == 1 +# define CATCH_PLATFORM_MAC +# elif TARGET_OS_IPHONE == 1 +# define CATCH_PLATFORM_IPHONE +# endif + +#elif defined(linux) || defined(__linux) || defined(__linux__) +# define CATCH_PLATFORM_LINUX + +#elif defined(WIN32) || defined(__WIN32__) || defined(_WIN32) || defined(_MSC_VER) +# define CATCH_PLATFORM_WINDOWS +#endif + +// end catch_platform.h +#ifdef CATCH_IMPL +# ifndef CLARA_CONFIG_MAIN +# define CLARA_CONFIG_MAIN_NOT_DEFINED +# define CLARA_CONFIG_MAIN +# endif +#endif + +// start catch_tag_alias_autoregistrar.h + +// start catch_common.h + +// start catch_compiler_capabilities.h + +// Detect a number of compiler features - by compiler +// The following features are defined: +// +// CATCH_CONFIG_COUNTER : is the __COUNTER__ macro supported? +// CATCH_CONFIG_WINDOWS_SEH : is Windows SEH supported? +// CATCH_CONFIG_POSIX_SIGNALS : are POSIX signals supported? +// **************** +// Note to maintainers: if new toggles are added please document them +// in configuration.md, too +// **************** + +// In general each macro has a _NO_ form +// (e.g. CATCH_CONFIG_NO_POSIX_SIGNALS) which disables the feature. +// Many features, at point of detection, define an _INTERNAL_ macro, so they +// can be combined, en-mass, with the _NO_ forms later. + +#ifdef __cplusplus + +# if __cplusplus >= 201402L +# define CATCH_CPP14_OR_GREATER +# endif + +#endif + +#ifdef __clang__ + +# define CATCH_INTERNAL_SUPPRESS_GLOBALS_WARNINGS \ + _Pragma( "clang diagnostic push" ) \ + _Pragma( "clang diagnostic ignored \"-Wexit-time-destructors\"" ) \ + _Pragma( "clang diagnostic ignored \"-Wglobal-constructors\"") +# define CATCH_INTERNAL_UNSUPPRESS_GLOBALS_WARNINGS \ + _Pragma( "clang diagnostic pop" ) + +# define CATCH_INTERNAL_SUPPRESS_PARENTHESES_WARNINGS \ + _Pragma( "clang diagnostic push" ) \ + _Pragma( "clang diagnostic ignored \"-Wparentheses\"" ) +# define CATCH_INTERNAL_UNSUPPRESS_PARENTHESES_WARNINGS \ + _Pragma( "clang diagnostic pop" ) + +#endif // __clang__ + +//////////////////////////////////////////////////////////////////////////////// +// We know some environments not to support full POSIX signals +#if defined(__CYGWIN__) || defined(__QNX__) + +# if !defined(CATCH_CONFIG_POSIX_SIGNALS) +# define CATCH_INTERNAL_CONFIG_NO_POSIX_SIGNALS +# endif + +#endif + +#ifdef __OS400__ +# define CATCH_INTERNAL_CONFIG_NO_POSIX_SIGNALS +# define CATCH_CONFIG_COLOUR_NONE +#endif + +//////////////////////////////////////////////////////////////////////////////// +// Cygwin +#ifdef __CYGWIN__ + +// Required for some versions of Cygwin to declare gettimeofday +// see: http://stackoverflow.com/questions/36901803/gettimeofday-not-declared-in-this-scope-cygwin +# define _BSD_SOURCE + +#endif // __CYGWIN__ + +//////////////////////////////////////////////////////////////////////////////// +// Visual C++ +#ifdef _MSC_VER + +// Universal Windows platform does not support SEH +// Or console colours (or console at all...) +# if defined(WINAPI_FAMILY) && (WINAPI_FAMILY == WINAPI_FAMILY_APP) +# define CATCH_CONFIG_COLOUR_NONE +# else +# define CATCH_INTERNAL_CONFIG_WINDOWS_SEH +# endif + +#endif // _MSC_VER + +//////////////////////////////////////////////////////////////////////////////// + +// Use of __COUNTER__ is suppressed during code analysis in +// CLion/AppCode 2017.2.x and former, because __COUNTER__ is not properly +// handled by it. +// Otherwise all supported compilers support COUNTER macro, +// but user still might want to turn it off +#if ( !defined(__JETBRAINS_IDE__) || __JETBRAINS_IDE__ >= 20170300L ) + #define CATCH_INTERNAL_CONFIG_COUNTER +#endif + +#if defined(CATCH_INTERNAL_CONFIG_COUNTER) && !defined(CATCH_CONFIG_NO_COUNTER) && !defined(CATCH_CONFIG_COUNTER) +# define CATCH_CONFIG_COUNTER +#endif +#if defined(CATCH_INTERNAL_CONFIG_WINDOWS_SEH) && !defined(CATCH_CONFIG_NO_WINDOWS_SEH) && !defined(CATCH_CONFIG_WINDOWS_SEH) +# define CATCH_CONFIG_WINDOWS_SEH +#endif +// This is set by default, because we assume that unix compilers are posix-signal-compatible by default. +#if !defined(CATCH_INTERNAL_CONFIG_NO_POSIX_SIGNALS) && !defined(CATCH_CONFIG_NO_POSIX_SIGNALS) && !defined(CATCH_CONFIG_POSIX_SIGNALS) +# define CATCH_CONFIG_POSIX_SIGNALS +#endif + +#if !defined(CATCH_INTERNAL_SUPPRESS_PARENTHESES_WARNINGS) +# define CATCH_INTERNAL_SUPPRESS_PARENTHESES_WARNINGS +# define CATCH_INTERNAL_UNSUPPRESS_PARENTHESES_WARNINGS +#endif +#if !defined(CATCH_INTERNAL_SUPPRESS_GLOBALS_WARNINGS) +# define CATCH_INTERNAL_SUPPRESS_GLOBALS_WARNINGS +# define CATCH_INTERNAL_UNSUPPRESS_GLOBALS_WARNINGS +#endif + +// end catch_compiler_capabilities.h +#define INTERNAL_CATCH_UNIQUE_NAME_LINE2( name, line ) name##line +#define INTERNAL_CATCH_UNIQUE_NAME_LINE( name, line ) INTERNAL_CATCH_UNIQUE_NAME_LINE2( name, line ) +#ifdef CATCH_CONFIG_COUNTER +# define INTERNAL_CATCH_UNIQUE_NAME( name ) INTERNAL_CATCH_UNIQUE_NAME_LINE( name, __COUNTER__ ) +#else +# define INTERNAL_CATCH_UNIQUE_NAME( name ) INTERNAL_CATCH_UNIQUE_NAME_LINE( name, __LINE__ ) +#endif + +#include +#include +#include + +namespace Catch { + + struct CaseSensitive { enum Choice { + Yes, + No + }; }; + + class NonCopyable { + NonCopyable( NonCopyable const& ) = delete; + NonCopyable( NonCopyable && ) = delete; + NonCopyable& operator = ( NonCopyable const& ) = delete; + NonCopyable& operator = ( NonCopyable && ) = delete; + + protected: + NonCopyable(); + virtual ~NonCopyable(); + }; + + struct SourceLineInfo { + + SourceLineInfo() = delete; + SourceLineInfo( char const* _file, std::size_t _line ) noexcept; + + SourceLineInfo( SourceLineInfo const& other ) = default; + SourceLineInfo( SourceLineInfo && ) = default; + SourceLineInfo& operator = ( SourceLineInfo const& ) = default; + SourceLineInfo& operator = ( SourceLineInfo && ) = default; + + bool empty() const noexcept; + bool operator == ( SourceLineInfo const& other ) const noexcept; + bool operator < ( SourceLineInfo const& other ) const noexcept; + + char const* file; + std::size_t line; + }; + + std::ostream& operator << ( std::ostream& os, SourceLineInfo const& info ); + + // This is just here to avoid compiler warnings with macro constants and boolean literals + bool isTrue( bool value ); + bool alwaysTrue(); + bool alwaysFalse(); + + // Use this in variadic streaming macros to allow + // >> +StreamEndStop + // as well as + // >> stuff +StreamEndStop + struct StreamEndStop { + std::string operator+() const; + }; + template + T const& operator + ( T const& value, StreamEndStop ) { + return value; + } +} + +#define CATCH_INTERNAL_LINEINFO \ + ::Catch::SourceLineInfo( __FILE__, static_cast( __LINE__ ) ) + +// end catch_common.h +namespace Catch { + + struct RegistrarForTagAliases { + RegistrarForTagAliases( char const* alias, char const* tag, SourceLineInfo const& lineInfo ); + }; + +} // end namespace Catch + +#define CATCH_REGISTER_TAG_ALIAS( alias, spec ) namespace{ Catch::RegistrarForTagAliases INTERNAL_CATCH_UNIQUE_NAME( AutoRegisterTagAlias )( alias, spec, CATCH_INTERNAL_LINEINFO ); } + +// end catch_tag_alias_autoregistrar.h +// start catch_test_registry.h + +// start catch_interfaces_testcase.h + +#include +#include + +namespace Catch { + + class TestSpec; + + struct ITestInvoker { + virtual void invoke () const = 0; + virtual ~ITestInvoker(); + }; + + using ITestCasePtr = std::shared_ptr; + + class TestCase; + struct IConfig; + + struct ITestCaseRegistry { + virtual ~ITestCaseRegistry(); + virtual std::vector const& getAllTests() const = 0; + virtual std::vector const& getAllTestsSorted( IConfig const& config ) const = 0; + }; + + bool matchTest( TestCase const& testCase, TestSpec const& testSpec, IConfig const& config ); + std::vector filterTests( std::vector const& testCases, TestSpec const& testSpec, IConfig const& config ); + std::vector const& getAllTestCasesSorted( IConfig const& config ); + +} + +// end catch_interfaces_testcase.h +// start catch_stringref.h + +#include +#include +#include + +namespace Catch { + + class StringData; + + /// A non-owning string class (similar to the forthcoming std::string_view) + /// Note that, because a StringRef may be a substring of another string, + /// it may not be null terminated. c_str() must return a null terminated + /// string, however, and so the StringRef will internally take ownership + /// (taking a copy), if necessary. In theory this ownership is not externally + /// visible - but it does mean (substring) StringRefs should not be shared between + /// threads. + class StringRef { + friend struct StringRefTestAccess; + + using size_type = std::size_t; + + char const* m_start; + size_type m_size; + + char* m_data = nullptr; + + void takeOwnership(); + + public: // construction/ assignment + StringRef() noexcept; + StringRef( StringRef const& other ) noexcept; + StringRef( StringRef&& other ) noexcept; + StringRef( char const* rawChars ) noexcept; + StringRef( char const* rawChars, size_type size ) noexcept; + StringRef( std::string const& stdString ) noexcept; + ~StringRef() noexcept; + + auto operator = ( StringRef other ) noexcept -> StringRef&; + operator std::string() const; + + void swap( StringRef& other ) noexcept; + + public: // operators + auto operator == ( StringRef const& other ) const noexcept -> bool; + auto operator != ( StringRef const& other ) const noexcept -> bool; + + auto operator[] ( size_type index ) const noexcept -> char; + + public: // named queries + auto empty() const noexcept -> bool; + auto size() const noexcept -> size_type; + auto numberOfCharacters() const noexcept -> size_type; + auto c_str() const -> char const*; + + public: // substrings and searches + auto substr( size_type start, size_type size ) const noexcept -> StringRef; + + private: // ownership queries - may not be consistent between calls + auto isOwned() const noexcept -> bool; + auto isSubstring() const noexcept -> bool; + auto data() const noexcept -> char const*; + }; + + auto operator + ( StringRef const& lhs, StringRef const& rhs ) -> std::string; + auto operator + ( StringRef const& lhs, char const* rhs ) -> std::string; + auto operator + ( char const* lhs, StringRef const& rhs ) -> std::string; + + auto operator << ( std::ostream& os, StringRef const& sr ) -> std::ostream&; + +} // namespace Catch + +// end catch_stringref.h +namespace Catch { + +template +class TestInvokerAsMethod : public ITestInvoker { + void (C::*m_testAsMethod)(); +public: + TestInvokerAsMethod( void (C::*testAsMethod)() ) noexcept : m_testAsMethod( testAsMethod ) {} + + void invoke() const override { + C obj; + (obj.*m_testAsMethod)(); + } +}; + +auto makeTestInvoker( void(*testAsFunction)() ) noexcept -> ITestInvoker*; + +template +auto makeTestInvoker( void (C::*testAsMethod)() ) noexcept -> ITestInvoker* { + return new(std::nothrow) TestInvokerAsMethod( testAsMethod ); +} + +struct NameAndTags { + NameAndTags( StringRef name_ = "", StringRef tags_ = "" ) noexcept; + StringRef name; + StringRef tags; +}; + +struct AutoReg : NonCopyable { + AutoReg( ITestInvoker* invoker, SourceLineInfo const& lineInfo, StringRef classOrMethod, NameAndTags const& nameAndTags ) noexcept; + ~AutoReg(); +}; + +} // end namespace Catch + +#if defined(CATCH_CONFIG_DISABLE) + #define INTERNAL_CATCH_TESTCASE_NO_REGISTRATION( TestName, ... ) \ + static void TestName() + #define INTERNAL_CATCH_TESTCASE_METHOD_NO_REGISTRATION( TestName, ClassName, ... ) \ + namespace{ \ + struct TestName : ClassName { \ + void test(); \ + }; \ + } \ + void TestName::test() + +#endif + + /////////////////////////////////////////////////////////////////////////////// + #define INTERNAL_CATCH_TESTCASE2( TestName, ... ) \ + static void TestName(); \ + CATCH_INTERNAL_SUPPRESS_GLOBALS_WARNINGS \ + namespace{ Catch::AutoReg INTERNAL_CATCH_UNIQUE_NAME( autoRegistrar )( Catch::makeTestInvoker( &TestName ), CATCH_INTERNAL_LINEINFO, "", Catch::NameAndTags{ __VA_ARGS__ } ); } /* NOLINT */ \ + CATCH_INTERNAL_UNSUPPRESS_GLOBALS_WARNINGS \ + static void TestName() + #define INTERNAL_CATCH_TESTCASE( ... ) \ + INTERNAL_CATCH_TESTCASE2( INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_S_T____ ), __VA_ARGS__ ) + + /////////////////////////////////////////////////////////////////////////////// + #define INTERNAL_CATCH_METHOD_AS_TEST_CASE( QualifiedMethod, ... ) \ + CATCH_INTERNAL_SUPPRESS_GLOBALS_WARNINGS \ + namespace{ Catch::AutoReg INTERNAL_CATCH_UNIQUE_NAME( autoRegistrar )( Catch::makeTestInvoker( &QualifiedMethod ), CATCH_INTERNAL_LINEINFO, "&" #QualifiedMethod, Catch::NameAndTags{ __VA_ARGS__ } ); } /* NOLINT */ \ + CATCH_INTERNAL_UNSUPPRESS_GLOBALS_WARNINGS + + /////////////////////////////////////////////////////////////////////////////// + #define INTERNAL_CATCH_TEST_CASE_METHOD2( TestName, ClassName, ... )\ + CATCH_INTERNAL_SUPPRESS_GLOBALS_WARNINGS \ + namespace{ \ + struct TestName : ClassName{ \ + void test(); \ + }; \ + Catch::AutoReg INTERNAL_CATCH_UNIQUE_NAME( autoRegistrar ) ( Catch::makeTestInvoker( &TestName::test ), CATCH_INTERNAL_LINEINFO, #ClassName, Catch::NameAndTags{ __VA_ARGS__ } ); /* NOLINT */ \ + } \ + CATCH_INTERNAL_UNSUPPRESS_GLOBALS_WARNINGS \ + void TestName::test() + #define INTERNAL_CATCH_TEST_CASE_METHOD( ClassName, ... ) \ + INTERNAL_CATCH_TEST_CASE_METHOD2( INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_S_T____ ), ClassName, __VA_ARGS__ ) + + /////////////////////////////////////////////////////////////////////////////// + #define INTERNAL_CATCH_REGISTER_TESTCASE( Function, ... ) \ + CATCH_INTERNAL_SUPPRESS_GLOBALS_WARNINGS \ + Catch::AutoReg INTERNAL_CATCH_UNIQUE_NAME( autoRegistrar )( Catch::makeTestInvoker( Function ), CATCH_INTERNAL_LINEINFO, "", Catch::NameAndTags{ __VA_ARGS__ } ); /* NOLINT */ \ + CATCH_INTERNAL_UNSUPPRESS_GLOBALS_WARNINGS + +// end catch_test_registry.h +// start catch_capture.hpp + +// start catch_assertionhandler.h + +// start catch_decomposer.h + +// start catch_tostring.h + +#include +#include +#include +#include +#include + +#ifdef __OBJC__ +// start catch_objc_arc.hpp + +#import + +#ifdef __has_feature +#define CATCH_ARC_ENABLED __has_feature(objc_arc) +#else +#define CATCH_ARC_ENABLED 0 +#endif + +void arcSafeRelease( NSObject* obj ); +id performOptionalSelector( id obj, SEL sel ); + +#if !CATCH_ARC_ENABLED +inline void arcSafeRelease( NSObject* obj ) { + [obj release]; +} +inline id performOptionalSelector( id obj, SEL sel ) { + if( [obj respondsToSelector: sel] ) + return [obj performSelector: sel]; + return nil; +} +#define CATCH_UNSAFE_UNRETAINED +#define CATCH_ARC_STRONG +#else +inline void arcSafeRelease( NSObject* ){} +inline id performOptionalSelector( id obj, SEL sel ) { +#ifdef __clang__ +#pragma clang diagnostic push +#pragma clang diagnostic ignored "-Warc-performSelector-leaks" +#endif + if( [obj respondsToSelector: sel] ) + return [obj performSelector: sel]; +#ifdef __clang__ +#pragma clang diagnostic pop +#endif + return nil; +} +#define CATCH_UNSAFE_UNRETAINED __unsafe_unretained +#define CATCH_ARC_STRONG __strong +#endif + +// end catch_objc_arc.hpp +#endif + +#ifdef _MSC_VER +#pragma warning(push) +#pragma warning(disable:4180) // We attempt to stream a function (address) by const&, which MSVC complains about but is harmless +#endif + +// We need a dummy global operator<< so we can bring it into Catch namespace later +struct Catch_global_namespace_dummy; +std::ostream& operator<<(std::ostream&, Catch_global_namespace_dummy); + +namespace Catch { + // Bring in operator<< from global namespace into Catch namespace + using ::operator<<; + + namespace Detail { + + extern const std::string unprintableString; + + std::string rawMemoryToString( const void *object, std::size_t size ); + + template + std::string rawMemoryToString( const T& object ) { + return rawMemoryToString( &object, sizeof(object) ); + } + + template + class IsStreamInsertable { + template + static auto test(int) + -> decltype(std::declval() << std::declval(), std::true_type()); + + template + static auto test(...)->std::false_type; + + public: + static const bool value = decltype(test(0))::value; + }; + + } // namespace Detail + + // If we decide for C++14, change these to enable_if_ts + template + struct StringMaker { + template + static + typename std::enable_if<::Catch::Detail::IsStreamInsertable::value, std::string>::type + convert(const Fake& t) { + std::ostringstream sstr; + sstr << t; + return sstr.str(); + } + + template + static + typename std::enable_if::value, std::string>::type + convert(const Fake&) { + return Detail::unprintableString; + } + }; + + namespace Detail { + + // This function dispatches all stringification requests inside of Catch. + // Should be preferably called fully qualified, like ::Catch::Detail::stringify + template + std::string stringify(const T& e) { + return ::Catch::StringMaker::type>::type>::convert(e); + } + + } // namespace Detail + + // Some predefined specializations + + template<> + struct StringMaker { + static std::string convert(const std::string& str); + }; + template<> + struct StringMaker { + static std::string convert(const std::wstring& wstr); + }; + + template<> + struct StringMaker { + static std::string convert(char const * str); + }; + template<> + struct StringMaker { + static std::string convert(char * str); + }; + template<> + struct StringMaker { + static std::string convert(wchar_t const * str); + }; + template<> + struct StringMaker { + static std::string convert(wchar_t * str); + }; + + template + struct StringMaker { + static std::string convert(const char* str) { + return ::Catch::Detail::stringify(std::string{ str }); + } + }; + template + struct StringMaker { + static std::string convert(const char* str) { + return ::Catch::Detail::stringify(std::string{ str }); + } + }; + template + struct StringMaker { + static std::string convert(const char* str) { + return ::Catch::Detail::stringify(std::string{ str }); + } + }; + + template<> + struct StringMaker { + static std::string convert(int value); + }; + template<> + struct StringMaker { + static std::string convert(long value); + }; + template<> + struct StringMaker { + static std::string convert(long long value); + }; + template<> + struct StringMaker { + static std::string convert(unsigned int value); + }; + template<> + struct StringMaker { + static std::string convert(unsigned long value); + }; + template<> + struct StringMaker { + static std::string convert(unsigned long long value); + }; + + template<> + struct StringMaker { + static std::string convert(bool b); + }; + + template<> + struct StringMaker { + static std::string convert(char c); + }; + template<> + struct StringMaker { + static std::string convert(signed char c); + }; + template<> + struct StringMaker { + static std::string convert(unsigned char c); + }; + + template<> + struct StringMaker { + static std::string convert(std::nullptr_t); + }; + + template<> + struct StringMaker { + static std::string convert(float value); + }; + template<> + struct StringMaker { + static std::string convert(double value); + }; + + template + struct StringMaker { + template + static std::string convert(U* p) { + if (p) { + return ::Catch::Detail::rawMemoryToString(p); + } else { + return "nullptr"; + } + } + }; + + template + struct StringMaker { + static std::string convert(R C::* p) { + if (p) { + return ::Catch::Detail::rawMemoryToString(p); + } else { + return "nullptr"; + } + } + }; + + namespace Detail { + template + std::string rangeToString(InputIterator first, InputIterator last) { + std::ostringstream oss; + oss << "{ "; + if (first != last) { + oss << ::Catch::Detail::stringify(*first); + for (++first; first != last; ++first) + oss << ", " << ::Catch::Detail::stringify(*first); + } + oss << " }"; + return oss.str(); + } + } + + template + struct StringMaker > { + static std::string convert( std::vector const& v ) { + return ::Catch::Detail::rangeToString( v.begin(), v.end() ); + } + }; + + template + struct EnumStringMaker { + static std::string convert(const T& t) { + return ::Catch::Detail::stringify(static_cast::type>(t)); + } + }; + +#ifdef __OBJC__ + template<> + struct StringMaker { + static std::string convert(NSString * nsstring) { + if (!nsstring) + return "nil"; + return std::string("@") + [nsstring UTF8String]; + } + }; + template<> + struct StringMaker { + static std::string convert(NSObject* nsObject) { + return ::Catch::Detail::stringify([nsObject description]); + } + + }; + namespace Detail { + inline std::string stringify( NSString* nsstring ) { + return StringMaker::convert( nsstring ); + } + + } // namespace Detail +#endif // __OBJC__ + +} // namespace Catch + +////////////////////////////////////////////////////// +// Separate std-lib types stringification, so it can be selectively enabled +// This means that we do not bring in + +#if defined(CATCH_CONFIG_ENABLE_ALL_STRINGMAKERS) +# define CATCH_CONFIG_ENABLE_PAIR_STRINGMAKER +# define CATCH_CONFIG_ENABLE_TUPLE_STRINGMAKER +# define CATCH_CONFIG_ENABLE_CHRONO_STRINGMAKER +#endif + +// Separate std::pair specialization +#if defined(CATCH_CONFIG_ENABLE_PAIR_STRINGMAKER) +#include +namespace Catch { + template + struct StringMaker > { + static std::string convert(const std::pair& pair) { + std::ostringstream oss; + oss << "{ " + << ::Catch::Detail::stringify(pair.first) + << ", " + << ::Catch::Detail::stringify(pair.second) + << " }"; + return oss.str(); + } + }; +} +#endif // CATCH_CONFIG_ENABLE_PAIR_STRINGMAKER + +// Separate std::tuple specialization +#if defined(CATCH_CONFIG_ENABLE_TUPLE_STRINGMAKER) +#include +namespace Catch { + namespace Detail { + template< + typename Tuple, + std::size_t N = 0, + bool = (N < std::tuple_size::value) + > + struct TupleElementPrinter { + static void print(const Tuple& tuple, std::ostream& os) { + os << (N ? ", " : " ") + << ::Catch::Detail::stringify(std::get(tuple)); + TupleElementPrinter::print(tuple, os); + } + }; + + template< + typename Tuple, + std::size_t N + > + struct TupleElementPrinter { + static void print(const Tuple&, std::ostream&) {} + }; + + } + + template + struct StringMaker> { + static std::string convert(const std::tuple& tuple) { + std::ostringstream os; + os << '{'; + Detail::TupleElementPrinter>::print(tuple, os); + os << " }"; + return os.str(); + } + }; +} +#endif // CATCH_CONFIG_ENABLE_TUPLE_STRINGMAKER + +// Separate std::chrono::duration specialization +#if defined(CATCH_CONFIG_ENABLE_CHRONO_STRINGMAKER) +#include +#include +#include + +template +struct ratio_string { + static std::string symbol(); +}; + +template +std::string ratio_string::symbol() { + std::ostringstream oss; + oss << '[' << Ratio::num << '/' + << Ratio::den << ']'; + return oss.str(); +} +template <> +struct ratio_string { + static std::string symbol() { return "a"; } +}; +template <> +struct ratio_string { + static std::string symbol() { return "f"; } +}; +template <> +struct ratio_string { + static std::string symbol() { return "p"; } +}; +template <> +struct ratio_string { + static std::string symbol() { return "n"; } +}; +template <> +struct ratio_string { + static std::string symbol() { return "u"; } +}; +template <> +struct ratio_string { + static std::string symbol() { return "m"; } +}; + +namespace Catch { + //////////// + // std::chrono::duration specializations + template + struct StringMaker> { + static std::string convert(std::chrono::duration const& duration) { + std::ostringstream oss; + oss << duration.count() << ' ' << ratio_string::symbol() << 's'; + return oss.str(); + } + }; + template + struct StringMaker>> { + static std::string convert(std::chrono::duration> const& duration) { + std::ostringstream oss; + oss << duration.count() << " s"; + return oss.str(); + } + }; + template + struct StringMaker>> { + static std::string convert(std::chrono::duration> const& duration) { + std::ostringstream oss; + oss << duration.count() << " m"; + return oss.str(); + } + }; + template + struct StringMaker>> { + static std::string convert(std::chrono::duration> const& duration) { + std::ostringstream oss; + oss << duration.count() << " h"; + return oss.str(); + } + }; + + //////////// + // std::chrono::time_point specialization + // Generic time_point cannot be specialized, only std::chrono::time_point + template + struct StringMaker> { + static std::string convert(std::chrono::time_point const& time_point) { + return ::Catch::Detail::stringify(time_point.time_since_epoch()) + " since epoch"; + } + }; + // std::chrono::time_point specialization + template + struct StringMaker> { + static std::string convert(std::chrono::time_point const& time_point) { + auto converted = std::chrono::system_clock::to_time_t(time_point); + +#ifdef _MSC_VER + std::tm timeInfo = {}; + gmtime_s(&timeInfo, &converted); +#else + std::tm* timeInfo = std::gmtime(&converted); +#endif + + auto const timeStampSize = sizeof("2017-01-16T17:06:45Z"); + char timeStamp[timeStampSize]; + const char * const fmt = "%Y-%m-%dT%H:%M:%SZ"; + +#ifdef _MSC_VER + std::strftime(timeStamp, timeStampSize, fmt, &timeInfo); +#else + std::strftime(timeStamp, timeStampSize, fmt, timeInfo); +#endif + return std::string(timeStamp); + } + }; +} +#endif // CATCH_CONFIG_ENABLE_CHRONO_STRINGMAKER + +#ifdef _MSC_VER +#pragma warning(pop) +#endif + +// end catch_tostring.h +#include + +#ifdef _MSC_VER +#pragma warning(push) +#pragma warning(disable:4389) // '==' : signed/unsigned mismatch +#pragma warning(disable:4018) // more "signed/unsigned mismatch" +#pragma warning(disable:4312) // Converting int to T* using reinterpret_cast (issue on x64 platform) +#pragma warning(disable:4180) // qualifier applied to function type has no meaning +#endif + +namespace Catch { + + struct ITransientExpression { + virtual auto isBinaryExpression() const -> bool = 0; + virtual auto getResult() const -> bool = 0; + virtual void streamReconstructedExpression( std::ostream &os ) const = 0; + + // We don't actually need a virtual destructore, but many static analysers + // complain if it's not here :-( + virtual ~ITransientExpression(); + }; + + void formatReconstructedExpression( std::ostream &os, std::string const& lhs, StringRef op, std::string const& rhs ); + + template + class BinaryExpr : public ITransientExpression { + bool m_result; + LhsT m_lhs; + StringRef m_op; + RhsT m_rhs; + + auto isBinaryExpression() const -> bool override { return true; } + auto getResult() const -> bool override { return m_result; } + + void streamReconstructedExpression( std::ostream &os ) const override { + formatReconstructedExpression + ( os, Catch::Detail::stringify( m_lhs ), m_op, Catch::Detail::stringify( m_rhs ) ); + } + + public: + BinaryExpr( bool comparisonResult, LhsT lhs, StringRef op, RhsT rhs ) + : m_result( comparisonResult ), + m_lhs( lhs ), + m_op( op ), + m_rhs( rhs ) + {} + }; + + template + class UnaryExpr : public ITransientExpression { + LhsT m_lhs; + + auto isBinaryExpression() const -> bool override { return false; } + auto getResult() const -> bool override { return m_lhs ? true : false; } + + void streamReconstructedExpression( std::ostream &os ) const override { + os << Catch::Detail::stringify( m_lhs ); + } + + public: + UnaryExpr( LhsT lhs ) : m_lhs( lhs ) {} + }; + + // Specialised comparison functions to handle equality comparisons between ints and pointers (NULL deduces as an int) + template + auto compareEqual( LhsT const& lhs, RhsT const& rhs ) -> bool { return lhs == rhs; }; + template + auto compareEqual( T* const& lhs, int rhs ) -> bool { return lhs == reinterpret_cast( rhs ); } + template + auto compareEqual( T* const& lhs, long rhs ) -> bool { return lhs == reinterpret_cast( rhs ); } + template + auto compareEqual( int lhs, T* const& rhs ) -> bool { return reinterpret_cast( lhs ) == rhs; } + template + auto compareEqual( long lhs, T* const& rhs ) -> bool { return reinterpret_cast( lhs ) == rhs; } + + template + auto compareNotEqual( LhsT const& lhs, RhsT&& rhs ) -> bool { return lhs != rhs; }; + template + auto compareNotEqual( T* const& lhs, int rhs ) -> bool { return lhs != reinterpret_cast( rhs ); } + template + auto compareNotEqual( T* const& lhs, long rhs ) -> bool { return lhs != reinterpret_cast( rhs ); } + template + auto compareNotEqual( int lhs, T* const& rhs ) -> bool { return reinterpret_cast( lhs ) != rhs; } + template + auto compareNotEqual( long lhs, T* const& rhs ) -> bool { return reinterpret_cast( lhs ) != rhs; } + + template + class ExprLhs { + LhsT m_lhs; + public: + ExprLhs( LhsT lhs ) : m_lhs( lhs ) {} + + template + auto operator == ( RhsT const& rhs ) -> BinaryExpr const { + return BinaryExpr( compareEqual( m_lhs, rhs ), m_lhs, "==", rhs ); + } + auto operator == ( bool rhs ) -> BinaryExpr const { + return BinaryExpr( m_lhs == rhs, m_lhs, "==", rhs ); + } + + template + auto operator != ( RhsT const& rhs ) -> BinaryExpr const { + return BinaryExpr( compareNotEqual( m_lhs, rhs ), m_lhs, "!=", rhs ); + } + auto operator != ( bool rhs ) -> BinaryExpr const { + return BinaryExpr( m_lhs != rhs, m_lhs, "!=", rhs ); + } + + template + auto operator > ( RhsT const& rhs ) -> BinaryExpr const { + return BinaryExpr( m_lhs > rhs, m_lhs, ">", rhs ); + } + template + auto operator < ( RhsT const& rhs ) -> BinaryExpr const { + return BinaryExpr( m_lhs < rhs, m_lhs, "<", rhs ); + } + template + auto operator >= ( RhsT const& rhs ) -> BinaryExpr const { + return BinaryExpr( m_lhs >= rhs, m_lhs, ">=", rhs ); + } + template + auto operator <= ( RhsT const& rhs ) -> BinaryExpr const { + return BinaryExpr( m_lhs <= rhs, m_lhs, "<=", rhs ); + } + + auto makeUnaryExpr() const -> UnaryExpr { + return UnaryExpr( m_lhs ); + } + }; + + void handleExpression( ITransientExpression const& expr ); + + template + void handleExpression( ExprLhs const& expr ) { + handleExpression( expr.makeUnaryExpr() ); + } + + struct Decomposer { + template + auto operator <= ( T const& lhs ) -> ExprLhs { + return ExprLhs( lhs ); + } + auto operator <=( bool value ) -> ExprLhs { + return ExprLhs( value ); + } + }; + +} // end namespace Catch + +#ifdef _MSC_VER +#pragma warning(pop) +#endif + +// end catch_decomposer.h +// start catch_assertioninfo.h + +// start catch_result_type.h + +namespace Catch { + + // ResultWas::OfType enum + struct ResultWas { enum OfType { + Unknown = -1, + Ok = 0, + Info = 1, + Warning = 2, + + FailureBit = 0x10, + + ExpressionFailed = FailureBit | 1, + ExplicitFailure = FailureBit | 2, + + Exception = 0x100 | FailureBit, + + ThrewException = Exception | 1, + DidntThrowException = Exception | 2, + + FatalErrorCondition = 0x200 | FailureBit + + }; }; + + bool isOk( ResultWas::OfType resultType ); + bool isJustInfo( int flags ); + + // ResultDisposition::Flags enum + struct ResultDisposition { enum Flags { + Normal = 0x01, + + ContinueOnFailure = 0x02, // Failures fail test, but execution continues + FalseTest = 0x04, // Prefix expression with ! + SuppressFail = 0x08 // Failures are reported but do not fail the test + }; }; + + ResultDisposition::Flags operator | ( ResultDisposition::Flags lhs, ResultDisposition::Flags rhs ); + + bool shouldContinueOnFailure( int flags ); + bool isFalseTest( int flags ); + bool shouldSuppressFailure( int flags ); + +} // end namespace Catch + +// end catch_result_type.h +namespace Catch { + + struct AssertionInfo + { + StringRef macroName; + SourceLineInfo lineInfo; + StringRef capturedExpression; + ResultDisposition::Flags resultDisposition; + + // We want to delete this constructor but a compiler bug in 4.8 means + // the struct is then treated as non-aggregate + //AssertionInfo() = delete; + }; + +} // end namespace Catch + +// end catch_assertioninfo.h +namespace Catch { + + struct TestFailureException{}; + struct AssertionResultData; + + class LazyExpression { + friend class AssertionHandler; + friend struct AssertionStats; + + ITransientExpression const* m_transientExpression = nullptr; + bool m_isNegated; + public: + LazyExpression( bool isNegated ); + LazyExpression( LazyExpression const& other ); + LazyExpression& operator = ( LazyExpression const& ) = delete; + + explicit operator bool() const; + + friend auto operator << ( std::ostream& os, LazyExpression const& lazyExpr ) -> std::ostream&; + }; + + class AssertionHandler { + AssertionInfo m_assertionInfo; + bool m_shouldDebugBreak = false; + bool m_shouldThrow = false; + bool m_inExceptionGuard = false; + + public: + AssertionHandler + ( StringRef macroName, + SourceLineInfo const& lineInfo, + StringRef capturedExpression, + ResultDisposition::Flags resultDisposition ); + ~AssertionHandler(); + + void handle( ITransientExpression const& expr ); + + template + void handle( ExprLhs const& expr ) { + handle( expr.makeUnaryExpr() ); + } + void handle( ResultWas::OfType resultType ); + void handle( ResultWas::OfType resultType, StringRef const& message ); + void handle( ResultWas::OfType resultType, ITransientExpression const* expr, bool negated ); + void handle( AssertionResultData const& resultData, ITransientExpression const* expr ); + + auto shouldDebugBreak() const -> bool; + auto allowThrows() const -> bool; + void reactWithDebugBreak() const; + void reactWithoutDebugBreak() const; + void useActiveException(); + void setExceptionGuard(); + void unsetExceptionGuard(); + }; + + void handleExceptionMatchExpr( AssertionHandler& handler, std::string const& str, StringRef matcherString ); + +} // namespace Catch + +// end catch_assertionhandler.h +// start catch_message.h + +#include +#include + +namespace Catch { + + struct MessageInfo { + MessageInfo( std::string const& _macroName, + SourceLineInfo const& _lineInfo, + ResultWas::OfType _type ); + + std::string macroName; + std::string message; + SourceLineInfo lineInfo; + ResultWas::OfType type; + unsigned int sequence; + + bool operator == ( MessageInfo const& other ) const; + bool operator < ( MessageInfo const& other ) const; + private: + static unsigned int globalCount; + }; + + struct MessageStream { + + template + MessageStream& operator << ( T const& value ) { + m_stream << value; + return *this; + } + + // !TBD reuse a global/ thread-local stream + std::ostringstream m_stream; + }; + + struct MessageBuilder : MessageStream { + MessageBuilder( std::string const& macroName, + SourceLineInfo const& lineInfo, + ResultWas::OfType type ); + + template + MessageBuilder& operator << ( T const& value ) { + m_stream << value; + return *this; + } + + MessageInfo m_info; + }; + + class ScopedMessage { + public: + ScopedMessage( MessageBuilder const& builder ); + ~ScopedMessage(); + + MessageInfo m_info; + }; + +} // end namespace Catch + +// end catch_message.h +// start catch_interfaces_capture.h + +#include + +namespace Catch { + + class AssertionResult; + struct AssertionInfo; + struct SectionInfo; + struct SectionEndInfo; + struct MessageInfo; + struct Counts; + struct BenchmarkInfo; + struct BenchmarkStats; + + struct IResultCapture { + + virtual ~IResultCapture(); + + virtual void assertionStarting( AssertionInfo const& info ) = 0; + virtual void assertionEnded( AssertionResult const& result ) = 0; + virtual bool sectionStarted( SectionInfo const& sectionInfo, + Counts& assertions ) = 0; + virtual void sectionEnded( SectionEndInfo const& endInfo ) = 0; + virtual void sectionEndedEarly( SectionEndInfo const& endInfo ) = 0; + + virtual void benchmarkStarting( BenchmarkInfo const& info ) = 0; + virtual void benchmarkEnded( BenchmarkStats const& stats ) = 0; + + virtual void pushScopedMessage( MessageInfo const& message ) = 0; + virtual void popScopedMessage( MessageInfo const& message ) = 0; + + virtual std::string getCurrentTestName() const = 0; + virtual const AssertionResult* getLastResult() const = 0; + + virtual void exceptionEarlyReported() = 0; + + virtual void handleFatalErrorCondition( StringRef message ) = 0; + + virtual bool lastAssertionPassed() = 0; + virtual void assertionPassed() = 0; + virtual void assertionRun() = 0; + }; + + IResultCapture& getResultCapture(); +} + +// end catch_interfaces_capture.h +// start catch_debugger.h + +namespace Catch { + bool isDebuggerActive(); +} + +#ifdef CATCH_PLATFORM_MAC + + #define CATCH_TRAP() __asm__("int $3\n" : : ) /* NOLINT */ + +#elif defined(CATCH_PLATFORM_LINUX) + // If we can use inline assembler, do it because this allows us to break + // directly at the location of the failing check instead of breaking inside + // raise() called from it, i.e. one stack frame below. + #if defined(__GNUC__) && (defined(__i386) || defined(__x86_64)) + #define CATCH_TRAP() asm volatile ("int $3") /* NOLINT */ + #else // Fall back to the generic way. + #include + + #define CATCH_TRAP() raise(SIGTRAP) + #endif +#elif defined(_MSC_VER) + #define CATCH_TRAP() __debugbreak() +#elif defined(__MINGW32__) + extern "C" __declspec(dllimport) void __stdcall DebugBreak(); + #define CATCH_TRAP() DebugBreak() +#endif + +#ifdef CATCH_TRAP + #define CATCH_BREAK_INTO_DEBUGGER() if( Catch::isDebuggerActive() ) { CATCH_TRAP(); } +#else + #define CATCH_BREAK_INTO_DEBUGGER() Catch::alwaysTrue(); +#endif + +// end catch_debugger.h +#if !defined(CATCH_CONFIG_DISABLE) + +#if !defined(CATCH_CONFIG_DISABLE_STRINGIFICATION) + #define CATCH_INTERNAL_STRINGIFY(...) #__VA_ARGS__ +#else + #define CATCH_INTERNAL_STRINGIFY(...) "Disabled by CATCH_CONFIG_DISABLE_STRINGIFICATION" +#endif + +#if defined(CATCH_CONFIG_FAST_COMPILE) +/////////////////////////////////////////////////////////////////////////////// +// We can speedup compilation significantly by breaking into debugger lower in +// the callstack, because then we don't have to expand CATCH_BREAK_INTO_DEBUGGER +// macro in each assertion +#define INTERNAL_CATCH_REACT( handler ) \ + handler.reactWithDebugBreak(); + +/////////////////////////////////////////////////////////////////////////////// +// Another way to speed-up compilation is to omit local try-catch for REQUIRE* +// macros. +// This can potentially cause false negative, if the test code catches +// the exception before it propagates back up to the runner. +#define INTERNAL_CATCH_TRY( capturer ) capturer.setExceptionGuard(); +#define INTERNAL_CATCH_CATCH( capturer ) capturer.unsetExceptionGuard(); + +#else // CATCH_CONFIG_FAST_COMPILE + +/////////////////////////////////////////////////////////////////////////////// +// In the event of a failure works out if the debugger needs to be invoked +// and/or an exception thrown and takes appropriate action. +// This needs to be done as a macro so the debugger will stop in the user +// source code rather than in Catch library code +#define INTERNAL_CATCH_REACT( handler ) \ + if( handler.shouldDebugBreak() ) CATCH_BREAK_INTO_DEBUGGER(); \ + handler.reactWithoutDebugBreak(); + +#define INTERNAL_CATCH_TRY( capturer ) try +#define INTERNAL_CATCH_CATCH( capturer ) catch(...) { capturer.useActiveException(); } + +#endif + +/////////////////////////////////////////////////////////////////////////////// +#define INTERNAL_CATCH_TEST( macroName, resultDisposition, ... ) \ + do { \ + Catch::AssertionHandler catchAssertionHandler( macroName, CATCH_INTERNAL_LINEINFO, CATCH_INTERNAL_STRINGIFY(__VA_ARGS__), resultDisposition ); \ + INTERNAL_CATCH_TRY( catchAssertionHandler ) { \ + CATCH_INTERNAL_SUPPRESS_PARENTHESES_WARNINGS \ + catchAssertionHandler.handle( Catch::Decomposer() <= __VA_ARGS__ ); \ + CATCH_INTERNAL_UNSUPPRESS_PARENTHESES_WARNINGS \ + } INTERNAL_CATCH_CATCH( catchAssertionHandler ) \ + INTERNAL_CATCH_REACT( catchAssertionHandler ) \ + } while( Catch::isTrue( false && static_cast( !!(__VA_ARGS__) ) ) ) // the expression here is never evaluated at runtime but it forces the compiler to give it a look + // The double negation silences MSVC's C4800 warning, the static_cast forces short-circuit evaluation if the type has overloaded &&. + +/////////////////////////////////////////////////////////////////////////////// +#define INTERNAL_CATCH_IF( macroName, resultDisposition, ... ) \ + INTERNAL_CATCH_TEST( macroName, resultDisposition, __VA_ARGS__ ); \ + if( Catch::getResultCapture().lastAssertionPassed() ) + +/////////////////////////////////////////////////////////////////////////////// +#define INTERNAL_CATCH_ELSE( macroName, resultDisposition, ... ) \ + INTERNAL_CATCH_TEST( macroName, resultDisposition, __VA_ARGS__ ); \ + if( !Catch::getResultCapture().lastAssertionPassed() ) + +/////////////////////////////////////////////////////////////////////////////// +#define INTERNAL_CATCH_NO_THROW( macroName, resultDisposition, ... ) \ + do { \ + Catch::AssertionHandler catchAssertionHandler( macroName, CATCH_INTERNAL_LINEINFO, CATCH_INTERNAL_STRINGIFY(__VA_ARGS__), resultDisposition ); \ + try { \ + static_cast(__VA_ARGS__); \ + catchAssertionHandler.handle( Catch::ResultWas::Ok ); \ + } \ + catch( ... ) { \ + catchAssertionHandler.useActiveException(); \ + } \ + INTERNAL_CATCH_REACT( catchAssertionHandler ) \ + } while( Catch::alwaysFalse() ) + +/////////////////////////////////////////////////////////////////////////////// +#define INTERNAL_CATCH_THROWS( macroName, resultDisposition, ... ) \ + do { \ + Catch::AssertionHandler catchAssertionHandler( macroName, CATCH_INTERNAL_LINEINFO, CATCH_INTERNAL_STRINGIFY(__VA_ARGS__), resultDisposition); \ + if( catchAssertionHandler.allowThrows() ) \ + try { \ + static_cast(__VA_ARGS__); \ + catchAssertionHandler.handle( Catch::ResultWas::DidntThrowException ); \ + } \ + catch( ... ) { \ + catchAssertionHandler.handle( Catch::ResultWas::Ok ); \ + } \ + else \ + catchAssertionHandler.handle( Catch::ResultWas::Ok ); \ + INTERNAL_CATCH_REACT( catchAssertionHandler ) \ + } while( Catch::alwaysFalse() ) + +/////////////////////////////////////////////////////////////////////////////// +#define INTERNAL_CATCH_THROWS_AS( macroName, exceptionType, resultDisposition, expr ) \ + do { \ + Catch::AssertionHandler catchAssertionHandler( macroName, CATCH_INTERNAL_LINEINFO, CATCH_INTERNAL_STRINGIFY(expr) ", " CATCH_INTERNAL_STRINGIFY(exceptionType), resultDisposition ); \ + if( catchAssertionHandler.allowThrows() ) \ + try { \ + static_cast(expr); \ + catchAssertionHandler.handle( Catch::ResultWas::DidntThrowException ); \ + } \ + catch( exceptionType const& ) { \ + catchAssertionHandler.handle( Catch::ResultWas::Ok ); \ + } \ + catch( ... ) { \ + catchAssertionHandler.useActiveException(); \ + } \ + else \ + catchAssertionHandler.handle( Catch::ResultWas::Ok ); \ + INTERNAL_CATCH_REACT( catchAssertionHandler ) \ + } while( Catch::alwaysFalse() ) + +/////////////////////////////////////////////////////////////////////////////// +#define INTERNAL_CATCH_MSG( macroName, messageType, resultDisposition, ... ) \ + do { \ + Catch::AssertionHandler catchAssertionHandler( macroName, CATCH_INTERNAL_LINEINFO, "", resultDisposition ); \ + catchAssertionHandler.handle( messageType, ( Catch::MessageStream() << __VA_ARGS__ + ::Catch::StreamEndStop() ).m_stream.str() ); \ + INTERNAL_CATCH_REACT( catchAssertionHandler ) \ + } while( Catch::alwaysFalse() ) + +/////////////////////////////////////////////////////////////////////////////// +#define INTERNAL_CATCH_INFO( macroName, log ) \ + Catch::ScopedMessage INTERNAL_CATCH_UNIQUE_NAME( scopedMessage ) = Catch::MessageBuilder( macroName, CATCH_INTERNAL_LINEINFO, Catch::ResultWas::Info ) << log; + +/////////////////////////////////////////////////////////////////////////////// +// Although this is matcher-based, it can be used with just a string +#define INTERNAL_CATCH_THROWS_STR_MATCHES( macroName, resultDisposition, matcher, ... ) \ + do { \ + Catch::AssertionHandler catchAssertionHandler( macroName, CATCH_INTERNAL_LINEINFO, CATCH_INTERNAL_STRINGIFY(__VA_ARGS__) ", " CATCH_INTERNAL_STRINGIFY(matcher), resultDisposition ); \ + if( catchAssertionHandler.allowThrows() ) \ + try { \ + static_cast(__VA_ARGS__); \ + catchAssertionHandler.handle( Catch::ResultWas::DidntThrowException ); \ + } \ + catch( ... ) { \ + handleExceptionMatchExpr( catchAssertionHandler, matcher, #matcher ); \ + } \ + else \ + catchAssertionHandler.handle( Catch::ResultWas::Ok ); \ + INTERNAL_CATCH_REACT( catchAssertionHandler ) \ + } while( Catch::alwaysFalse() ) + +#endif // CATCH_CONFIG_DISABLE + +// end catch_capture.hpp +// start catch_section.h + +// start catch_section_info.h + +// start catch_totals.h + +#include + +namespace Catch { + + struct Counts { + Counts operator - ( Counts const& other ) const; + Counts& operator += ( Counts const& other ); + + std::size_t total() const; + bool allPassed() const; + bool allOk() const; + + std::size_t passed = 0; + std::size_t failed = 0; + std::size_t failedButOk = 0; + }; + + struct Totals { + + Totals operator - ( Totals const& other ) const; + Totals& operator += ( Totals const& other ); + + Totals delta( Totals const& prevTotals ) const; + + Counts assertions; + Counts testCases; + }; +} + +// end catch_totals.h +#include + +namespace Catch { + + struct SectionInfo { + SectionInfo + ( SourceLineInfo const& _lineInfo, + std::string const& _name, + std::string const& _description = std::string() ); + + std::string name; + std::string description; + SourceLineInfo lineInfo; + }; + + struct SectionEndInfo { + SectionEndInfo( SectionInfo const& _sectionInfo, Counts const& _prevAssertions, double _durationInSeconds ); + + SectionInfo sectionInfo; + Counts prevAssertions; + double durationInSeconds; + }; + +} // end namespace Catch + +// end catch_section_info.h +// start catch_timer.h + +#include + +namespace Catch { + + auto getCurrentNanosecondsSinceEpoch() -> uint64_t; + auto getEstimatedClockResolution() -> uint64_t; + + class Timer { + uint64_t m_nanoseconds = 0; + public: + void start(); + auto getElapsedNanoseconds() const -> unsigned int; + auto getElapsedMicroseconds() const -> unsigned int; + auto getElapsedMilliseconds() const -> unsigned int; + auto getElapsedSeconds() const -> double; + }; + +} // namespace Catch + +// end catch_timer.h +#include + +namespace Catch { + + class Section : NonCopyable { + public: + Section( SectionInfo const& info ); + ~Section(); + + // This indicates whether the section should be executed or not + explicit operator bool() const; + + private: + SectionInfo m_info; + + std::string m_name; + Counts m_assertions; + bool m_sectionIncluded; + Timer m_timer; + }; + +} // end namespace Catch + + #define INTERNAL_CATCH_SECTION( ... ) \ + if( Catch::Section const& INTERNAL_CATCH_UNIQUE_NAME( catch_internal_Section ) = Catch::SectionInfo( CATCH_INTERNAL_LINEINFO, __VA_ARGS__ ) ) + +// end catch_section.h +// start catch_benchmark.h + +#include +#include + +namespace Catch { + + class BenchmarkLooper { + + std::string m_name; + std::size_t m_count = 0; + std::size_t m_iterationsToRun = 1; + uint64_t m_resolution; + Timer m_timer; + + static auto getResolution() -> uint64_t; + public: + // Keep most of this inline as it's on the code path that is being timed + BenchmarkLooper( StringRef name ) + : m_name( name ), + m_resolution( getResolution() ) + { + reportStart(); + m_timer.start(); + } + + explicit operator bool() { + if( m_count < m_iterationsToRun ) + return true; + return needsMoreIterations(); + } + + void increment() { + ++m_count; + } + + void reportStart(); + auto needsMoreIterations() -> bool; + }; + +} // end namespace Catch + +#define BENCHMARK( name ) \ + for( Catch::BenchmarkLooper looper( name ); looper; looper.increment() ) + +// end catch_benchmark.h +// start catch_interfaces_exception.h + +// start catch_interfaces_registry_hub.h + +#include +#include + +namespace Catch { + + class TestCase; + struct ITestCaseRegistry; + struct IExceptionTranslatorRegistry; + struct IExceptionTranslator; + struct IReporterRegistry; + struct IReporterFactory; + struct ITagAliasRegistry; + class StartupExceptionRegistry; + + using IReporterFactoryPtr = std::shared_ptr; + + struct IRegistryHub { + virtual ~IRegistryHub(); + + virtual IReporterRegistry const& getReporterRegistry() const = 0; + virtual ITestCaseRegistry const& getTestCaseRegistry() const = 0; + virtual ITagAliasRegistry const& getTagAliasRegistry() const = 0; + + virtual IExceptionTranslatorRegistry& getExceptionTranslatorRegistry() = 0; + + virtual StartupExceptionRegistry const& getStartupExceptionRegistry() const = 0; + }; + + struct IMutableRegistryHub { + virtual ~IMutableRegistryHub(); + virtual void registerReporter( std::string const& name, IReporterFactoryPtr const& factory ) = 0; + virtual void registerListener( IReporterFactoryPtr const& factory ) = 0; + virtual void registerTest( TestCase const& testInfo ) = 0; + virtual void registerTranslator( const IExceptionTranslator* translator ) = 0; + virtual void registerTagAlias( std::string const& alias, std::string const& tag, SourceLineInfo const& lineInfo ) = 0; + virtual void registerStartupException() noexcept = 0; + }; + + IRegistryHub& getRegistryHub(); + IMutableRegistryHub& getMutableRegistryHub(); + void cleanUp(); + std::string translateActiveException(); + +} + +// end catch_interfaces_registry_hub.h +#if defined(CATCH_CONFIG_DISABLE) + #define INTERNAL_CATCH_TRANSLATE_EXCEPTION_NO_REG( translatorName, signature) \ + static std::string translatorName( signature ) +#endif + +#include +#include +#include + +namespace Catch { + using exceptionTranslateFunction = std::string(*)(); + + struct IExceptionTranslator; + using ExceptionTranslators = std::vector>; + + struct IExceptionTranslator { + virtual ~IExceptionTranslator(); + virtual std::string translate( ExceptionTranslators::const_iterator it, ExceptionTranslators::const_iterator itEnd ) const = 0; + }; + + struct IExceptionTranslatorRegistry { + virtual ~IExceptionTranslatorRegistry(); + + virtual std::string translateActiveException() const = 0; + }; + + class ExceptionTranslatorRegistrar { + template + class ExceptionTranslator : public IExceptionTranslator { + public: + + ExceptionTranslator( std::string(*translateFunction)( T& ) ) + : m_translateFunction( translateFunction ) + {} + + std::string translate( ExceptionTranslators::const_iterator it, ExceptionTranslators::const_iterator itEnd ) const override { + try { + if( it == itEnd ) + std::rethrow_exception(std::current_exception()); + else + return (*it)->translate( it+1, itEnd ); + } + catch( T& ex ) { + return m_translateFunction( ex ); + } + } + + protected: + std::string(*m_translateFunction)( T& ); + }; + + public: + template + ExceptionTranslatorRegistrar( std::string(*translateFunction)( T& ) ) { + getMutableRegistryHub().registerTranslator + ( new ExceptionTranslator( translateFunction ) ); + } + }; +} + +/////////////////////////////////////////////////////////////////////////////// +#define INTERNAL_CATCH_TRANSLATE_EXCEPTION2( translatorName, signature ) \ + static std::string translatorName( signature ); \ + namespace{ Catch::ExceptionTranslatorRegistrar INTERNAL_CATCH_UNIQUE_NAME( catch_internal_ExceptionRegistrar )( &translatorName ); }\ + static std::string translatorName( signature ) + +#define INTERNAL_CATCH_TRANSLATE_EXCEPTION( signature ) INTERNAL_CATCH_TRANSLATE_EXCEPTION2( INTERNAL_CATCH_UNIQUE_NAME( catch_internal_ExceptionTranslator ), signature ) + +// end catch_interfaces_exception.h +// start catch_approx.h + +// start catch_enforce.h + +#include +#include + +#define CATCH_PREPARE_EXCEPTION( type, msg ) \ + type( static_cast( std::ostringstream() << msg ).str() ) +#define CATCH_INTERNAL_ERROR( msg ) \ + throw CATCH_PREPARE_EXCEPTION( std::logic_error, CATCH_INTERNAL_LINEINFO << ": Internal Catch error: " << msg); +#define CATCH_ERROR( msg ) \ + throw CATCH_PREPARE_EXCEPTION( std::domain_error, msg ) +#define CATCH_ENFORCE( condition, msg ) \ + do{ if( !(condition) ) CATCH_ERROR( msg ); } while(false) + +// end catch_enforce.h +#include + +namespace Catch { +namespace Detail { + + class Approx { + private: + bool equalityComparisonImpl(double other) const; + + public: + explicit Approx ( double value ); + + static Approx custom(); + + template ::value>::type> + Approx operator()( T const& value ) { + Approx approx( static_cast(value) ); + approx.epsilon( m_epsilon ); + approx.margin( m_margin ); + approx.scale( m_scale ); + return approx; + } + + template ::value>::type> + explicit Approx( T const& value ): Approx(static_cast(value)) + {} + + template ::value>::type> + friend bool operator == ( const T& lhs, Approx const& rhs ) { + auto lhs_v = static_cast(lhs); + return rhs.equalityComparisonImpl(lhs_v); + } + + template ::value>::type> + friend bool operator == ( Approx const& lhs, const T& rhs ) { + return operator==( rhs, lhs ); + } + + template ::value>::type> + friend bool operator != ( T const& lhs, Approx const& rhs ) { + return !operator==( lhs, rhs ); + } + + template ::value>::type> + friend bool operator != ( Approx const& lhs, T const& rhs ) { + return !operator==( rhs, lhs ); + } + + template ::value>::type> + friend bool operator <= ( T const& lhs, Approx const& rhs ) { + return static_cast(lhs) < rhs.m_value || lhs == rhs; + } + + template ::value>::type> + friend bool operator <= ( Approx const& lhs, T const& rhs ) { + return lhs.m_value < static_cast(rhs) || lhs == rhs; + } + + template ::value>::type> + friend bool operator >= ( T const& lhs, Approx const& rhs ) { + return static_cast(lhs) > rhs.m_value || lhs == rhs; + } + + template ::value>::type> + friend bool operator >= ( Approx const& lhs, T const& rhs ) { + return lhs.m_value > static_cast(rhs) || lhs == rhs; + } + + template ::value>::type> + Approx& epsilon( T const& newEpsilon ) { + double epsilonAsDouble = static_cast(newEpsilon); + CATCH_ENFORCE(epsilonAsDouble >= 0 && epsilonAsDouble <= 1.0, + "Invalid Approx::epsilon: " << epsilonAsDouble + << ", Approx::epsilon has to be between 0 and 1"); + m_epsilon = epsilonAsDouble; + return *this; + } + + template ::value>::type> + Approx& margin( T const& newMargin ) { + double marginAsDouble = static_cast(newMargin); + CATCH_ENFORCE(marginAsDouble >= 0, + "Invalid Approx::margin: " << marginAsDouble + << ", Approx::Margin has to be non-negative."); + m_margin = marginAsDouble; + return *this; + } + + template ::value>::type> + Approx& scale( T const& newScale ) { + m_scale = static_cast(newScale); + return *this; + } + + std::string toString() const; + + private: + double m_epsilon; + double m_margin; + double m_scale; + double m_value; + }; +} + +template<> +struct StringMaker { + static std::string convert(Catch::Detail::Approx const& value); +}; + +} // end namespace Catch + +// end catch_approx.h +// start catch_string_manip.h + +#include +#include + +namespace Catch { + + bool startsWith( std::string const& s, std::string const& prefix ); + bool startsWith( std::string const& s, char prefix ); + bool endsWith( std::string const& s, std::string const& suffix ); + bool endsWith( std::string const& s, char suffix ); + bool contains( std::string const& s, std::string const& infix ); + void toLowerInPlace( std::string& s ); + std::string toLower( std::string const& s ); + std::string trim( std::string const& str ); + bool replaceInPlace( std::string& str, std::string const& replaceThis, std::string const& withThis ); + + struct pluralise { + pluralise( std::size_t count, std::string const& label ); + + friend std::ostream& operator << ( std::ostream& os, pluralise const& pluraliser ); + + std::size_t m_count; + std::string m_label; + }; +} + +// end catch_string_manip.h +#ifndef CATCH_CONFIG_DISABLE_MATCHERS +// start catch_capture_matchers.h + +// start catch_matchers.h + +#include +#include + +namespace Catch { +namespace Matchers { + namespace Impl { + + template struct MatchAllOf; + template struct MatchAnyOf; + template struct MatchNotOf; + + class MatcherUntypedBase { + public: + MatcherUntypedBase() = default; + MatcherUntypedBase ( MatcherUntypedBase const& ) = default; + MatcherUntypedBase& operator = ( MatcherUntypedBase const& ) = delete; + std::string toString() const; + + protected: + virtual ~MatcherUntypedBase(); + virtual std::string describe() const = 0; + mutable std::string m_cachedToString; + }; + + template + struct MatcherMethod { + virtual bool match( ObjectT const& arg ) const = 0; + }; + template + struct MatcherMethod { + virtual bool match( PtrT* arg ) const = 0; + }; + + template + struct MatcherBase : MatcherUntypedBase, MatcherMethod { + + MatchAllOf operator && ( MatcherBase const& other ) const; + MatchAnyOf operator || ( MatcherBase const& other ) const; + MatchNotOf operator ! () const; + }; + + template + struct MatchAllOf : MatcherBase { + bool match( ArgT const& arg ) const override { + for( auto matcher : m_matchers ) { + if (!matcher->match(arg)) + return false; + } + return true; + } + std::string describe() const override { + std::string description; + description.reserve( 4 + m_matchers.size()*32 ); + description += "( "; + bool first = true; + for( auto matcher : m_matchers ) { + if( first ) + first = false; + else + description += " and "; + description += matcher->toString(); + } + description += " )"; + return description; + } + + MatchAllOf& operator && ( MatcherBase const& other ) { + m_matchers.push_back( &other ); + return *this; + } + + std::vector const*> m_matchers; + }; + template + struct MatchAnyOf : MatcherBase { + + bool match( ArgT const& arg ) const override { + for( auto matcher : m_matchers ) { + if (matcher->match(arg)) + return true; + } + return false; + } + std::string describe() const override { + std::string description; + description.reserve( 4 + m_matchers.size()*32 ); + description += "( "; + bool first = true; + for( auto matcher : m_matchers ) { + if( first ) + first = false; + else + description += " or "; + description += matcher->toString(); + } + description += " )"; + return description; + } + + MatchAnyOf& operator || ( MatcherBase const& other ) { + m_matchers.push_back( &other ); + return *this; + } + + std::vector const*> m_matchers; + }; + + template + struct MatchNotOf : MatcherBase { + + MatchNotOf( MatcherBase const& underlyingMatcher ) : m_underlyingMatcher( underlyingMatcher ) {} + + bool match( ArgT const& arg ) const override { + return !m_underlyingMatcher.match( arg ); + } + + std::string describe() const override { + return "not " + m_underlyingMatcher.toString(); + } + MatcherBase const& m_underlyingMatcher; + }; + + template + MatchAllOf MatcherBase::operator && ( MatcherBase const& other ) const { + return MatchAllOf() && *this && other; + } + template + MatchAnyOf MatcherBase::operator || ( MatcherBase const& other ) const { + return MatchAnyOf() || *this || other; + } + template + MatchNotOf MatcherBase::operator ! () const { + return MatchNotOf( *this ); + } + + } // namespace Impl + +} // namespace Matchers + +using namespace Matchers; +using Matchers::Impl::MatcherBase; + +} // namespace Catch + +// end catch_matchers.h +// start catch_matchers_string.h + +#include + +namespace Catch { +namespace Matchers { + + namespace StdString { + + struct CasedString + { + CasedString( std::string const& str, CaseSensitive::Choice caseSensitivity ); + std::string adjustString( std::string const& str ) const; + std::string caseSensitivitySuffix() const; + + CaseSensitive::Choice m_caseSensitivity; + std::string m_str; + }; + + struct StringMatcherBase : MatcherBase { + StringMatcherBase( std::string const& operation, CasedString const& comparator ); + std::string describe() const override; + + CasedString m_comparator; + std::string m_operation; + }; + + struct EqualsMatcher : StringMatcherBase { + EqualsMatcher( CasedString const& comparator ); + bool match( std::string const& source ) const override; + }; + struct ContainsMatcher : StringMatcherBase { + ContainsMatcher( CasedString const& comparator ); + bool match( std::string const& source ) const override; + }; + struct StartsWithMatcher : StringMatcherBase { + StartsWithMatcher( CasedString const& comparator ); + bool match( std::string const& source ) const override; + }; + struct EndsWithMatcher : StringMatcherBase { + EndsWithMatcher( CasedString const& comparator ); + bool match( std::string const& source ) const override; + }; + + } // namespace StdString + + // The following functions create the actual matcher objects. + // This allows the types to be inferred + + StdString::EqualsMatcher Equals( std::string const& str, CaseSensitive::Choice caseSensitivity = CaseSensitive::Yes ); + StdString::ContainsMatcher Contains( std::string const& str, CaseSensitive::Choice caseSensitivity = CaseSensitive::Yes ); + StdString::EndsWithMatcher EndsWith( std::string const& str, CaseSensitive::Choice caseSensitivity = CaseSensitive::Yes ); + StdString::StartsWithMatcher StartsWith( std::string const& str, CaseSensitive::Choice caseSensitivity = CaseSensitive::Yes ); + +} // namespace Matchers +} // namespace Catch + +// end catch_matchers_string.h +// start catch_matchers_vector.h + +namespace Catch { +namespace Matchers { + + namespace Vector { + + template + struct ContainsElementMatcher : MatcherBase, T> { + + ContainsElementMatcher(T const &comparator) : m_comparator( comparator) {} + + bool match(std::vector const &v) const override { + for (auto const& el : v) { + if (el == m_comparator) { + return true; + } + } + return false; + } + + std::string describe() const override { + return "Contains: " + ::Catch::Detail::stringify( m_comparator ); + } + + T const& m_comparator; + }; + + template + struct ContainsMatcher : MatcherBase, std::vector > { + + ContainsMatcher(std::vector const &comparator) : m_comparator( comparator ) {} + + bool match(std::vector const &v) const override { + // !TBD: see note in EqualsMatcher + if (m_comparator.size() > v.size()) + return false; + for (auto const& comparator : m_comparator) { + auto present = false; + for (const auto& el : v) { + if (el == comparator) { + present = true; + break; + } + } + if (!present) { + return false; + } + } + return true; + } + std::string describe() const override { + return "Contains: " + ::Catch::Detail::stringify( m_comparator ); + } + + std::vector const& m_comparator; + }; + + template + struct EqualsMatcher : MatcherBase, std::vector > { + + EqualsMatcher(std::vector const &comparator) : m_comparator( comparator ) {} + + bool match(std::vector const &v) const override { + // !TBD: This currently works if all elements can be compared using != + // - a more general approach would be via a compare template that defaults + // to using !=. but could be specialised for, e.g. std::vector etc + // - then just call that directly + if (m_comparator.size() != v.size()) + return false; + for (std::size_t i = 0; i < v.size(); ++i) + if (m_comparator[i] != v[i]) + return false; + return true; + } + std::string describe() const override { + return "Equals: " + ::Catch::Detail::stringify( m_comparator ); + } + std::vector const& m_comparator; + }; + + } // namespace Vector + + // The following functions create the actual matcher objects. + // This allows the types to be inferred + + template + Vector::ContainsMatcher Contains( std::vector const& comparator ) { + return Vector::ContainsMatcher( comparator ); + } + + template + Vector::ContainsElementMatcher VectorContains( T const& comparator ) { + return Vector::ContainsElementMatcher( comparator ); + } + + template + Vector::EqualsMatcher Equals( std::vector const& comparator ) { + return Vector::EqualsMatcher( comparator ); + } + +} // namespace Matchers +} // namespace Catch + +// end catch_matchers_vector.h +namespace Catch { + + template + class MatchExpr : public ITransientExpression { + ArgT const& m_arg; + MatcherT m_matcher; + StringRef m_matcherString; + bool m_result; + public: + MatchExpr( ArgT const& arg, MatcherT const& matcher, StringRef matcherString ) + : m_arg( arg ), + m_matcher( matcher ), + m_matcherString( matcherString ), + m_result( matcher.match( arg ) ) + {} + + auto isBinaryExpression() const -> bool override { return true; } + auto getResult() const -> bool override { return m_result; } + + void streamReconstructedExpression( std::ostream &os ) const override { + auto matcherAsString = m_matcher.toString(); + os << Catch::Detail::stringify( m_arg ) << ' '; + if( matcherAsString == Detail::unprintableString ) + os << m_matcherString; + else + os << matcherAsString; + } + }; + + using StringMatcher = Matchers::Impl::MatcherBase; + + void handleExceptionMatchExpr( AssertionHandler& handler, StringMatcher const& matcher, StringRef matcherString ); + + template + auto makeMatchExpr( ArgT const& arg, MatcherT const& matcher, StringRef matcherString ) -> MatchExpr { + return MatchExpr( arg, matcher, matcherString ); + } + +} // namespace Catch + +/////////////////////////////////////////////////////////////////////////////// +#define INTERNAL_CHECK_THAT( macroName, matcher, resultDisposition, arg ) \ + do { \ + Catch::AssertionHandler catchAssertionHandler( macroName, CATCH_INTERNAL_LINEINFO, CATCH_INTERNAL_STRINGIFY(arg) ", " CATCH_INTERNAL_STRINGIFY(matcher), resultDisposition ); \ + INTERNAL_CATCH_TRY( catchAssertionHandler ) { \ + catchAssertionHandler.handle( Catch::makeMatchExpr( arg, matcher, #matcher ) ); \ + } INTERNAL_CATCH_CATCH( catchAssertionHandler ) \ + INTERNAL_CATCH_REACT( catchAssertionHandler ) \ + } while( Catch::alwaysFalse() ) + +/////////////////////////////////////////////////////////////////////////////// +#define INTERNAL_CATCH_THROWS_MATCHES( macroName, exceptionType, resultDisposition, matcher, ... ) \ + do { \ + Catch::AssertionHandler catchAssertionHandler( macroName, CATCH_INTERNAL_LINEINFO, CATCH_INTERNAL_STRINGIFY(__VA_ARGS__) ", " CATCH_INTERNAL_STRINGIFY(exceptionType) ", " CATCH_INTERNAL_STRINGIFY(matcher), resultDisposition ); \ + if( catchAssertionHandler.allowThrows() ) \ + try { \ + static_cast(__VA_ARGS__ ); \ + catchAssertionHandler.handle( Catch::ResultWas::DidntThrowException ); \ + } \ + catch( exceptionType const& ex ) { \ + catchAssertionHandler.handle( Catch::makeMatchExpr( ex, matcher, #matcher ) ); \ + } \ + catch( ... ) { \ + catchAssertionHandler.useActiveException(); \ + } \ + else \ + catchAssertionHandler.handle( Catch::ResultWas::Ok ); \ + INTERNAL_CATCH_REACT( catchAssertionHandler ) \ + } while( Catch::alwaysFalse() ) + +// end catch_capture_matchers.h +#endif + +// These files are included here so the single_include script doesn't put them +// in the conditionally compiled sections +// start catch_test_case_info.h + +#include +#include +#include + +#ifdef __clang__ +#pragma clang diagnostic push +#pragma clang diagnostic ignored "-Wpadded" +#endif + +namespace Catch { + + struct ITestInvoker; + + struct TestCaseInfo { + enum SpecialProperties{ + None = 0, + IsHidden = 1 << 1, + ShouldFail = 1 << 2, + MayFail = 1 << 3, + Throws = 1 << 4, + NonPortable = 1 << 5, + Benchmark = 1 << 6 + }; + + TestCaseInfo( std::string const& _name, + std::string const& _className, + std::string const& _description, + std::vector const& _tags, + SourceLineInfo const& _lineInfo ); + + friend void setTags( TestCaseInfo& testCaseInfo, std::vector tags ); + + bool isHidden() const; + bool throws() const; + bool okToFail() const; + bool expectedToFail() const; + + std::string tagsAsString() const; + + std::string name; + std::string className; + std::string description; + std::vector tags; + std::vector lcaseTags; + SourceLineInfo lineInfo; + SpecialProperties properties; + }; + + class TestCase : public TestCaseInfo { + public: + + TestCase( ITestInvoker* testCase, TestCaseInfo const& info ); + + TestCase withName( std::string const& _newName ) const; + + void invoke() const; + + TestCaseInfo const& getTestCaseInfo() const; + + bool operator == ( TestCase const& other ) const; + bool operator < ( TestCase const& other ) const; + + private: + std::shared_ptr test; + }; + + TestCase makeTestCase( ITestInvoker* testCase, + std::string const& className, + std::string const& name, + std::string const& description, + SourceLineInfo const& lineInfo ); +} + +#ifdef __clang__ +#pragma clang diagnostic pop +#endif + +// end catch_test_case_info.h +// start catch_interfaces_runner.h + +namespace Catch { + + struct IRunner { + virtual ~IRunner(); + virtual bool aborting() const = 0; + }; +} + +// end catch_interfaces_runner.h + +#ifdef __OBJC__ +// start catch_objc.hpp + +#import + +#include + +// NB. Any general catch headers included here must be included +// in catch.hpp first to make sure they are included by the single +// header for non obj-usage + +/////////////////////////////////////////////////////////////////////////////// +// This protocol is really only here for (self) documenting purposes, since +// all its methods are optional. +@protocol OcFixture + +@optional + +-(void) setUp; +-(void) tearDown; + +@end + +namespace Catch { + + class OcMethod : public ITestInvoker { + + public: + OcMethod( Class cls, SEL sel ) : m_cls( cls ), m_sel( sel ) {} + + virtual void invoke() const { + id obj = [[m_cls alloc] init]; + + performOptionalSelector( obj, @selector(setUp) ); + performOptionalSelector( obj, m_sel ); + performOptionalSelector( obj, @selector(tearDown) ); + + arcSafeRelease( obj ); + } + private: + virtual ~OcMethod() {} + + Class m_cls; + SEL m_sel; + }; + + namespace Detail{ + + inline std::string getAnnotation( Class cls, + std::string const& annotationName, + std::string const& testCaseName ) { + NSString* selStr = [[NSString alloc] initWithFormat:@"Catch_%s_%s", annotationName.c_str(), testCaseName.c_str()]; + SEL sel = NSSelectorFromString( selStr ); + arcSafeRelease( selStr ); + id value = performOptionalSelector( cls, sel ); + if( value ) + return [(NSString*)value UTF8String]; + return ""; + } + } + + inline std::size_t registerTestMethods() { + std::size_t noTestMethods = 0; + int noClasses = objc_getClassList( nullptr, 0 ); + + Class* classes = (CATCH_UNSAFE_UNRETAINED Class *)malloc( sizeof(Class) * noClasses); + objc_getClassList( classes, noClasses ); + + for( int c = 0; c < noClasses; c++ ) { + Class cls = classes[c]; + { + u_int count; + Method* methods = class_copyMethodList( cls, &count ); + for( u_int m = 0; m < count ; m++ ) { + SEL selector = method_getName(methods[m]); + std::string methodName = sel_getName(selector); + if( startsWith( methodName, "Catch_TestCase_" ) ) { + std::string testCaseName = methodName.substr( 15 ); + std::string name = Detail::getAnnotation( cls, "Name", testCaseName ); + std::string desc = Detail::getAnnotation( cls, "Description", testCaseName ); + const char* className = class_getName( cls ); + + getMutableRegistryHub().registerTest( makeTestCase( new OcMethod( cls, selector ), className, name.c_str(), desc.c_str(), SourceLineInfo("",0) ) ); + noTestMethods++; + } + } + free(methods); + } + } + return noTestMethods; + } + +#if !defined(CATCH_CONFIG_DISABLE_MATCHERS) + + namespace Matchers { + namespace Impl { + namespace NSStringMatchers { + + struct StringHolder : MatcherBase{ + StringHolder( NSString* substr ) : m_substr( [substr copy] ){} + StringHolder( StringHolder const& other ) : m_substr( [other.m_substr copy] ){} + StringHolder() { + arcSafeRelease( m_substr ); + } + + bool match( NSString* arg ) const override { + return false; + } + + NSString* CATCH_ARC_STRONG m_substr; + }; + + struct Equals : StringHolder { + Equals( NSString* substr ) : StringHolder( substr ){} + + bool match( NSString* str ) const override { + return (str != nil || m_substr == nil ) && + [str isEqualToString:m_substr]; + } + + std::string describe() const override { + return "equals string: " + Catch::Detail::stringify( m_substr ); + } + }; + + struct Contains : StringHolder { + Contains( NSString* substr ) : StringHolder( substr ){} + + bool match( NSString* str ) const { + return (str != nil || m_substr == nil ) && + [str rangeOfString:m_substr].location != NSNotFound; + } + + std::string describe() const override { + return "contains string: " + Catch::Detail::stringify( m_substr ); + } + }; + + struct StartsWith : StringHolder { + StartsWith( NSString* substr ) : StringHolder( substr ){} + + bool match( NSString* str ) const override { + return (str != nil || m_substr == nil ) && + [str rangeOfString:m_substr].location == 0; + } + + std::string describe() const override { + return "starts with: " + Catch::Detail::stringify( m_substr ); + } + }; + struct EndsWith : StringHolder { + EndsWith( NSString* substr ) : StringHolder( substr ){} + + bool match( NSString* str ) const override { + return (str != nil || m_substr == nil ) && + [str rangeOfString:m_substr].location == [str length] - [m_substr length]; + } + + std::string describe() const override { + return "ends with: " + Catch::Detail::stringify( m_substr ); + } + }; + + } // namespace NSStringMatchers + } // namespace Impl + + inline Impl::NSStringMatchers::Equals + Equals( NSString* substr ){ return Impl::NSStringMatchers::Equals( substr ); } + + inline Impl::NSStringMatchers::Contains + Contains( NSString* substr ){ return Impl::NSStringMatchers::Contains( substr ); } + + inline Impl::NSStringMatchers::StartsWith + StartsWith( NSString* substr ){ return Impl::NSStringMatchers::StartsWith( substr ); } + + inline Impl::NSStringMatchers::EndsWith + EndsWith( NSString* substr ){ return Impl::NSStringMatchers::EndsWith( substr ); } + + } // namespace Matchers + + using namespace Matchers; + +#endif // CATCH_CONFIG_DISABLE_MATCHERS + +} // namespace Catch + +/////////////////////////////////////////////////////////////////////////////// +#define OC_MAKE_UNIQUE_NAME( root, uniqueSuffix ) root##uniqueSuffix +#define OC_TEST_CASE2( name, desc, uniqueSuffix ) \ ++(NSString*) OC_MAKE_UNIQUE_NAME( Catch_Name_test_, uniqueSuffix ) \ +{ \ +return @ name; \ +} \ ++(NSString*) OC_MAKE_UNIQUE_NAME( Catch_Description_test_, uniqueSuffix ) \ +{ \ +return @ desc; \ +} \ +-(void) OC_MAKE_UNIQUE_NAME( Catch_TestCase_test_, uniqueSuffix ) + +#define OC_TEST_CASE( name, desc ) OC_TEST_CASE2( name, desc, __LINE__ ) + +// end catch_objc.hpp +#endif + +#ifdef CATCH_CONFIG_EXTERNAL_INTERFACES +// start catch_external_interfaces.h + +// start catch_reporter_bases.hpp + +// start catch_interfaces_reporter.h + +// start catch_config.hpp + +// start catch_test_spec_parser.h + +#ifdef __clang__ +#pragma clang diagnostic push +#pragma clang diagnostic ignored "-Wpadded" +#endif + +// start catch_test_spec.h + +#ifdef __clang__ +#pragma clang diagnostic push +#pragma clang diagnostic ignored "-Wpadded" +#endif + +// start catch_wildcard_pattern.h + +namespace Catch +{ + class WildcardPattern { + enum WildcardPosition { + NoWildcard = 0, + WildcardAtStart = 1, + WildcardAtEnd = 2, + WildcardAtBothEnds = WildcardAtStart | WildcardAtEnd + }; + + public: + + WildcardPattern( std::string const& pattern, CaseSensitive::Choice caseSensitivity ); + virtual ~WildcardPattern() = default; + virtual bool matches( std::string const& str ) const; + + private: + std::string adjustCase( std::string const& str ) const; + CaseSensitive::Choice m_caseSensitivity; + WildcardPosition m_wildcard = NoWildcard; + std::string m_pattern; + }; +} + +// end catch_wildcard_pattern.h +#include +#include +#include + +namespace Catch { + + class TestSpec { + struct Pattern { + virtual ~Pattern(); + virtual bool matches( TestCaseInfo const& testCase ) const = 0; + }; + using PatternPtr = std::shared_ptr; + + class NamePattern : public Pattern { + public: + NamePattern( std::string const& name ); + virtual ~NamePattern(); + virtual bool matches( TestCaseInfo const& testCase ) const override; + private: + WildcardPattern m_wildcardPattern; + }; + + class TagPattern : public Pattern { + public: + TagPattern( std::string const& tag ); + virtual ~TagPattern(); + virtual bool matches( TestCaseInfo const& testCase ) const override; + private: + std::string m_tag; + }; + + class ExcludedPattern : public Pattern { + public: + ExcludedPattern( PatternPtr const& underlyingPattern ); + virtual ~ExcludedPattern(); + virtual bool matches( TestCaseInfo const& testCase ) const override; + private: + PatternPtr m_underlyingPattern; + }; + + struct Filter { + std::vector m_patterns; + + bool matches( TestCaseInfo const& testCase ) const; + }; + + public: + bool hasFilters() const; + bool matches( TestCaseInfo const& testCase ) const; + + private: + std::vector m_filters; + + friend class TestSpecParser; + }; +} + +#ifdef __clang__ +#pragma clang diagnostic pop +#endif + +// end catch_test_spec.h +// start catch_interfaces_tag_alias_registry.h + +#include + +namespace Catch { + + struct TagAlias; + + struct ITagAliasRegistry { + virtual ~ITagAliasRegistry(); + // Nullptr if not present + virtual TagAlias const* find( std::string const& alias ) const = 0; + virtual std::string expandAliases( std::string const& unexpandedTestSpec ) const = 0; + + static ITagAliasRegistry const& get(); + }; + +} // end namespace Catch + +// end catch_interfaces_tag_alias_registry.h +namespace Catch { + + class TestSpecParser { + enum Mode{ None, Name, QuotedName, Tag, EscapedName }; + Mode m_mode = None; + bool m_exclusion = false; + std::size_t m_start = std::string::npos, m_pos = 0; + std::string m_arg; + std::vector m_escapeChars; + TestSpec::Filter m_currentFilter; + TestSpec m_testSpec; + ITagAliasRegistry const* m_tagAliases = nullptr; + + public: + TestSpecParser( ITagAliasRegistry const& tagAliases ); + + TestSpecParser& parse( std::string const& arg ); + TestSpec testSpec(); + + private: + void visitChar( char c ); + void startNewMode( Mode mode, std::size_t start ); + void escape(); + std::string subString() const; + + template + void addPattern() { + std::string token = subString(); + for( std::size_t i = 0; i < m_escapeChars.size(); ++i ) + token = token.substr( 0, m_escapeChars[i]-m_start-i ) + token.substr( m_escapeChars[i]-m_start-i+1 ); + m_escapeChars.clear(); + if( startsWith( token, "exclude:" ) ) { + m_exclusion = true; + token = token.substr( 8 ); + } + if( !token.empty() ) { + TestSpec::PatternPtr pattern = std::make_shared( token ); + if( m_exclusion ) + pattern = std::make_shared( pattern ); + m_currentFilter.m_patterns.push_back( pattern ); + } + m_exclusion = false; + m_mode = None; + } + + void addFilter(); + }; + TestSpec parseTestSpec( std::string const& arg ); + +} // namespace Catch + +#ifdef __clang__ +#pragma clang diagnostic pop +#endif + +// end catch_test_spec_parser.h +// start catch_interfaces_config.h + +#include +#include +#include +#include + +namespace Catch { + + enum class Verbosity { + Quiet = 0, + Normal, + High + }; + + struct WarnAbout { enum What { + Nothing = 0x00, + NoAssertions = 0x01 + }; }; + + struct ShowDurations { enum OrNot { + DefaultForReporter, + Always, + Never + }; }; + struct RunTests { enum InWhatOrder { + InDeclarationOrder, + InLexicographicalOrder, + InRandomOrder + }; }; + struct UseColour { enum YesOrNo { + Auto, + Yes, + No + }; }; + struct WaitForKeypress { enum When { + Never, + BeforeStart = 1, + BeforeExit = 2, + BeforeStartAndExit = BeforeStart | BeforeExit + }; }; + + class TestSpec; + + struct IConfig : NonCopyable { + + virtual ~IConfig(); + + virtual bool allowThrows() const = 0; + virtual std::ostream& stream() const = 0; + virtual std::string name() const = 0; + virtual bool includeSuccessfulResults() const = 0; + virtual bool shouldDebugBreak() const = 0; + virtual bool warnAboutMissingAssertions() const = 0; + virtual int abortAfter() const = 0; + virtual bool showInvisibles() const = 0; + virtual ShowDurations::OrNot showDurations() const = 0; + virtual TestSpec const& testSpec() const = 0; + virtual RunTests::InWhatOrder runOrder() const = 0; + virtual unsigned int rngSeed() const = 0; + virtual int benchmarkResolutionMultiple() const = 0; + virtual UseColour::YesOrNo useColour() const = 0; + virtual std::vector const& getSectionsToRun() const = 0; + virtual Verbosity verbosity() const = 0; + }; + + using IConfigPtr = std::shared_ptr; +} + +// end catch_interfaces_config.h +// Libstdc++ doesn't like incomplete classes for unique_ptr +// start catch_stream.h + +// start catch_streambuf.h + +#include + +namespace Catch { + + class StreamBufBase : public std::streambuf { + public: + virtual ~StreamBufBase(); + }; +} + +// end catch_streambuf.h +#include +#include +#include +#include + +namespace Catch { + + std::ostream& cout(); + std::ostream& cerr(); + std::ostream& clog(); + + struct IStream { + virtual ~IStream(); + virtual std::ostream& stream() const = 0; + }; + + class FileStream : public IStream { + mutable std::ofstream m_ofs; + public: + FileStream( std::string const& filename ); + ~FileStream() override = default; + public: // IStream + std::ostream& stream() const override; + }; + + class CoutStream : public IStream { + mutable std::ostream m_os; + public: + CoutStream(); + ~CoutStream() override = default; + + public: // IStream + std::ostream& stream() const override; + }; + + class DebugOutStream : public IStream { + std::unique_ptr m_streamBuf; + mutable std::ostream m_os; + public: + DebugOutStream(); + ~DebugOutStream() override = default; + + public: // IStream + std::ostream& stream() const override; + }; +} + +// end catch_stream.h + +#include +#include +#include + +#ifndef CATCH_CONFIG_CONSOLE_WIDTH +#define CATCH_CONFIG_CONSOLE_WIDTH 80 +#endif + +namespace Catch { + + struct IStream; + + struct ConfigData { + bool listTests = false; + bool listTags = false; + bool listReporters = false; + bool listTestNamesOnly = false; + + bool showSuccessfulTests = false; + bool shouldDebugBreak = false; + bool noThrow = false; + bool showHelp = false; + bool showInvisibles = false; + bool filenamesAsTags = false; + bool libIdentify = false; + + int abortAfter = -1; + unsigned int rngSeed = 0; + int benchmarkResolutionMultiple = 100; + + Verbosity verbosity = Verbosity::Normal; + WarnAbout::What warnings = WarnAbout::Nothing; + ShowDurations::OrNot showDurations = ShowDurations::DefaultForReporter; + RunTests::InWhatOrder runOrder = RunTests::InDeclarationOrder; + UseColour::YesOrNo useColour = UseColour::Auto; + WaitForKeypress::When waitForKeypress = WaitForKeypress::Never; + + std::string outputFilename; + std::string name; + std::string processName; + + std::vector reporterNames; + std::vector testsOrTags; + std::vector sectionsToRun; + }; + + class Config : public IConfig { + public: + + Config() = default; + Config( ConfigData const& data ); + virtual ~Config() = default; + + std::string const& getFilename() const; + + bool listTests() const; + bool listTestNamesOnly() const; + bool listTags() const; + bool listReporters() const; + + std::string getProcessName() const; + + std::vector const& getReporterNames() const; + std::vector const& getSectionsToRun() const override; + + virtual TestSpec const& testSpec() const override; + + bool showHelp() const; + + // IConfig interface + bool allowThrows() const override; + std::ostream& stream() const override; + std::string name() const override; + bool includeSuccessfulResults() const override; + bool warnAboutMissingAssertions() const override; + ShowDurations::OrNot showDurations() const override; + RunTests::InWhatOrder runOrder() const override; + unsigned int rngSeed() const override; + int benchmarkResolutionMultiple() const override; + UseColour::YesOrNo useColour() const override; + bool shouldDebugBreak() const override; + int abortAfter() const override; + bool showInvisibles() const override; + Verbosity verbosity() const override; + + private: + + IStream const* openStream(); + ConfigData m_data; + + std::unique_ptr m_stream; + TestSpec m_testSpec; + }; + +} // end namespace Catch + +// end catch_config.hpp +// start catch_assertionresult.h + +#include + +namespace Catch { + + struct AssertionResultData + { + AssertionResultData() = delete; + + AssertionResultData( ResultWas::OfType _resultType, LazyExpression const& _lazyExpression ); + + std::string message; + mutable std::string reconstructedExpression; + LazyExpression lazyExpression; + ResultWas::OfType resultType; + + std::string reconstructExpression() const; + }; + + class AssertionResult { + public: + AssertionResult() = delete; + AssertionResult( AssertionInfo const& info, AssertionResultData const& data ); + + bool isOk() const; + bool succeeded() const; + ResultWas::OfType getResultType() const; + bool hasExpression() const; + bool hasMessage() const; + std::string getExpression() const; + std::string getExpressionInMacro() const; + bool hasExpandedExpression() const; + std::string getExpandedExpression() const; + std::string getMessage() const; + SourceLineInfo getSourceInfo() const; + std::string getTestMacroName() const; + + //protected: + AssertionInfo m_info; + AssertionResultData m_resultData; + }; + +} // end namespace Catch + +// end catch_assertionresult.h +// start catch_option.hpp + +namespace Catch { + + // An optional type + template + class Option { + public: + Option() : nullableValue( nullptr ) {} + Option( T const& _value ) + : nullableValue( new( storage ) T( _value ) ) + {} + Option( Option const& _other ) + : nullableValue( _other ? new( storage ) T( *_other ) : nullptr ) + {} + + ~Option() { + reset(); + } + + Option& operator= ( Option const& _other ) { + if( &_other != this ) { + reset(); + if( _other ) + nullableValue = new( storage ) T( *_other ); + } + return *this; + } + Option& operator = ( T const& _value ) { + reset(); + nullableValue = new( storage ) T( _value ); + return *this; + } + + void reset() { + if( nullableValue ) + nullableValue->~T(); + nullableValue = nullptr; + } + + T& operator*() { return *nullableValue; } + T const& operator*() const { return *nullableValue; } + T* operator->() { return nullableValue; } + const T* operator->() const { return nullableValue; } + + T valueOr( T const& defaultValue ) const { + return nullableValue ? *nullableValue : defaultValue; + } + + bool some() const { return nullableValue != nullptr; } + bool none() const { return nullableValue == nullptr; } + + bool operator !() const { return nullableValue == nullptr; } + explicit operator bool() const { + return some(); + } + + private: + T *nullableValue; + alignas(alignof(T)) char storage[sizeof(T)]; + }; + +} // end namespace Catch + +// end catch_option.hpp +#include +#include +#include +#include +#include + +namespace Catch { + + struct ReporterConfig { + explicit ReporterConfig( IConfigPtr const& _fullConfig ); + + ReporterConfig( IConfigPtr const& _fullConfig, std::ostream& _stream ); + + std::ostream& stream() const; + IConfigPtr fullConfig() const; + + private: + std::ostream* m_stream; + IConfigPtr m_fullConfig; + }; + + struct ReporterPreferences { + bool shouldRedirectStdOut = false; + }; + + template + struct LazyStat : Option { + LazyStat& operator=( T const& _value ) { + Option::operator=( _value ); + used = false; + return *this; + } + void reset() { + Option::reset(); + used = false; + } + bool used = false; + }; + + struct TestRunInfo { + TestRunInfo( std::string const& _name ); + std::string name; + }; + struct GroupInfo { + GroupInfo( std::string const& _name, + std::size_t _groupIndex, + std::size_t _groupsCount ); + + std::string name; + std::size_t groupIndex; + std::size_t groupsCounts; + }; + + struct AssertionStats { + AssertionStats( AssertionResult const& _assertionResult, + std::vector const& _infoMessages, + Totals const& _totals ); + + AssertionStats( AssertionStats const& ) = default; + AssertionStats( AssertionStats && ) = default; + AssertionStats& operator = ( AssertionStats const& ) = default; + AssertionStats& operator = ( AssertionStats && ) = default; + virtual ~AssertionStats(); + + AssertionResult assertionResult; + std::vector infoMessages; + Totals totals; + }; + + struct SectionStats { + SectionStats( SectionInfo const& _sectionInfo, + Counts const& _assertions, + double _durationInSeconds, + bool _missingAssertions ); + SectionStats( SectionStats const& ) = default; + SectionStats( SectionStats && ) = default; + SectionStats& operator = ( SectionStats const& ) = default; + SectionStats& operator = ( SectionStats && ) = default; + virtual ~SectionStats(); + + SectionInfo sectionInfo; + Counts assertions; + double durationInSeconds; + bool missingAssertions; + }; + + struct TestCaseStats { + TestCaseStats( TestCaseInfo const& _testInfo, + Totals const& _totals, + std::string const& _stdOut, + std::string const& _stdErr, + bool _aborting ); + + TestCaseStats( TestCaseStats const& ) = default; + TestCaseStats( TestCaseStats && ) = default; + TestCaseStats& operator = ( TestCaseStats const& ) = default; + TestCaseStats& operator = ( TestCaseStats && ) = default; + virtual ~TestCaseStats(); + + TestCaseInfo testInfo; + Totals totals; + std::string stdOut; + std::string stdErr; + bool aborting; + }; + + struct TestGroupStats { + TestGroupStats( GroupInfo const& _groupInfo, + Totals const& _totals, + bool _aborting ); + TestGroupStats( GroupInfo const& _groupInfo ); + + TestGroupStats( TestGroupStats const& ) = default; + TestGroupStats( TestGroupStats && ) = default; + TestGroupStats& operator = ( TestGroupStats const& ) = default; + TestGroupStats& operator = ( TestGroupStats && ) = default; + virtual ~TestGroupStats(); + + GroupInfo groupInfo; + Totals totals; + bool aborting; + }; + + struct TestRunStats { + TestRunStats( TestRunInfo const& _runInfo, + Totals const& _totals, + bool _aborting ); + + TestRunStats( TestRunStats const& ) = default; + TestRunStats( TestRunStats && ) = default; + TestRunStats& operator = ( TestRunStats const& ) = default; + TestRunStats& operator = ( TestRunStats && ) = default; + virtual ~TestRunStats(); + + TestRunInfo runInfo; + Totals totals; + bool aborting; + }; + + struct BenchmarkInfo { + std::string name; + }; + struct BenchmarkStats { + BenchmarkInfo info; + std::size_t iterations; + uint64_t elapsedTimeInNanoseconds; + }; + + struct IStreamingReporter { + virtual ~IStreamingReporter() = default; + + // Implementing class must also provide the following static methods: + // static std::string getDescription(); + // static std::set getSupportedVerbosities() + + virtual ReporterPreferences getPreferences() const = 0; + + virtual void noMatchingTestCases( std::string const& spec ) = 0; + + virtual void testRunStarting( TestRunInfo const& testRunInfo ) = 0; + virtual void testGroupStarting( GroupInfo const& groupInfo ) = 0; + + virtual void testCaseStarting( TestCaseInfo const& testInfo ) = 0; + virtual void sectionStarting( SectionInfo const& sectionInfo ) = 0; + + // *** experimental *** + virtual void benchmarkStarting( BenchmarkInfo const& ) {} + + virtual void assertionStarting( AssertionInfo const& assertionInfo ) = 0; + + // The return value indicates if the messages buffer should be cleared: + virtual bool assertionEnded( AssertionStats const& assertionStats ) = 0; + + // *** experimental *** + virtual void benchmarkEnded( BenchmarkStats const& ) {} + + virtual void sectionEnded( SectionStats const& sectionStats ) = 0; + virtual void testCaseEnded( TestCaseStats const& testCaseStats ) = 0; + virtual void testGroupEnded( TestGroupStats const& testGroupStats ) = 0; + virtual void testRunEnded( TestRunStats const& testRunStats ) = 0; + + virtual void skipTest( TestCaseInfo const& testInfo ) = 0; + + // Default empty implementation provided + virtual void fatalErrorEncountered( StringRef name ); + + virtual bool isMulti() const; + }; + using IStreamingReporterPtr = std::unique_ptr; + + struct IReporterFactory { + virtual ~IReporterFactory(); + virtual IStreamingReporterPtr create( ReporterConfig const& config ) const = 0; + virtual std::string getDescription() const = 0; + }; + using IReporterFactoryPtr = std::shared_ptr; + + struct IReporterRegistry { + using FactoryMap = std::map; + using Listeners = std::vector; + + virtual ~IReporterRegistry(); + virtual IStreamingReporterPtr create( std::string const& name, IConfigPtr const& config ) const = 0; + virtual FactoryMap const& getFactories() const = 0; + virtual Listeners const& getListeners() const = 0; + }; + + void addReporter( IStreamingReporterPtr& existingReporter, IStreamingReporterPtr&& additionalReporter ); + +} // end namespace Catch + +// end catch_interfaces_reporter.h +#include +#include +#include +#include +#include +#include + +namespace Catch { + void prepareExpandedExpression(AssertionResult& result); + + // Returns double formatted as %.3f (format expected on output) + std::string getFormattedDuration( double duration ); + + template + struct StreamingReporterBase : IStreamingReporter { + + StreamingReporterBase( ReporterConfig const& _config ) + : m_config( _config.fullConfig() ), + stream( _config.stream() ) + { + m_reporterPrefs.shouldRedirectStdOut = false; + CATCH_ENFORCE( DerivedT::getSupportedVerbosities().count( m_config->verbosity() ), "Verbosity level not supported by this reporter" ); + } + + ReporterPreferences getPreferences() const override { + return m_reporterPrefs; + } + + static std::set getSupportedVerbosities() { + return { Verbosity::Normal }; + } + + ~StreamingReporterBase() override = default; + + void noMatchingTestCases(std::string const&) override {} + + void testRunStarting(TestRunInfo const& _testRunInfo) override { + currentTestRunInfo = _testRunInfo; + } + void testGroupStarting(GroupInfo const& _groupInfo) override { + currentGroupInfo = _groupInfo; + } + + void testCaseStarting(TestCaseInfo const& _testInfo) override { + currentTestCaseInfo = _testInfo; + } + void sectionStarting(SectionInfo const& _sectionInfo) override { + m_sectionStack.push_back(_sectionInfo); + } + + void sectionEnded(SectionStats const& /* _sectionStats */) override { + m_sectionStack.pop_back(); + } + void testCaseEnded(TestCaseStats const& /* _testCaseStats */) override { + currentTestCaseInfo.reset(); + } + void testGroupEnded(TestGroupStats const& /* _testGroupStats */) override { + currentGroupInfo.reset(); + } + void testRunEnded(TestRunStats const& /* _testRunStats */) override { + currentTestCaseInfo.reset(); + currentGroupInfo.reset(); + currentTestRunInfo.reset(); + } + + void skipTest(TestCaseInfo const&) override { + // Don't do anything with this by default. + // It can optionally be overridden in the derived class. + } + + IConfigPtr m_config; + std::ostream& stream; + + LazyStat currentTestRunInfo; + LazyStat currentGroupInfo; + LazyStat currentTestCaseInfo; + + std::vector m_sectionStack; + ReporterPreferences m_reporterPrefs; + }; + + template + struct CumulativeReporterBase : IStreamingReporter { + template + struct Node { + explicit Node( T const& _value ) : value( _value ) {} + virtual ~Node() {} + + using ChildNodes = std::vector>; + T value; + ChildNodes children; + }; + struct SectionNode { + explicit SectionNode(SectionStats const& _stats) : stats(_stats) {} + virtual ~SectionNode() = default; + + bool operator == (SectionNode const& other) const { + return stats.sectionInfo.lineInfo == other.stats.sectionInfo.lineInfo; + } + bool operator == (std::shared_ptr const& other) const { + return operator==(*other); + } + + SectionStats stats; + using ChildSections = std::vector>; + using Assertions = std::vector; + ChildSections childSections; + Assertions assertions; + std::string stdOut; + std::string stdErr; + }; + + struct BySectionInfo { + BySectionInfo( SectionInfo const& other ) : m_other( other ) {} + BySectionInfo( BySectionInfo const& other ) : m_other( other.m_other ) {} + bool operator() (std::shared_ptr const& node) const { + return ((node->stats.sectionInfo.name == m_other.name) && + (node->stats.sectionInfo.lineInfo == m_other.lineInfo)); + } + void operator=(BySectionInfo const&) = delete; + + private: + SectionInfo const& m_other; + }; + + using TestCaseNode = Node; + using TestGroupNode = Node; + using TestRunNode = Node; + + CumulativeReporterBase( ReporterConfig const& _config ) + : m_config( _config.fullConfig() ), + stream( _config.stream() ) + { + m_reporterPrefs.shouldRedirectStdOut = false; + CATCH_ENFORCE( DerivedT::getSupportedVerbosities().count( m_config->verbosity() ), "Verbosity level not supported by this reporter" ); + } + ~CumulativeReporterBase() override = default; + + ReporterPreferences getPreferences() const override { + return m_reporterPrefs; + } + + static std::set getSupportedVerbosities() { + return { Verbosity::Normal }; + } + + void testRunStarting( TestRunInfo const& ) override {} + void testGroupStarting( GroupInfo const& ) override {} + + void testCaseStarting( TestCaseInfo const& ) override {} + + void sectionStarting( SectionInfo const& sectionInfo ) override { + SectionStats incompleteStats( sectionInfo, Counts(), 0, false ); + std::shared_ptr node; + if( m_sectionStack.empty() ) { + if( !m_rootSection ) + m_rootSection = std::make_shared( incompleteStats ); + node = m_rootSection; + } + else { + SectionNode& parentNode = *m_sectionStack.back(); + auto it = + std::find_if( parentNode.childSections.begin(), + parentNode.childSections.end(), + BySectionInfo( sectionInfo ) ); + if( it == parentNode.childSections.end() ) { + node = std::make_shared( incompleteStats ); + parentNode.childSections.push_back( node ); + } + else + node = *it; + } + m_sectionStack.push_back( node ); + m_deepestSection = std::move(node); + } + + void assertionStarting(AssertionInfo const&) override {} + + bool assertionEnded(AssertionStats const& assertionStats) override { + assert(!m_sectionStack.empty()); + // AssertionResult holds a pointer to a temporary DecomposedExpression, + // which getExpandedExpression() calls to build the expression string. + // Our section stack copy of the assertionResult will likely outlive the + // temporary, so it must be expanded or discarded now to avoid calling + // a destroyed object later. + prepareExpandedExpression(const_cast( assertionStats.assertionResult ) ); + SectionNode& sectionNode = *m_sectionStack.back(); + sectionNode.assertions.push_back(assertionStats); + return true; + } + void sectionEnded(SectionStats const& sectionStats) override { + assert(!m_sectionStack.empty()); + SectionNode& node = *m_sectionStack.back(); + node.stats = sectionStats; + m_sectionStack.pop_back(); + } + void testCaseEnded(TestCaseStats const& testCaseStats) override { + auto node = std::make_shared(testCaseStats); + assert(m_sectionStack.size() == 0); + node->children.push_back(m_rootSection); + m_testCases.push_back(node); + m_rootSection.reset(); + + assert(m_deepestSection); + m_deepestSection->stdOut = testCaseStats.stdOut; + m_deepestSection->stdErr = testCaseStats.stdErr; + } + void testGroupEnded(TestGroupStats const& testGroupStats) override { + auto node = std::make_shared(testGroupStats); + node->children.swap(m_testCases); + m_testGroups.push_back(node); + } + void testRunEnded(TestRunStats const& testRunStats) override { + auto node = std::make_shared(testRunStats); + node->children.swap(m_testGroups); + m_testRuns.push_back(node); + testRunEndedCumulative(); + } + virtual void testRunEndedCumulative() = 0; + + void skipTest(TestCaseInfo const&) override {} + + IConfigPtr m_config; + std::ostream& stream; + std::vector m_assertions; + std::vector>> m_sections; + std::vector> m_testCases; + std::vector> m_testGroups; + + std::vector> m_testRuns; + + std::shared_ptr m_rootSection; + std::shared_ptr m_deepestSection; + std::vector> m_sectionStack; + ReporterPreferences m_reporterPrefs; + }; + + template + char const* getLineOfChars() { + static char line[CATCH_CONFIG_CONSOLE_WIDTH] = {0}; + if( !*line ) { + std::memset( line, C, CATCH_CONFIG_CONSOLE_WIDTH-1 ); + line[CATCH_CONFIG_CONSOLE_WIDTH-1] = 0; + } + return line; + } + + struct TestEventListenerBase : StreamingReporterBase { + TestEventListenerBase( ReporterConfig const& _config ); + + void assertionStarting(AssertionInfo const&) override; + bool assertionEnded(AssertionStats const&) override; + }; + +} // end namespace Catch + +// end catch_reporter_bases.hpp +// start catch_console_colour.h + +namespace Catch { + + struct Colour { + enum Code { + None = 0, + + White, + Red, + Green, + Blue, + Cyan, + Yellow, + Grey, + + Bright = 0x10, + + BrightRed = Bright | Red, + BrightGreen = Bright | Green, + LightGrey = Bright | Grey, + BrightWhite = Bright | White, + + // By intention + FileName = LightGrey, + Warning = Yellow, + ResultError = BrightRed, + ResultSuccess = BrightGreen, + ResultExpectedFailure = Warning, + + Error = BrightRed, + Success = Green, + + OriginalExpression = Cyan, + ReconstructedExpression = Yellow, + + SecondaryText = LightGrey, + Headers = White + }; + + // Use constructed object for RAII guard + Colour( Code _colourCode ); + Colour( Colour&& other ) noexcept; + Colour& operator=( Colour&& other ) noexcept; + ~Colour(); + + // Use static method for one-shot changes + static void use( Code _colourCode ); + + private: + bool m_moved = false; + }; + + std::ostream& operator << ( std::ostream& os, Colour const& ); + +} // end namespace Catch + +// end catch_console_colour.h +// start catch_reporter_registrars.hpp + + +namespace Catch { + + template + class ReporterRegistrar { + + class ReporterFactory : public IReporterFactory { + + virtual IStreamingReporterPtr create( ReporterConfig const& config ) const override { + return std::unique_ptr( new T( config ) ); + } + + virtual std::string getDescription() const override { + return T::getDescription(); + } + }; + + public: + + ReporterRegistrar( std::string const& name ) { + getMutableRegistryHub().registerReporter( name, std::make_shared() ); + } + }; + + template + class ListenerRegistrar { + + class ListenerFactory : public IReporterFactory { + + virtual IStreamingReporterPtr create( ReporterConfig const& config ) const override { + return std::unique_ptr( new T( config ) ); + } + virtual std::string getDescription() const override { + return std::string(); + } + }; + + public: + + ListenerRegistrar() { + getMutableRegistryHub().registerListener( std::make_shared() ); + } + }; +} + +#if !defined(CATCH_CONFIG_DISABLE) + +#define CATCH_REGISTER_REPORTER( name, reporterType ) \ + CATCH_INTERNAL_SUPPRESS_GLOBALS_WARNINGS \ + namespace{ Catch::ReporterRegistrar catch_internal_RegistrarFor##reporterType( name ); } \ + CATCH_INTERNAL_UNSUPPRESS_GLOBALS_WARNINGS + +#define CATCH_REGISTER_LISTENER( listenerType ) \ + CATCH_INTERNAL_SUPPRESS_GLOBALS_WARNINGS \ + namespace{ Catch::ListenerRegistrar catch_internal_RegistrarFor##listenerType; } \ + CATCH_INTERNAL_SUPPRESS_GLOBALS_WARNINGS +#else // CATCH_CONFIG_DISABLE + +#define CATCH_REGISTER_REPORTER(name, reporterType) +#define CATCH_REGISTER_LISTENER(listenerType) + +#endif // CATCH_CONFIG_DISABLE + +// end catch_reporter_registrars.hpp +// end catch_external_interfaces.h +#endif + +#ifdef CATCH_IMPL +// start catch_impl.hpp + +#ifdef __clang__ +#pragma clang diagnostic push +#pragma clang diagnostic ignored "-Wweak-vtables" +#endif + +// Keep these here for external reporters +// start catch_test_case_tracker.h + +#include +#include +#include + +namespace Catch { +namespace TestCaseTracking { + + struct NameAndLocation { + std::string name; + SourceLineInfo location; + + NameAndLocation( std::string const& _name, SourceLineInfo const& _location ); + }; + + struct ITracker; + + using ITrackerPtr = std::shared_ptr; + + struct ITracker { + virtual ~ITracker(); + + // static queries + virtual NameAndLocation const& nameAndLocation() const = 0; + + // dynamic queries + virtual bool isComplete() const = 0; // Successfully completed or failed + virtual bool isSuccessfullyCompleted() const = 0; + virtual bool isOpen() const = 0; // Started but not complete + virtual bool hasChildren() const = 0; + + virtual ITracker& parent() = 0; + + // actions + virtual void close() = 0; // Successfully complete + virtual void fail() = 0; + virtual void markAsNeedingAnotherRun() = 0; + + virtual void addChild( ITrackerPtr const& child ) = 0; + virtual ITrackerPtr findChild( NameAndLocation const& nameAndLocation ) = 0; + virtual void openChild() = 0; + + // Debug/ checking + virtual bool isSectionTracker() const = 0; + virtual bool isIndexTracker() const = 0; + }; + + class TrackerContext { + + enum RunState { + NotStarted, + Executing, + CompletedCycle + }; + + ITrackerPtr m_rootTracker; + ITracker* m_currentTracker = nullptr; + RunState m_runState = NotStarted; + + public: + + static TrackerContext& instance(); + + ITracker& startRun(); + void endRun(); + + void startCycle(); + void completeCycle(); + + bool completedCycle() const; + ITracker& currentTracker(); + void setCurrentTracker( ITracker* tracker ); + }; + + class TrackerBase : public ITracker { + protected: + enum CycleState { + NotStarted, + Executing, + ExecutingChildren, + NeedsAnotherRun, + CompletedSuccessfully, + Failed + }; + + class TrackerHasName { + NameAndLocation m_nameAndLocation; + public: + TrackerHasName( NameAndLocation const& nameAndLocation ); + bool operator ()( ITrackerPtr const& tracker ) const; + }; + + using Children = std::vector; + NameAndLocation m_nameAndLocation; + TrackerContext& m_ctx; + ITracker* m_parent; + Children m_children; + CycleState m_runState = NotStarted; + + public: + TrackerBase( NameAndLocation const& nameAndLocation, TrackerContext& ctx, ITracker* parent ); + + NameAndLocation const& nameAndLocation() const override; + bool isComplete() const override; + bool isSuccessfullyCompleted() const override; + bool isOpen() const override; + bool hasChildren() const override; + + void addChild( ITrackerPtr const& child ) override; + + ITrackerPtr findChild( NameAndLocation const& nameAndLocation ) override; + ITracker& parent() override; + + void openChild() override; + + bool isSectionTracker() const override; + bool isIndexTracker() const override; + + void open(); + + void close() override; + void fail() override; + void markAsNeedingAnotherRun() override; + + private: + void moveToParent(); + void moveToThis(); + }; + + class SectionTracker : public TrackerBase { + std::vector m_filters; + public: + SectionTracker( NameAndLocation const& nameAndLocation, TrackerContext& ctx, ITracker* parent ); + + bool isSectionTracker() const override; + + static SectionTracker& acquire( TrackerContext& ctx, NameAndLocation const& nameAndLocation ); + + void tryOpen(); + + void addInitialFilters( std::vector const& filters ); + void addNextFilters( std::vector const& filters ); + }; + + class IndexTracker : public TrackerBase { + int m_size; + int m_index = -1; + public: + IndexTracker( NameAndLocation const& nameAndLocation, TrackerContext& ctx, ITracker* parent, int size ); + + bool isIndexTracker() const override; + void close() override; + + static IndexTracker& acquire( TrackerContext& ctx, NameAndLocation const& nameAndLocation, int size ); + + int index() const; + + void moveNext(); + }; + +} // namespace TestCaseTracking + +using TestCaseTracking::ITracker; +using TestCaseTracking::TrackerContext; +using TestCaseTracking::SectionTracker; +using TestCaseTracking::IndexTracker; + +} // namespace Catch + +// end catch_test_case_tracker.h + +// start catch_leak_detector.h + +namespace Catch { + + struct LeakDetector { + LeakDetector(); + }; + +} +// end catch_leak_detector.h +// Cpp files will be included in the single-header file here +// start catch_approx.cpp + +#include +#include + +namespace { + +// Performs equivalent check of std::fabs(lhs - rhs) <= margin +// But without the subtraction to allow for INFINITY in comparison +bool marginComparison(double lhs, double rhs, double margin) { + return (lhs + margin >= rhs) && (rhs + margin >= lhs); +} + +} + +namespace Catch { +namespace Detail { + + Approx::Approx ( double value ) + : m_epsilon( std::numeric_limits::epsilon()*100 ), + m_margin( 0.0 ), + m_scale( 0.0 ), + m_value( value ) + {} + + Approx Approx::custom() { + return Approx( 0 ); + } + + std::string Approx::toString() const { + std::ostringstream oss; + oss << "Approx( " << ::Catch::Detail::stringify( m_value ) << " )"; + return oss.str(); + } + + bool Approx::equalityComparisonImpl(const double other) const { + // First try with fixed margin, then compute margin based on epsilon, scale and Approx's value + // Thanks to Richard Harris for his help refining the scaled margin value + return marginComparison(m_value, other, m_margin) || marginComparison(m_value, other, m_epsilon * (m_scale + std::fabs(m_value))); + } + +} // end namespace Detail + +std::string StringMaker::convert(Catch::Detail::Approx const& value) { + return value.toString(); +} + +} // end namespace Catch +// end catch_approx.cpp +// start catch_assertionhandler.cpp + +// start catch_context.h + +#include + +namespace Catch { + + struct IResultCapture; + struct IRunner; + struct IConfig; + + using IConfigPtr = std::shared_ptr; + + struct IContext + { + virtual ~IContext(); + + virtual IResultCapture* getResultCapture() = 0; + virtual IRunner* getRunner() = 0; + virtual IConfigPtr getConfig() const = 0; + }; + + struct IMutableContext : IContext + { + virtual ~IMutableContext(); + virtual void setResultCapture( IResultCapture* resultCapture ) = 0; + virtual void setRunner( IRunner* runner ) = 0; + virtual void setConfig( IConfigPtr const& config ) = 0; + }; + + IContext& getCurrentContext(); + IMutableContext& getCurrentMutableContext(); + void cleanUpContext(); +} + +// end catch_context.h +#include + +namespace Catch { + + auto operator <<( std::ostream& os, ITransientExpression const& expr ) -> std::ostream& { + expr.streamReconstructedExpression( os ); + return os; + } + + LazyExpression::LazyExpression( bool isNegated ) + : m_isNegated( isNegated ) + {} + + LazyExpression::LazyExpression( LazyExpression const& other ) : m_isNegated( other.m_isNegated ) {} + + LazyExpression::operator bool() const { + return m_transientExpression != nullptr; + } + + auto operator << ( std::ostream& os, LazyExpression const& lazyExpr ) -> std::ostream& { + if( lazyExpr.m_isNegated ) + os << "!"; + + if( lazyExpr ) { + if( lazyExpr.m_isNegated && lazyExpr.m_transientExpression->isBinaryExpression() ) + os << "(" << *lazyExpr.m_transientExpression << ")"; + else + os << *lazyExpr.m_transientExpression; + } + else { + os << "{** error - unchecked empty expression requested **}"; + } + return os; + } + + AssertionHandler::AssertionHandler + ( StringRef macroName, + SourceLineInfo const& lineInfo, + StringRef capturedExpression, + ResultDisposition::Flags resultDisposition ) + : m_assertionInfo{ macroName, lineInfo, capturedExpression, resultDisposition } + { + getCurrentContext().getResultCapture()->assertionStarting( m_assertionInfo ); + } + AssertionHandler::~AssertionHandler() { + if ( m_inExceptionGuard ) { + handle( ResultWas::ThrewException, "Exception translation was disabled by CATCH_CONFIG_FAST_COMPILE" ); + getCurrentContext().getResultCapture()->exceptionEarlyReported(); + } + } + + void AssertionHandler::handle( ITransientExpression const& expr ) { + + bool negated = isFalseTest( m_assertionInfo.resultDisposition ); + bool result = expr.getResult() != negated; + + handle( result ? ResultWas::Ok : ResultWas::ExpressionFailed, &expr, negated ); + } + void AssertionHandler::handle( ResultWas::OfType resultType ) { + handle( resultType, nullptr, false ); + } + void AssertionHandler::handle( ResultWas::OfType resultType, StringRef const& message ) { + AssertionResultData data( resultType, LazyExpression( false ) ); + data.message = message; + handle( data, nullptr ); + } + void AssertionHandler::handle( ResultWas::OfType resultType, ITransientExpression const* expr, bool negated ) { + AssertionResultData data( resultType, LazyExpression( negated ) ); + handle( data, expr ); + } + void AssertionHandler::handle( AssertionResultData const& resultData, ITransientExpression const* expr ) { + + getResultCapture().assertionRun(); + + AssertionResult assertionResult{ m_assertionInfo, resultData }; + assertionResult.m_resultData.lazyExpression.m_transientExpression = expr; + + getResultCapture().assertionEnded( assertionResult ); + + if( !assertionResult.isOk() ) { + m_shouldDebugBreak = getCurrentContext().getConfig()->shouldDebugBreak(); + m_shouldThrow = + getCurrentContext().getRunner()->aborting() || + (m_assertionInfo.resultDisposition & ResultDisposition::Normal); + } + } + + auto AssertionHandler::allowThrows() const -> bool { + return getCurrentContext().getConfig()->allowThrows(); + } + + auto AssertionHandler::shouldDebugBreak() const -> bool { + return m_shouldDebugBreak; + } + void AssertionHandler::reactWithDebugBreak() const { + if (m_shouldDebugBreak) { + /////////////////////////////////////////////////////////////////// + // To inspect the state during test, you need to go one level up the callstack + // To go back to the test and change execution, jump over the reactWithoutDebugBreak() call + /////////////////////////////////////////////////////////////////// + CATCH_BREAK_INTO_DEBUGGER(); + } + reactWithoutDebugBreak(); + } + void AssertionHandler::reactWithoutDebugBreak() const { + if( m_shouldThrow ) + throw Catch::TestFailureException(); + } + + void AssertionHandler::useActiveException() { + handle( ResultWas::ThrewException, Catch::translateActiveException() ); + } + + void AssertionHandler::setExceptionGuard() { + assert( m_inExceptionGuard == false ); + m_inExceptionGuard = true; + } + void AssertionHandler::unsetExceptionGuard() { + assert( m_inExceptionGuard == true ); + m_inExceptionGuard = false; + } + + // This is the overload that takes a string and infers the Equals matcher from it + // The more general overload, that takes any string matcher, is in catch_capture_matchers.cpp + void handleExceptionMatchExpr( AssertionHandler& handler, std::string const& str, StringRef matcherString ) { + handleExceptionMatchExpr( handler, Matchers::Equals( str ), matcherString ); + } + +} // namespace Catch +// end catch_assertionhandler.cpp +// start catch_assertionresult.cpp + +namespace Catch { + AssertionResultData::AssertionResultData(ResultWas::OfType _resultType, LazyExpression const & _lazyExpression): + lazyExpression(_lazyExpression), + resultType(_resultType) {} + + std::string AssertionResultData::reconstructExpression() const { + + if( reconstructedExpression.empty() ) { + if( lazyExpression ) { + // !TBD Use stringstream for now, but rework above to pass stream in + std::ostringstream oss; + oss << lazyExpression; + reconstructedExpression = oss.str(); + } + } + return reconstructedExpression; + } + + AssertionResult::AssertionResult( AssertionInfo const& info, AssertionResultData const& data ) + : m_info( info ), + m_resultData( data ) + {} + + // Result was a success + bool AssertionResult::succeeded() const { + return Catch::isOk( m_resultData.resultType ); + } + + // Result was a success, or failure is suppressed + bool AssertionResult::isOk() const { + return Catch::isOk( m_resultData.resultType ) || shouldSuppressFailure( m_info.resultDisposition ); + } + + ResultWas::OfType AssertionResult::getResultType() const { + return m_resultData.resultType; + } + + bool AssertionResult::hasExpression() const { + return m_info.capturedExpression[0] != 0; + } + + bool AssertionResult::hasMessage() const { + return !m_resultData.message.empty(); + } + + std::string AssertionResult::getExpression() const { + if( isFalseTest( m_info.resultDisposition ) ) + return "!(" + std::string(m_info.capturedExpression) + ")"; + else + return m_info.capturedExpression; + } + + std::string AssertionResult::getExpressionInMacro() const { + std::string expr; + if( m_info.macroName[0] == 0 ) + expr = m_info.capturedExpression; + else { + expr.reserve( m_info.macroName.size() + m_info.capturedExpression.size() + 4 ); + expr += m_info.macroName; + expr += "( "; + expr += m_info.capturedExpression; + expr += " )"; + } + return expr; + } + + bool AssertionResult::hasExpandedExpression() const { + return hasExpression() && getExpandedExpression() != getExpression(); + } + + std::string AssertionResult::getExpandedExpression() const { + std::string expr = m_resultData.reconstructExpression(); + return expr.empty() + ? getExpression() + : expr; + } + + std::string AssertionResult::getMessage() const { + return m_resultData.message; + } + SourceLineInfo AssertionResult::getSourceInfo() const { + return m_info.lineInfo; + } + + std::string AssertionResult::getTestMacroName() const { + return m_info.macroName; + } + +} // end namespace Catch +// end catch_assertionresult.cpp +// start catch_benchmark.cpp + +namespace Catch { + + auto BenchmarkLooper::getResolution() -> uint64_t { + return getEstimatedClockResolution() * getCurrentContext().getConfig()->benchmarkResolutionMultiple(); + } + + void BenchmarkLooper::reportStart() { + getResultCapture().benchmarkStarting( { m_name } ); + } + auto BenchmarkLooper::needsMoreIterations() -> bool { + auto elapsed = m_timer.getElapsedNanoseconds(); + + // Exponentially increasing iterations until we're confident in our timer resolution + if( elapsed < m_resolution ) { + m_iterationsToRun *= 10; + return true; + } + + getResultCapture().benchmarkEnded( { { m_name }, m_count, elapsed } ); + return false; + } + +} // end namespace Catch +// end catch_benchmark.cpp +// start catch_capture_matchers.cpp + +namespace Catch { + + using StringMatcher = Matchers::Impl::MatcherBase; + + // This is the general overload that takes a any string matcher + // There is another overload, in catch_assertinhandler.h/.cpp, that only takes a string and infers + // the Equals matcher (so the header does not mention matchers) + void handleExceptionMatchExpr( AssertionHandler& handler, StringMatcher const& matcher, StringRef matcherString ) { + std::string exceptionMessage = Catch::translateActiveException(); + MatchExpr expr( exceptionMessage, matcher, matcherString ); + handler.handle( expr ); + } + +} // namespace Catch +// end catch_capture_matchers.cpp +// start catch_commandline.cpp + +// start catch_commandline.h + +// start catch_clara.h + +// Use Catch's value for console width (store Clara's off to the side, if present) +#ifdef CLARA_CONFIG_CONSOLE_WIDTH +#define CATCH_TEMP_CLARA_CONFIG_CONSOLE_WIDTH CATCH_CLARA_TEXTFLOW_CONFIG_CONSOLE_WIDTH +#undef CATCH_CLARA_TEXTFLOW_CONFIG_CONSOLE_WIDTH +#endif +#define CATCH_CLARA_TEXTFLOW_CONFIG_CONSOLE_WIDTH CATCH_CONFIG_CONSOLE_WIDTH-1 + +#ifdef __clang__ +#pragma clang diagnostic push +#pragma clang diagnostic ignored "-Wweak-vtables" +#pragma clang diagnostic ignored "-Wexit-time-destructors" +#pragma clang diagnostic ignored "-Wshadow" +#endif + +// start clara.hpp +// v1.0-develop.2 +// See https://github.com/philsquared/Clara + + +#ifndef CATCH_CLARA_CONFIG_CONSOLE_WIDTH +#define CATCH_CLARA_CONFIG_CONSOLE_WIDTH 80 +#endif + +#ifndef CATCH_CLARA_TEXTFLOW_CONFIG_CONSOLE_WIDTH +#define CATCH_CLARA_TEXTFLOW_CONFIG_CONSOLE_WIDTH CATCH_CLARA_CONFIG_CONSOLE_WIDTH +#endif + +// ----------- #included from clara_textflow.hpp ----------- + +// TextFlowCpp +// +// A single-header library for wrapping and laying out basic text, by Phil Nash +// +// This work is licensed under the BSD 2-Clause license. +// See the accompanying LICENSE file, or the one at https://opensource.org/licenses/BSD-2-Clause +// +// This project is hosted at https://github.com/philsquared/textflowcpp + + +#include +#include +#include +#include + +#ifndef CATCH_CLARA_TEXTFLOW_CONFIG_CONSOLE_WIDTH +#define CATCH_CLARA_TEXTFLOW_CONFIG_CONSOLE_WIDTH 80 +#endif + +namespace Catch { namespace clara { namespace TextFlow { + + inline auto isWhitespace( char c ) -> bool { + static std::string chars = " \t\n\r"; + return chars.find( c ) != std::string::npos; + } + inline auto isBreakableBefore( char c ) -> bool { + static std::string chars = "[({<|"; + return chars.find( c ) != std::string::npos; + } + inline auto isBreakableAfter( char c ) -> bool { + static std::string chars = "])}>.,:;*+-=&/\\"; + return chars.find( c ) != std::string::npos; + } + + class Columns; + + class Column { + std::vector m_strings; + size_t m_width = CATCH_CLARA_TEXTFLOW_CONFIG_CONSOLE_WIDTH; + size_t m_indent = 0; + size_t m_initialIndent = std::string::npos; + + public: + class iterator { + friend Column; + + Column const& m_column; + size_t m_stringIndex = 0; + size_t m_pos = 0; + + size_t m_len = 0; + size_t m_end = 0; + bool m_suffix = false; + + iterator( Column const& column, size_t stringIndex ) + : m_column( column ), + m_stringIndex( stringIndex ) + {} + + auto line() const -> std::string const& { return m_column.m_strings[m_stringIndex]; } + + auto isBoundary( size_t at ) const -> bool { + assert( at > 0 ); + assert( at <= line().size() ); + + return at == line().size() || + ( isWhitespace( line()[at] ) && !isWhitespace( line()[at-1] ) ) || + isBreakableBefore( line()[at] ) || + isBreakableAfter( line()[at-1] ); + } + + void calcLength() { + assert( m_stringIndex < m_column.m_strings.size() ); + + m_suffix = false; + auto width = m_column.m_width-indent(); + m_end = m_pos; + while( m_end < line().size() && line()[m_end] != '\n' ) + ++m_end; + + if( m_end < m_pos + width ) { + m_len = m_end - m_pos; + } + else { + size_t len = width; + while (len > 0 && !isBoundary(m_pos + len)) + --len; + while (len > 0 && isWhitespace( line()[m_pos + len - 1] )) + --len; + + if (len > 0) { + m_len = len; + } else { + m_suffix = true; + m_len = width - 1; + } + } + } + + auto indent() const -> size_t { + auto initial = m_pos == 0 && m_stringIndex == 0 ? m_column.m_initialIndent : std::string::npos; + return initial == std::string::npos ? m_column.m_indent : initial; + } + + auto addIndentAndSuffix(std::string const &plain) const -> std::string { + return std::string( indent(), ' ' ) + (m_suffix ? plain + "-" : plain); + } + + public: + explicit iterator( Column const& column ) : m_column( column ) { + assert( m_column.m_width > m_column.m_indent ); + assert( m_column.m_initialIndent == std::string::npos || m_column.m_width > m_column.m_initialIndent ); + calcLength(); + if( m_len == 0 ) + m_stringIndex++; // Empty string + } + + auto operator *() const -> std::string { + assert( m_stringIndex < m_column.m_strings.size() ); + assert( m_pos <= m_end ); + if( m_pos + m_column.m_width < m_end ) + return addIndentAndSuffix(line().substr(m_pos, m_len)); + else + return addIndentAndSuffix(line().substr(m_pos, m_end - m_pos)); + } + + auto operator ++() -> iterator& { + m_pos += m_len; + if( m_pos < line().size() && line()[m_pos] == '\n' ) + m_pos += 1; + else + while( m_pos < line().size() && isWhitespace( line()[m_pos] ) ) + ++m_pos; + + if( m_pos == line().size() ) { + m_pos = 0; + ++m_stringIndex; + } + if( m_stringIndex < m_column.m_strings.size() ) + calcLength(); + return *this; + } + auto operator ++(int) -> iterator { + iterator prev( *this ); + operator++(); + return prev; + } + + auto operator ==( iterator const& other ) const -> bool { + return + m_pos == other.m_pos && + m_stringIndex == other.m_stringIndex && + &m_column == &other.m_column; + } + auto operator !=( iterator const& other ) const -> bool { + return !operator==( other ); + } + }; + using const_iterator = iterator; + + explicit Column( std::string const& text ) { m_strings.push_back( text ); } + + auto width( size_t newWidth ) -> Column& { + assert( newWidth > 0 ); + m_width = newWidth; + return *this; + } + auto indent( size_t newIndent ) -> Column& { + m_indent = newIndent; + return *this; + } + auto initialIndent( size_t newIndent ) -> Column& { + m_initialIndent = newIndent; + return *this; + } + + auto width() const -> size_t { return m_width; } + auto begin() const -> iterator { return iterator( *this ); } + auto end() const -> iterator { return { *this, m_strings.size() }; } + + inline friend std::ostream& operator << ( std::ostream& os, Column const& col ) { + bool first = true; + for( auto line : col ) { + if( first ) + first = false; + else + os << "\n"; + os << line; + } + return os; + } + + auto operator + ( Column const& other ) -> Columns; + + auto toString() const -> std::string { + std::ostringstream oss; + oss << *this; + return oss.str(); + } + }; + + class Spacer : public Column { + + public: + explicit Spacer( size_t spaceWidth ) : Column( "" ) { + width( spaceWidth ); + } + }; + + class Columns { + std::vector m_columns; + + public: + + class iterator { + friend Columns; + struct EndTag {}; + + std::vector const& m_columns; + std::vector m_iterators; + size_t m_activeIterators; + + iterator( Columns const& columns, EndTag ) + : m_columns( columns.m_columns ), + m_activeIterators( 0 ) + { + m_iterators.reserve( m_columns.size() ); + + for( auto const& col : m_columns ) + m_iterators.push_back( col.end() ); + } + + public: + explicit iterator( Columns const& columns ) + : m_columns( columns.m_columns ), + m_activeIterators( m_columns.size() ) + { + m_iterators.reserve( m_columns.size() ); + + for( auto const& col : m_columns ) + m_iterators.push_back( col.begin() ); + } + + auto operator ==( iterator const& other ) const -> bool { + return m_iterators == other.m_iterators; + } + auto operator !=( iterator const& other ) const -> bool { + return m_iterators != other.m_iterators; + } + auto operator *() const -> std::string { + std::string row, padding; + + for( size_t i = 0; i < m_columns.size(); ++i ) { + auto width = m_columns[i].width(); + if( m_iterators[i] != m_columns[i].end() ) { + std::string col = *m_iterators[i]; + row += padding + col; + if( col.size() < width ) + padding = std::string( width - col.size(), ' ' ); + else + padding = ""; + } + else { + padding += std::string( width, ' ' ); + } + } + return row; + } + auto operator ++() -> iterator& { + for( size_t i = 0; i < m_columns.size(); ++i ) { + if (m_iterators[i] != m_columns[i].end()) + ++m_iterators[i]; + } + return *this; + } + auto operator ++(int) -> iterator { + iterator prev( *this ); + operator++(); + return prev; + } + }; + using const_iterator = iterator; + + auto begin() const -> iterator { return iterator( *this ); } + auto end() const -> iterator { return { *this, iterator::EndTag() }; } + + auto operator += ( Column const& col ) -> Columns& { + m_columns.push_back( col ); + return *this; + } + auto operator + ( Column const& col ) -> Columns { + Columns combined = *this; + combined += col; + return combined; + } + + inline friend std::ostream& operator << ( std::ostream& os, Columns const& cols ) { + + bool first = true; + for( auto line : cols ) { + if( first ) + first = false; + else + os << "\n"; + os << line; + } + return os; + } + + auto toString() const -> std::string { + std::ostringstream oss; + oss << *this; + return oss.str(); + } + }; + + inline auto Column::operator + ( Column const& other ) -> Columns { + Columns cols; + cols += *this; + cols += other; + return cols; + } +}}} // namespace Catch::clara::TextFlow + +// ----------- end of #include from clara_textflow.hpp ----------- +// ........... back in clara.hpp + +#include +#include +#include + +#if !defined(CATCH_PLATFORM_WINDOWS) && ( defined(WIN32) || defined(__WIN32__) || defined(_WIN32) || defined(_MSC_VER) ) +#define CATCH_PLATFORM_WINDOWS +#endif + +namespace Catch { namespace clara { +namespace detail { + + // Traits for extracting arg and return type of lambdas (for single argument lambdas) + template + struct UnaryLambdaTraits : UnaryLambdaTraits {}; + + template + struct UnaryLambdaTraits { + static const bool isValid = false; + }; + + template + struct UnaryLambdaTraits { + static const bool isValid = true; + using ArgType = typename std::remove_const::type>::type;; + using ReturnType = ReturnT; + }; + + class TokenStream; + + // Transport for raw args (copied from main args, or supplied via init list for testing) + class Args { + friend TokenStream; + std::string m_exeName; + std::vector m_args; + + public: + Args( int argc, char *argv[] ) { + m_exeName = argv[0]; + for( int i = 1; i < argc; ++i ) + m_args.push_back( argv[i] ); + } + + Args( std::initializer_list args ) + : m_exeName( *args.begin() ), + m_args( args.begin()+1, args.end() ) + {} + + auto exeName() const -> std::string { + return m_exeName; + } + }; + + // Wraps a token coming from a token stream. These may not directly correspond to strings as a single string + // may encode an option + its argument if the : or = form is used + enum class TokenType { + Option, Argument + }; + struct Token { + TokenType type; + std::string token; + }; + + inline auto isOptPrefix( char c ) -> bool { + return c == '-' +#ifdef CATCH_PLATFORM_WINDOWS + || c == '/' +#endif + ; + } + + // Abstracts iterators into args as a stream of tokens, with option arguments uniformly handled + class TokenStream { + using Iterator = std::vector::const_iterator; + Iterator it; + Iterator itEnd; + std::vector m_tokenBuffer; + + void loadBuffer() { + m_tokenBuffer.resize( 0 ); + + // Skip any empty strings + while( it != itEnd && it->empty() ) + ++it; + + if( it != itEnd ) { + auto const &next = *it; + if( isOptPrefix( next[0] ) ) { + auto delimiterPos = next.find_first_of( " :=" ); + if( delimiterPos != std::string::npos ) { + m_tokenBuffer.push_back( { TokenType::Option, next.substr( 0, delimiterPos ) } ); + m_tokenBuffer.push_back( { TokenType::Argument, next.substr( delimiterPos + 1 ) } ); + } else { + if( next[1] != '-' && next.size() > 2 ) { + std::string opt = "- "; + for( size_t i = 1; i < next.size(); ++i ) { + opt[1] = next[i]; + m_tokenBuffer.push_back( { TokenType::Option, opt } ); + } + } else { + m_tokenBuffer.push_back( { TokenType::Option, next } ); + } + } + } else { + m_tokenBuffer.push_back( { TokenType::Argument, next } ); + } + } + } + + public: + explicit TokenStream( Args const &args ) : TokenStream( args.m_args.begin(), args.m_args.end() ) {} + + TokenStream( Iterator it, Iterator itEnd ) : it( it ), itEnd( itEnd ) { + loadBuffer(); + } + + explicit operator bool() const { + return !m_tokenBuffer.empty() || it != itEnd; + } + + auto count() const -> size_t { return m_tokenBuffer.size() + (itEnd - it); } + + auto operator*() const -> Token { + assert( !m_tokenBuffer.empty() ); + return m_tokenBuffer.front(); + } + + auto operator->() const -> Token const * { + assert( !m_tokenBuffer.empty() ); + return &m_tokenBuffer.front(); + } + + auto operator++() -> TokenStream & { + if( m_tokenBuffer.size() >= 2 ) { + m_tokenBuffer.erase( m_tokenBuffer.begin() ); + } else { + if( it != itEnd ) + ++it; + loadBuffer(); + } + return *this; + } + }; + + class ResultBase { + public: + enum Type { + Ok, LogicError, RuntimeError + }; + + protected: + ResultBase( Type type ) : m_type( type ) {} + virtual ~ResultBase() = default; + + virtual void enforceOk() const = 0; + + Type m_type; + }; + + template + class ResultValueBase : public ResultBase { + public: + auto value() const -> T const & { + enforceOk(); + return m_value; + } + + protected: + ResultValueBase( Type type ) : ResultBase( type ) {} + + ResultValueBase( ResultValueBase const &other ) : ResultBase( other ) { + if( m_type == ResultBase::Ok ) + new( &m_value ) T( other.m_value ); + } + + ResultValueBase( Type, T const &value ) : ResultBase( Ok ) { + new( &m_value ) T( value ); + } + + auto operator=( ResultValueBase const &other ) -> ResultValueBase & { + if( m_type == ResultBase::Ok ) + m_value.~T(); + ResultBase::operator=(other); + if( m_type == ResultBase::Ok ) + new( &m_value ) T( other.m_value ); + return *this; + } + + ~ResultValueBase() { + if( m_type == Ok ) + m_value.~T(); + } + + union { + T m_value; + }; + }; + + template<> + class ResultValueBase : public ResultBase { + protected: + using ResultBase::ResultBase; + }; + + template + class BasicResult : public ResultValueBase { + public: + template + explicit BasicResult( BasicResult const &other ) + : ResultValueBase( other.type() ), + m_errorMessage( other.errorMessage() ) + { + assert( type() != ResultBase::Ok ); + } + + template + static auto ok( U const &value ) -> BasicResult { return { ResultBase::Ok, value }; } + static auto ok() -> BasicResult { return { ResultBase::Ok }; } + static auto logicError( std::string const &message ) -> BasicResult { return { ResultBase::LogicError, message }; } + static auto runtimeError( std::string const &message ) -> BasicResult { return { ResultBase::RuntimeError, message }; } + + explicit operator bool() const { return m_type == ResultBase::Ok; } + auto type() const -> ResultBase::Type { return m_type; } + auto errorMessage() const -> std::string { return m_errorMessage; } + + protected: + virtual void enforceOk() const { + // !TBD: If no exceptions, std::terminate here or something + switch( m_type ) { + case ResultBase::LogicError: + throw std::logic_error( m_errorMessage ); + case ResultBase::RuntimeError: + throw std::runtime_error( m_errorMessage ); + case ResultBase::Ok: + break; + } + } + + std::string m_errorMessage; // Only populated if resultType is an error + + BasicResult( ResultBase::Type type, std::string const &message ) + : ResultValueBase(type), + m_errorMessage(message) + { + assert( m_type != ResultBase::Ok ); + } + + using ResultValueBase::ResultValueBase; + using ResultBase::m_type; + }; + + enum class ParseResultType { + Matched, NoMatch, ShortCircuitAll, ShortCircuitSame + }; + + class ParseState { + public: + + ParseState( ParseResultType type, TokenStream const &remainingTokens ) + : m_type(type), + m_remainingTokens( remainingTokens ) + {} + + auto type() const -> ParseResultType { return m_type; } + auto remainingTokens() const -> TokenStream { return m_remainingTokens; } + + private: + ParseResultType m_type; + TokenStream m_remainingTokens; + }; + + using Result = BasicResult; + using ParserResult = BasicResult; + using InternalParseResult = BasicResult; + + struct HelpColumns { + std::string left; + std::string right; + }; + + template + inline auto convertInto( std::string const &source, T& target ) -> ParserResult { + std::stringstream ss; + ss << source; + ss >> target; + if( ss.fail() ) + return ParserResult::runtimeError( "Unable to convert '" + source + "' to destination type" ); + else + return ParserResult::ok( ParseResultType::Matched ); + } + inline auto convertInto( std::string const &source, std::string& target ) -> ParserResult { + target = source; + return ParserResult::ok( ParseResultType::Matched ); + } + inline auto convertInto( std::string const &source, bool &target ) -> ParserResult { + std::string srcLC = source; + std::transform( srcLC.begin(), srcLC.end(), srcLC.begin(), []( char c ) { return static_cast( ::tolower(c) ); } ); + if (srcLC == "y" || srcLC == "1" || srcLC == "true" || srcLC == "yes" || srcLC == "on") + target = true; + else if (srcLC == "n" || srcLC == "0" || srcLC == "false" || srcLC == "no" || srcLC == "off") + target = false; + else + return ParserResult::runtimeError( "Expected a boolean value but did not recognise: '" + source + "'" ); + return ParserResult::ok( ParseResultType::Matched ); + } + + struct BoundRefBase { + BoundRefBase() = default; + BoundRefBase( BoundRefBase const & ) = delete; + BoundRefBase( BoundRefBase && ) = delete; + BoundRefBase &operator=( BoundRefBase const & ) = delete; + BoundRefBase &operator=( BoundRefBase && ) = delete; + + virtual ~BoundRefBase() = default; + + virtual auto isFlag() const -> bool = 0; + virtual auto isContainer() const -> bool { return false; } + virtual auto setValue( std::string const &arg ) -> ParserResult = 0; + virtual auto setFlag( bool flag ) -> ParserResult = 0; + }; + + struct BoundValueRefBase : BoundRefBase { + auto isFlag() const -> bool override { return false; } + + auto setFlag( bool ) -> ParserResult override { + return ParserResult::logicError( "Flags can only be set on boolean fields" ); + } + }; + + struct BoundFlagRefBase : BoundRefBase { + auto isFlag() const -> bool override { return true; } + + auto setValue( std::string const &arg ) -> ParserResult override { + bool flag; + auto result = convertInto( arg, flag ); + if( result ) + setFlag( flag ); + return result; + } + }; + + template + struct BoundRef : BoundValueRefBase { + T &m_ref; + + explicit BoundRef( T &ref ) : m_ref( ref ) {} + + auto setValue( std::string const &arg ) -> ParserResult override { + return convertInto( arg, m_ref ); + } + }; + + template + struct BoundRef> : BoundValueRefBase { + std::vector &m_ref; + + explicit BoundRef( std::vector &ref ) : m_ref( ref ) {} + + auto isContainer() const -> bool override { return true; } + + auto setValue( std::string const &arg ) -> ParserResult override { + T temp; + auto result = convertInto( arg, temp ); + if( result ) + m_ref.push_back( temp ); + return result; + } + }; + + struct BoundFlagRef : BoundFlagRefBase { + bool &m_ref; + + explicit BoundFlagRef( bool &ref ) : m_ref( ref ) {} + + auto setFlag( bool flag ) -> ParserResult override { + m_ref = flag; + return ParserResult::ok( ParseResultType::Matched ); + } + }; + + template + struct LambdaInvoker { + static_assert( std::is_same::value, "Lambda must return void or clara::ParserResult" ); + + template + static auto invoke( L const &lambda, ArgType const &arg ) -> ParserResult { + return lambda( arg ); + } + }; + + template<> + struct LambdaInvoker { + template + static auto invoke( L const &lambda, ArgType const &arg ) -> ParserResult { + lambda( arg ); + return ParserResult::ok( ParseResultType::Matched ); + } + }; + + template + inline auto invokeLambda( L const &lambda, std::string const &arg ) -> ParserResult { + ArgType temp; + auto result = convertInto( arg, temp ); + return !result + ? result + : LambdaInvoker::ReturnType>::invoke( lambda, temp ); + }; + + template + struct BoundLambda : BoundValueRefBase { + L m_lambda; + + static_assert( UnaryLambdaTraits::isValid, "Supplied lambda must take exactly one argument" ); + explicit BoundLambda( L const &lambda ) : m_lambda( lambda ) {} + + auto setValue( std::string const &arg ) -> ParserResult override { + return invokeLambda::ArgType>( m_lambda, arg ); + } + }; + + template + struct BoundFlagLambda : BoundFlagRefBase { + L m_lambda; + + static_assert( UnaryLambdaTraits::isValid, "Supplied lambda must take exactly one argument" ); + static_assert( std::is_same::ArgType, bool>::value, "flags must be boolean" ); + + explicit BoundFlagLambda( L const &lambda ) : m_lambda( lambda ) {} + + auto setFlag( bool flag ) -> ParserResult override { + return LambdaInvoker::ReturnType>::invoke( m_lambda, flag ); + } + }; + + enum class Optionality { Optional, Required }; + + struct Parser; + + class ParserBase { + public: + virtual ~ParserBase() = default; + virtual auto validate() const -> Result { return Result::ok(); } + virtual auto parse( std::string const& exeName, TokenStream const &tokens) const -> InternalParseResult = 0; + virtual auto cardinality() const -> size_t { return 1; } + + auto parse( Args const &args ) const -> InternalParseResult { + return parse( args.exeName(), TokenStream( args ) ); + } + }; + + template + class ComposableParserImpl : public ParserBase { + public: + template + auto operator|( T const &other ) const -> Parser; + }; + + // Common code and state for Args and Opts + template + class ParserRefImpl : public ComposableParserImpl { + protected: + Optionality m_optionality = Optionality::Optional; + std::shared_ptr m_ref; + std::string m_hint; + std::string m_description; + + explicit ParserRefImpl( std::shared_ptr const &ref ) : m_ref( ref ) {} + + public: + template + ParserRefImpl( T &ref, std::string const &hint ) + : m_ref( std::make_shared>( ref ) ), + m_hint( hint ) + {} + + template + ParserRefImpl( LambdaT const &ref, std::string const &hint ) + : m_ref( std::make_shared>( ref ) ), + m_hint(hint) + {} + + auto operator()( std::string const &description ) -> DerivedT & { + m_description = description; + return static_cast( *this ); + } + + auto optional() -> DerivedT & { + m_optionality = Optionality::Optional; + return static_cast( *this ); + }; + + auto required() -> DerivedT & { + m_optionality = Optionality::Required; + return static_cast( *this ); + }; + + auto isOptional() const -> bool { + return m_optionality == Optionality::Optional; + } + + auto cardinality() const -> size_t override { + if( m_ref->isContainer() ) + return 0; + else + return 1; + } + + auto hint() const -> std::string { return m_hint; } + }; + + class ExeName : public ComposableParserImpl { + std::shared_ptr m_name; + std::shared_ptr m_ref; + + template + static auto makeRef(LambdaT const &lambda) -> std::shared_ptr { + return std::make_shared>( lambda) ; + } + + public: + ExeName() : m_name( std::make_shared( "" ) ) {} + + explicit ExeName( std::string &ref ) : ExeName() { + m_ref = std::make_shared>( ref ); + } + + template + explicit ExeName( LambdaT const& lambda ) : ExeName() { + m_ref = std::make_shared>( lambda ); + } + + // The exe name is not parsed out of the normal tokens, but is handled specially + auto parse( std::string const&, TokenStream const &tokens ) const -> InternalParseResult override { + return InternalParseResult::ok( ParseState( ParseResultType::NoMatch, tokens ) ); + } + + auto name() const -> std::string { return *m_name; } + auto set( std::string const& newName ) -> ParserResult { + + auto lastSlash = newName.find_last_of( "\\/" ); + auto filename = ( lastSlash == std::string::npos ) + ? newName + : newName.substr( lastSlash+1 ); + + *m_name = filename; + if( m_ref ) + return m_ref->setValue( filename ); + else + return ParserResult::ok( ParseResultType::Matched ); + } + }; + + class Arg : public ParserRefImpl { + public: + using ParserRefImpl::ParserRefImpl; + + auto parse( std::string const &, TokenStream const &tokens ) const -> InternalParseResult override { + auto validationResult = validate(); + if( !validationResult ) + return InternalParseResult( validationResult ); + + auto remainingTokens = tokens; + auto const &token = *remainingTokens; + if( token.type != TokenType::Argument ) + return InternalParseResult::ok( ParseState( ParseResultType::NoMatch, remainingTokens ) ); + + auto result = m_ref->setValue( remainingTokens->token ); + if( !result ) + return InternalParseResult( result ); + else + return InternalParseResult::ok( ParseState( ParseResultType::Matched, ++remainingTokens ) ); + } + }; + + inline auto normaliseOpt( std::string const &optName ) -> std::string { +#ifdef CATCH_PLATFORM_WINDOWS + if( optName[0] == '/' ) + return "-" + optName.substr( 1 ); + else +#endif + return optName; + } + + class Opt : public ParserRefImpl { + protected: + std::vector m_optNames; + + public: + template + explicit Opt( LambdaT const &ref ) : ParserRefImpl( std::make_shared>( ref ) ) {} + + explicit Opt( bool &ref ) : ParserRefImpl( std::make_shared( ref ) ) {} + + template + Opt( LambdaT const &ref, std::string const &hint ) : ParserRefImpl( ref, hint ) {} + + template + Opt( T &ref, std::string const &hint ) : ParserRefImpl( ref, hint ) {} + + auto operator[]( std::string const &optName ) -> Opt & { + m_optNames.push_back( optName ); + return *this; + } + + auto getHelpColumns() const -> std::vector { + std::ostringstream oss; + bool first = true; + for( auto const &opt : m_optNames ) { + if (first) + first = false; + else + oss << ", "; + oss << opt; + } + if( !m_hint.empty() ) + oss << " <" << m_hint << ">"; + return { { oss.str(), m_description } }; + } + + auto isMatch( std::string const &optToken ) const -> bool { + auto normalisedToken = normaliseOpt( optToken ); + for( auto const &name : m_optNames ) { + if( normaliseOpt( name ) == normalisedToken ) + return true; + } + return false; + } + + using ParserBase::parse; + + auto parse( std::string const&, TokenStream const &tokens ) const -> InternalParseResult override { + auto validationResult = validate(); + if( !validationResult ) + return InternalParseResult( validationResult ); + + auto remainingTokens = tokens; + if( remainingTokens && remainingTokens->type == TokenType::Option ) { + auto const &token = *remainingTokens; + if( isMatch(token.token ) ) { + if( m_ref->isFlag() ) { + auto result = m_ref->setFlag( true ); + if( !result ) + return InternalParseResult( result ); + if( result.value() == ParseResultType::ShortCircuitAll ) + return InternalParseResult::ok( ParseState( result.value(), remainingTokens ) ); + } else { + ++remainingTokens; + if( !remainingTokens ) + return InternalParseResult::runtimeError( "Expected argument following " + token.token ); + auto const &argToken = *remainingTokens; + if( argToken.type != TokenType::Argument ) + return InternalParseResult::runtimeError( "Expected argument following " + token.token ); + auto result = m_ref->setValue( argToken.token ); + if( !result ) + return InternalParseResult( result ); + if( result.value() == ParseResultType::ShortCircuitAll ) + return InternalParseResult::ok( ParseState( result.value(), remainingTokens ) ); + } + return InternalParseResult::ok( ParseState( ParseResultType::Matched, ++remainingTokens ) ); + } + } + return InternalParseResult::ok( ParseState( ParseResultType::NoMatch, remainingTokens ) ); + } + + auto validate() const -> Result override { + if( m_optNames.empty() ) + return Result::logicError( "No options supplied to Opt" ); + for( auto const &name : m_optNames ) { + if( name.empty() ) + return Result::logicError( "Option name cannot be empty" ); +#ifdef CATCH_PLATFORM_WINDOWS + if( name[0] != '-' && name[0] != '/' ) + return Result::logicError( "Option name must begin with '-' or '/'" ); +#else + if( name[0] != '-' ) + return Result::logicError( "Option name must begin with '-'" ); +#endif + } + return ParserRefImpl::validate(); + } + }; + + struct Help : Opt { + Help( bool &showHelpFlag ) + : Opt([&]( bool flag ) { + showHelpFlag = flag; + return ParserResult::ok( ParseResultType::ShortCircuitAll ); + }) + { + static_cast( *this ) + ("display usage information") + ["-?"]["-h"]["--help"] + .optional(); + } + }; + + struct Parser : ParserBase { + + mutable ExeName m_exeName; + std::vector m_options; + std::vector m_args; + + auto operator|=( ExeName const &exeName ) -> Parser & { + m_exeName = exeName; + return *this; + } + + auto operator|=( Arg const &arg ) -> Parser & { + m_args.push_back(arg); + return *this; + } + + auto operator|=( Opt const &opt ) -> Parser & { + m_options.push_back(opt); + return *this; + } + + auto operator|=( Parser const &other ) -> Parser & { + m_options.insert(m_options.end(), other.m_options.begin(), other.m_options.end()); + m_args.insert(m_args.end(), other.m_args.begin(), other.m_args.end()); + return *this; + } + + template + auto operator|( T const &other ) const -> Parser { + return Parser( *this ) |= other; + } + + auto getHelpColumns() const -> std::vector { + std::vector cols; + for (auto const &o : m_options) { + auto childCols = o.getHelpColumns(); + cols.insert( cols.end(), childCols.begin(), childCols.end() ); + } + return cols; + } + + void writeToStream( std::ostream &os ) const { + if (!m_exeName.name().empty()) { + os << "usage:\n" << " " << m_exeName.name() << " "; + bool required = true, first = true; + for( auto const &arg : m_args ) { + if (first) + first = false; + else + os << " "; + if( arg.isOptional() && required ) { + os << "["; + required = false; + } + os << "<" << arg.hint() << ">"; + if( arg.cardinality() == 0 ) + os << " ... "; + } + if( !required ) + os << "]"; + if( !m_options.empty() ) + os << " options"; + os << "\n\nwhere options are:" << std::endl; + } + + auto rows = getHelpColumns(); + size_t consoleWidth = CATCH_CLARA_CONFIG_CONSOLE_WIDTH; + size_t optWidth = 0; + for( auto const &cols : rows ) + optWidth = (std::max)(optWidth, cols.left.size() + 2); + + for( auto const &cols : rows ) { + auto row = + TextFlow::Column( cols.left ).width( optWidth ).indent( 2 ) + + TextFlow::Spacer(4) + + TextFlow::Column( cols.right ).width( consoleWidth - 7 - optWidth ); + os << row << std::endl; + } + } + + friend auto operator<<( std::ostream &os, Parser const &parser ) -> std::ostream& { + parser.writeToStream( os ); + return os; + } + + auto validate() const -> Result override { + for( auto const &opt : m_options ) { + auto result = opt.validate(); + if( !result ) + return result; + } + for( auto const &arg : m_args ) { + auto result = arg.validate(); + if( !result ) + return result; + } + return Result::ok(); + } + + using ParserBase::parse; + + auto parse( std::string const& exeName, TokenStream const &tokens ) const -> InternalParseResult override { + + struct ParserInfo { + ParserBase const* parser = nullptr; + size_t count = 0; + }; + const size_t totalParsers = m_options.size() + m_args.size(); + assert( totalParsers < 512 ); + // ParserInfo parseInfos[totalParsers]; // <-- this is what we really want to do + ParserInfo parseInfos[512]; + + { + size_t i = 0; + for (auto const &opt : m_options) parseInfos[i++].parser = &opt; + for (auto const &arg : m_args) parseInfos[i++].parser = &arg; + } + + m_exeName.set( exeName ); + + auto result = InternalParseResult::ok( ParseState( ParseResultType::NoMatch, tokens ) ); + while( result.value().remainingTokens() ) { + bool tokenParsed = false; + + for( size_t i = 0; i < totalParsers; ++i ) { + auto& parseInfo = parseInfos[i]; + if( parseInfo.parser->cardinality() == 0 || parseInfo.count < parseInfo.parser->cardinality() ) { + result = parseInfo.parser->parse(exeName, result.value().remainingTokens()); + if (!result) + return result; + if (result.value().type() != ParseResultType::NoMatch) { + tokenParsed = true; + ++parseInfo.count; + break; + } + } + } + + if( result.value().type() == ParseResultType::ShortCircuitAll ) + return result; + if( !tokenParsed ) + return InternalParseResult::runtimeError( "Unrecognised token: " + result.value().remainingTokens()->token ); + } + // !TBD Check missing required options + return result; + } + }; + + template + template + auto ComposableParserImpl::operator|( T const &other ) const -> Parser { + return Parser() | static_cast( *this ) | other; + } +} // namespace detail + +// A Combined parser +using detail::Parser; + +// A parser for options +using detail::Opt; + +// A parser for arguments +using detail::Arg; + +// Wrapper for argc, argv from main() +using detail::Args; + +// Specifies the name of the executable +using detail::ExeName; + +// Convenience wrapper for option parser that specifies the help option +using detail::Help; + +// enum of result types from a parse +using detail::ParseResultType; + +// Result type for parser operation +using detail::ParserResult; + +}} // namespace Catch::clara + +// end clara.hpp +#ifdef __clang__ +#pragma clang diagnostic pop +#endif + +// Restore Clara's value for console width, if present +#ifdef CATCH_TEMP_CLARA_CONFIG_CONSOLE_WIDTH +#define CATCH_CLARA_TEXTFLOW_CONFIG_CONSOLE_WIDTH CATCH_TEMP_CLARA_CONFIG_CONSOLE_WIDTH +#undef CATCH_TEMP_CLARA_CONFIG_CONSOLE_WIDTH +#endif + +// end catch_clara.h +namespace Catch { + + clara::Parser makeCommandLineParser( ConfigData& config ); + +} // end namespace Catch + +// end catch_commandline.h +#include +#include + +namespace Catch { + + clara::Parser makeCommandLineParser( ConfigData& config ) { + + using namespace clara; + + auto const setWarning = [&]( std::string const& warning ) { + if( warning != "NoAssertions" ) + return ParserResult::runtimeError( "Unrecognised warning: '" + warning + "'" ); + config.warnings = static_cast( config.warnings | WarnAbout::NoAssertions ); + return ParserResult::ok( ParseResultType::Matched ); + }; + auto const loadTestNamesFromFile = [&]( std::string const& filename ) { + std::ifstream f( filename.c_str() ); + if( !f.is_open() ) + return ParserResult::runtimeError( "Unable to load input file: '" + filename + "'" ); + + std::string line; + while( std::getline( f, line ) ) { + line = trim(line); + if( !line.empty() && !startsWith( line, '#' ) ) { + if( !startsWith( line, '"' ) ) + line = '"' + line + '"'; + config.testsOrTags.push_back( line + ',' ); + } + } + return ParserResult::ok( ParseResultType::Matched ); + }; + auto const setTestOrder = [&]( std::string const& order ) { + if( startsWith( "declared", order ) ) + config.runOrder = RunTests::InDeclarationOrder; + else if( startsWith( "lexical", order ) ) + config.runOrder = RunTests::InLexicographicalOrder; + else if( startsWith( "random", order ) ) + config.runOrder = RunTests::InRandomOrder; + else + return clara::ParserResult::runtimeError( "Unrecognised ordering: '" + order + "'" ); + return ParserResult::ok( ParseResultType::Matched ); + }; + auto const setRngSeed = [&]( std::string const& seed ) { + if( seed != "time" ) + return clara::detail::convertInto( seed, config.rngSeed ); + config.rngSeed = static_cast( std::time(nullptr) ); + return ParserResult::ok( ParseResultType::Matched ); + }; + auto const setColourUsage = [&]( std::string const& useColour ) { + auto mode = toLower( useColour ); + + if( mode == "yes" ) + config.useColour = UseColour::Yes; + else if( mode == "no" ) + config.useColour = UseColour::No; + else if( mode == "auto" ) + config.useColour = UseColour::Auto; + else + return ParserResult::runtimeError( "colour mode must be one of: auto, yes or no. '" + useColour + "' not recognised" ); + return ParserResult::ok( ParseResultType::Matched ); + }; + auto const setWaitForKeypress = [&]( std::string const& keypress ) { + auto keypressLc = toLower( keypress ); + if( keypressLc == "start" ) + config.waitForKeypress = WaitForKeypress::BeforeStart; + else if( keypressLc == "exit" ) + config.waitForKeypress = WaitForKeypress::BeforeExit; + else if( keypressLc == "both" ) + config.waitForKeypress = WaitForKeypress::BeforeStartAndExit; + else + return ParserResult::runtimeError( "keypress argument must be one of: start, exit or both. '" + keypress + "' not recognised" ); + return ParserResult::ok( ParseResultType::Matched ); + }; + auto const setVerbosity = [&]( std::string const& verbosity ) { + auto lcVerbosity = toLower( verbosity ); + if( lcVerbosity == "quiet" ) + config.verbosity = Verbosity::Quiet; + else if( lcVerbosity == "normal" ) + config.verbosity = Verbosity::Normal; + else if( lcVerbosity == "high" ) + config.verbosity = Verbosity::High; + else + return ParserResult::runtimeError( "Unrecognised verbosity, '" + verbosity + "'" ); + return ParserResult::ok( ParseResultType::Matched ); + }; + + auto cli + = ExeName( config.processName ) + | Help( config.showHelp ) + | Opt( config.listTests ) + ["-l"]["--list-tests"] + ( "list all/matching test cases" ) + | Opt( config.listTags ) + ["-t"]["--list-tags"] + ( "list all/matching tags" ) + | Opt( config.showSuccessfulTests ) + ["-s"]["--success"] + ( "include successful tests in output" ) + | Opt( config.shouldDebugBreak ) + ["-b"]["--break"] + ( "break into debugger on failure" ) + | Opt( config.noThrow ) + ["-e"]["--nothrow"] + ( "skip exception tests" ) + | Opt( config.showInvisibles ) + ["-i"]["--invisibles"] + ( "show invisibles (tabs, newlines)" ) + | Opt( config.outputFilename, "filename" ) + ["-o"]["--out"] + ( "output filename" ) + | Opt( config.reporterNames, "name" ) + ["-r"]["--reporter"] + ( "reporter to use (defaults to console)" ) + | Opt( config.name, "name" ) + ["-n"]["--name"] + ( "suite name" ) + | Opt( [&]( bool ){ config.abortAfter = 1; } ) + ["-a"]["--abort"] + ( "abort at first failure" ) + | Opt( [&]( int x ){ config.abortAfter = x; }, "no. failures" ) + ["-x"]["--abortx"] + ( "abort after x failures" ) + | Opt( setWarning, "warning name" ) + ["-w"]["--warn"] + ( "enable warnings" ) + | Opt( [&]( bool flag ) { config.showDurations = flag ? ShowDurations::Always : ShowDurations::Never; }, "yes|no" ) + ["-d"]["--durations"] + ( "show test durations" ) + | Opt( loadTestNamesFromFile, "filename" ) + ["-f"]["--input-file"] + ( "load test names to run from a file" ) + | Opt( config.filenamesAsTags ) + ["-#"]["--filenames-as-tags"] + ( "adds a tag for the filename" ) + | Opt( config.sectionsToRun, "section name" ) + ["-c"]["--section"] + ( "specify section to run" ) + | Opt( setVerbosity, "quiet|normal|high" ) + ["-v"]["--verbosity"] + ( "set output verbosity" ) + | Opt( config.listTestNamesOnly ) + ["--list-test-names-only"] + ( "list all/matching test cases names only" ) + | Opt( config.listReporters ) + ["--list-reporters"] + ( "list all reporters" ) + | Opt( setTestOrder, "decl|lex|rand" ) + ["--order"] + ( "test case order (defaults to decl)" ) + | Opt( setRngSeed, "'time'|number" ) + ["--rng-seed"] + ( "set a specific seed for random numbers" ) + | Opt( setColourUsage, "yes|no" ) + ["--use-colour"] + ( "should output be colourised" ) + | Opt( config.libIdentify ) + ["--libidentify"] + ( "report name and version according to libidentify standard" ) + | Opt( setWaitForKeypress, "start|exit|both" ) + ["--wait-for-keypress"] + ( "waits for a keypress before exiting" ) + | Opt( config.benchmarkResolutionMultiple, "multiplier" ) + ["--benchmark-resolution-multiple"] + ( "multiple of clock resolution to run benchmarks" ) + + | Arg( config.testsOrTags, "test name|pattern|tags" ) + ( "which test or tests to use" ); + + return cli; + } + +} // end namespace Catch +// end catch_commandline.cpp +// start catch_common.cpp + +#include +#include + +namespace Catch { + + SourceLineInfo::SourceLineInfo( char const* _file, std::size_t _line ) noexcept + : file( _file ), + line( _line ) + {} + bool SourceLineInfo::empty() const noexcept { + return file[0] == '\0'; + } + bool SourceLineInfo::operator == ( SourceLineInfo const& other ) const noexcept { + return line == other.line && (file == other.file || std::strcmp(file, other.file) == 0); + } + bool SourceLineInfo::operator < ( SourceLineInfo const& other ) const noexcept { + return line < other.line || ( line == other.line && (std::strcmp(file, other.file) < 0)); + } + + std::ostream& operator << ( std::ostream& os, SourceLineInfo const& info ) { +#ifndef __GNUG__ + os << info.file << '(' << info.line << ')'; +#else + os << info.file << ':' << info.line; +#endif + return os; + } + + bool isTrue( bool value ){ return value; } + bool alwaysTrue() { return true; } + bool alwaysFalse() { return false; } + + std::string StreamEndStop::operator+() const { + return std::string(); + } + + NonCopyable::NonCopyable() = default; + NonCopyable::~NonCopyable() = default; + +} +// end catch_common.cpp +// start catch_config.cpp + +namespace Catch { + + Config::Config( ConfigData const& data ) + : m_data( data ), + m_stream( openStream() ) + { + if( !data.testsOrTags.empty() ) { + TestSpecParser parser( ITagAliasRegistry::get() ); + for( auto const& testOrTags : data.testsOrTags ) + parser.parse( testOrTags ); + m_testSpec = parser.testSpec(); + } + } + + std::string const& Config::getFilename() const { + return m_data.outputFilename ; + } + + bool Config::listTests() const { return m_data.listTests; } + bool Config::listTestNamesOnly() const { return m_data.listTestNamesOnly; } + bool Config::listTags() const { return m_data.listTags; } + bool Config::listReporters() const { return m_data.listReporters; } + + std::string Config::getProcessName() const { return m_data.processName; } + + std::vector const& Config::getReporterNames() const { return m_data.reporterNames; } + std::vector const& Config::getSectionsToRun() const { return m_data.sectionsToRun; } + + TestSpec const& Config::testSpec() const { return m_testSpec; } + + bool Config::showHelp() const { return m_data.showHelp; } + + // IConfig interface + bool Config::allowThrows() const { return !m_data.noThrow; } + std::ostream& Config::stream() const { return m_stream->stream(); } + std::string Config::name() const { return m_data.name.empty() ? m_data.processName : m_data.name; } + bool Config::includeSuccessfulResults() const { return m_data.showSuccessfulTests; } + bool Config::warnAboutMissingAssertions() const { return m_data.warnings & WarnAbout::NoAssertions; } + ShowDurations::OrNot Config::showDurations() const { return m_data.showDurations; } + RunTests::InWhatOrder Config::runOrder() const { return m_data.runOrder; } + unsigned int Config::rngSeed() const { return m_data.rngSeed; } + int Config::benchmarkResolutionMultiple() const { return m_data.benchmarkResolutionMultiple; } + UseColour::YesOrNo Config::useColour() const { return m_data.useColour; } + bool Config::shouldDebugBreak() const { return m_data.shouldDebugBreak; } + int Config::abortAfter() const { return m_data.abortAfter; } + bool Config::showInvisibles() const { return m_data.showInvisibles; } + Verbosity Config::verbosity() const { return m_data.verbosity; } + + IStream const* Config::openStream() { + if( m_data.outputFilename.empty() ) + return new CoutStream(); + else if( m_data.outputFilename[0] == '%' ) { + if( m_data.outputFilename == "%debug" ) + return new DebugOutStream(); + else + CATCH_ERROR( "Unrecognised stream: '" << m_data.outputFilename << "'" ); + } + else + return new FileStream( m_data.outputFilename ); + } + +} // end namespace Catch +// end catch_config.cpp +// start catch_console_colour.cpp + +#if defined(__clang__) +# pragma clang diagnostic push +# pragma clang diagnostic ignored "-Wexit-time-destructors" +#endif + +// start catch_errno_guard.h + +namespace Catch { + + class ErrnoGuard { + public: + ErrnoGuard(); + ~ErrnoGuard(); + private: + int m_oldErrno; + }; + +} + +// end catch_errno_guard.h +// start catch_windows_h_proxy.h + + +#if defined(CATCH_PLATFORM_WINDOWS) + +#if !defined(NOMINMAX) && !defined(CATCH_CONFIG_NO_NOMINMAX) +# define CATCH_DEFINED_NOMINMAX +# define NOMINMAX +#endif +#if !defined(WIN32_LEAN_AND_MEAN) && !defined(CATCH_CONFIG_NO_WIN32_LEAN_AND_MEAN) +# define CATCH_DEFINED_WIN32_LEAN_AND_MEAN +# define WIN32_LEAN_AND_MEAN +#endif + +#ifdef __AFXDLL +#include +#else +#include +#endif + +#ifdef CATCH_DEFINED_NOMINMAX +# undef NOMINMAX +#endif +#ifdef CATCH_DEFINED_WIN32_LEAN_AND_MEAN +# undef WIN32_LEAN_AND_MEAN +#endif + +#endif // defined(CATCH_PLATFORM_WINDOWS) + +// end catch_windows_h_proxy.h +namespace Catch { + namespace { + + struct IColourImpl { + virtual ~IColourImpl() = default; + virtual void use( Colour::Code _colourCode ) = 0; + }; + + struct NoColourImpl : IColourImpl { + void use( Colour::Code ) {} + + static IColourImpl* instance() { + static NoColourImpl s_instance; + return &s_instance; + } + }; + + } // anon namespace +} // namespace Catch + +#if !defined( CATCH_CONFIG_COLOUR_NONE ) && !defined( CATCH_CONFIG_COLOUR_WINDOWS ) && !defined( CATCH_CONFIG_COLOUR_ANSI ) +# ifdef CATCH_PLATFORM_WINDOWS +# define CATCH_CONFIG_COLOUR_WINDOWS +# else +# define CATCH_CONFIG_COLOUR_ANSI +# endif +#endif + +#if defined ( CATCH_CONFIG_COLOUR_WINDOWS ) ///////////////////////////////////////// + +namespace Catch { +namespace { + + class Win32ColourImpl : public IColourImpl { + public: + Win32ColourImpl() : stdoutHandle( GetStdHandle(STD_OUTPUT_HANDLE) ) + { + CONSOLE_SCREEN_BUFFER_INFO csbiInfo; + GetConsoleScreenBufferInfo( stdoutHandle, &csbiInfo ); + originalForegroundAttributes = csbiInfo.wAttributes & ~( BACKGROUND_GREEN | BACKGROUND_RED | BACKGROUND_BLUE | BACKGROUND_INTENSITY ); + originalBackgroundAttributes = csbiInfo.wAttributes & ~( FOREGROUND_GREEN | FOREGROUND_RED | FOREGROUND_BLUE | FOREGROUND_INTENSITY ); + } + + virtual void use( Colour::Code _colourCode ) override { + switch( _colourCode ) { + case Colour::None: return setTextAttribute( originalForegroundAttributes ); + case Colour::White: return setTextAttribute( FOREGROUND_GREEN | FOREGROUND_RED | FOREGROUND_BLUE ); + case Colour::Red: return setTextAttribute( FOREGROUND_RED ); + case Colour::Green: return setTextAttribute( FOREGROUND_GREEN ); + case Colour::Blue: return setTextAttribute( FOREGROUND_BLUE ); + case Colour::Cyan: return setTextAttribute( FOREGROUND_BLUE | FOREGROUND_GREEN ); + case Colour::Yellow: return setTextAttribute( FOREGROUND_RED | FOREGROUND_GREEN ); + case Colour::Grey: return setTextAttribute( 0 ); + + case Colour::LightGrey: return setTextAttribute( FOREGROUND_INTENSITY ); + case Colour::BrightRed: return setTextAttribute( FOREGROUND_INTENSITY | FOREGROUND_RED ); + case Colour::BrightGreen: return setTextAttribute( FOREGROUND_INTENSITY | FOREGROUND_GREEN ); + case Colour::BrightWhite: return setTextAttribute( FOREGROUND_INTENSITY | FOREGROUND_GREEN | FOREGROUND_RED | FOREGROUND_BLUE ); + + case Colour::Bright: CATCH_INTERNAL_ERROR( "not a colour" ); + } + } + + private: + void setTextAttribute( WORD _textAttribute ) { + SetConsoleTextAttribute( stdoutHandle, _textAttribute | originalBackgroundAttributes ); + } + HANDLE stdoutHandle; + WORD originalForegroundAttributes; + WORD originalBackgroundAttributes; + }; + + IColourImpl* platformColourInstance() { + static Win32ColourImpl s_instance; + + IConfigPtr config = getCurrentContext().getConfig(); + UseColour::YesOrNo colourMode = config + ? config->useColour() + : UseColour::Auto; + if( colourMode == UseColour::Auto ) + colourMode = UseColour::Yes; + return colourMode == UseColour::Yes + ? &s_instance + : NoColourImpl::instance(); + } + +} // end anon namespace +} // end namespace Catch + +#elif defined( CATCH_CONFIG_COLOUR_ANSI ) ////////////////////////////////////// + +#include + +namespace Catch { +namespace { + + // use POSIX/ ANSI console terminal codes + // Thanks to Adam Strzelecki for original contribution + // (http://github.com/nanoant) + // https://github.com/philsquared/Catch/pull/131 + class PosixColourImpl : public IColourImpl { + public: + virtual void use( Colour::Code _colourCode ) override { + switch( _colourCode ) { + case Colour::None: + case Colour::White: return setColour( "[0m" ); + case Colour::Red: return setColour( "[0;31m" ); + case Colour::Green: return setColour( "[0;32m" ); + case Colour::Blue: return setColour( "[0;34m" ); + case Colour::Cyan: return setColour( "[0;36m" ); + case Colour::Yellow: return setColour( "[0;33m" ); + case Colour::Grey: return setColour( "[1;30m" ); + + case Colour::LightGrey: return setColour( "[0;37m" ); + case Colour::BrightRed: return setColour( "[1;31m" ); + case Colour::BrightGreen: return setColour( "[1;32m" ); + case Colour::BrightWhite: return setColour( "[1;37m" ); + + case Colour::Bright: CATCH_INTERNAL_ERROR( "not a colour" ); + } + } + static IColourImpl* instance() { + static PosixColourImpl s_instance; + return &s_instance; + } + + private: + void setColour( const char* _escapeCode ) { + Catch::cout() << '\033' << _escapeCode; + } + }; + + bool useColourOnPlatform() { + return +#ifdef CATCH_PLATFORM_MAC + !isDebuggerActive() && +#endif + isatty(STDOUT_FILENO); + } + IColourImpl* platformColourInstance() { + ErrnoGuard guard; + IConfigPtr config = getCurrentContext().getConfig(); + UseColour::YesOrNo colourMode = config + ? config->useColour() + : UseColour::Auto; + if( colourMode == UseColour::Auto ) + colourMode = useColourOnPlatform() + ? UseColour::Yes + : UseColour::No; + return colourMode == UseColour::Yes + ? PosixColourImpl::instance() + : NoColourImpl::instance(); + } + +} // end anon namespace +} // end namespace Catch + +#else // not Windows or ANSI /////////////////////////////////////////////// + +namespace Catch { + + static IColourImpl* platformColourInstance() { return NoColourImpl::instance(); } + +} // end namespace Catch + +#endif // Windows/ ANSI/ None + +namespace Catch { + + Colour::Colour( Code _colourCode ) { use( _colourCode ); } + Colour::Colour( Colour&& rhs ) noexcept { + m_moved = rhs.m_moved; + rhs.m_moved = true; + } + Colour& Colour::operator=( Colour&& rhs ) noexcept { + m_moved = rhs.m_moved; + rhs.m_moved = true; + return *this; + } + + Colour::~Colour(){ if( !m_moved ) use( None ); } + + void Colour::use( Code _colourCode ) { + static IColourImpl* impl = platformColourInstance(); + impl->use( _colourCode ); + } + + std::ostream& operator << ( std::ostream& os, Colour const& ) { + return os; + } + +} // end namespace Catch + +#if defined(__clang__) +# pragma clang diagnostic pop +#endif + +// end catch_console_colour.cpp +// start catch_context.cpp + +namespace Catch { + + class Context : public IMutableContext, NonCopyable { + + public: // IContext + virtual IResultCapture* getResultCapture() override { + return m_resultCapture; + } + virtual IRunner* getRunner() override { + return m_runner; + } + + virtual IConfigPtr getConfig() const override { + return m_config; + } + + virtual ~Context() override; + + public: // IMutableContext + virtual void setResultCapture( IResultCapture* resultCapture ) override { + m_resultCapture = resultCapture; + } + virtual void setRunner( IRunner* runner ) override { + m_runner = runner; + } + virtual void setConfig( IConfigPtr const& config ) override { + m_config = config; + } + + friend IMutableContext& getCurrentMutableContext(); + + private: + IConfigPtr m_config; + IRunner* m_runner = nullptr; + IResultCapture* m_resultCapture = nullptr; + }; + + namespace { + Context* currentContext = nullptr; + } + IMutableContext& getCurrentMutableContext() { + if( !currentContext ) + currentContext = new Context(); + return *currentContext; + } + IContext& getCurrentContext() { + return getCurrentMutableContext(); + } + + void cleanUpContext() { + delete currentContext; + currentContext = nullptr; + } + IContext::~IContext() = default; + IMutableContext::~IMutableContext() = default; + Context::~Context() = default; +} +// end catch_context.cpp +// start catch_debug_console.cpp + +// start catch_debug_console.h + +#include + +namespace Catch { + void writeToDebugConsole( std::string const& text ); +} + +// end catch_debug_console.h +#ifdef CATCH_PLATFORM_WINDOWS + + namespace Catch { + void writeToDebugConsole( std::string const& text ) { + ::OutputDebugStringA( text.c_str() ); + } + } +#else + namespace Catch { + void writeToDebugConsole( std::string const& text ) { + // !TBD: Need a version for Mac/ XCode and other IDEs + Catch::cout() << text; + } + } +#endif // Platform +// end catch_debug_console.cpp +// start catch_debugger.cpp + +#ifdef CATCH_PLATFORM_MAC + + #include + #include + #include + #include + #include + + namespace Catch { + + // The following function is taken directly from the following technical note: + // http://developer.apple.com/library/mac/#qa/qa2004/qa1361.html + + // Returns true if the current process is being debugged (either + // running under the debugger or has a debugger attached post facto). + bool isDebuggerActive(){ + + int mib[4]; + struct kinfo_proc info; + std::size_t size; + + // Initialize the flags so that, if sysctl fails for some bizarre + // reason, we get a predictable result. + + info.kp_proc.p_flag = 0; + + // Initialize mib, which tells sysctl the info we want, in this case + // we're looking for information about a specific process ID. + + mib[0] = CTL_KERN; + mib[1] = KERN_PROC; + mib[2] = KERN_PROC_PID; + mib[3] = getpid(); + + // Call sysctl. + + size = sizeof(info); + if( sysctl(mib, sizeof(mib) / sizeof(*mib), &info, &size, nullptr, 0) != 0 ) { + Catch::cerr() << "\n** Call to sysctl failed - unable to determine if debugger is active **\n" << std::endl; + return false; + } + + // We're being debugged if the P_TRACED flag is set. + + return ( (info.kp_proc.p_flag & P_TRACED) != 0 ); + } + } // namespace Catch + +#elif defined(CATCH_PLATFORM_LINUX) + #include + #include + + namespace Catch{ + // The standard POSIX way of detecting a debugger is to attempt to + // ptrace() the process, but this needs to be done from a child and not + // this process itself to still allow attaching to this process later + // if wanted, so is rather heavy. Under Linux we have the PID of the + // "debugger" (which doesn't need to be gdb, of course, it could also + // be strace, for example) in /proc/$PID/status, so just get it from + // there instead. + bool isDebuggerActive(){ + // Libstdc++ has a bug, where std::ifstream sets errno to 0 + // This way our users can properly assert over errno values + ErrnoGuard guard; + std::ifstream in("/proc/self/status"); + for( std::string line; std::getline(in, line); ) { + static const int PREFIX_LEN = 11; + if( line.compare(0, PREFIX_LEN, "TracerPid:\t") == 0 ) { + // We're traced if the PID is not 0 and no other PID starts + // with 0 digit, so it's enough to check for just a single + // character. + return line.length() > PREFIX_LEN && line[PREFIX_LEN] != '0'; + } + } + + return false; + } + } // namespace Catch +#elif defined(_MSC_VER) + extern "C" __declspec(dllimport) int __stdcall IsDebuggerPresent(); + namespace Catch { + bool isDebuggerActive() { + return IsDebuggerPresent() != 0; + } + } +#elif defined(__MINGW32__) + extern "C" __declspec(dllimport) int __stdcall IsDebuggerPresent(); + namespace Catch { + bool isDebuggerActive() { + return IsDebuggerPresent() != 0; + } + } +#else + namespace Catch { + bool isDebuggerActive() { return false; } + } +#endif // Platform +// end catch_debugger.cpp +// start catch_decomposer.cpp + +namespace Catch { + + ITransientExpression::~ITransientExpression() = default; + + void formatReconstructedExpression( std::ostream &os, std::string const& lhs, StringRef op, std::string const& rhs ) { + if( lhs.size() + rhs.size() < 40 && + lhs.find('\n') == std::string::npos && + rhs.find('\n') == std::string::npos ) + os << lhs << " " << op << " " << rhs; + else + os << lhs << "\n" << op << "\n" << rhs; + } +} +// end catch_decomposer.cpp +// start catch_errno_guard.cpp + +#include + +namespace Catch { + ErrnoGuard::ErrnoGuard():m_oldErrno(errno){} + ErrnoGuard::~ErrnoGuard() { errno = m_oldErrno; } +} +// end catch_errno_guard.cpp +// start catch_exception_translator_registry.cpp + +// start catch_exception_translator_registry.h + +#include +#include +#include + +namespace Catch { + + class ExceptionTranslatorRegistry : public IExceptionTranslatorRegistry { + public: + ~ExceptionTranslatorRegistry(); + virtual void registerTranslator( const IExceptionTranslator* translator ); + virtual std::string translateActiveException() const override; + std::string tryTranslators() const; + + private: + std::vector> m_translators; + }; +} + +// end catch_exception_translator_registry.h +#ifdef __OBJC__ +#import "Foundation/Foundation.h" +#endif + +namespace Catch { + + ExceptionTranslatorRegistry::~ExceptionTranslatorRegistry() { + } + + void ExceptionTranslatorRegistry::registerTranslator( const IExceptionTranslator* translator ) { + m_translators.push_back( std::unique_ptr( translator ) ); + } + + std::string ExceptionTranslatorRegistry::translateActiveException() const { + try { +#ifdef __OBJC__ + // In Objective-C try objective-c exceptions first + @try { + return tryTranslators(); + } + @catch (NSException *exception) { + return Catch::Detail::stringify( [exception description] ); + } +#else + return tryTranslators(); +#endif + } + catch( TestFailureException& ) { + std::rethrow_exception(std::current_exception()); + } + catch( std::exception& ex ) { + return ex.what(); + } + catch( std::string& msg ) { + return msg; + } + catch( const char* msg ) { + return msg; + } + catch(...) { + return "Unknown exception"; + } + } + + std::string ExceptionTranslatorRegistry::tryTranslators() const { + if( m_translators.empty() ) + std::rethrow_exception(std::current_exception()); + else + return m_translators[0]->translate( m_translators.begin()+1, m_translators.end() ); + } +} +// end catch_exception_translator_registry.cpp +// start catch_fatal_condition.cpp + +// start catch_fatal_condition.h + +#include + +#if defined ( CATCH_PLATFORM_WINDOWS ) ///////////////////////////////////////// + +# if !defined ( CATCH_CONFIG_WINDOWS_SEH ) + +namespace Catch { + struct FatalConditionHandler { + void reset(); + }; +} + +# else // CATCH_CONFIG_WINDOWS_SEH is defined + +namespace Catch { + + struct FatalConditionHandler { + + static LONG CALLBACK handleVectoredException(PEXCEPTION_POINTERS ExceptionInfo); + FatalConditionHandler(); + static void reset(); + ~FatalConditionHandler(); + + private: + static bool isSet; + static ULONG guaranteeSize; + static PVOID exceptionHandlerHandle; + }; + +} // namespace Catch + +# endif // CATCH_CONFIG_WINDOWS_SEH + +#else // Not Windows - assumed to be POSIX compatible ////////////////////////// + +# if !defined(CATCH_CONFIG_POSIX_SIGNALS) + +namespace Catch { + struct FatalConditionHandler { + void reset(); + }; +} + +# else // CATCH_CONFIG_POSIX_SIGNALS is defined + +#include + +namespace Catch { + + struct FatalConditionHandler { + + static bool isSet; + static struct sigaction oldSigActions[];// [sizeof(signalDefs) / sizeof(SignalDefs)]; + static stack_t oldSigStack; + static char altStackMem[]; + + static void handleSignal( int sig ); + + FatalConditionHandler(); + ~FatalConditionHandler(); + static void reset(); + }; + +} // namespace Catch + +# endif // CATCH_CONFIG_POSIX_SIGNALS + +#endif // not Windows + +// end catch_fatal_condition.h +namespace { + // Report the error condition + void reportFatal( char const * const message ) { + Catch::getCurrentContext().getResultCapture()->handleFatalErrorCondition( message ); + } +} + +#if defined ( CATCH_PLATFORM_WINDOWS ) ///////////////////////////////////////// + +# if !defined ( CATCH_CONFIG_WINDOWS_SEH ) + +namespace Catch { + void FatalConditionHandler::reset() {} +} + +# else // CATCH_CONFIG_WINDOWS_SEH is defined + +namespace Catch { + struct SignalDefs { DWORD id; const char* name; }; + + // There is no 1-1 mapping between signals and windows exceptions. + // Windows can easily distinguish between SO and SigSegV, + // but SigInt, SigTerm, etc are handled differently. + static SignalDefs signalDefs[] = { + { EXCEPTION_ILLEGAL_INSTRUCTION, "SIGILL - Illegal instruction signal" }, + { EXCEPTION_STACK_OVERFLOW, "SIGSEGV - Stack overflow" }, + { EXCEPTION_ACCESS_VIOLATION, "SIGSEGV - Segmentation violation signal" }, + { EXCEPTION_INT_DIVIDE_BY_ZERO, "Divide by zero error" }, + }; + + LONG CALLBACK FatalConditionHandler::handleVectoredException(PEXCEPTION_POINTERS ExceptionInfo) { + for (auto const& def : signalDefs) { + if (ExceptionInfo->ExceptionRecord->ExceptionCode == def.id) { + reportFatal(def.name); + } + } + // If its not an exception we care about, pass it along. + // This stops us from eating debugger breaks etc. + return EXCEPTION_CONTINUE_SEARCH; + } + + FatalConditionHandler::FatalConditionHandler() { + isSet = true; + // 32k seems enough for Catch to handle stack overflow, + // but the value was found experimentally, so there is no strong guarantee + guaranteeSize = 32 * 1024; + exceptionHandlerHandle = nullptr; + // Register as first handler in current chain + exceptionHandlerHandle = AddVectoredExceptionHandler(1, handleVectoredException); + // Pass in guarantee size to be filled + SetThreadStackGuarantee(&guaranteeSize); + } + + void FatalConditionHandler::reset() { + if (isSet) { + // Unregister handler and restore the old guarantee + RemoveVectoredExceptionHandler(exceptionHandlerHandle); + SetThreadStackGuarantee(&guaranteeSize); + exceptionHandlerHandle = nullptr; + isSet = false; + } + } + + FatalConditionHandler::~FatalConditionHandler() { + reset(); + } + +bool FatalConditionHandler::isSet = false; +ULONG FatalConditionHandler::guaranteeSize = 0; +PVOID FatalConditionHandler::exceptionHandlerHandle = nullptr; + +} // namespace Catch + +# endif // CATCH_CONFIG_WINDOWS_SEH + +#else // Not Windows - assumed to be POSIX compatible ////////////////////////// + +# if !defined(CATCH_CONFIG_POSIX_SIGNALS) + +namespace Catch { + void FatalConditionHandler::reset() {} +} + +# else // CATCH_CONFIG_POSIX_SIGNALS is defined + +#include + +namespace Catch { + + struct SignalDefs { + int id; + const char* name; + }; + static SignalDefs signalDefs[] = { + { SIGINT, "SIGINT - Terminal interrupt signal" }, + { SIGILL, "SIGILL - Illegal instruction signal" }, + { SIGFPE, "SIGFPE - Floating point error signal" }, + { SIGSEGV, "SIGSEGV - Segmentation violation signal" }, + { SIGTERM, "SIGTERM - Termination request signal" }, + { SIGABRT, "SIGABRT - Abort (abnormal termination) signal" } + }; + + void FatalConditionHandler::handleSignal( int sig ) { + char const * name = ""; + for (auto const& def : signalDefs) { + if (sig == def.id) { + name = def.name; + break; + } + } + reset(); + reportFatal(name); + raise( sig ); + } + + FatalConditionHandler::FatalConditionHandler() { + isSet = true; + stack_t sigStack; + sigStack.ss_sp = altStackMem; + sigStack.ss_size = SIGSTKSZ; + sigStack.ss_flags = 0; + sigaltstack(&sigStack, &oldSigStack); + struct sigaction sa = { }; + + sa.sa_handler = handleSignal; + sa.sa_flags = SA_ONSTACK; + for (std::size_t i = 0; i < sizeof(signalDefs)/sizeof(SignalDefs); ++i) { + sigaction(signalDefs[i].id, &sa, &oldSigActions[i]); + } + } + + FatalConditionHandler::~FatalConditionHandler() { + reset(); + } + + void FatalConditionHandler::reset() { + if( isSet ) { + // Set signals back to previous values -- hopefully nobody overwrote them in the meantime + for( std::size_t i = 0; i < sizeof(signalDefs)/sizeof(SignalDefs); ++i ) { + sigaction(signalDefs[i].id, &oldSigActions[i], nullptr); + } + // Return the old stack + sigaltstack(&oldSigStack, nullptr); + isSet = false; + } + } + + bool FatalConditionHandler::isSet = false; + struct sigaction FatalConditionHandler::oldSigActions[sizeof(signalDefs)/sizeof(SignalDefs)] = {}; + stack_t FatalConditionHandler::oldSigStack = {}; + char FatalConditionHandler::altStackMem[SIGSTKSZ] = {}; + +} // namespace Catch + +# endif // CATCH_CONFIG_POSIX_SIGNALS + +#endif // not Windows +// end catch_fatal_condition.cpp +// start catch_interfaces_capture.cpp + +namespace Catch { + IResultCapture::~IResultCapture() = default; +} +// end catch_interfaces_capture.cpp +// start catch_interfaces_config.cpp + +namespace Catch { + IConfig::~IConfig() = default; +} +// end catch_interfaces_config.cpp +// start catch_interfaces_exception.cpp + +namespace Catch { + IExceptionTranslator::~IExceptionTranslator() = default; + IExceptionTranslatorRegistry::~IExceptionTranslatorRegistry() = default; +} +// end catch_interfaces_exception.cpp +// start catch_interfaces_registry_hub.cpp + +namespace Catch { + IRegistryHub::~IRegistryHub() = default; + IMutableRegistryHub::~IMutableRegistryHub() = default; +} +// end catch_interfaces_registry_hub.cpp +// start catch_interfaces_reporter.cpp + +// start catch_reporter_multi.h + +namespace Catch { + + class MultipleReporters : public IStreamingReporter { + using Reporters = std::vector; + Reporters m_reporters; + + public: + void add( IStreamingReporterPtr&& reporter ); + + public: // IStreamingReporter + + ReporterPreferences getPreferences() const override; + + void noMatchingTestCases( std::string const& spec ) override; + + static std::set getSupportedVerbosities(); + + void benchmarkStarting( BenchmarkInfo const& benchmarkInfo ) override; + void benchmarkEnded( BenchmarkStats const& benchmarkStats ) override; + + void testRunStarting( TestRunInfo const& testRunInfo ) override; + void testGroupStarting( GroupInfo const& groupInfo ) override; + void testCaseStarting( TestCaseInfo const& testInfo ) override; + void sectionStarting( SectionInfo const& sectionInfo ) override; + void assertionStarting( AssertionInfo const& assertionInfo ) override; + + // The return value indicates if the messages buffer should be cleared: + bool assertionEnded( AssertionStats const& assertionStats ) override; + void sectionEnded( SectionStats const& sectionStats ) override; + void testCaseEnded( TestCaseStats const& testCaseStats ) override; + void testGroupEnded( TestGroupStats const& testGroupStats ) override; + void testRunEnded( TestRunStats const& testRunStats ) override; + + void skipTest( TestCaseInfo const& testInfo ) override; + bool isMulti() const override; + + }; + +} // end namespace Catch + +// end catch_reporter_multi.h +namespace Catch { + + ReporterConfig::ReporterConfig( IConfigPtr const& _fullConfig ) + : m_stream( &_fullConfig->stream() ), m_fullConfig( _fullConfig ) {} + + ReporterConfig::ReporterConfig( IConfigPtr const& _fullConfig, std::ostream& _stream ) + : m_stream( &_stream ), m_fullConfig( _fullConfig ) {} + + std::ostream& ReporterConfig::stream() const { return *m_stream; } + IConfigPtr ReporterConfig::fullConfig() const { return m_fullConfig; } + + TestRunInfo::TestRunInfo( std::string const& _name ) : name( _name ) {} + + GroupInfo::GroupInfo( std::string const& _name, + std::size_t _groupIndex, + std::size_t _groupsCount ) + : name( _name ), + groupIndex( _groupIndex ), + groupsCounts( _groupsCount ) + {} + + AssertionStats::AssertionStats( AssertionResult const& _assertionResult, + std::vector const& _infoMessages, + Totals const& _totals ) + : assertionResult( _assertionResult ), + infoMessages( _infoMessages ), + totals( _totals ) + { + assertionResult.m_resultData.lazyExpression.m_transientExpression = _assertionResult.m_resultData.lazyExpression.m_transientExpression; + + if( assertionResult.hasMessage() ) { + // Copy message into messages list. + // !TBD This should have been done earlier, somewhere + MessageBuilder builder( assertionResult.getTestMacroName(), assertionResult.getSourceInfo(), assertionResult.getResultType() ); + builder << assertionResult.getMessage(); + builder.m_info.message = builder.m_stream.str(); + + infoMessages.push_back( builder.m_info ); + } + } + + AssertionStats::~AssertionStats() = default; + + SectionStats::SectionStats( SectionInfo const& _sectionInfo, + Counts const& _assertions, + double _durationInSeconds, + bool _missingAssertions ) + : sectionInfo( _sectionInfo ), + assertions( _assertions ), + durationInSeconds( _durationInSeconds ), + missingAssertions( _missingAssertions ) + {} + + SectionStats::~SectionStats() = default; + + TestCaseStats::TestCaseStats( TestCaseInfo const& _testInfo, + Totals const& _totals, + std::string const& _stdOut, + std::string const& _stdErr, + bool _aborting ) + : testInfo( _testInfo ), + totals( _totals ), + stdOut( _stdOut ), + stdErr( _stdErr ), + aborting( _aborting ) + {} + + TestCaseStats::~TestCaseStats() = default; + + TestGroupStats::TestGroupStats( GroupInfo const& _groupInfo, + Totals const& _totals, + bool _aborting ) + : groupInfo( _groupInfo ), + totals( _totals ), + aborting( _aborting ) + {} + + TestGroupStats::TestGroupStats( GroupInfo const& _groupInfo ) + : groupInfo( _groupInfo ), + aborting( false ) + {} + + TestGroupStats::~TestGroupStats() = default; + + TestRunStats::TestRunStats( TestRunInfo const& _runInfo, + Totals const& _totals, + bool _aborting ) + : runInfo( _runInfo ), + totals( _totals ), + aborting( _aborting ) + {} + + TestRunStats::~TestRunStats() = default; + + void IStreamingReporter::fatalErrorEncountered( StringRef ) {} + bool IStreamingReporter::isMulti() const { return false; } + + IReporterFactory::~IReporterFactory() = default; + IReporterRegistry::~IReporterRegistry() = default; + + void addReporter( IStreamingReporterPtr& existingReporter, IStreamingReporterPtr&& additionalReporter ) { + + if( !existingReporter ) { + existingReporter = std::move( additionalReporter ); + return; + } + + MultipleReporters* multi = nullptr; + + if( existingReporter->isMulti() ) { + multi = static_cast( existingReporter.get() ); + } + else { + auto newMulti = std::unique_ptr( new MultipleReporters ); + newMulti->add( std::move( existingReporter ) ); + multi = newMulti.get(); + existingReporter = std::move( newMulti ); + } + multi->add( std::move( additionalReporter ) ); + } + +} // end namespace Catch +// end catch_interfaces_reporter.cpp +// start catch_interfaces_runner.cpp + +namespace Catch { + IRunner::~IRunner() = default; +} +// end catch_interfaces_runner.cpp +// start catch_interfaces_testcase.cpp + +namespace Catch { + ITestInvoker::~ITestInvoker() = default; + ITestCaseRegistry::~ITestCaseRegistry() = default; +} +// end catch_interfaces_testcase.cpp +// start catch_leak_detector.cpp + +namespace Catch { + +#ifdef CATCH_CONFIG_WINDOWS_CRTDBG +#include + + LeakDetector::LeakDetector() { + int flag = _CrtSetDbgFlag(_CRTDBG_REPORT_FLAG); + flag |= _CRTDBG_LEAK_CHECK_DF; + flag |= _CRTDBG_ALLOC_MEM_DF; + _CrtSetDbgFlag(flag); + _CrtSetReportMode(_CRT_WARN, _CRTDBG_MODE_FILE | _CRTDBG_MODE_DEBUG); + _CrtSetReportFile(_CRT_WARN, _CRTDBG_FILE_STDERR); + // Change this to leaking allocation's number to break there + _CrtSetBreakAlloc(-1); + } + +#else + + LeakDetector::LeakDetector(){} + +#endif + +} +// end catch_leak_detector.cpp +// start catch_list.cpp + +// start catch_list.h + +#include + +namespace Catch { + + std::size_t listTests( Config const& config ); + + std::size_t listTestsNamesOnly( Config const& config ); + + struct TagInfo { + void add( std::string const& spelling ); + std::string all() const; + + std::set spellings; + std::size_t count = 0; + }; + + std::size_t listTags( Config const& config ); + + std::size_t listReporters( Config const& /*config*/ ); + + Option list( Config const& config ); + +} // end namespace Catch + +// end catch_list.h +// start catch_text.h + +namespace Catch { + using namespace clara::TextFlow; +} + +// end catch_text.h +#include +#include +#include + +namespace Catch { + + std::size_t listTests( Config const& config ) { + TestSpec testSpec = config.testSpec(); + if( config.testSpec().hasFilters() ) + Catch::cout() << "Matching test cases:\n"; + else { + Catch::cout() << "All available test cases:\n"; + testSpec = TestSpecParser( ITagAliasRegistry::get() ).parse( "*" ).testSpec(); + } + + auto matchedTestCases = filterTests( getAllTestCasesSorted( config ), testSpec, config ); + for( auto const& testCaseInfo : matchedTestCases ) { + Colour::Code colour = testCaseInfo.isHidden() + ? Colour::SecondaryText + : Colour::None; + Colour colourGuard( colour ); + + Catch::cout() << Column( testCaseInfo.name ).initialIndent( 2 ).indent( 4 ) << "\n"; + if( config.verbosity() >= Verbosity::High ) { + Catch::cout() << Column( Catch::Detail::stringify( testCaseInfo.lineInfo ) ).indent(4) << std::endl; + std::string description = testCaseInfo.description; + if( description.empty() ) + description = "(NO DESCRIPTION)"; + Catch::cout() << Column( description ).indent(4) << std::endl; + } + if( !testCaseInfo.tags.empty() ) + Catch::cout() << Column( testCaseInfo.tagsAsString() ).indent( 6 ) << "\n"; + } + + if( !config.testSpec().hasFilters() ) + Catch::cout() << pluralise( matchedTestCases.size(), "test case" ) << '\n' << std::endl; + else + Catch::cout() << pluralise( matchedTestCases.size(), "matching test case" ) << '\n' << std::endl; + return matchedTestCases.size(); + } + + std::size_t listTestsNamesOnly( Config const& config ) { + TestSpec testSpec = config.testSpec(); + if( !config.testSpec().hasFilters() ) + testSpec = TestSpecParser( ITagAliasRegistry::get() ).parse( "*" ).testSpec(); + std::size_t matchedTests = 0; + std::vector matchedTestCases = filterTests( getAllTestCasesSorted( config ), testSpec, config ); + for( auto const& testCaseInfo : matchedTestCases ) { + matchedTests++; + if( startsWith( testCaseInfo.name, '#' ) ) + Catch::cout() << '"' << testCaseInfo.name << '"'; + else + Catch::cout() << testCaseInfo.name; + if ( config.verbosity() >= Verbosity::High ) + Catch::cout() << "\t@" << testCaseInfo.lineInfo; + Catch::cout() << std::endl; + } + return matchedTests; + } + + void TagInfo::add( std::string const& spelling ) { + ++count; + spellings.insert( spelling ); + } + + std::string TagInfo::all() const { + std::string out; + for( auto const& spelling : spellings ) + out += "[" + spelling + "]"; + return out; + } + + std::size_t listTags( Config const& config ) { + TestSpec testSpec = config.testSpec(); + if( config.testSpec().hasFilters() ) + Catch::cout() << "Tags for matching test cases:\n"; + else { + Catch::cout() << "All available tags:\n"; + testSpec = TestSpecParser( ITagAliasRegistry::get() ).parse( "*" ).testSpec(); + } + + std::map tagCounts; + + std::vector matchedTestCases = filterTests( getAllTestCasesSorted( config ), testSpec, config ); + for( auto const& testCase : matchedTestCases ) { + for( auto const& tagName : testCase.getTestCaseInfo().tags ) { + std::string lcaseTagName = toLower( tagName ); + auto countIt = tagCounts.find( lcaseTagName ); + if( countIt == tagCounts.end() ) + countIt = tagCounts.insert( std::make_pair( lcaseTagName, TagInfo() ) ).first; + countIt->second.add( tagName ); + } + } + + for( auto const& tagCount : tagCounts ) { + std::ostringstream oss; + oss << " " << std::setw(2) << tagCount.second.count << " "; + auto wrapper = Column( tagCount.second.all() ) + .initialIndent( 0 ) + .indent( oss.str().size() ) + .width( CATCH_CONFIG_CONSOLE_WIDTH-10 ); + Catch::cout() << oss.str() << wrapper << '\n'; + } + Catch::cout() << pluralise( tagCounts.size(), "tag" ) << '\n' << std::endl; + return tagCounts.size(); + } + + std::size_t listReporters( Config const& /*config*/ ) { + Catch::cout() << "Available reporters:\n"; + IReporterRegistry::FactoryMap const& factories = getRegistryHub().getReporterRegistry().getFactories(); + std::size_t maxNameLen = 0; + for( auto const& factoryKvp : factories ) + maxNameLen = (std::max)( maxNameLen, factoryKvp.first.size() ); + + for( auto const& factoryKvp : factories ) { + Catch::cout() + << Column( factoryKvp.first + ":" ) + .indent(2) + .width( 5+maxNameLen ) + + Column( factoryKvp.second->getDescription() ) + .initialIndent(0) + .indent(2) + .width( CATCH_CONFIG_CONSOLE_WIDTH - maxNameLen-8 ) + << "\n"; + } + Catch::cout() << std::endl; + return factories.size(); + } + + Option list( Config const& config ) { + Option listedCount; + if( config.listTests() ) + listedCount = listedCount.valueOr(0) + listTests( config ); + if( config.listTestNamesOnly() ) + listedCount = listedCount.valueOr(0) + listTestsNamesOnly( config ); + if( config.listTags() ) + listedCount = listedCount.valueOr(0) + listTags( config ); + if( config.listReporters() ) + listedCount = listedCount.valueOr(0) + listReporters( config ); + return listedCount; + } + +} // end namespace Catch +// end catch_list.cpp +// start catch_matchers.cpp + +namespace Catch { +namespace Matchers { + namespace Impl { + + std::string MatcherUntypedBase::toString() const { + if( m_cachedToString.empty() ) + m_cachedToString = describe(); + return m_cachedToString; + } + + MatcherUntypedBase::~MatcherUntypedBase() = default; + + } // namespace Impl +} // namespace Matchers + +using namespace Matchers; +using Matchers::Impl::MatcherBase; + +} // namespace Catch +// end catch_matchers.cpp +// start catch_matchers_string.cpp + +namespace Catch { +namespace Matchers { + + namespace StdString { + + CasedString::CasedString( std::string const& str, CaseSensitive::Choice caseSensitivity ) + : m_caseSensitivity( caseSensitivity ), + m_str( adjustString( str ) ) + {} + std::string CasedString::adjustString( std::string const& str ) const { + return m_caseSensitivity == CaseSensitive::No + ? toLower( str ) + : str; + } + std::string CasedString::caseSensitivitySuffix() const { + return m_caseSensitivity == CaseSensitive::No + ? " (case insensitive)" + : std::string(); + } + + StringMatcherBase::StringMatcherBase( std::string const& operation, CasedString const& comparator ) + : m_comparator( comparator ), + m_operation( operation ) { + } + + std::string StringMatcherBase::describe() const { + std::string description; + description.reserve(5 + m_operation.size() + m_comparator.m_str.size() + + m_comparator.caseSensitivitySuffix().size()); + description += m_operation; + description += ": \""; + description += m_comparator.m_str; + description += "\""; + description += m_comparator.caseSensitivitySuffix(); + return description; + } + + EqualsMatcher::EqualsMatcher( CasedString const& comparator ) : StringMatcherBase( "equals", comparator ) {} + + bool EqualsMatcher::match( std::string const& source ) const { + return m_comparator.adjustString( source ) == m_comparator.m_str; + } + + ContainsMatcher::ContainsMatcher( CasedString const& comparator ) : StringMatcherBase( "contains", comparator ) {} + + bool ContainsMatcher::match( std::string const& source ) const { + return contains( m_comparator.adjustString( source ), m_comparator.m_str ); + } + + StartsWithMatcher::StartsWithMatcher( CasedString const& comparator ) : StringMatcherBase( "starts with", comparator ) {} + + bool StartsWithMatcher::match( std::string const& source ) const { + return startsWith( m_comparator.adjustString( source ), m_comparator.m_str ); + } + + EndsWithMatcher::EndsWithMatcher( CasedString const& comparator ) : StringMatcherBase( "ends with", comparator ) {} + + bool EndsWithMatcher::match( std::string const& source ) const { + return endsWith( m_comparator.adjustString( source ), m_comparator.m_str ); + } + + } // namespace StdString + + StdString::EqualsMatcher Equals( std::string const& str, CaseSensitive::Choice caseSensitivity ) { + return StdString::EqualsMatcher( StdString::CasedString( str, caseSensitivity) ); + } + StdString::ContainsMatcher Contains( std::string const& str, CaseSensitive::Choice caseSensitivity ) { + return StdString::ContainsMatcher( StdString::CasedString( str, caseSensitivity) ); + } + StdString::EndsWithMatcher EndsWith( std::string const& str, CaseSensitive::Choice caseSensitivity ) { + return StdString::EndsWithMatcher( StdString::CasedString( str, caseSensitivity) ); + } + StdString::StartsWithMatcher StartsWith( std::string const& str, CaseSensitive::Choice caseSensitivity ) { + return StdString::StartsWithMatcher( StdString::CasedString( str, caseSensitivity) ); + } + +} // namespace Matchers +} // namespace Catch +// end catch_matchers_string.cpp +// start catch_message.cpp + +namespace Catch { + + MessageInfo::MessageInfo( std::string const& _macroName, + SourceLineInfo const& _lineInfo, + ResultWas::OfType _type ) + : macroName( _macroName ), + lineInfo( _lineInfo ), + type( _type ), + sequence( ++globalCount ) + {} + + bool MessageInfo::operator==( MessageInfo const& other ) const { + return sequence == other.sequence; + } + + bool MessageInfo::operator<( MessageInfo const& other ) const { + return sequence < other.sequence; + } + + // This may need protecting if threading support is added + unsigned int MessageInfo::globalCount = 0; + + //////////////////////////////////////////////////////////////////////////// + + Catch::MessageBuilder::MessageBuilder( std::string const& macroName, + SourceLineInfo const& lineInfo, + ResultWas::OfType type ) + :m_info(macroName, lineInfo, type) {} + + //////////////////////////////////////////////////////////////////////////// + + ScopedMessage::ScopedMessage( MessageBuilder const& builder ) + : m_info( builder.m_info ) + { + m_info.message = builder.m_stream.str(); + getResultCapture().pushScopedMessage( m_info ); + } + + ScopedMessage::~ScopedMessage() { + if ( !std::uncaught_exception() ){ + getResultCapture().popScopedMessage(m_info); + } + } + +} // end namespace Catch +// end catch_message.cpp +// start catch_random_number_generator.cpp + +// start catch_random_number_generator.h + +#include + +namespace Catch { + + struct IConfig; + + void seedRng( IConfig const& config ); + + unsigned int rngSeed(); + + struct RandomNumberGenerator { + using result_type = unsigned int; + + static constexpr result_type (min)() { return 0; } + static constexpr result_type (max)() { return 1000000; } + + result_type operator()( result_type n ) const; + result_type operator()() const; + + template + static void shuffle( V& vector ) { + RandomNumberGenerator rng; + std::shuffle( vector.begin(), vector.end(), rng ); + } + }; + +} + +// end catch_random_number_generator.h +#include + +namespace Catch { + + void seedRng( IConfig const& config ) { + if( config.rngSeed() != 0 ) + std::srand( config.rngSeed() ); + } + unsigned int rngSeed() { + return getCurrentContext().getConfig()->rngSeed(); + } + + RandomNumberGenerator::result_type RandomNumberGenerator::operator()( result_type n ) const { + return std::rand() % n; + } + RandomNumberGenerator::result_type RandomNumberGenerator::operator()() const { + return std::rand() % (max)(); + } + +} +// end catch_random_number_generator.cpp +// start catch_registry_hub.cpp + +// start catch_test_case_registry_impl.h + +#include +#include +#include +#include + +namespace Catch { + + class TestCase; + struct IConfig; + + std::vector sortTests( IConfig const& config, std::vector const& unsortedTestCases ); + bool matchTest( TestCase const& testCase, TestSpec const& testSpec, IConfig const& config ); + + void enforceNoDuplicateTestCases( std::vector const& functions ); + + std::vector filterTests( std::vector const& testCases, TestSpec const& testSpec, IConfig const& config ); + std::vector const& getAllTestCasesSorted( IConfig const& config ); + + class TestRegistry : public ITestCaseRegistry { + public: + virtual ~TestRegistry() = default; + + virtual void registerTest( TestCase const& testCase ); + + std::vector const& getAllTests() const override; + std::vector const& getAllTestsSorted( IConfig const& config ) const override; + + private: + std::vector m_functions; + mutable RunTests::InWhatOrder m_currentSortOrder = RunTests::InDeclarationOrder; + mutable std::vector m_sortedFunctions; + std::size_t m_unnamedCount = 0; + std::ios_base::Init m_ostreamInit; // Forces cout/ cerr to be initialised + }; + + /////////////////////////////////////////////////////////////////////////// + + class TestInvokerAsFunction : public ITestInvoker { + void(*m_testAsFunction)(); + public: + TestInvokerAsFunction( void(*testAsFunction)() ) noexcept; + + void invoke() const override; + }; + + std::string extractClassName( std::string const& classOrQualifiedMethodName ); + + /////////////////////////////////////////////////////////////////////////// + +} // end namespace Catch + +// end catch_test_case_registry_impl.h +// start catch_reporter_registry.h + +#include + +namespace Catch { + + class ReporterRegistry : public IReporterRegistry { + + public: + + ~ReporterRegistry() override; + + IStreamingReporterPtr create( std::string const& name, IConfigPtr const& config ) const override; + + void registerReporter( std::string const& name, IReporterFactoryPtr const& factory ); + void registerListener( IReporterFactoryPtr const& factory ); + + FactoryMap const& getFactories() const override; + Listeners const& getListeners() const override; + + private: + FactoryMap m_factories; + Listeners m_listeners; + }; +} + +// end catch_reporter_registry.h +// start catch_tag_alias_registry.h + +// start catch_tag_alias.h + +#include + +namespace Catch { + + struct TagAlias { + TagAlias(std::string const& _tag, SourceLineInfo _lineInfo); + + std::string tag; + SourceLineInfo lineInfo; + }; + +} // end namespace Catch + +// end catch_tag_alias.h +#include + +namespace Catch { + + class TagAliasRegistry : public ITagAliasRegistry { + public: + ~TagAliasRegistry() override; + TagAlias const* find( std::string const& alias ) const override; + std::string expandAliases( std::string const& unexpandedTestSpec ) const override; + void add( std::string const& alias, std::string const& tag, SourceLineInfo const& lineInfo ); + + private: + std::map m_registry; + }; + +} // end namespace Catch + +// end catch_tag_alias_registry.h +// start catch_startup_exception_registry.h + +#include +#include + +namespace Catch { + + class StartupExceptionRegistry { + public: + void add(std::exception_ptr const& exception) noexcept; + std::vector const& getExceptions() const noexcept; + private: + std::vector m_exceptions; + }; + +} // end namespace Catch + +// end catch_startup_exception_registry.h +namespace Catch { + + namespace { + + class RegistryHub : public IRegistryHub, public IMutableRegistryHub, + private NonCopyable { + + public: // IRegistryHub + RegistryHub() = default; + IReporterRegistry const& getReporterRegistry() const override { + return m_reporterRegistry; + } + ITestCaseRegistry const& getTestCaseRegistry() const override { + return m_testCaseRegistry; + } + IExceptionTranslatorRegistry& getExceptionTranslatorRegistry() override { + return m_exceptionTranslatorRegistry; + } + ITagAliasRegistry const& getTagAliasRegistry() const override { + return m_tagAliasRegistry; + } + StartupExceptionRegistry const& getStartupExceptionRegistry() const override { + return m_exceptionRegistry; + } + + public: // IMutableRegistryHub + void registerReporter( std::string const& name, IReporterFactoryPtr const& factory ) override { + m_reporterRegistry.registerReporter( name, factory ); + } + void registerListener( IReporterFactoryPtr const& factory ) override { + m_reporterRegistry.registerListener( factory ); + } + void registerTest( TestCase const& testInfo ) override { + m_testCaseRegistry.registerTest( testInfo ); + } + void registerTranslator( const IExceptionTranslator* translator ) override { + m_exceptionTranslatorRegistry.registerTranslator( translator ); + } + void registerTagAlias( std::string const& alias, std::string const& tag, SourceLineInfo const& lineInfo ) override { + m_tagAliasRegistry.add( alias, tag, lineInfo ); + } + void registerStartupException() noexcept override { + m_exceptionRegistry.add(std::current_exception()); + } + + private: + TestRegistry m_testCaseRegistry; + ReporterRegistry m_reporterRegistry; + ExceptionTranslatorRegistry m_exceptionTranslatorRegistry; + TagAliasRegistry m_tagAliasRegistry; + StartupExceptionRegistry m_exceptionRegistry; + }; + + // Single, global, instance + RegistryHub*& getTheRegistryHub() { + static RegistryHub* theRegistryHub = nullptr; + if( !theRegistryHub ) + theRegistryHub = new RegistryHub(); + return theRegistryHub; + } + } + + IRegistryHub& getRegistryHub() { + return *getTheRegistryHub(); + } + IMutableRegistryHub& getMutableRegistryHub() { + return *getTheRegistryHub(); + } + void cleanUp() { + delete getTheRegistryHub(); + getTheRegistryHub() = nullptr; + cleanUpContext(); + } + std::string translateActiveException() { + return getRegistryHub().getExceptionTranslatorRegistry().translateActiveException(); + } + +} // end namespace Catch +// end catch_registry_hub.cpp +// start catch_reporter_registry.cpp + +namespace Catch { + + ReporterRegistry::~ReporterRegistry() = default; + + IStreamingReporterPtr ReporterRegistry::create( std::string const& name, IConfigPtr const& config ) const { + auto it = m_factories.find( name ); + if( it == m_factories.end() ) + return nullptr; + return it->second->create( ReporterConfig( config ) ); + } + + void ReporterRegistry::registerReporter( std::string const& name, IReporterFactoryPtr const& factory ) { + m_factories.emplace(name, factory); + } + void ReporterRegistry::registerListener( IReporterFactoryPtr const& factory ) { + m_listeners.push_back( factory ); + } + + IReporterRegistry::FactoryMap const& ReporterRegistry::getFactories() const { + return m_factories; + } + IReporterRegistry::Listeners const& ReporterRegistry::getListeners() const { + return m_listeners; + } + +} +// end catch_reporter_registry.cpp +// start catch_result_type.cpp + +namespace Catch { + + bool isOk( ResultWas::OfType resultType ) { + return ( resultType & ResultWas::FailureBit ) == 0; + } + bool isJustInfo( int flags ) { + return flags == ResultWas::Info; + } + + ResultDisposition::Flags operator | ( ResultDisposition::Flags lhs, ResultDisposition::Flags rhs ) { + return static_cast( static_cast( lhs ) | static_cast( rhs ) ); + } + + bool shouldContinueOnFailure( int flags ) { return ( flags & ResultDisposition::ContinueOnFailure ) != 0; } + bool isFalseTest( int flags ) { return ( flags & ResultDisposition::FalseTest ) != 0; } + bool shouldSuppressFailure( int flags ) { return ( flags & ResultDisposition::SuppressFail ) != 0; } + +} // end namespace Catch +// end catch_result_type.cpp +// start catch_run_context.cpp +// start catch_run_context.h + +#include + +namespace Catch { + + struct IMutableContext; + + class StreamRedirect { + + public: + StreamRedirect(std::ostream& stream, std::string& targetString); + + ~StreamRedirect(); + + private: + std::ostream& m_stream; + std::streambuf* m_prevBuf; + std::ostringstream m_oss; + std::string& m_targetString; + }; + + // StdErr has two constituent streams in C++, std::cerr and std::clog + // This means that we need to redirect 2 streams into 1 to keep proper + // order of writes and cannot use StreamRedirect on its own + class StdErrRedirect { + public: + StdErrRedirect(std::string& targetString); + ~StdErrRedirect(); + private: + std::streambuf* m_cerrBuf; + std::streambuf* m_clogBuf; + std::ostringstream m_oss; + std::string& m_targetString; + }; + + /////////////////////////////////////////////////////////////////////////// + + class RunContext : public IResultCapture, public IRunner { + + public: + RunContext( RunContext const& ) = delete; + RunContext& operator =( RunContext const& ) = delete; + + explicit RunContext(IConfigPtr const& _config, IStreamingReporterPtr&& reporter); + + virtual ~RunContext(); + + void testGroupStarting(std::string const& testSpec, std::size_t groupIndex, std::size_t groupsCount); + void testGroupEnded(std::string const& testSpec, Totals const& totals, std::size_t groupIndex, std::size_t groupsCount); + + Totals runTest(TestCase const& testCase); + + IConfigPtr config() const; + IStreamingReporter& reporter() const; + + private: // IResultCapture + + void assertionStarting(AssertionInfo const& info) override; + void assertionEnded(AssertionResult const& result) override; + + bool sectionStarted( SectionInfo const& sectionInfo, Counts& assertions ) override; + bool testForMissingAssertions(Counts& assertions); + + void sectionEnded(SectionEndInfo const& endInfo) override; + void sectionEndedEarly(SectionEndInfo const& endInfo) override; + + void benchmarkStarting( BenchmarkInfo const& info ) override; + void benchmarkEnded( BenchmarkStats const& stats ) override; + + void pushScopedMessage(MessageInfo const& message) override; + void popScopedMessage(MessageInfo const& message) override; + + std::string getCurrentTestName() const override; + + const AssertionResult* getLastResult() const override; + + void exceptionEarlyReported() override; + + void handleFatalErrorCondition( StringRef message ) override; + + bool lastAssertionPassed() override; + + void assertionPassed() override; + + void assertionRun() override; + + public: + // !TBD We need to do this another way! + bool aborting() const override; + + private: + + void runCurrentTest(std::string& redirectedCout, std::string& redirectedCerr); + void invokeActiveTestCase(); + + private: + + void handleUnfinishedSections(); + + TestRunInfo m_runInfo; + IMutableContext& m_context; + TestCase const* m_activeTestCase = nullptr; + ITracker* m_testCaseTracker; + Option m_lastResult; + + IConfigPtr m_config; + Totals m_totals; + IStreamingReporterPtr m_reporter; + std::vector m_messages; + AssertionInfo m_lastAssertionInfo; + std::vector m_unfinishedSections; + std::vector m_activeSections; + TrackerContext m_trackerContext; + std::size_t m_prevPassed = 0; + bool m_shouldReportUnexpected = true; + }; + + IResultCapture& getResultCapture(); + +} // end namespace Catch + +// end catch_run_context.h + +#include +#include + +namespace Catch { + + StreamRedirect::StreamRedirect(std::ostream& stream, std::string& targetString) + : m_stream(stream), + m_prevBuf(stream.rdbuf()), + m_targetString(targetString) { + stream.rdbuf(m_oss.rdbuf()); + } + + StreamRedirect::~StreamRedirect() { + m_targetString += m_oss.str(); + m_stream.rdbuf(m_prevBuf); + } + + StdErrRedirect::StdErrRedirect(std::string & targetString) + :m_cerrBuf(cerr().rdbuf()), m_clogBuf(clog().rdbuf()), + m_targetString(targetString) { + cerr().rdbuf(m_oss.rdbuf()); + clog().rdbuf(m_oss.rdbuf()); + } + + StdErrRedirect::~StdErrRedirect() { + m_targetString += m_oss.str(); + cerr().rdbuf(m_cerrBuf); + clog().rdbuf(m_clogBuf); + } + + RunContext::RunContext(IConfigPtr const& _config, IStreamingReporterPtr&& reporter) + : m_runInfo(_config->name()), + m_context(getCurrentMutableContext()), + m_config(_config), + m_reporter(std::move(reporter)), + m_lastAssertionInfo{ "", SourceLineInfo("",0), "", ResultDisposition::Normal } + { + m_context.setRunner(this); + m_context.setConfig(m_config); + m_context.setResultCapture(this); + m_reporter->testRunStarting(m_runInfo); + } + + RunContext::~RunContext() { + m_reporter->testRunEnded(TestRunStats(m_runInfo, m_totals, aborting())); + } + + void RunContext::testGroupStarting(std::string const& testSpec, std::size_t groupIndex, std::size_t groupsCount) { + m_reporter->testGroupStarting(GroupInfo(testSpec, groupIndex, groupsCount)); + } + + void RunContext::testGroupEnded(std::string const& testSpec, Totals const& totals, std::size_t groupIndex, std::size_t groupsCount) { + m_reporter->testGroupEnded(TestGroupStats(GroupInfo(testSpec, groupIndex, groupsCount), totals, aborting())); + } + + Totals RunContext::runTest(TestCase const& testCase) { + Totals prevTotals = m_totals; + + std::string redirectedCout; + std::string redirectedCerr; + + TestCaseInfo testInfo = testCase.getTestCaseInfo(); + + m_reporter->testCaseStarting(testInfo); + + m_activeTestCase = &testCase; + + ITracker& rootTracker = m_trackerContext.startRun(); + assert(rootTracker.isSectionTracker()); + static_cast(rootTracker).addInitialFilters(m_config->getSectionsToRun()); + do { + m_trackerContext.startCycle(); + m_testCaseTracker = &SectionTracker::acquire(m_trackerContext, TestCaseTracking::NameAndLocation(testInfo.name, testInfo.lineInfo)); + runCurrentTest(redirectedCout, redirectedCerr); + } while (!m_testCaseTracker->isSuccessfullyCompleted() && !aborting()); + + Totals deltaTotals = m_totals.delta(prevTotals); + if (testInfo.expectedToFail() && deltaTotals.testCases.passed > 0) { + deltaTotals.assertions.failed++; + deltaTotals.testCases.passed--; + deltaTotals.testCases.failed++; + } + m_totals.testCases += deltaTotals.testCases; + m_reporter->testCaseEnded(TestCaseStats(testInfo, + deltaTotals, + redirectedCout, + redirectedCerr, + aborting())); + + m_activeTestCase = nullptr; + m_testCaseTracker = nullptr; + + return deltaTotals; + } + + IConfigPtr RunContext::config() const { + return m_config; + } + + IStreamingReporter& RunContext::reporter() const { + return *m_reporter; + } + + void RunContext::assertionStarting(AssertionInfo const& info) { + m_reporter->assertionStarting( info ); + } + void RunContext::assertionEnded(AssertionResult const & result) { + if (result.getResultType() == ResultWas::Ok) { + m_totals.assertions.passed++; + } else if (!result.isOk()) { + if( m_activeTestCase->getTestCaseInfo().okToFail() ) + m_totals.assertions.failedButOk++; + else + m_totals.assertions.failed++; + } + + // We have no use for the return value (whether messages should be cleared), because messages were made scoped + // and should be let to clear themselves out. + static_cast(m_reporter->assertionEnded(AssertionStats(result, m_messages, m_totals))); + + // Reset working state + m_lastAssertionInfo = { "", m_lastAssertionInfo.lineInfo, "{Unknown expression after the reported line}", m_lastAssertionInfo.resultDisposition }; + m_lastResult = result; + } + + bool RunContext::sectionStarted(SectionInfo const & sectionInfo, Counts & assertions) { + ITracker& sectionTracker = SectionTracker::acquire(m_trackerContext, TestCaseTracking::NameAndLocation(sectionInfo.name, sectionInfo.lineInfo)); + if (!sectionTracker.isOpen()) + return false; + m_activeSections.push_back(§ionTracker); + + m_lastAssertionInfo.lineInfo = sectionInfo.lineInfo; + + m_reporter->sectionStarting(sectionInfo); + + assertions = m_totals.assertions; + + return true; + } + + bool RunContext::testForMissingAssertions(Counts& assertions) { + if (assertions.total() != 0) + return false; + if (!m_config->warnAboutMissingAssertions()) + return false; + if (m_trackerContext.currentTracker().hasChildren()) + return false; + m_totals.assertions.failed++; + assertions.failed++; + return true; + } + + void RunContext::sectionEnded(SectionEndInfo const & endInfo) { + Counts assertions = m_totals.assertions - endInfo.prevAssertions; + bool missingAssertions = testForMissingAssertions(assertions); + + if (!m_activeSections.empty()) { + m_activeSections.back()->close(); + m_activeSections.pop_back(); + } + + m_reporter->sectionEnded(SectionStats(endInfo.sectionInfo, assertions, endInfo.durationInSeconds, missingAssertions)); + m_messages.clear(); + } + + void RunContext::sectionEndedEarly(SectionEndInfo const & endInfo) { + if (m_unfinishedSections.empty()) + m_activeSections.back()->fail(); + else + m_activeSections.back()->close(); + m_activeSections.pop_back(); + + m_unfinishedSections.push_back(endInfo); + } + void RunContext::benchmarkStarting( BenchmarkInfo const& info ) { + m_reporter->benchmarkStarting( info ); + } + void RunContext::benchmarkEnded( BenchmarkStats const& stats ) { + m_reporter->benchmarkEnded( stats ); + } + + void RunContext::pushScopedMessage(MessageInfo const & message) { + m_messages.push_back(message); + } + + void RunContext::popScopedMessage(MessageInfo const & message) { + m_messages.erase(std::remove(m_messages.begin(), m_messages.end(), message), m_messages.end()); + } + + std::string RunContext::getCurrentTestName() const { + return m_activeTestCase + ? m_activeTestCase->getTestCaseInfo().name + : std::string(); + } + + const AssertionResult * RunContext::getLastResult() const { + return &(*m_lastResult); + } + + void RunContext::exceptionEarlyReported() { + m_shouldReportUnexpected = false; + } + + void RunContext::handleFatalErrorCondition( StringRef message ) { + // First notify reporter that bad things happened + m_reporter->fatalErrorEncountered(message); + + // Don't rebuild the result -- the stringification itself can cause more fatal errors + // Instead, fake a result data. + AssertionResultData tempResult( ResultWas::FatalErrorCondition, { false } ); + tempResult.message = message; + AssertionResult result(m_lastAssertionInfo, tempResult); + + getResultCapture().assertionEnded(result); + + handleUnfinishedSections(); + + // Recreate section for test case (as we will lose the one that was in scope) + auto const& testCaseInfo = m_activeTestCase->getTestCaseInfo(); + SectionInfo testCaseSection(testCaseInfo.lineInfo, testCaseInfo.name, testCaseInfo.description); + + Counts assertions; + assertions.failed = 1; + SectionStats testCaseSectionStats(testCaseSection, assertions, 0, false); + m_reporter->sectionEnded(testCaseSectionStats); + + auto const& testInfo = m_activeTestCase->getTestCaseInfo(); + + Totals deltaTotals; + deltaTotals.testCases.failed = 1; + deltaTotals.assertions.failed = 1; + m_reporter->testCaseEnded(TestCaseStats(testInfo, + deltaTotals, + std::string(), + std::string(), + false)); + m_totals.testCases.failed++; + testGroupEnded(std::string(), m_totals, 1, 1); + m_reporter->testRunEnded(TestRunStats(m_runInfo, m_totals, false)); + } + + bool RunContext::lastAssertionPassed() { + return m_totals.assertions.passed == (m_prevPassed + 1); + } + + void RunContext::assertionPassed() { + ++m_totals.assertions.passed; + m_lastAssertionInfo.capturedExpression = "{Unknown expression after the reported line}"; + m_lastAssertionInfo.macroName = ""; + } + + void RunContext::assertionRun() { + m_prevPassed = m_totals.assertions.passed; + } + + bool RunContext::aborting() const { + return m_totals.assertions.failed == static_cast(m_config->abortAfter()); + } + + void RunContext::runCurrentTest(std::string & redirectedCout, std::string & redirectedCerr) { + auto const& testCaseInfo = m_activeTestCase->getTestCaseInfo(); + SectionInfo testCaseSection(testCaseInfo.lineInfo, testCaseInfo.name, testCaseInfo.description); + m_reporter->sectionStarting(testCaseSection); + Counts prevAssertions = m_totals.assertions; + double duration = 0; + m_shouldReportUnexpected = true; + try { + m_lastAssertionInfo = { "TEST_CASE", testCaseInfo.lineInfo, "", ResultDisposition::Normal }; + + seedRng(*m_config); + + Timer timer; + timer.start(); + if (m_reporter->getPreferences().shouldRedirectStdOut) { + StreamRedirect coutRedir(cout(), redirectedCout); + StdErrRedirect errRedir(redirectedCerr); + invokeActiveTestCase(); + } else { + invokeActiveTestCase(); + } + duration = timer.getElapsedSeconds(); + } catch (TestFailureException&) { + // This just means the test was aborted due to failure + } catch (...) { + // Under CATCH_CONFIG_FAST_COMPILE, unexpected exceptions under REQUIRE assertions + // are reported without translation at the point of origin. + if (m_shouldReportUnexpected) { + AssertionHandler + ( m_lastAssertionInfo.macroName, + m_lastAssertionInfo.lineInfo, + m_lastAssertionInfo.capturedExpression, + m_lastAssertionInfo.resultDisposition ).useActiveException(); + } + } + m_testCaseTracker->close(); + handleUnfinishedSections(); + m_messages.clear(); + + Counts assertions = m_totals.assertions - prevAssertions; + bool missingAssertions = testForMissingAssertions(assertions); + SectionStats testCaseSectionStats(testCaseSection, assertions, duration, missingAssertions); + m_reporter->sectionEnded(testCaseSectionStats); + } + + void RunContext::invokeActiveTestCase() { + FatalConditionHandler fatalConditionHandler; // Handle signals + m_activeTestCase->invoke(); + fatalConditionHandler.reset(); + } + + void RunContext::handleUnfinishedSections() { + // If sections ended prematurely due to an exception we stored their + // infos here so we can tear them down outside the unwind process. + for (auto it = m_unfinishedSections.rbegin(), + itEnd = m_unfinishedSections.rend(); + it != itEnd; + ++it) + sectionEnded(*it); + m_unfinishedSections.clear(); + } + + IResultCapture& getResultCapture() { + if (auto* capture = getCurrentContext().getResultCapture()) + return *capture; + else + CATCH_INTERNAL_ERROR("No result capture instance"); + } +} +// end catch_run_context.cpp +// start catch_section.cpp + +namespace Catch { + + Section::Section( SectionInfo const& info ) + : m_info( info ), + m_sectionIncluded( getResultCapture().sectionStarted( m_info, m_assertions ) ) + { + m_timer.start(); + } + +#if defined(_MSC_VER) +#pragma warning(push) +#pragma warning(disable:4996) // std::uncaught_exception is deprecated in C++17 +#endif + Section::~Section() { + if( m_sectionIncluded ) { + SectionEndInfo endInfo( m_info, m_assertions, m_timer.getElapsedSeconds() ); + if( std::uncaught_exception() ) + getResultCapture().sectionEndedEarly( endInfo ); + else + getResultCapture().sectionEnded( endInfo ); + } + } +#if defined(_MSC_VER) +#pragma warning(pop) +#endif + + // This indicates whether the section should be executed or not + Section::operator bool() const { + return m_sectionIncluded; + } + +} // end namespace Catch +// end catch_section.cpp +// start catch_section_info.cpp + +namespace Catch { + + SectionInfo::SectionInfo + ( SourceLineInfo const& _lineInfo, + std::string const& _name, + std::string const& _description ) + : name( _name ), + description( _description ), + lineInfo( _lineInfo ) + {} + + SectionEndInfo::SectionEndInfo( SectionInfo const& _sectionInfo, Counts const& _prevAssertions, double _durationInSeconds ) + : sectionInfo( _sectionInfo ), prevAssertions( _prevAssertions ), durationInSeconds( _durationInSeconds ) + {} + +} // end namespace Catch +// end catch_section_info.cpp +// start catch_session.cpp + +// start catch_session.h + +#include + +namespace Catch { + + class Session : NonCopyable { + public: + + Session(); + ~Session() override; + + void showHelp() const; + void libIdentify(); + + int applyCommandLine( int argc, char* argv[] ); + + void useConfigData( ConfigData const& configData ); + + int run( int argc, char* argv[] ); + #if defined(WIN32) && defined(UNICODE) + int run( int argc, wchar_t* const argv[] ); + #endif + int run(); + + clara::Parser const& cli() const; + void cli( clara::Parser const& newParser ); + ConfigData& configData(); + Config& config(); + private: + int runInternal(); + + clara::Parser m_cli; + ConfigData m_configData; + std::shared_ptr m_config; + bool m_startupExceptions = false; + }; + +} // end namespace Catch + +// end catch_session.h +// start catch_version.h + +#include + +namespace Catch { + + // Versioning information + struct Version { + Version( Version const& ) = delete; + Version& operator=( Version const& ) = delete; + Version( unsigned int _majorVersion, + unsigned int _minorVersion, + unsigned int _patchNumber, + char const * const _branchName, + unsigned int _buildNumber ); + + unsigned int const majorVersion; + unsigned int const minorVersion; + unsigned int const patchNumber; + + // buildNumber is only used if branchName is not null + char const * const branchName; + unsigned int const buildNumber; + + friend std::ostream& operator << ( std::ostream& os, Version const& version ); + }; + + Version const& libraryVersion(); +} + +// end catch_version.h +#include +#include + +namespace { + const int MaxExitCode = 255; + using Catch::IStreamingReporterPtr; + using Catch::IConfigPtr; + using Catch::Config; + + IStreamingReporterPtr createReporter(std::string const& reporterName, IConfigPtr const& config) { + auto reporter = Catch::getRegistryHub().getReporterRegistry().create(reporterName, config); + CATCH_ENFORCE(reporter, "No reporter registered with name: '" << reporterName << "'"); + + return reporter; + } + +#ifndef CATCH_CONFIG_DEFAULT_REPORTER +#define CATCH_CONFIG_DEFAULT_REPORTER "console" +#endif + + IStreamingReporterPtr makeReporter(std::shared_ptr const& config) { + auto const& reporterNames = config->getReporterNames(); + if (reporterNames.empty()) + return createReporter(CATCH_CONFIG_DEFAULT_REPORTER, config); + + IStreamingReporterPtr reporter; + for (auto const& name : reporterNames) + addReporter(reporter, createReporter(name, config)); + return reporter; + } + +#undef CATCH_CONFIG_DEFAULT_REPORTER + + void addListeners(IStreamingReporterPtr& reporters, IConfigPtr const& config) { + auto const& listeners = Catch::getRegistryHub().getReporterRegistry().getListeners(); + for (auto const& listener : listeners) + addReporter(reporters, listener->create(Catch::ReporterConfig(config))); + } + + Catch::Totals runTests(std::shared_ptr const& config) { + using namespace Catch; + IStreamingReporterPtr reporter = makeReporter(config); + addListeners(reporter, config); + + RunContext context(config, std::move(reporter)); + + Totals totals; + + context.testGroupStarting(config->name(), 1, 1); + + TestSpec testSpec = config->testSpec(); + if (!testSpec.hasFilters()) + testSpec = TestSpecParser(ITagAliasRegistry::get()).parse("~[.]").testSpec(); // All not hidden tests + + auto const& allTestCases = getAllTestCasesSorted(*config); + for (auto const& testCase : allTestCases) { + if (!context.aborting() && matchTest(testCase, testSpec, *config)) + totals += context.runTest(testCase); + else + context.reporter().skipTest(testCase); + } + + context.testGroupEnded(config->name(), totals, 1, 1); + return totals; + } + + void applyFilenamesAsTags(Catch::IConfig const& config) { + using namespace Catch; + auto& tests = const_cast&>(getAllTestCasesSorted(config)); + for (auto& testCase : tests) { + auto tags = testCase.tags; + + std::string filename = testCase.lineInfo.file; + auto lastSlash = filename.find_last_of("\\/"); + if (lastSlash != std::string::npos) { + filename.erase(0, lastSlash); + filename[0] = '#'; + } + + auto lastDot = filename.find_last_of('.'); + if (lastDot != std::string::npos) { + filename.erase(lastDot); + } + + tags.push_back(std::move(filename)); + setTags(testCase, tags); + } + } + +} + +namespace Catch { + + Session::Session() { + static bool alreadyInstantiated = false; + if( alreadyInstantiated ) { + try { CATCH_INTERNAL_ERROR( "Only one instance of Catch::Session can ever be used" ); } + catch(...) { getMutableRegistryHub().registerStartupException(); } + } + + const auto& exceptions = getRegistryHub().getStartupExceptionRegistry().getExceptions(); + if ( !exceptions.empty() ) { + m_startupExceptions = true; + Colour colourGuard( Colour::Red ); + Catch::cerr() << "Errors occured during startup!" << '\n'; + // iterate over all exceptions and notify user + for ( const auto& ex_ptr : exceptions ) { + try { + std::rethrow_exception(ex_ptr); + } catch ( std::exception const& ex ) { + Catch::cerr() << Column( ex.what() ).indent(2) << '\n'; + } + } + } + + alreadyInstantiated = true; + m_cli = makeCommandLineParser( m_configData ); + } + Session::~Session() { + Catch::cleanUp(); + } + + void Session::showHelp() const { + Catch::cout() + << "\nCatch v" << libraryVersion() << "\n" + << m_cli << std::endl + << "For more detailed usage please see the project docs\n" << std::endl; + } + void Session::libIdentify() { + Catch::cout() + << std::left << std::setw(16) << "description: " << "A Catch test executable\n" + << std::left << std::setw(16) << "category: " << "testframework\n" + << std::left << std::setw(16) << "framework: " << "Catch Test\n" + << std::left << std::setw(16) << "version: " << libraryVersion() << std::endl; + } + + int Session::applyCommandLine( int argc, char* argv[] ) { + if( m_startupExceptions ) + return 1; + + auto result = m_cli.parse( clara::Args( argc, argv ) ); + if( !result ) { + Catch::cerr() + << Colour( Colour::Red ) + << "\nError(s) in input:\n" + << Column( result.errorMessage() ).indent( 2 ) + << "\n\n"; + Catch::cerr() << "Run with -? for usage\n" << std::endl; + return MaxExitCode; + } + + if( m_configData.showHelp ) + showHelp(); + if( m_configData.libIdentify ) + libIdentify(); + m_config.reset(); + return 0; + } + + void Session::useConfigData( ConfigData const& configData ) { + m_configData = configData; + m_config.reset(); + } + + int Session::run( int argc, char* argv[] ) { + if( m_startupExceptions ) + return 1; + int returnCode = applyCommandLine( argc, argv ); + if( returnCode == 0 ) + returnCode = run(); + return returnCode; + } + +#if defined(WIN32) && defined(UNICODE) + int Session::run( int argc, wchar_t* const argv[] ) { + + char **utf8Argv = new char *[ argc ]; + + for ( int i = 0; i < argc; ++i ) { + int bufSize = WideCharToMultiByte( CP_UTF8, 0, argv[i], -1, NULL, 0, NULL, NULL ); + + utf8Argv[ i ] = new char[ bufSize ]; + + WideCharToMultiByte( CP_UTF8, 0, argv[i], -1, utf8Argv[i], bufSize, NULL, NULL ); + } + + int returnCode = run( argc, utf8Argv ); + + for ( int i = 0; i < argc; ++i ) + delete [] utf8Argv[ i ]; + + delete [] utf8Argv; + + return returnCode; + } +#endif + int Session::run() { + if( ( m_configData.waitForKeypress & WaitForKeypress::BeforeStart ) != 0 ) { + Catch::cout() << "...waiting for enter/ return before starting" << std::endl; + static_cast(std::getchar()); + } + int exitCode = runInternal(); + if( ( m_configData.waitForKeypress & WaitForKeypress::BeforeExit ) != 0 ) { + Catch::cout() << "...waiting for enter/ return before exiting, with code: " << exitCode << std::endl; + static_cast(std::getchar()); + } + return exitCode; + } + + clara::Parser const& Session::cli() const { + return m_cli; + } + void Session::cli( clara::Parser const& newParser ) { + m_cli = newParser; + } + ConfigData& Session::configData() { + return m_configData; + } + Config& Session::config() { + if( !m_config ) + m_config = std::make_shared( m_configData ); + return *m_config; + } + + int Session::runInternal() { + if( m_startupExceptions ) + return 1; + + if( m_configData.showHelp || m_configData.libIdentify ) + return 0; + + try + { + config(); // Force config to be constructed + + seedRng( *m_config ); + + if( m_configData.filenamesAsTags ) + applyFilenamesAsTags( *m_config ); + + // Handle list request + if( Option listed = list( config() ) ) + return static_cast( *listed ); + + return (std::min)( MaxExitCode, static_cast( runTests( m_config ).assertions.failed ) ); + } + catch( std::exception& ex ) { + Catch::cerr() << ex.what() << std::endl; + return MaxExitCode; + } + } + +} // end namespace Catch +// end catch_session.cpp +// start catch_startup_exception_registry.cpp + +namespace Catch { + void StartupExceptionRegistry::add( std::exception_ptr const& exception ) noexcept { + try { + m_exceptions.push_back(exception); + } + catch(...) { + // If we run out of memory during start-up there's really not a lot more we can do about it + std::terminate(); + } + } + + std::vector const& StartupExceptionRegistry::getExceptions() const noexcept { + return m_exceptions; + } + +} // end namespace Catch +// end catch_startup_exception_registry.cpp +// start catch_stream.cpp + +#include +#include +#include + +namespace Catch { + + template + class StreamBufImpl : public StreamBufBase { + char data[bufferSize]; + WriterF m_writer; + + public: + StreamBufImpl() { + setp( data, data + sizeof(data) ); + } + + ~StreamBufImpl() noexcept { + StreamBufImpl::sync(); + } + + private: + int overflow( int c ) override { + sync(); + + if( c != EOF ) { + if( pbase() == epptr() ) + m_writer( std::string( 1, static_cast( c ) ) ); + else + sputc( static_cast( c ) ); + } + return 0; + } + + int sync() override { + if( pbase() != pptr() ) { + m_writer( std::string( pbase(), static_cast( pptr() - pbase() ) ) ); + setp( pbase(), epptr() ); + } + return 0; + } + }; + + /////////////////////////////////////////////////////////////////////////// + + Catch::IStream::~IStream() = default; + + FileStream::FileStream( std::string const& filename ) { + m_ofs.open( filename.c_str() ); + CATCH_ENFORCE( !m_ofs.fail(), "Unable to open file: '" << filename << "'" ); + } + + std::ostream& FileStream::stream() const { + return m_ofs; + } + + struct OutputDebugWriter { + + void operator()( std::string const&str ) { + writeToDebugConsole( str ); + } + }; + + DebugOutStream::DebugOutStream() + : m_streamBuf( new StreamBufImpl() ), + m_os( m_streamBuf.get() ) + {} + + std::ostream& DebugOutStream::stream() const { + return m_os; + } + + // Store the streambuf from cout up-front because + // cout may get redirected when running tests + CoutStream::CoutStream() + : m_os( Catch::cout().rdbuf() ) + {} + + std::ostream& CoutStream::stream() const { + return m_os; + } + +#ifndef CATCH_CONFIG_NOSTDOUT // If you #define this you must implement these functions + std::ostream& cout() { + return std::cout; + } + std::ostream& cerr() { + return std::cerr; + } + std::ostream& clog() { + return std::clog; + } +#endif +} +// end catch_stream.cpp +// start catch_streambuf.cpp + +namespace Catch { + StreamBufBase::~StreamBufBase() = default; +} +// end catch_streambuf.cpp +// start catch_string_manip.cpp + +#include +#include +#include +#include + +namespace Catch { + + bool startsWith( std::string const& s, std::string const& prefix ) { + return s.size() >= prefix.size() && std::equal(prefix.begin(), prefix.end(), s.begin()); + } + bool startsWith( std::string const& s, char prefix ) { + return !s.empty() && s[0] == prefix; + } + bool endsWith( std::string const& s, std::string const& suffix ) { + return s.size() >= suffix.size() && std::equal(suffix.rbegin(), suffix.rend(), s.rbegin()); + } + bool endsWith( std::string const& s, char suffix ) { + return !s.empty() && s[s.size()-1] == suffix; + } + bool contains( std::string const& s, std::string const& infix ) { + return s.find( infix ) != std::string::npos; + } + char toLowerCh(char c) { + return static_cast( std::tolower( c ) ); + } + void toLowerInPlace( std::string& s ) { + std::transform( s.begin(), s.end(), s.begin(), toLowerCh ); + } + std::string toLower( std::string const& s ) { + std::string lc = s; + toLowerInPlace( lc ); + return lc; + } + std::string trim( std::string const& str ) { + static char const* whitespaceChars = "\n\r\t "; + std::string::size_type start = str.find_first_not_of( whitespaceChars ); + std::string::size_type end = str.find_last_not_of( whitespaceChars ); + + return start != std::string::npos ? str.substr( start, 1+end-start ) : std::string(); + } + + bool replaceInPlace( std::string& str, std::string const& replaceThis, std::string const& withThis ) { + bool replaced = false; + std::size_t i = str.find( replaceThis ); + while( i != std::string::npos ) { + replaced = true; + str = str.substr( 0, i ) + withThis + str.substr( i+replaceThis.size() ); + if( i < str.size()-withThis.size() ) + i = str.find( replaceThis, i+withThis.size() ); + else + i = std::string::npos; + } + return replaced; + } + + pluralise::pluralise( std::size_t count, std::string const& label ) + : m_count( count ), + m_label( label ) + {} + + std::ostream& operator << ( std::ostream& os, pluralise const& pluraliser ) { + os << pluraliser.m_count << ' ' << pluraliser.m_label; + if( pluraliser.m_count != 1 ) + os << 's'; + return os; + } + +} +// end catch_string_manip.cpp +// start catch_stringref.cpp + +#if defined(__clang__) +# pragma clang diagnostic push +# pragma clang diagnostic ignored "-Wexit-time-destructors" +#endif + +#include +#include +#include + +namespace Catch { + + auto getEmptyStringRef() -> StringRef { + static StringRef s_emptyStringRef(""); + return s_emptyStringRef; + } + + StringRef::StringRef() noexcept + : StringRef( getEmptyStringRef() ) + {} + + StringRef::StringRef( StringRef const& other ) noexcept + : m_start( other.m_start ), + m_size( other.m_size ) + {} + + StringRef::StringRef( StringRef&& other ) noexcept + : m_start( other.m_start ), + m_size( other.m_size ), + m_data( other.m_data ) + { + other.m_data = nullptr; + } + + StringRef::StringRef( char const* rawChars ) noexcept + : m_start( rawChars ), + m_size( static_cast( std::strlen( rawChars ) ) ) + { + assert( rawChars != nullptr ); + } + + StringRef::StringRef( char const* rawChars, size_type size ) noexcept + : m_start( rawChars ), + m_size( size ) + { + size_type rawSize = rawChars == nullptr ? 0 : static_cast( std::strlen( rawChars ) ); + if( rawSize < size ) + m_size = rawSize; + } + + StringRef::StringRef( std::string const& stdString ) noexcept + : m_start( stdString.c_str() ), + m_size( stdString.size() ) + {} + + StringRef::~StringRef() noexcept { + delete[] m_data; + } + + auto StringRef::operator = ( StringRef other ) noexcept -> StringRef& { + swap( other ); + return *this; + } + StringRef::operator std::string() const { + return std::string( m_start, m_size ); + } + + void StringRef::swap( StringRef& other ) noexcept { + std::swap( m_start, other.m_start ); + std::swap( m_size, other.m_size ); + std::swap( m_data, other.m_data ); + } + + auto StringRef::c_str() const -> char const* { + if( isSubstring() ) + const_cast( this )->takeOwnership(); + return m_start; + } + auto StringRef::data() const noexcept -> char const* { + return m_start; + } + + auto StringRef::isOwned() const noexcept -> bool { + return m_data != nullptr; + } + auto StringRef::isSubstring() const noexcept -> bool { + return m_start[m_size] != '\0'; + } + + void StringRef::takeOwnership() { + if( !isOwned() ) { + m_data = new char[m_size+1]; + memcpy( m_data, m_start, m_size ); + m_data[m_size] = '\0'; + m_start = m_data; + } + } + auto StringRef::substr( size_type start, size_type size ) const noexcept -> StringRef { + if( start < m_size ) + return StringRef( m_start+start, size ); + else + return StringRef(); + } + auto StringRef::operator == ( StringRef const& other ) const noexcept -> bool { + return + size() == other.size() && + (std::strncmp( m_start, other.m_start, size() ) == 0); + } + auto StringRef::operator != ( StringRef const& other ) const noexcept -> bool { + return !operator==( other ); + } + + auto StringRef::operator[](size_type index) const noexcept -> char { + return m_start[index]; + } + + auto StringRef::empty() const noexcept -> bool { + return m_size == 0; + } + + auto StringRef::size() const noexcept -> size_type { + return m_size; + } + auto StringRef::numberOfCharacters() const noexcept -> size_type { + size_type noChars = m_size; + // Make adjustments for uft encodings + for( size_type i=0; i < m_size; ++i ) { + char c = m_start[i]; + if( ( c & 0b11000000 ) == 0b11000000 ) { + if( ( c & 0b11100000 ) == 0b11000000 ) + noChars--; + else if( ( c & 0b11110000 ) == 0b11100000 ) + noChars-=2; + else if( ( c & 0b11111000 ) == 0b11110000 ) + noChars-=3; + } + } + return noChars; + } + + auto operator + ( StringRef const& lhs, StringRef const& rhs ) -> std::string { + std::string str; + str.reserve( lhs.size() + rhs.size() ); + str += lhs; + str += rhs; + return str; + } + auto operator + ( StringRef const& lhs, const char* rhs ) -> std::string { + return std::string( lhs ) + std::string( rhs ); + } + auto operator + ( char const* lhs, StringRef const& rhs ) -> std::string { + return std::string( lhs ) + std::string( rhs ); + } + + auto operator << ( std::ostream& os, StringRef const& str ) -> std::ostream& { + return os << str.c_str(); + } + +} // namespace Catch + +#if defined(__clang__) +# pragma clang diagnostic pop +#endif +// end catch_stringref.cpp +// start catch_tag_alias.cpp + +namespace Catch { + TagAlias::TagAlias(std::string const & _tag, SourceLineInfo _lineInfo): tag(_tag), lineInfo(_lineInfo) {} +} +// end catch_tag_alias.cpp +// start catch_tag_alias_autoregistrar.cpp + +namespace Catch { + + RegistrarForTagAliases::RegistrarForTagAliases(char const* alias, char const* tag, SourceLineInfo const& lineInfo) { + try { + getMutableRegistryHub().registerTagAlias(alias, tag, lineInfo); + } catch (...) { + // Do not throw when constructing global objects, instead register the exception to be processed later + getMutableRegistryHub().registerStartupException(); + } + } + +} +// end catch_tag_alias_autoregistrar.cpp +// start catch_tag_alias_registry.cpp + +namespace Catch { + + TagAliasRegistry::~TagAliasRegistry() {} + + TagAlias const* TagAliasRegistry::find( std::string const& alias ) const { + auto it = m_registry.find( alias ); + if( it != m_registry.end() ) + return &(it->second); + else + return nullptr; + } + + std::string TagAliasRegistry::expandAliases( std::string const& unexpandedTestSpec ) const { + std::string expandedTestSpec = unexpandedTestSpec; + for( auto const& registryKvp : m_registry ) { + std::size_t pos = expandedTestSpec.find( registryKvp.first ); + if( pos != std::string::npos ) { + expandedTestSpec = expandedTestSpec.substr( 0, pos ) + + registryKvp.second.tag + + expandedTestSpec.substr( pos + registryKvp.first.size() ); + } + } + return expandedTestSpec; + } + + void TagAliasRegistry::add( std::string const& alias, std::string const& tag, SourceLineInfo const& lineInfo ) { + CATCH_ENFORCE( startsWith(alias, "[@") && endsWith(alias, ']'), + "error: tag alias, '" << alias << "' is not of the form [@alias name].\n" << lineInfo ); + + CATCH_ENFORCE( m_registry.insert(std::make_pair(alias, TagAlias(tag, lineInfo))).second, + "error: tag alias, '" << alias << "' already registered.\n" + << "\tFirst seen at: " << find(alias)->lineInfo << "\n" + << "\tRedefined at: " << lineInfo ); + } + + ITagAliasRegistry::~ITagAliasRegistry() {} + + ITagAliasRegistry const& ITagAliasRegistry::get() { + return getRegistryHub().getTagAliasRegistry(); + } + +} // end namespace Catch +// end catch_tag_alias_registry.cpp +// start catch_test_case_info.cpp + +#include +#include +#include + +namespace Catch { + + TestCaseInfo::SpecialProperties parseSpecialTag( std::string const& tag ) { + if( startsWith( tag, '.' ) || + tag == "!hide" ) + return TestCaseInfo::IsHidden; + else if( tag == "!throws" ) + return TestCaseInfo::Throws; + else if( tag == "!shouldfail" ) + return TestCaseInfo::ShouldFail; + else if( tag == "!mayfail" ) + return TestCaseInfo::MayFail; + else if( tag == "!nonportable" ) + return TestCaseInfo::NonPortable; + else if( tag == "!benchmark" ) + return static_cast( TestCaseInfo::Benchmark | TestCaseInfo::IsHidden ); + else + return TestCaseInfo::None; + } + bool isReservedTag( std::string const& tag ) { + return parseSpecialTag( tag ) == TestCaseInfo::None && tag.size() > 0 && !std::isalnum( tag[0] ); + } + void enforceNotReservedTag( std::string const& tag, SourceLineInfo const& _lineInfo ) { + CATCH_ENFORCE( !isReservedTag(tag), + "Tag name: [" << tag << "] is not allowed.\n" + << "Tag names starting with non alpha-numeric characters are reserved\n" + << _lineInfo ); + } + + TestCase makeTestCase( ITestInvoker* _testCase, + std::string const& _className, + std::string const& _name, + std::string const& _descOrTags, + SourceLineInfo const& _lineInfo ) + { + bool isHidden = false; + + // Parse out tags + std::vector tags; + std::string desc, tag; + bool inTag = false; + for (char c : _descOrTags) { + if( !inTag ) { + if( c == '[' ) + inTag = true; + else + desc += c; + } + else { + if( c == ']' ) { + TestCaseInfo::SpecialProperties prop = parseSpecialTag( tag ); + if( ( prop & TestCaseInfo::IsHidden ) != 0 ) + isHidden = true; + else if( prop == TestCaseInfo::None ) + enforceNotReservedTag( tag, _lineInfo ); + + tags.push_back( tag ); + tag.clear(); + inTag = false; + } + else + tag += c; + } + } + if( isHidden ) { + tags.push_back( "." ); + } + + TestCaseInfo info( _name, _className, desc, tags, _lineInfo ); + return TestCase( _testCase, info ); + } + + void setTags( TestCaseInfo& testCaseInfo, std::vector tags ) { + std::sort(begin(tags), end(tags)); + tags.erase(std::unique(begin(tags), end(tags)), end(tags)); + testCaseInfo.lcaseTags.clear(); + + for( auto const& tag : tags ) { + std::string lcaseTag = toLower( tag ); + testCaseInfo.properties = static_cast( testCaseInfo.properties | parseSpecialTag( lcaseTag ) ); + testCaseInfo.lcaseTags.push_back( lcaseTag ); + } + testCaseInfo.tags = std::move(tags); + } + + TestCaseInfo::TestCaseInfo( std::string const& _name, + std::string const& _className, + std::string const& _description, + std::vector const& _tags, + SourceLineInfo const& _lineInfo ) + : name( _name ), + className( _className ), + description( _description ), + lineInfo( _lineInfo ), + properties( None ) + { + setTags( *this, _tags ); + } + + bool TestCaseInfo::isHidden() const { + return ( properties & IsHidden ) != 0; + } + bool TestCaseInfo::throws() const { + return ( properties & Throws ) != 0; + } + bool TestCaseInfo::okToFail() const { + return ( properties & (ShouldFail | MayFail ) ) != 0; + } + bool TestCaseInfo::expectedToFail() const { + return ( properties & (ShouldFail ) ) != 0; + } + + std::string TestCaseInfo::tagsAsString() const { + std::string ret; + // '[' and ']' per tag + std::size_t full_size = 2 * tags.size(); + for (const auto& tag : tags) { + full_size += tag.size(); + } + ret.reserve(full_size); + for (const auto& tag : tags) { + ret.push_back('['); + ret.append(tag); + ret.push_back(']'); + } + + return ret; + } + + TestCase::TestCase( ITestInvoker* testCase, TestCaseInfo const& info ) : TestCaseInfo( info ), test( testCase ) {} + + TestCase TestCase::withName( std::string const& _newName ) const { + TestCase other( *this ); + other.name = _newName; + return other; + } + + void TestCase::invoke() const { + test->invoke(); + } + + bool TestCase::operator == ( TestCase const& other ) const { + return test.get() == other.test.get() && + name == other.name && + className == other.className; + } + + bool TestCase::operator < ( TestCase const& other ) const { + return name < other.name; + } + + TestCaseInfo const& TestCase::getTestCaseInfo() const + { + return *this; + } + +} // end namespace Catch +// end catch_test_case_info.cpp +// start catch_test_case_registry_impl.cpp + +#include + +namespace Catch { + + std::vector sortTests( IConfig const& config, std::vector const& unsortedTestCases ) { + + std::vector sorted = unsortedTestCases; + + switch( config.runOrder() ) { + case RunTests::InLexicographicalOrder: + std::sort( sorted.begin(), sorted.end() ); + break; + case RunTests::InRandomOrder: + seedRng( config ); + RandomNumberGenerator::shuffle( sorted ); + break; + case RunTests::InDeclarationOrder: + // already in declaration order + break; + } + return sorted; + } + bool matchTest( TestCase const& testCase, TestSpec const& testSpec, IConfig const& config ) { + return testSpec.matches( testCase ) && ( config.allowThrows() || !testCase.throws() ); + } + + void enforceNoDuplicateTestCases( std::vector const& functions ) { + std::set seenFunctions; + for( auto const& function : functions ) { + auto prev = seenFunctions.insert( function ); + CATCH_ENFORCE( prev.second, + "error: TEST_CASE( \"" << function.name << "\" ) already defined.\n" + << "\tFirst seen at " << prev.first->getTestCaseInfo().lineInfo << "\n" + << "\tRedefined at " << function.getTestCaseInfo().lineInfo ); + } + } + + std::vector filterTests( std::vector const& testCases, TestSpec const& testSpec, IConfig const& config ) { + std::vector filtered; + filtered.reserve( testCases.size() ); + for( auto const& testCase : testCases ) + if( matchTest( testCase, testSpec, config ) ) + filtered.push_back( testCase ); + return filtered; + } + std::vector const& getAllTestCasesSorted( IConfig const& config ) { + return getRegistryHub().getTestCaseRegistry().getAllTestsSorted( config ); + } + + void TestRegistry::registerTest( TestCase const& testCase ) { + std::string name = testCase.getTestCaseInfo().name; + if( name.empty() ) { + std::ostringstream oss; + oss << "Anonymous test case " << ++m_unnamedCount; + return registerTest( testCase.withName( oss.str() ) ); + } + m_functions.push_back( testCase ); + } + + std::vector const& TestRegistry::getAllTests() const { + return m_functions; + } + std::vector const& TestRegistry::getAllTestsSorted( IConfig const& config ) const { + if( m_sortedFunctions.empty() ) + enforceNoDuplicateTestCases( m_functions ); + + if( m_currentSortOrder != config.runOrder() || m_sortedFunctions.empty() ) { + m_sortedFunctions = sortTests( config, m_functions ); + m_currentSortOrder = config.runOrder(); + } + return m_sortedFunctions; + } + + /////////////////////////////////////////////////////////////////////////// + TestInvokerAsFunction::TestInvokerAsFunction( void(*testAsFunction)() ) noexcept : m_testAsFunction( testAsFunction ) {} + + void TestInvokerAsFunction::invoke() const { + m_testAsFunction(); + } + + std::string extractClassName( std::string const& classOrQualifiedMethodName ) { + std::string className = classOrQualifiedMethodName; + if( startsWith( className, '&' ) ) + { + std::size_t lastColons = className.rfind( "::" ); + std::size_t penultimateColons = className.rfind( "::", lastColons-1 ); + if( penultimateColons == std::string::npos ) + penultimateColons = 1; + className = className.substr( penultimateColons, lastColons-penultimateColons ); + } + return className; + } + +} // end namespace Catch +// end catch_test_case_registry_impl.cpp +// start catch_test_case_tracker.cpp + +#include +#include +#include +#include + +#if defined(__clang__) +# pragma clang diagnostic push +# pragma clang diagnostic ignored "-Wexit-time-destructors" +#endif + +namespace Catch { +namespace TestCaseTracking { + + NameAndLocation::NameAndLocation( std::string const& _name, SourceLineInfo const& _location ) + : name( _name ), + location( _location ) + {} + + ITracker::~ITracker() = default; + + TrackerContext& TrackerContext::instance() { + static TrackerContext s_instance; + return s_instance; + } + + ITracker& TrackerContext::startRun() { + m_rootTracker = std::make_shared( NameAndLocation( "{root}", CATCH_INTERNAL_LINEINFO ), *this, nullptr ); + m_currentTracker = nullptr; + m_runState = Executing; + return *m_rootTracker; + } + + void TrackerContext::endRun() { + m_rootTracker.reset(); + m_currentTracker = nullptr; + m_runState = NotStarted; + } + + void TrackerContext::startCycle() { + m_currentTracker = m_rootTracker.get(); + m_runState = Executing; + } + void TrackerContext::completeCycle() { + m_runState = CompletedCycle; + } + + bool TrackerContext::completedCycle() const { + return m_runState == CompletedCycle; + } + ITracker& TrackerContext::currentTracker() { + return *m_currentTracker; + } + void TrackerContext::setCurrentTracker( ITracker* tracker ) { + m_currentTracker = tracker; + } + + TrackerBase::TrackerHasName::TrackerHasName( NameAndLocation const& nameAndLocation ) : m_nameAndLocation( nameAndLocation ) {} + bool TrackerBase::TrackerHasName::operator ()( ITrackerPtr const& tracker ) const { + return + tracker->nameAndLocation().name == m_nameAndLocation.name && + tracker->nameAndLocation().location == m_nameAndLocation.location; + } + + TrackerBase::TrackerBase( NameAndLocation const& nameAndLocation, TrackerContext& ctx, ITracker* parent ) + : m_nameAndLocation( nameAndLocation ), + m_ctx( ctx ), + m_parent( parent ) + {} + + NameAndLocation const& TrackerBase::nameAndLocation() const { + return m_nameAndLocation; + } + bool TrackerBase::isComplete() const { + return m_runState == CompletedSuccessfully || m_runState == Failed; + } + bool TrackerBase::isSuccessfullyCompleted() const { + return m_runState == CompletedSuccessfully; + } + bool TrackerBase::isOpen() const { + return m_runState != NotStarted && !isComplete(); + } + bool TrackerBase::hasChildren() const { + return !m_children.empty(); + } + + void TrackerBase::addChild( ITrackerPtr const& child ) { + m_children.push_back( child ); + } + + ITrackerPtr TrackerBase::findChild( NameAndLocation const& nameAndLocation ) { + auto it = std::find_if( m_children.begin(), m_children.end(), TrackerHasName( nameAndLocation ) ); + return( it != m_children.end() ) + ? *it + : nullptr; + } + ITracker& TrackerBase::parent() { + assert( m_parent ); // Should always be non-null except for root + return *m_parent; + } + + void TrackerBase::openChild() { + if( m_runState != ExecutingChildren ) { + m_runState = ExecutingChildren; + if( m_parent ) + m_parent->openChild(); + } + } + + bool TrackerBase::isSectionTracker() const { return false; } + bool TrackerBase::isIndexTracker() const { return false; } + + void TrackerBase::open() { + m_runState = Executing; + moveToThis(); + if( m_parent ) + m_parent->openChild(); + } + + void TrackerBase::close() { + + // Close any still open children (e.g. generators) + while( &m_ctx.currentTracker() != this ) + m_ctx.currentTracker().close(); + + switch( m_runState ) { + case NeedsAnotherRun: + break; + + case Executing: + m_runState = CompletedSuccessfully; + break; + case ExecutingChildren: + if( m_children.empty() || m_children.back()->isComplete() ) + m_runState = CompletedSuccessfully; + break; + + case NotStarted: + case CompletedSuccessfully: + case Failed: + CATCH_INTERNAL_ERROR( "Illogical state: " << m_runState ); + + default: + CATCH_INTERNAL_ERROR( "Unknown state: " << m_runState ); + } + moveToParent(); + m_ctx.completeCycle(); + } + void TrackerBase::fail() { + m_runState = Failed; + if( m_parent ) + m_parent->markAsNeedingAnotherRun(); + moveToParent(); + m_ctx.completeCycle(); + } + void TrackerBase::markAsNeedingAnotherRun() { + m_runState = NeedsAnotherRun; + } + + void TrackerBase::moveToParent() { + assert( m_parent ); + m_ctx.setCurrentTracker( m_parent ); + } + void TrackerBase::moveToThis() { + m_ctx.setCurrentTracker( this ); + } + + SectionTracker::SectionTracker( NameAndLocation const& nameAndLocation, TrackerContext& ctx, ITracker* parent ) + : TrackerBase( nameAndLocation, ctx, parent ) + { + if( parent ) { + while( !parent->isSectionTracker() ) + parent = &parent->parent(); + + SectionTracker& parentSection = static_cast( *parent ); + addNextFilters( parentSection.m_filters ); + } + } + + bool SectionTracker::isSectionTracker() const { return true; } + + SectionTracker& SectionTracker::acquire( TrackerContext& ctx, NameAndLocation const& nameAndLocation ) { + std::shared_ptr section; + + ITracker& currentTracker = ctx.currentTracker(); + if( ITrackerPtr childTracker = currentTracker.findChild( nameAndLocation ) ) { + assert( childTracker ); + assert( childTracker->isSectionTracker() ); + section = std::static_pointer_cast( childTracker ); + } + else { + section = std::make_shared( nameAndLocation, ctx, ¤tTracker ); + currentTracker.addChild( section ); + } + if( !ctx.completedCycle() ) + section->tryOpen(); + return *section; + } + + void SectionTracker::tryOpen() { + if( !isComplete() && (m_filters.empty() || m_filters[0].empty() || m_filters[0] == m_nameAndLocation.name ) ) + open(); + } + + void SectionTracker::addInitialFilters( std::vector const& filters ) { + if( !filters.empty() ) { + m_filters.push_back(""); // Root - should never be consulted + m_filters.push_back(""); // Test Case - not a section filter + m_filters.insert( m_filters.end(), filters.begin(), filters.end() ); + } + } + void SectionTracker::addNextFilters( std::vector const& filters ) { + if( filters.size() > 1 ) + m_filters.insert( m_filters.end(), ++filters.begin(), filters.end() ); + } + + IndexTracker::IndexTracker( NameAndLocation const& nameAndLocation, TrackerContext& ctx, ITracker* parent, int size ) + : TrackerBase( nameAndLocation, ctx, parent ), + m_size( size ) + {} + + bool IndexTracker::isIndexTracker() const { return true; } + + IndexTracker& IndexTracker::acquire( TrackerContext& ctx, NameAndLocation const& nameAndLocation, int size ) { + std::shared_ptr tracker; + + ITracker& currentTracker = ctx.currentTracker(); + if( ITrackerPtr childTracker = currentTracker.findChild( nameAndLocation ) ) { + assert( childTracker ); + assert( childTracker->isIndexTracker() ); + tracker = std::static_pointer_cast( childTracker ); + } + else { + tracker = std::make_shared( nameAndLocation, ctx, ¤tTracker, size ); + currentTracker.addChild( tracker ); + } + + if( !ctx.completedCycle() && !tracker->isComplete() ) { + if( tracker->m_runState != ExecutingChildren && tracker->m_runState != NeedsAnotherRun ) + tracker->moveNext(); + tracker->open(); + } + + return *tracker; + } + + int IndexTracker::index() const { return m_index; } + + void IndexTracker::moveNext() { + m_index++; + m_children.clear(); + } + + void IndexTracker::close() { + TrackerBase::close(); + if( m_runState == CompletedSuccessfully && m_index < m_size-1 ) + m_runState = Executing; + } + +} // namespace TestCaseTracking + +using TestCaseTracking::ITracker; +using TestCaseTracking::TrackerContext; +using TestCaseTracking::SectionTracker; +using TestCaseTracking::IndexTracker; + +} // namespace Catch + +#if defined(__clang__) +# pragma clang diagnostic pop +#endif +// end catch_test_case_tracker.cpp +// start catch_test_registry.cpp + +namespace Catch { + + auto makeTestInvoker( void(*testAsFunction)() ) noexcept -> ITestInvoker* { + return new(std::nothrow) TestInvokerAsFunction( testAsFunction ); + } + + NameAndTags::NameAndTags( StringRef name_ , StringRef tags_ ) noexcept : name( name_ ), tags( tags_ ) {} + + AutoReg::AutoReg( ITestInvoker* invoker, SourceLineInfo const& lineInfo, StringRef classOrMethod, NameAndTags const& nameAndTags ) noexcept { + try { + getMutableRegistryHub() + .registerTest( + makeTestCase( + invoker, + extractClassName( classOrMethod ), + nameAndTags.name, + nameAndTags.tags, + lineInfo)); + } catch (...) { + // Do not throw when constructing global objects, instead register the exception to be processed later + getMutableRegistryHub().registerStartupException(); + } + } + + AutoReg::~AutoReg() = default; +} +// end catch_test_registry.cpp +// start catch_test_spec.cpp + +#include +#include +#include +#include + +namespace Catch { + + TestSpec::Pattern::~Pattern() = default; + TestSpec::NamePattern::~NamePattern() = default; + TestSpec::TagPattern::~TagPattern() = default; + TestSpec::ExcludedPattern::~ExcludedPattern() = default; + + TestSpec::NamePattern::NamePattern( std::string const& name ) + : m_wildcardPattern( toLower( name ), CaseSensitive::No ) + {} + bool TestSpec::NamePattern::matches( TestCaseInfo const& testCase ) const { + return m_wildcardPattern.matches( toLower( testCase.name ) ); + } + + TestSpec::TagPattern::TagPattern( std::string const& tag ) : m_tag( toLower( tag ) ) {} + bool TestSpec::TagPattern::matches( TestCaseInfo const& testCase ) const { + return std::find(begin(testCase.lcaseTags), + end(testCase.lcaseTags), + m_tag) != end(testCase.lcaseTags); + } + + TestSpec::ExcludedPattern::ExcludedPattern( PatternPtr const& underlyingPattern ) : m_underlyingPattern( underlyingPattern ) {} + bool TestSpec::ExcludedPattern::matches( TestCaseInfo const& testCase ) const { return !m_underlyingPattern->matches( testCase ); } + + bool TestSpec::Filter::matches( TestCaseInfo const& testCase ) const { + // All patterns in a filter must match for the filter to be a match + for( auto const& pattern : m_patterns ) { + if( !pattern->matches( testCase ) ) + return false; + } + return true; + } + + bool TestSpec::hasFilters() const { + return !m_filters.empty(); + } + bool TestSpec::matches( TestCaseInfo const& testCase ) const { + // A TestSpec matches if any filter matches + for( auto const& filter : m_filters ) + if( filter.matches( testCase ) ) + return true; + return false; + } +} +// end catch_test_spec.cpp +// start catch_test_spec_parser.cpp + +namespace Catch { + + TestSpecParser::TestSpecParser( ITagAliasRegistry const& tagAliases ) : m_tagAliases( &tagAliases ) {} + + TestSpecParser& TestSpecParser::parse( std::string const& arg ) { + m_mode = None; + m_exclusion = false; + m_start = std::string::npos; + m_arg = m_tagAliases->expandAliases( arg ); + m_escapeChars.clear(); + for( m_pos = 0; m_pos < m_arg.size(); ++m_pos ) + visitChar( m_arg[m_pos] ); + if( m_mode == Name ) + addPattern(); + return *this; + } + TestSpec TestSpecParser::testSpec() { + addFilter(); + return m_testSpec; + } + + void TestSpecParser::visitChar( char c ) { + if( m_mode == None ) { + switch( c ) { + case ' ': return; + case '~': m_exclusion = true; return; + case '[': return startNewMode( Tag, ++m_pos ); + case '"': return startNewMode( QuotedName, ++m_pos ); + case '\\': return escape(); + default: startNewMode( Name, m_pos ); break; + } + } + if( m_mode == Name ) { + if( c == ',' ) { + addPattern(); + addFilter(); + } + else if( c == '[' ) { + if( subString() == "exclude:" ) + m_exclusion = true; + else + addPattern(); + startNewMode( Tag, ++m_pos ); + } + else if( c == '\\' ) + escape(); + } + else if( m_mode == EscapedName ) + m_mode = Name; + else if( m_mode == QuotedName && c == '"' ) + addPattern(); + else if( m_mode == Tag && c == ']' ) + addPattern(); + } + void TestSpecParser::startNewMode( Mode mode, std::size_t start ) { + m_mode = mode; + m_start = start; + } + void TestSpecParser::escape() { + if( m_mode == None ) + m_start = m_pos; + m_mode = EscapedName; + m_escapeChars.push_back( m_pos ); + } + std::string TestSpecParser::subString() const { return m_arg.substr( m_start, m_pos - m_start ); } + + void TestSpecParser::addFilter() { + if( !m_currentFilter.m_patterns.empty() ) { + m_testSpec.m_filters.push_back( m_currentFilter ); + m_currentFilter = TestSpec::Filter(); + } + } + + TestSpec parseTestSpec( std::string const& arg ) { + return TestSpecParser( ITagAliasRegistry::get() ).parse( arg ).testSpec(); + } + +} // namespace Catch +// end catch_test_spec_parser.cpp +// start catch_timer.cpp + +#include + +namespace Catch { + + auto getCurrentNanosecondsSinceEpoch() -> uint64_t { + return std::chrono::duration_cast( std::chrono::high_resolution_clock::now().time_since_epoch() ).count(); + } + + auto estimateClockResolution() -> uint64_t { + uint64_t sum = 0; + static const uint64_t iterations = 1000000; + + for( std::size_t i = 0; i < iterations; ++i ) { + + uint64_t ticks; + uint64_t baseTicks = getCurrentNanosecondsSinceEpoch(); + do { + ticks = getCurrentNanosecondsSinceEpoch(); + } + while( ticks == baseTicks ); + + auto delta = ticks - baseTicks; + sum += delta; + } + + // We're just taking the mean, here. To do better we could take the std. dev and exclude outliers + // - and potentially do more iterations if there's a high variance. + return sum/iterations; + } + auto getEstimatedClockResolution() -> uint64_t { + static auto s_resolution = estimateClockResolution(); + return s_resolution; + } + + void Timer::start() { + m_nanoseconds = getCurrentNanosecondsSinceEpoch(); + } + auto Timer::getElapsedNanoseconds() const -> unsigned int { + return static_cast(getCurrentNanosecondsSinceEpoch() - m_nanoseconds); + } + auto Timer::getElapsedMicroseconds() const -> unsigned int { + return static_cast(getElapsedNanoseconds()/1000); + } + auto Timer::getElapsedMilliseconds() const -> unsigned int { + return static_cast(getElapsedMicroseconds()/1000); + } + auto Timer::getElapsedSeconds() const -> double { + return getElapsedMicroseconds()/1000000.0; + } + +} // namespace Catch +// end catch_timer.cpp +// start catch_tostring.cpp + +#if defined(__clang__) +# pragma clang diagnostic push +# pragma clang diagnostic ignored "-Wexit-time-destructors" +# pragma clang diagnostic ignored "-Wglobal-constructors" +#endif + +#include + +namespace Catch { + +namespace Detail { + + const std::string unprintableString = "{?}"; + + namespace { + const int hexThreshold = 255; + + struct Endianness { + enum Arch { Big, Little }; + + static Arch which() { + union _{ + int asInt; + char asChar[sizeof (int)]; + } u; + + u.asInt = 1; + return ( u.asChar[sizeof(int)-1] == 1 ) ? Big : Little; + } + }; + } + + std::string rawMemoryToString( const void *object, std::size_t size ) { + // Reverse order for little endian architectures + int i = 0, end = static_cast( size ), inc = 1; + if( Endianness::which() == Endianness::Little ) { + i = end-1; + end = inc = -1; + } + + unsigned char const *bytes = static_cast(object); + std::ostringstream os; + os << "0x" << std::setfill('0') << std::hex; + for( ; i != end; i += inc ) + os << std::setw(2) << static_cast(bytes[i]); + return os.str(); + } +} + +template +std::string fpToString( T value, int precision ) { + std::ostringstream oss; + oss << std::setprecision( precision ) + << std::fixed + << value; + std::string d = oss.str(); + std::size_t i = d.find_last_not_of( '0' ); + if( i != std::string::npos && i != d.size()-1 ) { + if( d[i] == '.' ) + i++; + d = d.substr( 0, i+1 ); + } + return d; +} + +//// ======================================================= //// +// +// Out-of-line defs for full specialization of StringMaker +// +//// ======================================================= //// + +std::string StringMaker::convert(const std::string& str) { + if (!getCurrentContext().getConfig()->showInvisibles()) { + return '"' + str + '"'; + } + + std::string s("\""); + for (char c : str) { + switch (c) { + case '\n': + s.append("\\n"); + break; + case '\t': + s.append("\\t"); + break; + default: + s.push_back(c); + break; + } + } + s.append("\""); + return s; +} + +std::string StringMaker::convert(const std::wstring& wstr) { + std::string s; + s.reserve(wstr.size()); + for (auto c : wstr) { + s += (c <= 0xff) ? static_cast(c) : '?'; + } + return ::Catch::Detail::stringify(s); +} + +std::string StringMaker::convert(char const* str) { + if (str) { + return ::Catch::Detail::stringify(std::string{ str }); + } else { + return{ "{null string}" }; + } +} +std::string StringMaker::convert(char* str) { + if (str) { + return ::Catch::Detail::stringify(std::string{ str }); + } else { + return{ "{null string}" }; + } +} +std::string StringMaker::convert(wchar_t const * str) { + if (str) { + return ::Catch::Detail::stringify(std::wstring{ str }); + } else { + return{ "{null string}" }; + } +} +std::string StringMaker::convert(wchar_t * str) { + if (str) { + return ::Catch::Detail::stringify(std::wstring{ str }); + } else { + return{ "{null string}" }; + } +} + +std::string StringMaker::convert(int value) { + return ::Catch::Detail::stringify(static_cast(value)); +} +std::string StringMaker::convert(long value) { + return ::Catch::Detail::stringify(static_cast(value)); +} +std::string StringMaker::convert(long long value) { + std::ostringstream oss; + oss << value; + if (value > Detail::hexThreshold) { + oss << " (0x" << std::hex << value << ')'; + } + return oss.str(); +} + +std::string StringMaker::convert(unsigned int value) { + return ::Catch::Detail::stringify(static_cast(value)); +} +std::string StringMaker::convert(unsigned long value) { + return ::Catch::Detail::stringify(static_cast(value)); +} +std::string StringMaker::convert(unsigned long long value) { + std::ostringstream oss; + oss << value; + if (value > Detail::hexThreshold) { + oss << " (0x" << std::hex << value << ')'; + } + return oss.str(); +} + +std::string StringMaker::convert(bool b) { + return b ? "true" : "false"; +} + +std::string StringMaker::convert(char value) { + if (value == '\r') { + return "'\\r'"; + } else if (value == '\f') { + return "'\\f'"; + } else if (value == '\n') { + return "'\\n'"; + } else if (value == '\t') { + return "'\\t'"; + } else if ('\0' <= value && value < ' ') { + return ::Catch::Detail::stringify(static_cast(value)); + } else { + char chstr[] = "' '"; + chstr[1] = value; + return chstr; + } +} +std::string StringMaker::convert(signed char c) { + return ::Catch::Detail::stringify(static_cast(c)); +} +std::string StringMaker::convert(unsigned char c) { + return ::Catch::Detail::stringify(static_cast(c)); +} + +std::string StringMaker::convert(std::nullptr_t) { + return "nullptr"; +} + +std::string StringMaker::convert(float value) { + return fpToString(value, 5) + 'f'; +} +std::string StringMaker::convert(double value) { + return fpToString(value, 10); +} + +} // end namespace Catch + +#if defined(__clang__) +# pragma clang diagnostic pop +#endif + +// end catch_tostring.cpp +// start catch_totals.cpp + +namespace Catch { + + Counts Counts::operator - ( Counts const& other ) const { + Counts diff; + diff.passed = passed - other.passed; + diff.failed = failed - other.failed; + diff.failedButOk = failedButOk - other.failedButOk; + return diff; + } + + Counts& Counts::operator += ( Counts const& other ) { + passed += other.passed; + failed += other.failed; + failedButOk += other.failedButOk; + return *this; + } + + std::size_t Counts::total() const { + return passed + failed + failedButOk; + } + bool Counts::allPassed() const { + return failed == 0 && failedButOk == 0; + } + bool Counts::allOk() const { + return failed == 0; + } + + Totals Totals::operator - ( Totals const& other ) const { + Totals diff; + diff.assertions = assertions - other.assertions; + diff.testCases = testCases - other.testCases; + return diff; + } + + Totals& Totals::operator += ( Totals const& other ) { + assertions += other.assertions; + testCases += other.testCases; + return *this; + } + + Totals Totals::delta( Totals const& prevTotals ) const { + Totals diff = *this - prevTotals; + if( diff.assertions.failed > 0 ) + ++diff.testCases.failed; + else if( diff.assertions.failedButOk > 0 ) + ++diff.testCases.failedButOk; + else + ++diff.testCases.passed; + return diff; + } + +} +// end catch_totals.cpp +// start catch_version.cpp + +#include + +namespace Catch { + + Version::Version + ( unsigned int _majorVersion, + unsigned int _minorVersion, + unsigned int _patchNumber, + char const * const _branchName, + unsigned int _buildNumber ) + : majorVersion( _majorVersion ), + minorVersion( _minorVersion ), + patchNumber( _patchNumber ), + branchName( _branchName ), + buildNumber( _buildNumber ) + {} + + std::ostream& operator << ( std::ostream& os, Version const& version ) { + os << version.majorVersion << '.' + << version.minorVersion << '.' + << version.patchNumber; + // branchName is never null -> 0th char is \0 if it is empty + if (version.branchName[0]) { + os << '-' << version.branchName + << '.' << version.buildNumber; + } + return os; + } + + Version const& libraryVersion() { + static Version version( 2, 0, 1, "", 0 ); + return version; + } + +} +// end catch_version.cpp +// start catch_wildcard_pattern.cpp + +namespace Catch { + + WildcardPattern::WildcardPattern( std::string const& pattern, + CaseSensitive::Choice caseSensitivity ) + : m_caseSensitivity( caseSensitivity ), + m_pattern( adjustCase( pattern ) ) + { + if( startsWith( m_pattern, '*' ) ) { + m_pattern = m_pattern.substr( 1 ); + m_wildcard = WildcardAtStart; + } + if( endsWith( m_pattern, '*' ) ) { + m_pattern = m_pattern.substr( 0, m_pattern.size()-1 ); + m_wildcard = static_cast( m_wildcard | WildcardAtEnd ); + } + } + + bool WildcardPattern::matches( std::string const& str ) const { + switch( m_wildcard ) { + case NoWildcard: + return m_pattern == adjustCase( str ); + case WildcardAtStart: + return endsWith( adjustCase( str ), m_pattern ); + case WildcardAtEnd: + return startsWith( adjustCase( str ), m_pattern ); + case WildcardAtBothEnds: + return contains( adjustCase( str ), m_pattern ); + default: + CATCH_INTERNAL_ERROR( "Unknown enum" ); + } + } + + std::string WildcardPattern::adjustCase( std::string const& str ) const { + return m_caseSensitivity == CaseSensitive::No ? toLower( str ) : str; + } +} +// end catch_wildcard_pattern.cpp +// start catch_xmlwriter.cpp + +// start catch_xmlwriter.h + +#include +#include + +namespace Catch { + + class XmlEncode { + public: + enum ForWhat { ForTextNodes, ForAttributes }; + + XmlEncode( std::string const& str, ForWhat forWhat = ForTextNodes ); + + void encodeTo( std::ostream& os ) const; + + friend std::ostream& operator << ( std::ostream& os, XmlEncode const& xmlEncode ); + + private: + std::string m_str; + ForWhat m_forWhat; + }; + + class XmlWriter { + public: + + class ScopedElement { + public: + ScopedElement( XmlWriter* writer ); + + ScopedElement( ScopedElement&& other ) noexcept; + ScopedElement& operator=( ScopedElement&& other ) noexcept; + + ~ScopedElement(); + + ScopedElement& writeText( std::string const& text, bool indent = true ); + + template + ScopedElement& writeAttribute( std::string const& name, T const& attribute ) { + m_writer->writeAttribute( name, attribute ); + return *this; + } + + private: + mutable XmlWriter* m_writer = nullptr; + }; + + XmlWriter( std::ostream& os = Catch::cout() ); + ~XmlWriter(); + + XmlWriter( XmlWriter const& ) = delete; + XmlWriter& operator=( XmlWriter const& ) = delete; + + XmlWriter& startElement( std::string const& name ); + + ScopedElement scopedElement( std::string const& name ); + + XmlWriter& endElement(); + + XmlWriter& writeAttribute( std::string const& name, std::string const& attribute ); + + XmlWriter& writeAttribute( std::string const& name, bool attribute ); + + template + XmlWriter& writeAttribute( std::string const& name, T const& attribute ) { + m_oss.clear(); + m_oss.str(std::string()); + m_oss << attribute; + return writeAttribute( name, m_oss.str() ); + } + + XmlWriter& writeText( std::string const& text, bool indent = true ); + + XmlWriter& writeComment( std::string const& text ); + + void writeStylesheetRef( std::string const& url ); + + XmlWriter& writeBlankLine(); + + void ensureTagClosed(); + + private: + + void writeDeclaration(); + + void newlineIfNecessary(); + + bool m_tagIsOpen = false; + bool m_needsNewline = false; + std::vector m_tags; + std::string m_indent; + std::ostream& m_os; + std::ostringstream m_oss; + }; + +} + +// end catch_xmlwriter.h +#include + +namespace Catch { + + XmlEncode::XmlEncode( std::string const& str, ForWhat forWhat ) + : m_str( str ), + m_forWhat( forWhat ) + {} + + void XmlEncode::encodeTo( std::ostream& os ) const { + + // Apostrophe escaping not necessary if we always use " to write attributes + // (see: http://www.w3.org/TR/xml/#syntax) + + for( std::size_t i = 0; i < m_str.size(); ++ i ) { + char c = m_str[i]; + switch( c ) { + case '<': os << "<"; break; + case '&': os << "&"; break; + + case '>': + // See: http://www.w3.org/TR/xml/#syntax + if( i > 2 && m_str[i-1] == ']' && m_str[i-2] == ']' ) + os << ">"; + else + os << c; + break; + + case '\"': + if( m_forWhat == ForAttributes ) + os << """; + else + os << c; + break; + + default: + // Escape control chars - based on contribution by @espenalb in PR #465 and + // by @mrpi PR #588 + if ( ( c >= 0 && c < '\x09' ) || ( c > '\x0D' && c < '\x20') || c=='\x7F' ) { + // see http://stackoverflow.com/questions/404107/why-are-control-characters-illegal-in-xml-1-0 + os << "\\x" << std::uppercase << std::hex << std::setfill('0') << std::setw(2) + << static_cast( c ); + } + else + os << c; + } + } + } + + std::ostream& operator << ( std::ostream& os, XmlEncode const& xmlEncode ) { + xmlEncode.encodeTo( os ); + return os; + } + + XmlWriter::ScopedElement::ScopedElement( XmlWriter* writer ) + : m_writer( writer ) + {} + + XmlWriter::ScopedElement::ScopedElement( ScopedElement&& other ) noexcept + : m_writer( other.m_writer ){ + other.m_writer = nullptr; + } + XmlWriter::ScopedElement& XmlWriter::ScopedElement::operator=( ScopedElement&& other ) noexcept { + if ( m_writer ) { + m_writer->endElement(); + } + m_writer = other.m_writer; + other.m_writer = nullptr; + return *this; + } + + XmlWriter::ScopedElement::~ScopedElement() { + if( m_writer ) + m_writer->endElement(); + } + + XmlWriter::ScopedElement& XmlWriter::ScopedElement::writeText( std::string const& text, bool indent ) { + m_writer->writeText( text, indent ); + return *this; + } + + XmlWriter::XmlWriter( std::ostream& os ) : m_os( os ) + { + writeDeclaration(); + } + + XmlWriter::~XmlWriter() { + while( !m_tags.empty() ) + endElement(); + } + + XmlWriter& XmlWriter::startElement( std::string const& name ) { + ensureTagClosed(); + newlineIfNecessary(); + m_os << m_indent << '<' << name; + m_tags.push_back( name ); + m_indent += " "; + m_tagIsOpen = true; + return *this; + } + + XmlWriter::ScopedElement XmlWriter::scopedElement( std::string const& name ) { + ScopedElement scoped( this ); + startElement( name ); + return scoped; + } + + XmlWriter& XmlWriter::endElement() { + newlineIfNecessary(); + m_indent = m_indent.substr( 0, m_indent.size()-2 ); + if( m_tagIsOpen ) { + m_os << "/>"; + m_tagIsOpen = false; + } + else { + m_os << m_indent << ""; + } + m_os << std::endl; + m_tags.pop_back(); + return *this; + } + + XmlWriter& XmlWriter::writeAttribute( std::string const& name, std::string const& attribute ) { + if( !name.empty() && !attribute.empty() ) + m_os << ' ' << name << "=\"" << XmlEncode( attribute, XmlEncode::ForAttributes ) << '"'; + return *this; + } + + XmlWriter& XmlWriter::writeAttribute( std::string const& name, bool attribute ) { + m_os << ' ' << name << "=\"" << ( attribute ? "true" : "false" ) << '"'; + return *this; + } + + XmlWriter& XmlWriter::writeText( std::string const& text, bool indent ) { + if( !text.empty() ){ + bool tagWasOpen = m_tagIsOpen; + ensureTagClosed(); + if( tagWasOpen && indent ) + m_os << m_indent; + m_os << XmlEncode( text ); + m_needsNewline = true; + } + return *this; + } + + XmlWriter& XmlWriter::writeComment( std::string const& text ) { + ensureTagClosed(); + m_os << m_indent << ""; + m_needsNewline = true; + return *this; + } + + void XmlWriter::writeStylesheetRef( std::string const& url ) { + m_os << "\n"; + } + + XmlWriter& XmlWriter::writeBlankLine() { + ensureTagClosed(); + m_os << '\n'; + return *this; + } + + void XmlWriter::ensureTagClosed() { + if( m_tagIsOpen ) { + m_os << ">" << std::endl; + m_tagIsOpen = false; + } + } + + void XmlWriter::writeDeclaration() { + m_os << "\n"; + } + + void XmlWriter::newlineIfNecessary() { + if( m_needsNewline ) { + m_os << std::endl; + m_needsNewline = false; + } + } +} +// end catch_xmlwriter.cpp +// start catch_reporter_bases.cpp + +#include +#include +#include +#include +#include + +namespace Catch { + void prepareExpandedExpression(AssertionResult& result) { + result.getExpandedExpression(); + } + + // Because formatting using c++ streams is stateful, drop down to C is required + // Alternatively we could use stringstream, but its performance is... not good. + std::string getFormattedDuration( double duration ) { + // Max exponent + 1 is required to represent the whole part + // + 1 for decimal point + // + 3 for the 3 decimal places + // + 1 for null terminator + const std::size_t maxDoubleSize = DBL_MAX_10_EXP + 1 + 1 + 3 + 1; + char buffer[maxDoubleSize]; + + // Save previous errno, to prevent sprintf from overwriting it + ErrnoGuard guard; +#ifdef _MSC_VER + sprintf_s(buffer, "%.3f", duration); +#else + sprintf(buffer, "%.3f", duration); +#endif + return std::string(buffer); + } + + TestEventListenerBase::TestEventListenerBase(ReporterConfig const & _config) + :StreamingReporterBase(_config) {} + + void TestEventListenerBase::assertionStarting(AssertionInfo const &) {} + + bool TestEventListenerBase::assertionEnded(AssertionStats const &) { + return false; + } + +} // end namespace Catch +// end catch_reporter_bases.cpp +// start catch_reporter_compact.cpp + +namespace { + +#ifdef CATCH_PLATFORM_MAC + const char* failedString() { return "FAILED"; } + const char* passedString() { return "PASSED"; } +#else + const char* failedString() { return "failed"; } + const char* passedString() { return "passed"; } +#endif + + // Colour::LightGrey + Catch::Colour::Code dimColour() { return Catch::Colour::FileName; } + + std::string bothOrAll( std::size_t count ) { + return count == 1 ? std::string() : + count == 2 ? "both " : "all " ; + } +} + +namespace Catch { + + struct CompactReporter : StreamingReporterBase { + + using StreamingReporterBase::StreamingReporterBase; + + ~CompactReporter() override; + + static std::string getDescription() { + return "Reports test results on a single line, suitable for IDEs"; + } + + ReporterPreferences getPreferences() const override { + ReporterPreferences prefs; + prefs.shouldRedirectStdOut = false; + return prefs; + } + + void noMatchingTestCases( std::string const& spec ) override { + stream << "No test cases matched '" << spec << '\'' << std::endl; + } + + void assertionStarting( AssertionInfo const& ) override {} + + bool assertionEnded( AssertionStats const& _assertionStats ) override { + AssertionResult const& result = _assertionStats.assertionResult; + + bool printInfoMessages = true; + + // Drop out if result was successful and we're not printing those + if( !m_config->includeSuccessfulResults() && result.isOk() ) { + if( result.getResultType() != ResultWas::Warning ) + return false; + printInfoMessages = false; + } + + AssertionPrinter printer( stream, _assertionStats, printInfoMessages ); + printer.print(); + + stream << std::endl; + return true; + } + + void sectionEnded(SectionStats const& _sectionStats) override { + if (m_config->showDurations() == ShowDurations::Always) { + stream << getFormattedDuration(_sectionStats.durationInSeconds) << " s: " << _sectionStats.sectionInfo.name << std::endl; + } + } + + void testRunEnded( TestRunStats const& _testRunStats ) override { + printTotals( _testRunStats.totals ); + stream << '\n' << std::endl; + StreamingReporterBase::testRunEnded( _testRunStats ); + } + + private: + class AssertionPrinter { + public: + AssertionPrinter& operator= ( AssertionPrinter const& ) = delete; + AssertionPrinter( AssertionPrinter const& ) = delete; + AssertionPrinter( std::ostream& _stream, AssertionStats const& _stats, bool _printInfoMessages ) + : stream( _stream ) + , result( _stats.assertionResult ) + , messages( _stats.infoMessages ) + , itMessage( _stats.infoMessages.begin() ) + , printInfoMessages( _printInfoMessages ) + {} + + void print() { + printSourceInfo(); + + itMessage = messages.begin(); + + switch( result.getResultType() ) { + case ResultWas::Ok: + printResultType( Colour::ResultSuccess, passedString() ); + printOriginalExpression(); + printReconstructedExpression(); + if ( ! result.hasExpression() ) + printRemainingMessages( Colour::None ); + else + printRemainingMessages(); + break; + case ResultWas::ExpressionFailed: + if( result.isOk() ) + printResultType( Colour::ResultSuccess, failedString() + std::string( " - but was ok" ) ); + else + printResultType( Colour::Error, failedString() ); + printOriginalExpression(); + printReconstructedExpression(); + printRemainingMessages(); + break; + case ResultWas::ThrewException: + printResultType( Colour::Error, failedString() ); + printIssue( "unexpected exception with message:" ); + printMessage(); + printExpressionWas(); + printRemainingMessages(); + break; + case ResultWas::FatalErrorCondition: + printResultType( Colour::Error, failedString() ); + printIssue( "fatal error condition with message:" ); + printMessage(); + printExpressionWas(); + printRemainingMessages(); + break; + case ResultWas::DidntThrowException: + printResultType( Colour::Error, failedString() ); + printIssue( "expected exception, got none" ); + printExpressionWas(); + printRemainingMessages(); + break; + case ResultWas::Info: + printResultType( Colour::None, "info" ); + printMessage(); + printRemainingMessages(); + break; + case ResultWas::Warning: + printResultType( Colour::None, "warning" ); + printMessage(); + printRemainingMessages(); + break; + case ResultWas::ExplicitFailure: + printResultType( Colour::Error, failedString() ); + printIssue( "explicitly" ); + printRemainingMessages( Colour::None ); + break; + // These cases are here to prevent compiler warnings + case ResultWas::Unknown: + case ResultWas::FailureBit: + case ResultWas::Exception: + printResultType( Colour::Error, "** internal error **" ); + break; + } + } + + private: + void printSourceInfo() const { + Colour colourGuard( Colour::FileName ); + stream << result.getSourceInfo() << ':'; + } + + void printResultType( Colour::Code colour, std::string const& passOrFail ) const { + if( !passOrFail.empty() ) { + { + Colour colourGuard( colour ); + stream << ' ' << passOrFail; + } + stream << ':'; + } + } + + void printIssue( std::string const& issue ) const { + stream << ' ' << issue; + } + + void printExpressionWas() { + if( result.hasExpression() ) { + stream << ';'; + { + Colour colour( dimColour() ); + stream << " expression was:"; + } + printOriginalExpression(); + } + } + + void printOriginalExpression() const { + if( result.hasExpression() ) { + stream << ' ' << result.getExpression(); + } + } + + void printReconstructedExpression() const { + if( result.hasExpandedExpression() ) { + { + Colour colour( dimColour() ); + stream << " for: "; + } + stream << result.getExpandedExpression(); + } + } + + void printMessage() { + if ( itMessage != messages.end() ) { + stream << " '" << itMessage->message << '\''; + ++itMessage; + } + } + + void printRemainingMessages( Colour::Code colour = dimColour() ) { + if ( itMessage == messages.end() ) + return; + + // using messages.end() directly yields (or auto) compilation error: + std::vector::const_iterator itEnd = messages.end(); + const std::size_t N = static_cast( std::distance( itMessage, itEnd ) ); + + { + Colour colourGuard( colour ); + stream << " with " << pluralise( N, "message" ) << ':'; + } + + for(; itMessage != itEnd; ) { + // If this assertion is a warning ignore any INFO messages + if( printInfoMessages || itMessage->type != ResultWas::Info ) { + stream << " '" << itMessage->message << '\''; + if ( ++itMessage != itEnd ) { + Colour colourGuard( dimColour() ); + stream << " and"; + } + } + } + } + + private: + std::ostream& stream; + AssertionResult const& result; + std::vector messages; + std::vector::const_iterator itMessage; + bool printInfoMessages; + }; + + // Colour, message variants: + // - white: No tests ran. + // - red: Failed [both/all] N test cases, failed [both/all] M assertions. + // - white: Passed [both/all] N test cases (no assertions). + // - red: Failed N tests cases, failed M assertions. + // - green: Passed [both/all] N tests cases with M assertions. + + void printTotals( const Totals& totals ) const { + if( totals.testCases.total() == 0 ) { + stream << "No tests ran."; + } + else if( totals.testCases.failed == totals.testCases.total() ) { + Colour colour( Colour::ResultError ); + const std::string qualify_assertions_failed = + totals.assertions.failed == totals.assertions.total() ? + bothOrAll( totals.assertions.failed ) : std::string(); + stream << + "Failed " << bothOrAll( totals.testCases.failed ) + << pluralise( totals.testCases.failed, "test case" ) << ", " + "failed " << qualify_assertions_failed << + pluralise( totals.assertions.failed, "assertion" ) << '.'; + } + else if( totals.assertions.total() == 0 ) { + stream << + "Passed " << bothOrAll( totals.testCases.total() ) + << pluralise( totals.testCases.total(), "test case" ) + << " (no assertions)."; + } + else if( totals.assertions.failed ) { + Colour colour( Colour::ResultError ); + stream << + "Failed " << pluralise( totals.testCases.failed, "test case" ) << ", " + "failed " << pluralise( totals.assertions.failed, "assertion" ) << '.'; + } + else { + Colour colour( Colour::ResultSuccess ); + stream << + "Passed " << bothOrAll( totals.testCases.passed ) + << pluralise( totals.testCases.passed, "test case" ) << + " with " << pluralise( totals.assertions.passed, "assertion" ) << '.'; + } + } + }; + + CompactReporter::~CompactReporter() {} + + CATCH_REGISTER_REPORTER( "compact", CompactReporter ) + +} // end namespace Catch +// end catch_reporter_compact.cpp +// start catch_reporter_console.cpp + +#include +#include + +#if defined(_MSC_VER) +#pragma warning(push) +#pragma warning(disable:4061) // Not all labels are EXPLICITLY handled in switch + // Note that 4062 (not all labels are handled + // and default is missing) is enabled +#endif + +namespace Catch { + + namespace { + std::size_t makeRatio( std::size_t number, std::size_t total ) { + std::size_t ratio = total > 0 ? CATCH_CONFIG_CONSOLE_WIDTH * number/ total : 0; + return ( ratio == 0 && number > 0 ) ? 1 : ratio; + } + + std::size_t& findMax( std::size_t& i, std::size_t& j, std::size_t& k ) { + if( i > j && i > k ) + return i; + else if( j > k ) + return j; + else + return k; + } + + struct ColumnInfo { + enum Justification { Left, Right }; + std::string name; + int width; + Justification justification; + }; + struct ColumnBreak {}; + struct RowBreak {}; + + class TablePrinter { + std::ostream& m_os; + std::vector m_columnInfos; + std::ostringstream m_oss; + int m_currentColumn = -1; + bool m_isOpen = false; + + public: + TablePrinter( std::ostream& os, std::vector const& columnInfos ) + : m_os( os ), + m_columnInfos( columnInfos ) + {} + + auto columnInfos() const -> std::vector const& { + return m_columnInfos; + } + + void open() { + if( !m_isOpen ) { + m_isOpen = true; + *this << RowBreak(); + for( auto const& info : m_columnInfos ) + *this << info.name << ColumnBreak(); + *this << RowBreak(); + m_os << Catch::getLineOfChars<'-'>() << "\n"; + } + } + void close() { + if( m_isOpen ) { + *this << RowBreak(); + m_os << std::endl; + m_isOpen = false; + } + } + + template + friend TablePrinter& operator << ( TablePrinter& tp, T const& value ) { + tp.m_oss << value; + return tp; + } + + friend TablePrinter& operator << ( TablePrinter& tp, ColumnBreak ) { + auto colStr = tp.m_oss.str(); + // This takes account of utf8 encodings + auto strSize = Catch::StringRef( colStr ).numberOfCharacters(); + tp.m_oss.str(""); + tp.open(); + if( tp.m_currentColumn == static_cast(tp.m_columnInfos.size()-1) ) { + tp.m_currentColumn = -1; + tp.m_os << "\n"; + } + tp.m_currentColumn++; + + auto colInfo = tp.m_columnInfos[tp.m_currentColumn]; + auto padding = ( strSize+2 < static_cast( colInfo.width ) ) + ? std::string( colInfo.width-(strSize+2), ' ' ) + : std::string(); + if( colInfo.justification == ColumnInfo::Left ) + tp.m_os << colStr << padding << " "; + else + tp.m_os << padding << colStr << " "; + return tp; + } + + friend TablePrinter& operator << ( TablePrinter& tp, RowBreak ) { + if( tp.m_currentColumn > 0 ) { + tp.m_os << "\n"; + tp.m_currentColumn = -1; + } + return tp; + } + }; + + class Duration { + enum class Unit { + Auto, + Nanoseconds, + Microseconds, + Milliseconds, + Seconds, + Minutes + }; + static const uint64_t s_nanosecondsInAMicrosecond = 1000; + static const uint64_t s_nanosecondsInAMillisecond = 1000*s_nanosecondsInAMicrosecond; + static const uint64_t s_nanosecondsInASecond = 1000*s_nanosecondsInAMillisecond; + static const uint64_t s_nanosecondsInAMinute = 60*s_nanosecondsInASecond; + + uint64_t m_inNanoseconds; + Unit m_units; + + public: + Duration( uint64_t inNanoseconds, Unit units = Unit::Auto ) + : m_inNanoseconds( inNanoseconds ), + m_units( units ) + { + if( m_units == Unit::Auto ) { + if( m_inNanoseconds < s_nanosecondsInAMicrosecond ) + m_units = Unit::Nanoseconds; + else if( m_inNanoseconds < s_nanosecondsInAMillisecond ) + m_units = Unit::Microseconds; + else if( m_inNanoseconds < s_nanosecondsInASecond ) + m_units = Unit::Milliseconds; + else if( m_inNanoseconds < s_nanosecondsInAMinute ) + m_units = Unit::Seconds; + else + m_units = Unit::Minutes; + } + + } + + auto value() const -> double { + switch( m_units ) { + case Unit::Microseconds: + return m_inNanoseconds / static_cast( s_nanosecondsInAMicrosecond ); + case Unit::Milliseconds: + return m_inNanoseconds / static_cast( s_nanosecondsInAMillisecond ); + case Unit::Seconds: + return m_inNanoseconds / static_cast( s_nanosecondsInASecond ); + case Unit::Minutes: + return m_inNanoseconds / static_cast( s_nanosecondsInAMinute ); + default: + return static_cast( m_inNanoseconds ); + } + } + auto unitsAsString() const -> std::string { + switch( m_units ) { + case Unit::Nanoseconds: + return "ns"; + case Unit::Microseconds: + return "µs"; + case Unit::Milliseconds: + return "ms"; + case Unit::Seconds: + return "s"; + case Unit::Minutes: + return "m"; + default: + return "** internal error **"; + } + + } + friend auto operator << ( std::ostream& os, Duration const& duration ) -> std::ostream& { + return os << duration.value() << " " << duration.unitsAsString(); + } + }; + } // end anon namespace + + struct ConsoleReporter : StreamingReporterBase { + TablePrinter m_tablePrinter; + + ConsoleReporter( ReporterConfig const& config ) + : StreamingReporterBase( config ), + m_tablePrinter( config.stream(), + { + { "benchmark name", CATCH_CONFIG_CONSOLE_WIDTH-32, ColumnInfo::Left }, + { "iters", 8, ColumnInfo::Right }, + { "elapsed ns", 14, ColumnInfo::Right }, + { "average", 14, ColumnInfo::Right } + } ) + {} + ~ConsoleReporter() override; + static std::string getDescription() { + return "Reports test results as plain lines of text"; + } + + void noMatchingTestCases( std::string const& spec ) override { + stream << "No test cases matched '" << spec << '\'' << std::endl; + } + + void assertionStarting( AssertionInfo const& ) override { + } + + bool assertionEnded( AssertionStats const& _assertionStats ) override { + AssertionResult const& result = _assertionStats.assertionResult; + + bool includeResults = m_config->includeSuccessfulResults() || !result.isOk(); + + // Drop out if result was successful but we're not printing them. + if( !includeResults && result.getResultType() != ResultWas::Warning ) + return false; + + lazyPrint(); + + AssertionPrinter printer( stream, _assertionStats, includeResults ); + printer.print(); + stream << std::endl; + return true; + } + + void sectionStarting( SectionInfo const& _sectionInfo ) override { + m_headerPrinted = false; + StreamingReporterBase::sectionStarting( _sectionInfo ); + } + void sectionEnded( SectionStats const& _sectionStats ) override { + m_tablePrinter.close(); + if( _sectionStats.missingAssertions ) { + lazyPrint(); + Colour colour( Colour::ResultError ); + if( m_sectionStack.size() > 1 ) + stream << "\nNo assertions in section"; + else + stream << "\nNo assertions in test case"; + stream << " '" << _sectionStats.sectionInfo.name << "'\n" << std::endl; + } + if( m_config->showDurations() == ShowDurations::Always ) { + stream << getFormattedDuration(_sectionStats.durationInSeconds) << " s: " << _sectionStats.sectionInfo.name << std::endl; + } + if( m_headerPrinted ) { + m_headerPrinted = false; + } + StreamingReporterBase::sectionEnded( _sectionStats ); + } + + void benchmarkStarting( BenchmarkInfo const& info ) override { + lazyPrintWithoutClosingBenchmarkTable(); + + auto nameCol = Column( info.name ).width( m_tablePrinter.columnInfos()[0].width-2 ); + + bool firstLine = true; + for( auto line : nameCol ) { + if( !firstLine ) + m_tablePrinter << ColumnBreak() << ColumnBreak() << ColumnBreak(); + else + firstLine = false; + + m_tablePrinter << line << ColumnBreak(); + } + } + void benchmarkEnded( BenchmarkStats const& stats ) override { + Duration average( stats.elapsedTimeInNanoseconds/stats.iterations ); + m_tablePrinter + << stats.iterations << ColumnBreak() + << stats.elapsedTimeInNanoseconds << ColumnBreak() + << average << ColumnBreak(); + } + + void testCaseEnded( TestCaseStats const& _testCaseStats ) override { + m_tablePrinter.close(); + StreamingReporterBase::testCaseEnded( _testCaseStats ); + m_headerPrinted = false; + } + void testGroupEnded( TestGroupStats const& _testGroupStats ) override { + if( currentGroupInfo.used ) { + printSummaryDivider(); + stream << "Summary for group '" << _testGroupStats.groupInfo.name << "':\n"; + printTotals( _testGroupStats.totals ); + stream << '\n' << std::endl; + } + StreamingReporterBase::testGroupEnded( _testGroupStats ); + } + void testRunEnded( TestRunStats const& _testRunStats ) override { + printTotalsDivider( _testRunStats.totals ); + printTotals( _testRunStats.totals ); + stream << std::endl; + StreamingReporterBase::testRunEnded( _testRunStats ); + } + + private: + + class AssertionPrinter { + public: + AssertionPrinter& operator= ( AssertionPrinter const& ) = delete; + AssertionPrinter( AssertionPrinter const& ) = delete; + AssertionPrinter( std::ostream& _stream, AssertionStats const& _stats, bool _printInfoMessages ) + : stream( _stream ), + stats( _stats ), + result( _stats.assertionResult ), + colour( Colour::None ), + message( result.getMessage() ), + messages( _stats.infoMessages ), + printInfoMessages( _printInfoMessages ) + { + switch( result.getResultType() ) { + case ResultWas::Ok: + colour = Colour::Success; + passOrFail = "PASSED"; + //if( result.hasMessage() ) + if( _stats.infoMessages.size() == 1 ) + messageLabel = "with message"; + if( _stats.infoMessages.size() > 1 ) + messageLabel = "with messages"; + break; + case ResultWas::ExpressionFailed: + if( result.isOk() ) { + colour = Colour::Success; + passOrFail = "FAILED - but was ok"; + } + else { + colour = Colour::Error; + passOrFail = "FAILED"; + } + if( _stats.infoMessages.size() == 1 ) + messageLabel = "with message"; + if( _stats.infoMessages.size() > 1 ) + messageLabel = "with messages"; + break; + case ResultWas::ThrewException: + colour = Colour::Error; + passOrFail = "FAILED"; + messageLabel = "due to unexpected exception with "; + if (_stats.infoMessages.size() == 1) + messageLabel += "message"; + if (_stats.infoMessages.size() > 1) + messageLabel += "messages"; + break; + case ResultWas::FatalErrorCondition: + colour = Colour::Error; + passOrFail = "FAILED"; + messageLabel = "due to a fatal error condition"; + break; + case ResultWas::DidntThrowException: + colour = Colour::Error; + passOrFail = "FAILED"; + messageLabel = "because no exception was thrown where one was expected"; + break; + case ResultWas::Info: + messageLabel = "info"; + break; + case ResultWas::Warning: + messageLabel = "warning"; + break; + case ResultWas::ExplicitFailure: + passOrFail = "FAILED"; + colour = Colour::Error; + if( _stats.infoMessages.size() == 1 ) + messageLabel = "explicitly with message"; + if( _stats.infoMessages.size() > 1 ) + messageLabel = "explicitly with messages"; + break; + // These cases are here to prevent compiler warnings + case ResultWas::Unknown: + case ResultWas::FailureBit: + case ResultWas::Exception: + passOrFail = "** internal error **"; + colour = Colour::Error; + break; + } + } + + void print() const { + printSourceInfo(); + if( stats.totals.assertions.total() > 0 ) { + if( result.isOk() ) + stream << '\n'; + printResultType(); + printOriginalExpression(); + printReconstructedExpression(); + } + else { + stream << '\n'; + } + printMessage(); + } + + private: + void printResultType() const { + if( !passOrFail.empty() ) { + Colour colourGuard( colour ); + stream << passOrFail << ":\n"; + } + } + void printOriginalExpression() const { + if( result.hasExpression() ) { + Colour colourGuard( Colour::OriginalExpression ); + stream << " "; + stream << result.getExpressionInMacro(); + stream << '\n'; + } + } + void printReconstructedExpression() const { + if( result.hasExpandedExpression() ) { + stream << "with expansion:\n"; + Colour colourGuard( Colour::ReconstructedExpression ); + stream << Column( result.getExpandedExpression() ).indent(2) << '\n'; + } + } + void printMessage() const { + if( !messageLabel.empty() ) + stream << messageLabel << ':' << '\n'; + for( auto const& msg : messages ) { + // If this assertion is a warning ignore any INFO messages + if( printInfoMessages || msg.type != ResultWas::Info ) + stream << Column( msg.message ).indent(2) << '\n'; + } + } + void printSourceInfo() const { + Colour colourGuard( Colour::FileName ); + stream << result.getSourceInfo() << ": "; + } + + std::ostream& stream; + AssertionStats const& stats; + AssertionResult const& result; + Colour::Code colour; + std::string passOrFail; + std::string messageLabel; + std::string message; + std::vector messages; + bool printInfoMessages; + }; + + void lazyPrint() { + + m_tablePrinter.close(); + lazyPrintWithoutClosingBenchmarkTable(); + } + + void lazyPrintWithoutClosingBenchmarkTable() { + + if( !currentTestRunInfo.used ) + lazyPrintRunInfo(); + if( !currentGroupInfo.used ) + lazyPrintGroupInfo(); + + if( !m_headerPrinted ) { + printTestCaseAndSectionHeader(); + m_headerPrinted = true; + } + } + void lazyPrintRunInfo() { + stream << '\n' << getLineOfChars<'~'>() << '\n'; + Colour colour( Colour::SecondaryText ); + stream << currentTestRunInfo->name + << " is a Catch v" << libraryVersion() << " host application.\n" + << "Run with -? for options\n\n"; + + if( m_config->rngSeed() != 0 ) + stream << "Randomness seeded to: " << m_config->rngSeed() << "\n\n"; + + currentTestRunInfo.used = true; + } + void lazyPrintGroupInfo() { + if( !currentGroupInfo->name.empty() && currentGroupInfo->groupsCounts > 1 ) { + printClosedHeader( "Group: " + currentGroupInfo->name ); + currentGroupInfo.used = true; + } + } + void printTestCaseAndSectionHeader() { + assert( !m_sectionStack.empty() ); + printOpenHeader( currentTestCaseInfo->name ); + + if( m_sectionStack.size() > 1 ) { + Colour colourGuard( Colour::Headers ); + + auto + it = m_sectionStack.begin()+1, // Skip first section (test case) + itEnd = m_sectionStack.end(); + for( ; it != itEnd; ++it ) + printHeaderString( it->name, 2 ); + } + + SourceLineInfo lineInfo = m_sectionStack.back().lineInfo; + + if( !lineInfo.empty() ){ + stream << getLineOfChars<'-'>() << '\n'; + Colour colourGuard( Colour::FileName ); + stream << lineInfo << '\n'; + } + stream << getLineOfChars<'.'>() << '\n' << std::endl; + } + + void printClosedHeader( std::string const& _name ) { + printOpenHeader( _name ); + stream << getLineOfChars<'.'>() << '\n'; + } + void printOpenHeader( std::string const& _name ) { + stream << getLineOfChars<'-'>() << '\n'; + { + Colour colourGuard( Colour::Headers ); + printHeaderString( _name ); + } + } + + // if string has a : in first line will set indent to follow it on + // subsequent lines + void printHeaderString( std::string const& _string, std::size_t indent = 0 ) { + std::size_t i = _string.find( ": " ); + if( i != std::string::npos ) + i+=2; + else + i = 0; + stream << Column( _string ).indent( indent+i ).initialIndent( indent ) << '\n'; + } + + struct SummaryColumn { + + SummaryColumn( std::string const& _label, Colour::Code _colour ) + : label( _label ), + colour( _colour ) + {} + SummaryColumn addRow( std::size_t count ) { + std::ostringstream oss; + oss << count; + std::string row = oss.str(); + for( auto& oldRow : rows ) { + while( oldRow.size() < row.size() ) + oldRow = ' ' + oldRow; + while( oldRow.size() > row.size() ) + row = ' ' + row; + } + rows.push_back( row ); + return *this; + } + + std::string label; + Colour::Code colour; + std::vector rows; + + }; + + void printTotals( Totals const& totals ) { + if( totals.testCases.total() == 0 ) { + stream << Colour( Colour::Warning ) << "No tests ran\n"; + } + else if( totals.assertions.total() > 0 && totals.testCases.allPassed() ) { + stream << Colour( Colour::ResultSuccess ) << "All tests passed"; + stream << " (" + << pluralise( totals.assertions.passed, "assertion" ) << " in " + << pluralise( totals.testCases.passed, "test case" ) << ')' + << '\n'; + } + else { + + std::vector columns; + columns.push_back( SummaryColumn( "", Colour::None ) + .addRow( totals.testCases.total() ) + .addRow( totals.assertions.total() ) ); + columns.push_back( SummaryColumn( "passed", Colour::Success ) + .addRow( totals.testCases.passed ) + .addRow( totals.assertions.passed ) ); + columns.push_back( SummaryColumn( "failed", Colour::ResultError ) + .addRow( totals.testCases.failed ) + .addRow( totals.assertions.failed ) ); + columns.push_back( SummaryColumn( "failed as expected", Colour::ResultExpectedFailure ) + .addRow( totals.testCases.failedButOk ) + .addRow( totals.assertions.failedButOk ) ); + + printSummaryRow( "test cases", columns, 0 ); + printSummaryRow( "assertions", columns, 1 ); + } + } + void printSummaryRow( std::string const& label, std::vector const& cols, std::size_t row ) { + for( auto col : cols ) { + std::string value = col.rows[row]; + if( col.label.empty() ) { + stream << label << ": "; + if( value != "0" ) + stream << value; + else + stream << Colour( Colour::Warning ) << "- none -"; + } + else if( value != "0" ) { + stream << Colour( Colour::LightGrey ) << " | "; + stream << Colour( col.colour ) + << value << ' ' << col.label; + } + } + stream << '\n'; + } + + void printTotalsDivider( Totals const& totals ) { + if( totals.testCases.total() > 0 ) { + std::size_t failedRatio = makeRatio( totals.testCases.failed, totals.testCases.total() ); + std::size_t failedButOkRatio = makeRatio( totals.testCases.failedButOk, totals.testCases.total() ); + std::size_t passedRatio = makeRatio( totals.testCases.passed, totals.testCases.total() ); + while( failedRatio + failedButOkRatio + passedRatio < CATCH_CONFIG_CONSOLE_WIDTH-1 ) + findMax( failedRatio, failedButOkRatio, passedRatio )++; + while( failedRatio + failedButOkRatio + passedRatio > CATCH_CONFIG_CONSOLE_WIDTH-1 ) + findMax( failedRatio, failedButOkRatio, passedRatio )--; + + stream << Colour( Colour::Error ) << std::string( failedRatio, '=' ); + stream << Colour( Colour::ResultExpectedFailure ) << std::string( failedButOkRatio, '=' ); + if( totals.testCases.allPassed() ) + stream << Colour( Colour::ResultSuccess ) << std::string( passedRatio, '=' ); + else + stream << Colour( Colour::Success ) << std::string( passedRatio, '=' ); + } + else { + stream << Colour( Colour::Warning ) << std::string( CATCH_CONFIG_CONSOLE_WIDTH-1, '=' ); + } + stream << '\n'; + } + void printSummaryDivider() { + stream << getLineOfChars<'-'>() << '\n'; + } + + private: + bool m_headerPrinted = false; + }; + + CATCH_REGISTER_REPORTER( "console", ConsoleReporter ) + + ConsoleReporter::~ConsoleReporter() {} + +} // end namespace Catch + +#if defined(_MSC_VER) +#pragma warning(pop) +#endif +// end catch_reporter_console.cpp +// start catch_reporter_junit.cpp + +#include + +#include +#include + +namespace Catch { + + namespace { + std::string getCurrentTimestamp() { + // Beware, this is not reentrant because of backward compatibility issues + // Also, UTC only, again because of backward compatibility (%z is C++11) + time_t rawtime; + std::time(&rawtime); + auto const timeStampSize = sizeof("2017-01-16T17:06:45Z"); + +#ifdef _MSC_VER + std::tm timeInfo = {}; + gmtime_s(&timeInfo, &rawtime); +#else + std::tm* timeInfo; + timeInfo = std::gmtime(&rawtime); +#endif + + char timeStamp[timeStampSize]; + const char * const fmt = "%Y-%m-%dT%H:%M:%SZ"; + +#ifdef _MSC_VER + std::strftime(timeStamp, timeStampSize, fmt, &timeInfo); +#else + std::strftime(timeStamp, timeStampSize, fmt, timeInfo); +#endif + return std::string(timeStamp); + } + + std::string fileNameTag(const std::vector &tags) { + auto it = std::find_if(begin(tags), + end(tags), + [] (std::string const& tag) {return tag.front() == '#'; }); + if (it != tags.end()) + return it->substr(1); + return std::string(); + } + } + + class JunitReporter : public CumulativeReporterBase { + public: + JunitReporter( ReporterConfig const& _config ) + : CumulativeReporterBase( _config ), + xml( _config.stream() ) + { + m_reporterPrefs.shouldRedirectStdOut = true; + } + + ~JunitReporter() override; + + static std::string getDescription() { + return "Reports test results in an XML format that looks like Ant's junitreport target"; + } + + void noMatchingTestCases( std::string const& /*spec*/ ) override {} + + void testRunStarting( TestRunInfo const& runInfo ) override { + CumulativeReporterBase::testRunStarting( runInfo ); + xml.startElement( "testsuites" ); + } + + void testGroupStarting( GroupInfo const& groupInfo ) override { + suiteTimer.start(); + stdOutForSuite.str(""); + stdErrForSuite.str(""); + unexpectedExceptions = 0; + CumulativeReporterBase::testGroupStarting( groupInfo ); + } + + void testCaseStarting( TestCaseInfo const& testCaseInfo ) override { + m_okToFail = testCaseInfo.okToFail(); + } + bool assertionEnded( AssertionStats const& assertionStats ) override { + if( assertionStats.assertionResult.getResultType() == ResultWas::ThrewException && !m_okToFail ) + unexpectedExceptions++; + return CumulativeReporterBase::assertionEnded( assertionStats ); + } + + void testCaseEnded( TestCaseStats const& testCaseStats ) override { + stdOutForSuite << testCaseStats.stdOut; + stdErrForSuite << testCaseStats.stdErr; + CumulativeReporterBase::testCaseEnded( testCaseStats ); + } + + void testGroupEnded( TestGroupStats const& testGroupStats ) override { + double suiteTime = suiteTimer.getElapsedSeconds(); + CumulativeReporterBase::testGroupEnded( testGroupStats ); + writeGroup( *m_testGroups.back(), suiteTime ); + } + + void testRunEndedCumulative() override { + xml.endElement(); + } + + void writeGroup( TestGroupNode const& groupNode, double suiteTime ) { + XmlWriter::ScopedElement e = xml.scopedElement( "testsuite" ); + TestGroupStats const& stats = groupNode.value; + xml.writeAttribute( "name", stats.groupInfo.name ); + xml.writeAttribute( "errors", unexpectedExceptions ); + xml.writeAttribute( "failures", stats.totals.assertions.failed-unexpectedExceptions ); + xml.writeAttribute( "tests", stats.totals.assertions.total() ); + xml.writeAttribute( "hostname", "tbd" ); // !TBD + if( m_config->showDurations() == ShowDurations::Never ) + xml.writeAttribute( "time", "" ); + else + xml.writeAttribute( "time", suiteTime ); + xml.writeAttribute( "timestamp", getCurrentTimestamp() ); + + // Write test cases + for( auto const& child : groupNode.children ) + writeTestCase( *child ); + + xml.scopedElement( "system-out" ).writeText( trim( stdOutForSuite.str() ), false ); + xml.scopedElement( "system-err" ).writeText( trim( stdErrForSuite.str() ), false ); + } + + void writeTestCase( TestCaseNode const& testCaseNode ) { + TestCaseStats const& stats = testCaseNode.value; + + // All test cases have exactly one section - which represents the + // test case itself. That section may have 0-n nested sections + assert( testCaseNode.children.size() == 1 ); + SectionNode const& rootSection = *testCaseNode.children.front(); + + std::string className = stats.testInfo.className; + + if( className.empty() ) { + className = fileNameTag(stats.testInfo.tags); + if ( className.empty() ) + className = "global"; + } + + if ( !m_config->name().empty() ) + className = m_config->name() + "." + className; + + writeSection( className, "", rootSection ); + } + + void writeSection( std::string const& className, + std::string const& rootName, + SectionNode const& sectionNode ) { + std::string name = trim( sectionNode.stats.sectionInfo.name ); + if( !rootName.empty() ) + name = rootName + '/' + name; + + if( !sectionNode.assertions.empty() || + !sectionNode.stdOut.empty() || + !sectionNode.stdErr.empty() ) { + XmlWriter::ScopedElement e = xml.scopedElement( "testcase" ); + if( className.empty() ) { + xml.writeAttribute( "classname", name ); + xml.writeAttribute( "name", "root" ); + } + else { + xml.writeAttribute( "classname", className ); + xml.writeAttribute( "name", name ); + } + xml.writeAttribute( "time", ::Catch::Detail::stringify( sectionNode.stats.durationInSeconds ) ); + + writeAssertions( sectionNode ); + + if( !sectionNode.stdOut.empty() ) + xml.scopedElement( "system-out" ).writeText( trim( sectionNode.stdOut ), false ); + if( !sectionNode.stdErr.empty() ) + xml.scopedElement( "system-err" ).writeText( trim( sectionNode.stdErr ), false ); + } + for( auto const& childNode : sectionNode.childSections ) + if( className.empty() ) + writeSection( name, "", *childNode ); + else + writeSection( className, name, *childNode ); + } + + void writeAssertions( SectionNode const& sectionNode ) { + for( auto const& assertion : sectionNode.assertions ) + writeAssertion( assertion ); + } + void writeAssertion( AssertionStats const& stats ) { + AssertionResult const& result = stats.assertionResult; + if( !result.isOk() ) { + std::string elementName; + switch( result.getResultType() ) { + case ResultWas::ThrewException: + case ResultWas::FatalErrorCondition: + elementName = "error"; + break; + case ResultWas::ExplicitFailure: + elementName = "failure"; + break; + case ResultWas::ExpressionFailed: + elementName = "failure"; + break; + case ResultWas::DidntThrowException: + elementName = "failure"; + break; + + // We should never see these here: + case ResultWas::Info: + case ResultWas::Warning: + case ResultWas::Ok: + case ResultWas::Unknown: + case ResultWas::FailureBit: + case ResultWas::Exception: + elementName = "internalError"; + break; + } + + XmlWriter::ScopedElement e = xml.scopedElement( elementName ); + + xml.writeAttribute( "message", result.getExpandedExpression() ); + xml.writeAttribute( "type", result.getTestMacroName() ); + + std::ostringstream oss; + if( !result.getMessage().empty() ) + oss << result.getMessage() << '\n'; + for( auto const& msg : stats.infoMessages ) + if( msg.type == ResultWas::Info ) + oss << msg.message << '\n'; + + oss << "at " << result.getSourceInfo(); + xml.writeText( oss.str(), false ); + } + } + + XmlWriter xml; + Timer suiteTimer; + std::ostringstream stdOutForSuite; + std::ostringstream stdErrForSuite; + unsigned int unexpectedExceptions = 0; + bool m_okToFail = false; + }; + + JunitReporter::~JunitReporter() {} + CATCH_REGISTER_REPORTER( "junit", JunitReporter ) + +} // end namespace Catch +// end catch_reporter_junit.cpp +// start catch_reporter_multi.cpp + +namespace Catch { + + void MultipleReporters::add( IStreamingReporterPtr&& reporter ) { + m_reporters.push_back( std::move( reporter ) ); + } + + ReporterPreferences MultipleReporters::getPreferences() const { + return m_reporters[0]->getPreferences(); + } + + std::set MultipleReporters::getSupportedVerbosities() { + return std::set{ }; + } + + void MultipleReporters::noMatchingTestCases( std::string const& spec ) { + for( auto const& reporter : m_reporters ) + reporter->noMatchingTestCases( spec ); + } + + void MultipleReporters::benchmarkStarting( BenchmarkInfo const& benchmarkInfo ) { + for( auto const& reporter : m_reporters ) + reporter->benchmarkStarting( benchmarkInfo ); + } + void MultipleReporters::benchmarkEnded( BenchmarkStats const& benchmarkStats ) { + for( auto const& reporter : m_reporters ) + reporter->benchmarkEnded( benchmarkStats ); + } + + void MultipleReporters::testRunStarting( TestRunInfo const& testRunInfo ) { + for( auto const& reporter : m_reporters ) + reporter->testRunStarting( testRunInfo ); + } + + void MultipleReporters::testGroupStarting( GroupInfo const& groupInfo ) { + for( auto const& reporter : m_reporters ) + reporter->testGroupStarting( groupInfo ); + } + + void MultipleReporters::testCaseStarting( TestCaseInfo const& testInfo ) { + for( auto const& reporter : m_reporters ) + reporter->testCaseStarting( testInfo ); + } + + void MultipleReporters::sectionStarting( SectionInfo const& sectionInfo ) { + for( auto const& reporter : m_reporters ) + reporter->sectionStarting( sectionInfo ); + } + + void MultipleReporters::assertionStarting( AssertionInfo const& assertionInfo ) { + for( auto const& reporter : m_reporters ) + reporter->assertionStarting( assertionInfo ); + } + + // The return value indicates if the messages buffer should be cleared: + bool MultipleReporters::assertionEnded( AssertionStats const& assertionStats ) { + bool clearBuffer = false; + for( auto const& reporter : m_reporters ) + clearBuffer |= reporter->assertionEnded( assertionStats ); + return clearBuffer; + } + + void MultipleReporters::sectionEnded( SectionStats const& sectionStats ) { + for( auto const& reporter : m_reporters ) + reporter->sectionEnded( sectionStats ); + } + + void MultipleReporters::testCaseEnded( TestCaseStats const& testCaseStats ) { + for( auto const& reporter : m_reporters ) + reporter->testCaseEnded( testCaseStats ); + } + + void MultipleReporters::testGroupEnded( TestGroupStats const& testGroupStats ) { + for( auto const& reporter : m_reporters ) + reporter->testGroupEnded( testGroupStats ); + } + + void MultipleReporters::testRunEnded( TestRunStats const& testRunStats ) { + for( auto const& reporter : m_reporters ) + reporter->testRunEnded( testRunStats ); + } + + void MultipleReporters::skipTest( TestCaseInfo const& testInfo ) { + for( auto const& reporter : m_reporters ) + reporter->skipTest( testInfo ); + } + + bool MultipleReporters::isMulti() const { + return true; + } + +} // end namespace Catch +// end catch_reporter_multi.cpp +// start catch_reporter_xml.cpp + +#if defined(_MSC_VER) +#pragma warning(push) +#pragma warning(disable:4061) // Not all labels are EXPLICITLY handled in switch + // Note that 4062 (not all labels are handled + // and default is missing) is enabled +#endif + +namespace Catch { + class XmlReporter : public StreamingReporterBase { + public: + XmlReporter( ReporterConfig const& _config ) + : StreamingReporterBase( _config ), + m_xml(_config.stream()) + { + m_reporterPrefs.shouldRedirectStdOut = true; + } + + ~XmlReporter() override; + + static std::string getDescription() { + return "Reports test results as an XML document"; + } + + virtual std::string getStylesheetRef() const { + return std::string(); + } + + void writeSourceInfo( SourceLineInfo const& sourceInfo ) { + m_xml + .writeAttribute( "filename", sourceInfo.file ) + .writeAttribute( "line", sourceInfo.line ); + } + + public: // StreamingReporterBase + + void noMatchingTestCases( std::string const& s ) override { + StreamingReporterBase::noMatchingTestCases( s ); + } + + void testRunStarting( TestRunInfo const& testInfo ) override { + StreamingReporterBase::testRunStarting( testInfo ); + std::string stylesheetRef = getStylesheetRef(); + if( !stylesheetRef.empty() ) + m_xml.writeStylesheetRef( stylesheetRef ); + m_xml.startElement( "Catch" ); + if( !m_config->name().empty() ) + m_xml.writeAttribute( "name", m_config->name() ); + } + + void testGroupStarting( GroupInfo const& groupInfo ) override { + StreamingReporterBase::testGroupStarting( groupInfo ); + m_xml.startElement( "Group" ) + .writeAttribute( "name", groupInfo.name ); + } + + void testCaseStarting( TestCaseInfo const& testInfo ) override { + StreamingReporterBase::testCaseStarting(testInfo); + m_xml.startElement( "TestCase" ) + .writeAttribute( "name", trim( testInfo.name ) ) + .writeAttribute( "description", testInfo.description ) + .writeAttribute( "tags", testInfo.tagsAsString() ); + + writeSourceInfo( testInfo.lineInfo ); + + if ( m_config->showDurations() == ShowDurations::Always ) + m_testCaseTimer.start(); + m_xml.ensureTagClosed(); + } + + void sectionStarting( SectionInfo const& sectionInfo ) override { + StreamingReporterBase::sectionStarting( sectionInfo ); + if( m_sectionDepth++ > 0 ) { + m_xml.startElement( "Section" ) + .writeAttribute( "name", trim( sectionInfo.name ) ) + .writeAttribute( "description", sectionInfo.description ); + writeSourceInfo( sectionInfo.lineInfo ); + m_xml.ensureTagClosed(); + } + } + + void assertionStarting( AssertionInfo const& ) override { } + + bool assertionEnded( AssertionStats const& assertionStats ) override { + + AssertionResult const& result = assertionStats.assertionResult; + + bool includeResults = m_config->includeSuccessfulResults() || !result.isOk(); + + if( includeResults ) { + // Print any info messages in tags. + for( auto const& msg : assertionStats.infoMessages ) { + if( msg.type == ResultWas::Info ) { + m_xml.scopedElement( "Info" ) + .writeText( msg.message ); + } else if ( msg.type == ResultWas::Warning ) { + m_xml.scopedElement( "Warning" ) + .writeText( msg.message ); + } + } + } + + // Drop out if result was successful but we're not printing them. + if( !includeResults && result.getResultType() != ResultWas::Warning ) + return true; + + // Print the expression if there is one. + if( result.hasExpression() ) { + m_xml.startElement( "Expression" ) + .writeAttribute( "success", result.succeeded() ) + .writeAttribute( "type", result.getTestMacroName() ); + + writeSourceInfo( result.getSourceInfo() ); + + m_xml.scopedElement( "Original" ) + .writeText( result.getExpression() ); + m_xml.scopedElement( "Expanded" ) + .writeText( result.getExpandedExpression() ); + } + + // And... Print a result applicable to each result type. + switch( result.getResultType() ) { + case ResultWas::ThrewException: + m_xml.startElement( "Exception" ); + writeSourceInfo( result.getSourceInfo() ); + m_xml.writeText( result.getMessage() ); + m_xml.endElement(); + break; + case ResultWas::FatalErrorCondition: + m_xml.startElement( "FatalErrorCondition" ); + writeSourceInfo( result.getSourceInfo() ); + m_xml.writeText( result.getMessage() ); + m_xml.endElement(); + break; + case ResultWas::Info: + m_xml.scopedElement( "Info" ) + .writeText( result.getMessage() ); + break; + case ResultWas::Warning: + // Warning will already have been written + break; + case ResultWas::ExplicitFailure: + m_xml.startElement( "Failure" ); + writeSourceInfo( result.getSourceInfo() ); + m_xml.writeText( result.getMessage() ); + m_xml.endElement(); + break; + default: + break; + } + + if( result.hasExpression() ) + m_xml.endElement(); + + return true; + } + + void sectionEnded( SectionStats const& sectionStats ) override { + StreamingReporterBase::sectionEnded( sectionStats ); + if( --m_sectionDepth > 0 ) { + XmlWriter::ScopedElement e = m_xml.scopedElement( "OverallResults" ); + e.writeAttribute( "successes", sectionStats.assertions.passed ); + e.writeAttribute( "failures", sectionStats.assertions.failed ); + e.writeAttribute( "expectedFailures", sectionStats.assertions.failedButOk ); + + if ( m_config->showDurations() == ShowDurations::Always ) + e.writeAttribute( "durationInSeconds", sectionStats.durationInSeconds ); + + m_xml.endElement(); + } + } + + void testCaseEnded( TestCaseStats const& testCaseStats ) override { + StreamingReporterBase::testCaseEnded( testCaseStats ); + XmlWriter::ScopedElement e = m_xml.scopedElement( "OverallResult" ); + e.writeAttribute( "success", testCaseStats.totals.assertions.allOk() ); + + if ( m_config->showDurations() == ShowDurations::Always ) + e.writeAttribute( "durationInSeconds", m_testCaseTimer.getElapsedSeconds() ); + + if( !testCaseStats.stdOut.empty() ) + m_xml.scopedElement( "StdOut" ).writeText( trim( testCaseStats.stdOut ), false ); + if( !testCaseStats.stdErr.empty() ) + m_xml.scopedElement( "StdErr" ).writeText( trim( testCaseStats.stdErr ), false ); + + m_xml.endElement(); + } + + void testGroupEnded( TestGroupStats const& testGroupStats ) override { + StreamingReporterBase::testGroupEnded( testGroupStats ); + // TODO: Check testGroupStats.aborting and act accordingly. + m_xml.scopedElement( "OverallResults" ) + .writeAttribute( "successes", testGroupStats.totals.assertions.passed ) + .writeAttribute( "failures", testGroupStats.totals.assertions.failed ) + .writeAttribute( "expectedFailures", testGroupStats.totals.assertions.failedButOk ); + m_xml.endElement(); + } + + void testRunEnded( TestRunStats const& testRunStats ) override { + StreamingReporterBase::testRunEnded( testRunStats ); + m_xml.scopedElement( "OverallResults" ) + .writeAttribute( "successes", testRunStats.totals.assertions.passed ) + .writeAttribute( "failures", testRunStats.totals.assertions.failed ) + .writeAttribute( "expectedFailures", testRunStats.totals.assertions.failedButOk ); + m_xml.endElement(); + } + + private: + Timer m_testCaseTimer; + XmlWriter m_xml; + int m_sectionDepth = 0; + }; + + XmlReporter::~XmlReporter() {} + CATCH_REGISTER_REPORTER( "xml", XmlReporter ) + +} // end namespace Catch + +#if defined(_MSC_VER) +#pragma warning(pop) +#endif +// end catch_reporter_xml.cpp + +namespace Catch { + LeakDetector leakDetector; +} + +#ifdef __clang__ +#pragma clang diagnostic pop +#endif + +// end catch_impl.hpp +#endif + +#ifdef CATCH_CONFIG_MAIN +// start catch_default_main.hpp + +#ifndef __OBJC__ + +#if defined(WIN32) && defined(_UNICODE) && !defined(DO_NOT_USE_WMAIN) +// Standard C/C++ Win32 Unicode wmain entry point +extern "C" int wmain (int argc, wchar_t * argv[], wchar_t * []) { +#else +// Standard C/C++ main entry point +int main (int argc, char * argv[]) { +#endif + + return Catch::Session().run( argc, argv ); +} + +#else // __OBJC__ + +// Objective-C entry point +int main (int argc, char * const argv[]) { +#if !CATCH_ARC_ENABLED + NSAutoreleasePool * pool = [[NSAutoreleasePool alloc] init]; +#endif + + Catch::registerTestMethods(); + int result = Catch::Session().run( argc, (char**)argv ); + +#if !CATCH_ARC_ENABLED + [pool drain]; +#endif + + return result; +} + +#endif // __OBJC__ + +// end catch_default_main.hpp +#endif + +#ifdef CLARA_CONFIG_MAIN_NOT_DEFINED +# undef CLARA_CONFIG_MAIN +#endif + +#if !defined(CATCH_CONFIG_DISABLE) +////// +// If this config identifier is defined then all CATCH macros are prefixed with CATCH_ +#ifdef CATCH_CONFIG_PREFIX_ALL + +#define CATCH_REQUIRE( ... ) INTERNAL_CATCH_TEST( "CATCH_REQUIRE", Catch::ResultDisposition::Normal, __VA_ARGS__ ) +#define CATCH_REQUIRE_FALSE( ... ) INTERNAL_CATCH_TEST( "CATCH_REQUIRE_FALSE", Catch::ResultDisposition::Normal | Catch::ResultDisposition::FalseTest, __VA_ARGS__ ) + +#define CATCH_REQUIRE_THROWS( ... ) INTERNAL_CATCH_THROWS( "CATCH_REQUIRE_THROWS", Catch::ResultDisposition::Normal, "", __VA_ARGS__ ) +#define CATCH_REQUIRE_THROWS_AS( expr, exceptionType ) INTERNAL_CATCH_THROWS_AS( "CATCH_REQUIRE_THROWS_AS", exceptionType, Catch::ResultDisposition::Normal, expr ) +#define CATCH_REQUIRE_THROWS_WITH( expr, matcher ) INTERNAL_CATCH_THROWS_STR_MATCHES( "CATCH_REQUIRE_THROWS_WITH", Catch::ResultDisposition::Normal, matcher, expr ) +#if !defined(CATCH_CONFIG_DISABLE_MATCHERS) +#define CATCH_REQUIRE_THROWS_MATCHES( expr, exceptionType, matcher ) INTERNAL_CATCH_THROWS_MATCHES( "CATCH_REQUIRE_THROWS_MATCHES", exceptionType, Catch::ResultDisposition::Normal, matcher, expr ) +#endif// CATCH_CONFIG_DISABLE_MATCHERS +#define CATCH_REQUIRE_NOTHROW( ... ) INTERNAL_CATCH_NO_THROW( "CATCH_REQUIRE_NOTHROW", Catch::ResultDisposition::Normal, __VA_ARGS__ ) + +#define CATCH_CHECK( ... ) INTERNAL_CATCH_TEST( "CATCH_CHECK", Catch::ResultDisposition::ContinueOnFailure, __VA_ARGS__ ) +#define CATCH_CHECK_FALSE( ... ) INTERNAL_CATCH_TEST( "CATCH_CHECK_FALSE", Catch::ResultDisposition::ContinueOnFailure | Catch::ResultDisposition::FalseTest, __VA_ARGS__ ) +#define CATCH_CHECKED_IF( ... ) INTERNAL_CATCH_IF( "CATCH_CHECKED_IF", Catch::ResultDisposition::ContinueOnFailure, __VA_ARGS__ ) +#define CATCH_CHECKED_ELSE( ... ) INTERNAL_CATCH_ELSE( "CATCH_CHECKED_ELSE", Catch::ResultDisposition::ContinueOnFailure, __VA_ARGS__ ) +#define CATCH_CHECK_NOFAIL( ... ) INTERNAL_CATCH_TEST( "CATCH_CHECK_NOFAIL", Catch::ResultDisposition::ContinueOnFailure | Catch::ResultDisposition::SuppressFail, __VA_ARGS__ ) + +#define CATCH_CHECK_THROWS( ... ) INTERNAL_CATCH_THROWS( "CATCH_CHECK_THROWS", Catch::ResultDisposition::ContinueOnFailure, "", __VA_ARGS__ ) +#define CATCH_CHECK_THROWS_AS( expr, exceptionType ) INTERNAL_CATCH_THROWS_AS( "CATCH_CHECK_THROWS_AS", exceptionType, Catch::ResultDisposition::ContinueOnFailure, expr ) +#define CATCH_CHECK_THROWS_WITH( expr, matcher ) INTERNAL_CATCH_THROWS_STR_MATCHES( "CATCH_CHECK_THROWS_WITH", Catch::ResultDisposition::ContinueOnFailure, matcher, expr ) +#if !defined(CATCH_CONFIG_DISABLE_MATCHERS) +#define CATCH_CHECK_THROWS_MATCHES( expr, exceptionType, matcher ) INTERNAL_CATCH_THROWS_MATCHES( "CATCH_CHECK_THROWS_MATCHES", exceptionType, Catch::ResultDisposition::ContinueOnFailure, matcher, expr ) +#endif // CATCH_CONFIG_DISABLE_MATCHERS +#define CATCH_CHECK_NOTHROW( ... ) INTERNAL_CATCH_NO_THROW( "CATCH_CHECK_NOTHROW", Catch::ResultDisposition::ContinueOnFailure, __VA_ARGS__ ) + +#if !defined(CATCH_CONFIG_DISABLE_MATCHERS) +#define CATCH_CHECK_THAT( arg, matcher ) INTERNAL_CHECK_THAT( "CATCH_CHECK_THAT", matcher, Catch::ResultDisposition::ContinueOnFailure, arg ) + +#define CATCH_REQUIRE_THAT( arg, matcher ) INTERNAL_CHECK_THAT( "CATCH_REQUIRE_THAT", matcher, Catch::ResultDisposition::Normal, arg ) +#endif // CATCH_CONFIG_DISABLE_MATCHERS + +#define CATCH_INFO( msg ) INTERNAL_CATCH_INFO( "CATCH_INFO", msg ) +#define CATCH_WARN( msg ) INTERNAL_CATCH_MSG( "CATCH_WARN", Catch::ResultWas::Warning, Catch::ResultDisposition::ContinueOnFailure, msg ) +#define CATCH_CAPTURE( msg ) INTERNAL_CATCH_INFO( "CATCH_CAPTURE", #msg " := " << ::Catch::Detail::stringify(msg) ) + +#define CATCH_TEST_CASE( ... ) INTERNAL_CATCH_TESTCASE( __VA_ARGS__ ) +#define CATCH_TEST_CASE_METHOD( className, ... ) INTERNAL_CATCH_TEST_CASE_METHOD( className, __VA_ARGS__ ) +#define CATCH_METHOD_AS_TEST_CASE( method, ... ) INTERNAL_CATCH_METHOD_AS_TEST_CASE( method, __VA_ARGS__ ) +#define CATCH_REGISTER_TEST_CASE( Function, ... ) INTERNAL_CATCH_REGISTER_TESTCASE( Function, __VA_ARGS__ ) +#define CATCH_SECTION( ... ) INTERNAL_CATCH_SECTION( __VA_ARGS__ ) +#define CATCH_FAIL( ... ) INTERNAL_CATCH_MSG( "CATCH_FAIL", Catch::ResultWas::ExplicitFailure, Catch::ResultDisposition::Normal, __VA_ARGS__ ) +#define CATCH_FAIL_CHECK( ... ) INTERNAL_CATCH_MSG( "CATCH_FAIL_CHECK", Catch::ResultWas::ExplicitFailure, Catch::ResultDisposition::ContinueOnFailure, __VA_ARGS__ ) +#define CATCH_SUCCEED( ... ) INTERNAL_CATCH_MSG( "CATCH_SUCCEED", Catch::ResultWas::Ok, Catch::ResultDisposition::ContinueOnFailure, __VA_ARGS__ ) + +#define CATCH_ANON_TEST_CASE() INTERNAL_CATCH_TESTCASE() + +// "BDD-style" convenience wrappers +#define CATCH_SCENARIO( ... ) CATCH_TEST_CASE( "Scenario: " __VA_ARGS__ ) +#define CATCH_SCENARIO_METHOD( className, ... ) INTERNAL_CATCH_TEST_CASE_METHOD( className, "Scenario: " __VA_ARGS__ ) +#define CATCH_GIVEN( desc ) CATCH_SECTION( std::string( "Given: ") + desc ) +#define CATCH_WHEN( desc ) CATCH_SECTION( std::string( " When: ") + desc ) +#define CATCH_AND_WHEN( desc ) CATCH_SECTION( std::string( " And: ") + desc ) +#define CATCH_THEN( desc ) CATCH_SECTION( std::string( " Then: ") + desc ) +#define CATCH_AND_THEN( desc ) CATCH_SECTION( std::string( " And: ") + desc ) + +// If CATCH_CONFIG_PREFIX_ALL is not defined then the CATCH_ prefix is not required +#else + +#define REQUIRE( ... ) INTERNAL_CATCH_TEST( "REQUIRE", Catch::ResultDisposition::Normal, __VA_ARGS__ ) +#define REQUIRE_FALSE( ... ) INTERNAL_CATCH_TEST( "REQUIRE_FALSE", Catch::ResultDisposition::Normal | Catch::ResultDisposition::FalseTest, __VA_ARGS__ ) + +#define REQUIRE_THROWS( ... ) INTERNAL_CATCH_THROWS( "REQUIRE_THROWS", Catch::ResultDisposition::Normal, __VA_ARGS__ ) +#define REQUIRE_THROWS_AS( expr, exceptionType ) INTERNAL_CATCH_THROWS_AS( "REQUIRE_THROWS_AS", exceptionType, Catch::ResultDisposition::Normal, expr ) +#define REQUIRE_THROWS_WITH( expr, matcher ) INTERNAL_CATCH_THROWS_STR_MATCHES( "REQUIRE_THROWS_WITH", Catch::ResultDisposition::Normal, matcher, expr ) +#if !defined(CATCH_CONFIG_DISABLE_MATCHERS) +#define REQUIRE_THROWS_MATCHES( expr, exceptionType, matcher ) INTERNAL_CATCH_THROWS_MATCHES( "REQUIRE_THROWS_MATCHES", exceptionType, Catch::ResultDisposition::Normal, matcher, expr ) +#endif // CATCH_CONFIG_DISABLE_MATCHERS +#define REQUIRE_NOTHROW( ... ) INTERNAL_CATCH_NO_THROW( "REQUIRE_NOTHROW", Catch::ResultDisposition::Normal, __VA_ARGS__ ) + +#define CHECK( ... ) INTERNAL_CATCH_TEST( "CHECK", Catch::ResultDisposition::ContinueOnFailure, __VA_ARGS__ ) +#define CHECK_FALSE( ... ) INTERNAL_CATCH_TEST( "CHECK_FALSE", Catch::ResultDisposition::ContinueOnFailure | Catch::ResultDisposition::FalseTest, __VA_ARGS__ ) +#define CHECKED_IF( ... ) INTERNAL_CATCH_IF( "CHECKED_IF", Catch::ResultDisposition::ContinueOnFailure, __VA_ARGS__ ) +#define CHECKED_ELSE( ... ) INTERNAL_CATCH_ELSE( "CHECKED_ELSE", Catch::ResultDisposition::ContinueOnFailure, __VA_ARGS__ ) +#define CHECK_NOFAIL( ... ) INTERNAL_CATCH_TEST( "CHECK_NOFAIL", Catch::ResultDisposition::ContinueOnFailure | Catch::ResultDisposition::SuppressFail, __VA_ARGS__ ) + +#define CHECK_THROWS( ... ) INTERNAL_CATCH_THROWS( "CHECK_THROWS", Catch::ResultDisposition::ContinueOnFailure, __VA_ARGS__ ) +#define CHECK_THROWS_AS( expr, exceptionType ) INTERNAL_CATCH_THROWS_AS( "CHECK_THROWS_AS", exceptionType, Catch::ResultDisposition::ContinueOnFailure, expr ) +#define CHECK_THROWS_WITH( expr, matcher ) INTERNAL_CATCH_THROWS_STR_MATCHES( "CHECK_THROWS_WITH", Catch::ResultDisposition::ContinueOnFailure, matcher, expr ) +#if !defined(CATCH_CONFIG_DISABLE_MATCHERS) +#define CHECK_THROWS_MATCHES( expr, exceptionType, matcher ) INTERNAL_CATCH_THROWS_MATCHES( "CHECK_THROWS_MATCHES", exceptionType, Catch::ResultDisposition::ContinueOnFailure, matcher, expr ) +#endif // CATCH_CONFIG_DISABLE_MATCHERS +#define CHECK_NOTHROW( ... ) INTERNAL_CATCH_NO_THROW( "CHECK_NOTHROW", Catch::ResultDisposition::ContinueOnFailure, __VA_ARGS__ ) + +#if !defined(CATCH_CONFIG_DISABLE_MATCHERS) +#define CHECK_THAT( arg, matcher ) INTERNAL_CHECK_THAT( "CHECK_THAT", matcher, Catch::ResultDisposition::ContinueOnFailure, arg ) + +#define REQUIRE_THAT( arg, matcher ) INTERNAL_CHECK_THAT( "REQUIRE_THAT", matcher, Catch::ResultDisposition::Normal, arg ) +#endif // CATCH_CONFIG_DISABLE_MATCHERS + +#define INFO( msg ) INTERNAL_CATCH_INFO( "INFO", msg ) +#define WARN( msg ) INTERNAL_CATCH_MSG( "WARN", Catch::ResultWas::Warning, Catch::ResultDisposition::ContinueOnFailure, msg ) +#define CAPTURE( msg ) INTERNAL_CATCH_INFO( "CAPTURE", #msg " := " << ::Catch::Detail::stringify(msg) ) + +#define TEST_CASE( ... ) INTERNAL_CATCH_TESTCASE( __VA_ARGS__ ) +#define TEST_CASE_METHOD( className, ... ) INTERNAL_CATCH_TEST_CASE_METHOD( className, __VA_ARGS__ ) +#define METHOD_AS_TEST_CASE( method, ... ) INTERNAL_CATCH_METHOD_AS_TEST_CASE( method, __VA_ARGS__ ) +#define REGISTER_TEST_CASE( Function, ... ) INTERNAL_CATCH_REGISTER_TESTCASE( Function, __VA_ARGS__ ) +#define SECTION( ... ) INTERNAL_CATCH_SECTION( __VA_ARGS__ ) +#define FAIL( ... ) INTERNAL_CATCH_MSG( "FAIL", Catch::ResultWas::ExplicitFailure, Catch::ResultDisposition::Normal, __VA_ARGS__ ) +#define FAIL_CHECK( ... ) INTERNAL_CATCH_MSG( "FAIL_CHECK", Catch::ResultWas::ExplicitFailure, Catch::ResultDisposition::ContinueOnFailure, __VA_ARGS__ ) +#define SUCCEED( ... ) INTERNAL_CATCH_MSG( "SUCCEED", Catch::ResultWas::Ok, Catch::ResultDisposition::ContinueOnFailure, __VA_ARGS__ ) +#define ANON_TEST_CASE() INTERNAL_CATCH_TESTCASE() + +#endif + +#define CATCH_TRANSLATE_EXCEPTION( signature ) INTERNAL_CATCH_TRANSLATE_EXCEPTION( signature ) + +// "BDD-style" convenience wrappers +#define SCENARIO( ... ) TEST_CASE( "Scenario: " __VA_ARGS__ ) +#define SCENARIO_METHOD( className, ... ) INTERNAL_CATCH_TEST_CASE_METHOD( className, "Scenario: " __VA_ARGS__ ) + +#define GIVEN( desc ) SECTION( std::string(" Given: ") + desc ) +#define WHEN( desc ) SECTION( std::string(" When: ") + desc ) +#define AND_WHEN( desc ) SECTION( std::string("And when: ") + desc ) +#define THEN( desc ) SECTION( std::string(" Then: ") + desc ) +#define AND_THEN( desc ) SECTION( std::string(" And: ") + desc ) + +using Catch::Detail::Approx; + +#else +////// +// If this config identifier is defined then all CATCH macros are prefixed with CATCH_ +#ifdef CATCH_CONFIG_PREFIX_ALL + +#define CATCH_REQUIRE( ... ) (void)(0) +#define CATCH_REQUIRE_FALSE( ... ) (void)(0) + +#define CATCH_REQUIRE_THROWS( ... ) (void)(0) +#define CATCH_REQUIRE_THROWS_AS( expr, exceptionType ) (void)(0) +#define CATCH_REQUIRE_THROWS_WITH( expr, matcher ) (void)(0) +#if !defined(CATCH_CONFIG_DISABLE_MATCHERS) +#define CATCH_REQUIRE_THROWS_MATCHES( expr, exceptionType, matcher ) (void)(0) +#endif// CATCH_CONFIG_DISABLE_MATCHERS +#define CATCH_REQUIRE_NOTHROW( ... ) (void)(0) + +#define CATCH_CHECK( ... ) (void)(0) +#define CATCH_CHECK_FALSE( ... ) (void)(0) +#define CATCH_CHECKED_IF( ... ) if (__VA_ARGS__) +#define CATCH_CHECKED_ELSE( ... ) if (!(__VA_ARGS__)) +#define CATCH_CHECK_NOFAIL( ... ) (void)(0) + +#define CATCH_CHECK_THROWS( ... ) (void)(0) +#define CATCH_CHECK_THROWS_AS( expr, exceptionType ) (void)(0) +#define CATCH_CHECK_THROWS_WITH( expr, matcher ) (void)(0) +#if !defined(CATCH_CONFIG_DISABLE_MATCHERS) +#define CATCH_CHECK_THROWS_MATCHES( expr, exceptionType, matcher ) (void)(0) +#endif // CATCH_CONFIG_DISABLE_MATCHERS +#define CATCH_CHECK_NOTHROW( ... ) (void)(0) + +#if !defined(CATCH_CONFIG_DISABLE_MATCHERS) +#define CATCH_CHECK_THAT( arg, matcher ) (void)(0) + +#define CATCH_REQUIRE_THAT( arg, matcher ) (void)(0) +#endif // CATCH_CONFIG_DISABLE_MATCHERS + +#define CATCH_INFO( msg ) (void)(0) +#define CATCH_WARN( msg ) (void)(0) +#define CATCH_CAPTURE( msg ) (void)(0) + +#define CATCH_TEST_CASE( ... ) INTERNAL_CATCH_TESTCASE_NO_REGISTRATION(INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_S_T____ )) +#define CATCH_TEST_CASE_METHOD( className, ... ) INTERNAL_CATCH_TESTCASE_NO_REGISTRATION(INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_S_T____ )) +#define CATCH_METHOD_AS_TEST_CASE( method, ... ) +#define CATCH_REGISTER_TEST_CASE( Function, ... ) (void)(0) +#define CATCH_SECTION( ... ) +#define CATCH_FAIL( ... ) (void)(0) +#define CATCH_FAIL_CHECK( ... ) (void)(0) +#define CATCH_SUCCEED( ... ) (void)(0) + +#define CATCH_ANON_TEST_CASE() INTERNAL_CATCH_TESTCASE_NO_REGISTRATION(INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_S_T____ )) + +// "BDD-style" convenience wrappers +#define CATCH_SCENARIO( ... ) INTERNAL_CATCH_TESTCASE_NO_REGISTRATION(INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_S_T____ )) +#define CATCH_SCENARIO_METHOD( className, ... ) INTERNAL_CATCH_TESTCASE_METHOD_NO_REGISTRATION(INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_S_T____ ), className ) +#define CATCH_GIVEN( desc ) +#define CATCH_WHEN( desc ) +#define CATCH_AND_WHEN( desc ) +#define CATCH_THEN( desc ) +#define CATCH_AND_THEN( desc ) + +// If CATCH_CONFIG_PREFIX_ALL is not defined then the CATCH_ prefix is not required +#else + +#define REQUIRE( ... ) (void)(0) +#define REQUIRE_FALSE( ... ) (void)(0) + +#define REQUIRE_THROWS( ... ) (void)(0) +#define REQUIRE_THROWS_AS( expr, exceptionType ) (void)(0) +#define REQUIRE_THROWS_WITH( expr, matcher ) (void)(0) +#if !defined(CATCH_CONFIG_DISABLE_MATCHERS) +#define REQUIRE_THROWS_MATCHES( expr, exceptionType, matcher ) (void)(0) +#endif // CATCH_CONFIG_DISABLE_MATCHERS +#define REQUIRE_NOTHROW( ... ) (void)(0) + +#define CHECK( ... ) (void)(0) +#define CHECK_FALSE( ... ) (void)(0) +#define CHECKED_IF( ... ) if (__VA_ARGS__) +#define CHECKED_ELSE( ... ) if (!(__VA_ARGS__)) +#define CHECK_NOFAIL( ... ) (void)(0) + +#define CHECK_THROWS( ... ) (void)(0) +#define CHECK_THROWS_AS( expr, exceptionType ) (void)(0) +#define CHECK_THROWS_WITH( expr, matcher ) (void)(0) +#if !defined(CATCH_CONFIG_DISABLE_MATCHERS) +#define CHECK_THROWS_MATCHES( expr, exceptionType, matcher ) (void)(0) +#endif // CATCH_CONFIG_DISABLE_MATCHERS +#define CHECK_NOTHROW( ... ) (void)(0) + +#if !defined(CATCH_CONFIG_DISABLE_MATCHERS) +#define CHECK_THAT( arg, matcher ) (void)(0) + +#define REQUIRE_THAT( arg, matcher ) (void)(0) +#endif // CATCH_CONFIG_DISABLE_MATCHERS + +#define INFO( msg ) (void)(0) +#define WARN( msg ) (void)(0) +#define CAPTURE( msg ) (void)(0) + +#define TEST_CASE( ... ) INTERNAL_CATCH_TESTCASE_NO_REGISTRATION(INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_S_T____ )) +#define TEST_CASE_METHOD( className, ... ) INTERNAL_CATCH_TESTCASE_NO_REGISTRATION(INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_S_T____ )) +#define METHOD_AS_TEST_CASE( method, ... ) +#define REGISTER_TEST_CASE( Function, ... ) (void)(0) +#define SECTION( ... ) +#define FAIL( ... ) (void)(0) +#define FAIL_CHECK( ... ) (void)(0) +#define SUCCEED( ... ) (void)(0) +#define ANON_TEST_CASE() INTERNAL_CATCH_TESTCASE_NO_REGISTRATION(INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_S_T____ )) + +#endif + +#define CATCH_TRANSLATE_EXCEPTION( signature ) INTERNAL_CATCH_TRANSLATE_EXCEPTION_NO_REG( INTERNAL_CATCH_UNIQUE_NAME( catch_internal_ExceptionTranslator ), signature ) + +// "BDD-style" convenience wrappers +#define SCENARIO( ... ) INTERNAL_CATCH_TESTCASE_NO_REGISTRATION(INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_S_T____ ) ) +#define SCENARIO_METHOD( className, ... ) INTERNAL_CATCH_TESTCASE_METHOD_NO_REGISTRATION(INTERNAL_CATCH_UNIQUE_NAME( ____C_A_T_C_H____T_E_S_T____ ), className ) + +#define GIVEN( desc ) +#define WHEN( desc ) +#define AND_WHEN( desc ) +#define THEN( desc ) +#define AND_THEN( desc ) + +using Catch::Detail::Approx; + +#endif + +// start catch_reenable_warnings.h + + +#ifdef __clang__ +# ifdef __ICC // icpc defines the __clang__ macro +# pragma warning(pop) +# else +# pragma clang diagnostic pop +# endif +#elif defined __GNUC__ +# pragma GCC diagnostic pop +#endif + +// end catch_reenable_warnings.h +// end catch.hpp +#endif // TWOBLUECUBES_SINGLE_INCLUDE_CATCH_HPP_INCLUDED + diff --git a/tests/catch/test_main.cpp b/tests/catch/test_main.cpp new file mode 100644 index 00000000..4b5cbf14 --- /dev/null +++ b/tests/catch/test_main.cpp @@ -0,0 +1,28 @@ +/* + * Copyright (c) 2018 UAVCAN Team + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in all + * copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE + * SOFTWARE. + * + * Contributors: https://github.com/UAVCAN/libcanard/contributors + */ + +// For speedy compilation, the file that contains CATCH_CONFIG_MAIN should not contain any actual tests. +// https://github.com/catchorg/Catch2/blob/master/docs/slow-compiles.md +#define CATCH_CONFIG_MAIN +#include "catch.hpp" // NOLINT diff --git a/tests/stm32/test_can_timings.cpp b/tests/stm32/test_can_timings.cpp index 1c996682..4da3ed65 100644 --- a/tests/stm32/test_can_timings.cpp +++ b/tests/stm32/test_can_timings.cpp @@ -22,7 +22,7 @@ * Contributors: https://github.com/UAVCAN/libcanard/contributors */ -#include +#include #include #include #include @@ -65,19 +65,19 @@ static std::uint32_t computeBDTR(const std::uint32_t pclk1, /* * Reference values were validated manually with the help of http://www.bittiming.can-wiki.info/ */ -TEST(STM32, CANTimings) +TEST_CASE("STM32, CANTimings") { - EXPECT_EQ(0x00060003, computeBDTR(36000000, 1000000)); - EXPECT_EQ(0x00180005, computeBDTR(36000000, 500000)); - EXPECT_EQ(0x001c0008, computeBDTR(36000000, 250000)); - EXPECT_EQ(0x001c0011, computeBDTR(36000000, 125000)); - EXPECT_EQ(0x001b0017, computeBDTR(36000000, 100000)); - EXPECT_EQ(0x001c00e0, computeBDTR(36000000, 10000)); + CHECK(0x00060003 == computeBDTR(36000000, 1000000)); + CHECK(0x00180005 == computeBDTR(36000000, 500000)); + CHECK(0x001c0008 == computeBDTR(36000000, 250000)); + CHECK(0x001c0011 == computeBDTR(36000000, 125000)); + CHECK(0x001b0017 == computeBDTR(36000000, 100000)); + CHECK(0x001c00e0 == computeBDTR(36000000, 10000)); - EXPECT_EQ(0x00070008, computeBDTR(90000000, 1000000)); - EXPECT_EQ(0x001b000b, computeBDTR(90000000, 500000)); - EXPECT_EQ(0x001b0017, computeBDTR(90000000, 250000)); - EXPECT_EQ(0x001c002c, computeBDTR(90000000, 125000)); - EXPECT_EQ(0x001b003b, computeBDTR(90000000, 100000)); - EXPECT_EQ(0x001b0257, computeBDTR(90000000, 10000)); + CHECK(0x00070008 == computeBDTR(90000000, 1000000)); + CHECK(0x001b000b == computeBDTR(90000000, 500000)); + CHECK(0x001b0017 == computeBDTR(90000000, 250000)); + CHECK(0x001c002c == computeBDTR(90000000, 125000)); + CHECK(0x001b003b == computeBDTR(90000000, 100000)); + CHECK(0x001b0257 == computeBDTR(90000000, 10000)); } diff --git a/tests/test_crc.cpp b/tests/test_crc.cpp index 83fd1a05..d20b99a5 100644 --- a/tests/test_crc.cpp +++ b/tests/test_crc.cpp @@ -22,7 +22,7 @@ * Contributors: https://github.com/UAVCAN/libcanard/contributors */ -#include +#include #include "canard_internals.h" /* @@ -39,7 +39,7 @@ * '29B1' */ -TEST(CRC, Correctness) +TEST_CASE("CRC, Correctness") { uint16_t crc = 0xFFFFU; @@ -47,9 +47,9 @@ TEST(CRC, Correctness) crc = crcAdd(crc, reinterpret_cast("2"), 1); crc = crcAdd(crc, reinterpret_cast("3"), 1); - ASSERT_EQ(0x5BCE, crc); // Using Libuavcan as reference + REQUIRE(0x5BCE == crc); // Using Libuavcan as reference crc = crcAdd(crc, reinterpret_cast("456789"), 6); - ASSERT_EQ(0x29B1, crc); + REQUIRE(0x29B1 == crc); } diff --git a/tests/test_float16.cpp b/tests/test_float16.cpp index c1fabb97..5d6f1d93 100644 --- a/tests/test_float16.cpp +++ b/tests/test_float16.cpp @@ -22,42 +22,42 @@ * Contributors: https://github.com/UAVCAN/libcanard/contributors */ -#include +#include #include #include "canard.h" -TEST(Float16, FromNative) +TEST_CASE("Float16, FromNative") { // Reference values were generated manually with libuavcan and numpy.float16() - ASSERT_EQ(0b0000000000000000, canardConvertNativeFloatToFloat16(0)); - ASSERT_EQ(0b0011110000000000, canardConvertNativeFloatToFloat16(1)); - ASSERT_EQ(0b1100000000000000, canardConvertNativeFloatToFloat16(-2)); - ASSERT_EQ(0b0111110000000000, canardConvertNativeFloatToFloat16(999999)); // +inf - ASSERT_EQ(0b1111101111111111, canardConvertNativeFloatToFloat16(-65519)); // -max - ASSERT_EQ(0b0111111111111111, canardConvertNativeFloatToFloat16(std::nanf(""))); // nan + REQUIRE(0b0000000000000000 == canardConvertNativeFloatToFloat16(0)); + REQUIRE(0b0011110000000000 == canardConvertNativeFloatToFloat16(1)); + REQUIRE(0b1100000000000000 == canardConvertNativeFloatToFloat16(-2)); + REQUIRE(0b0111110000000000 == canardConvertNativeFloatToFloat16(999999)); // +inf + REQUIRE(0b1111101111111111 == canardConvertNativeFloatToFloat16(-65519)); // -max + REQUIRE(0b0111111111111111 == canardConvertNativeFloatToFloat16(std::nanf(""))); // nan } -TEST(Float16, ToNative) +TEST_CASE("Float16, ToNative") { // Reference values were generated manually with libuavcan and numpy.float16() - ASSERT_FLOAT_EQ(0, canardConvertFloat16ToNativeFloat(0b0000000000000000)); - ASSERT_FLOAT_EQ(1, canardConvertFloat16ToNativeFloat(0b0011110000000000)); - ASSERT_FLOAT_EQ(-2, canardConvertFloat16ToNativeFloat(0b1100000000000000)); - ASSERT_FLOAT_EQ(INFINITY, canardConvertFloat16ToNativeFloat(0b0111110000000000)); - ASSERT_FLOAT_EQ(-65504, canardConvertFloat16ToNativeFloat(0b1111101111111111)); + REQUIRE(Approx(0.0F) == canardConvertFloat16ToNativeFloat(0b0000000000000000)); + REQUIRE(Approx(1.0F) == canardConvertFloat16ToNativeFloat(0b0011110000000000)); + REQUIRE(Approx(-2.0F) == canardConvertFloat16ToNativeFloat(0b1100000000000000)); + REQUIRE(Approx(-65504.0F) == canardConvertFloat16ToNativeFloat(0b1111101111111111)); + REQUIRE(std::isinf(canardConvertFloat16ToNativeFloat(0b0111110000000000))); - ASSERT_TRUE(bool(std::isnan(canardConvertFloat16ToNativeFloat(0b0111111111111111)))); + REQUIRE(bool(std::isnan(canardConvertFloat16ToNativeFloat(0b0111111111111111)))); } -TEST(Float16, BackAndForth) +TEST_CASE("Float16, BackAndForth") { float x = -1000.0F; while (x <= 1000.0F) { - ASSERT_FLOAT_EQ(x, canardConvertFloat16ToNativeFloat(canardConvertNativeFloatToFloat16(x))); + REQUIRE(Approx(x) == canardConvertFloat16ToNativeFloat(canardConvertNativeFloatToFloat16(x))); x += 0.5F; } } diff --git a/tests/test_init.cpp b/tests/test_init.cpp index 2d082e6f..5c9dc46d 100644 --- a/tests/test_init.cpp +++ b/tests/test_init.cpp @@ -22,7 +22,7 @@ * Contributors: https://github.com/UAVCAN/libcanard/contributors */ -#include +#include #include "canard.h" static bool shouldAcceptTransferMock(const CanardInstance*, @@ -40,7 +40,7 @@ static void onTransferReceptionMock(CanardInstance*, } -TEST(Init, UserReference) +TEST_CASE("Init, UserReference") { std::uint8_t memory_arena[1024]; @@ -52,5 +52,5 @@ TEST(Init, UserReference) &shouldAcceptTransferMock, reinterpret_cast(12345)); - ASSERT_EQ(12345, reinterpret_cast(canardGetUserReference(&ins))); + REQUIRE(12345 == reinterpret_cast(canardGetUserReference(&ins))); } diff --git a/tests/test_memory_allocator.cpp b/tests/test_memory_allocator.cpp index 24b32b4b..ee7c8099 100644 --- a/tests/test_memory_allocator.cpp +++ b/tests/test_memory_allocator.cpp @@ -22,55 +22,55 @@ * Contributors: https://github.com/UAVCAN/libcanard/contributors */ -#include +#include #include "canard_internals.h" #define AVAILABLE_BLOCKS 3 -class MemoryAllocatorTestGroup: public ::testing::Test +TEST_CASE("MemoryAllocatorTestGroup, FreeListIsConstructedCorrectly") { -protected: CanardPoolAllocator allocator; CanardPoolAllocatorBlock buffer[AVAILABLE_BLOCKS]; + initPoolAllocator(&allocator, buffer, AVAILABLE_BLOCKS); - virtual void SetUp() - { - initPoolAllocator(&allocator, buffer, AVAILABLE_BLOCKS); - } -}; - -TEST_F(MemoryAllocatorTestGroup, FreeListIsConstructedCorrectly) -{ // Check that the memory list is constructed correctly. - ASSERT_EQ(&buffer[0], allocator.free_list); - ASSERT_EQ(&buffer[1], allocator.free_list->next); - ASSERT_EQ(&buffer[2], allocator.free_list->next->next); - ASSERT_EQ(NULL, allocator.free_list->next->next->next); + REQUIRE(&buffer[0] == allocator.free_list); + REQUIRE(&buffer[1] == allocator.free_list->next); + REQUIRE(&buffer[2] == allocator.free_list->next->next); + REQUIRE(NULL == allocator.free_list->next->next->next); // Check statistics - EXPECT_EQ(AVAILABLE_BLOCKS, allocator.statistics.capacity_blocks); - EXPECT_EQ(0, allocator.statistics.current_usage_blocks); - EXPECT_EQ(0, allocator.statistics.peak_usage_blocks); + REQUIRE(AVAILABLE_BLOCKS == allocator.statistics.capacity_blocks); + REQUIRE(0 == allocator.statistics.current_usage_blocks); + REQUIRE(0 == allocator.statistics.peak_usage_blocks); } -TEST_F(MemoryAllocatorTestGroup, CanAllocateBlock) +TEST_CASE("MemoryAllocatorTestGroup, CanAllocateBlock") { + CanardPoolAllocator allocator; + CanardPoolAllocatorBlock buffer[AVAILABLE_BLOCKS]; + initPoolAllocator(&allocator, buffer, AVAILABLE_BLOCKS); + void* block = allocateBlock(&allocator); // Check that the first free memory block was used and that the next block is ready. - ASSERT_EQ(&buffer[0], block); - ASSERT_EQ(&buffer[1], allocator.free_list); + REQUIRE(&buffer[0] == block); + REQUIRE(&buffer[1] == allocator.free_list); // Check statistics - EXPECT_EQ(AVAILABLE_BLOCKS, allocator.statistics.capacity_blocks); - EXPECT_EQ(1, allocator.statistics.current_usage_blocks); - EXPECT_EQ(1, allocator.statistics.peak_usage_blocks); + REQUIRE(AVAILABLE_BLOCKS == allocator.statistics.capacity_blocks); + REQUIRE(1 == allocator.statistics.current_usage_blocks); + REQUIRE(1 == allocator.statistics.peak_usage_blocks); } -TEST_F(MemoryAllocatorTestGroup, ReturnsNullIfThereIsNoBlockLeft) +TEST_CASE("MemoryAllocatorTestGroup, ReturnsNullIfThereIsNoBlockLeft") { + CanardPoolAllocator allocator; + CanardPoolAllocatorBlock buffer[AVAILABLE_BLOCKS]; + initPoolAllocator(&allocator, buffer, AVAILABLE_BLOCKS); + // First exhaust all availables block for (int i = 0; i < AVAILABLE_BLOCKS; ++i) { @@ -79,26 +79,30 @@ TEST_F(MemoryAllocatorTestGroup, ReturnsNullIfThereIsNoBlockLeft) // Try to allocate one extra block void* block = allocateBlock(&allocator); - ASSERT_EQ(NULL, block); + REQUIRE(NULL == block); // Check statistics - EXPECT_EQ(AVAILABLE_BLOCKS, allocator.statistics.capacity_blocks); - EXPECT_EQ(AVAILABLE_BLOCKS, allocator.statistics.current_usage_blocks); - EXPECT_EQ(AVAILABLE_BLOCKS, allocator.statistics.peak_usage_blocks); + REQUIRE(AVAILABLE_BLOCKS == allocator.statistics.capacity_blocks); + REQUIRE(AVAILABLE_BLOCKS == allocator.statistics.current_usage_blocks); + REQUIRE(AVAILABLE_BLOCKS == allocator.statistics.peak_usage_blocks); } -TEST_F(MemoryAllocatorTestGroup, CanFreeBlock) +TEST_CASE("MemoryAllocatorTestGroup, CanFreeBlock") { + CanardPoolAllocator allocator; + CanardPoolAllocatorBlock buffer[AVAILABLE_BLOCKS]; + initPoolAllocator(&allocator, buffer, AVAILABLE_BLOCKS); + void* block = allocateBlock(&allocator); freeBlock(&allocator, block); // Check that the block was added back to the beginning - ASSERT_EQ(&buffer[0], allocator.free_list); - ASSERT_EQ(&buffer[1], allocator.free_list->next); + REQUIRE(&buffer[0] == allocator.free_list); + REQUIRE(&buffer[1] == allocator.free_list->next); // Check statistics - EXPECT_EQ(AVAILABLE_BLOCKS, allocator.statistics.capacity_blocks); - EXPECT_EQ(0, allocator.statistics.current_usage_blocks); - EXPECT_EQ(1, allocator.statistics.peak_usage_blocks); + REQUIRE(AVAILABLE_BLOCKS == allocator.statistics.capacity_blocks); + REQUIRE(0 == allocator.statistics.current_usage_blocks); + REQUIRE(1 == allocator.statistics.peak_usage_blocks); } diff --git a/tests/test_scalar_encoding.cpp b/tests/test_scalar_encoding.cpp index 1f3b98e5..c69d0f5c 100644 --- a/tests/test_scalar_encoding.cpp +++ b/tests/test_scalar_encoding.cpp @@ -26,14 +26,15 @@ #include #include #include -#include +#include +#include #include "canard_internals.h" -TEST(BigEndian, Check) +TEST_CASE("BigEndian, Check") { // Assuming that unit tests can only be run on little-endian platforms! - ASSERT_FALSE(isBigEndian()); + REQUIRE_FALSE(isBigEndian()); } @@ -53,7 +54,7 @@ static inline T read(CanardRxTransfer* transfer, uint32_t bit_offset, uint8_t bi } -TEST(ScalarDecode, SingleFrame) +TEST_CASE("ScalarDecode, SingleFrame") { auto transfer = CanardRxTransfer(); @@ -71,14 +72,14 @@ TEST(ScalarDecode, SingleFrame) transfer.payload_head = &buf[0]; transfer.payload_len = sizeof(buf); - ASSERT_EQ(0b10100101, read(&transfer, 0, 8)); - ASSERT_EQ(0b01011100, read(&transfer, 4, 8)); - ASSERT_EQ(0b00000101, read(&transfer, 4, 4)); + REQUIRE(0b10100101 == read(&transfer, 0, 8)); + REQUIRE(0b01011100 == read(&transfer, 4, 8)); + REQUIRE(0b00000101 == read(&transfer, 4, 4)); - ASSERT_EQ(true, read(&transfer, 9, 1)); - ASSERT_EQ(false, read(&transfer, 10, 1)); + REQUIRE(read(&transfer, 9, 1)); + REQUIRE_FALSE(read(&transfer, 10, 1)); - ASSERT_EQ(0b11101000101010100101010101111110, read(&transfer, 24, 32)); + REQUIRE(0b11101000101010100101010101111110 == read(&transfer, 24, 32)); /* * Raw bit stream with offset 21: @@ -88,25 +89,25 @@ TEST(ScalarDecode, SingleFrame) * Which is little endian representation of: * 0b01011101101101011100101011101111 */ - ASSERT_EQ(0b01011101101101011100101011101111, read(&transfer, 21, 32)); + REQUIRE(0b01011101101101011100101011101111 == read(&transfer, 21, 32)); // Should fail - ASSERT_THROW(read(&transfer, 25, 32), std::runtime_error); + REQUIRE_THROWS_AS(read(&transfer, 25, 32), std::runtime_error); // Inexact size - ASSERT_EQ(0b010111101101011100101011101111, read(&transfer, 21, 30)); + REQUIRE(0b010111101101011100101011101111 == read(&transfer, 21, 30)); // Negatives; reference values taken from libuavcan test suite or computed manually - ASSERT_EQ(-1, read(&transfer, 16, 3)); // 0b111 - ASSERT_EQ(-4, read(&transfer, 2, 3)); // 0b100 + REQUIRE(-1 == read(&transfer, 16, 3)); // 0b111 + REQUIRE(-4 == read(&transfer, 2, 3)); // 0b100 - ASSERT_EQ(-91, read(&transfer, 0, 8)); // 0b10100101 - ASSERT_EQ(-15451, read(&transfer, 0, 16)); // 0b1100001110100101 - ASSERT_EQ(-7771, read(&transfer, 0, 15)); // 0b100001110100101 + REQUIRE(-91 == read(&transfer, 0, 8)); // 0b10100101 + REQUIRE(-15451 == read(&transfer, 0, 16)); // 0b1100001110100101 + REQUIRE(-7771 == read(&transfer, 0, 15)); // 0b100001110100101 } -TEST(ScalarDecode, MultiFrame) +TEST_CASE("ScalarDecode, MultiFrame") { /* * Configuring allocator @@ -156,24 +157,24 @@ TEST(ScalarDecode, MultiFrame) /* * Testing */ - ASSERT_EQ(0b10100101, read(&transfer, 0, 8)); - ASSERT_EQ(0b01011010, read(&transfer, 4, 8)); - ASSERT_EQ(0b00000101, read(&transfer, 4, 4)); + REQUIRE(0b10100101 == read(&transfer, 0, 8)); + REQUIRE(0b01011010 == read(&transfer, 4, 8)); + REQUIRE(0b00000101 == read(&transfer, 4, 4)); - ASSERT_EQ(false, read(&transfer, CANARD_MULTIFRAME_RX_PAYLOAD_HEAD_SIZE * 8, 1)); - ASSERT_EQ(true, read(&transfer, CANARD_MULTIFRAME_RX_PAYLOAD_HEAD_SIZE * 8 + 1, 1)); + REQUIRE_FALSE(read(&transfer, CANARD_MULTIFRAME_RX_PAYLOAD_HEAD_SIZE * 8, 1)); + REQUIRE(read(&transfer, CANARD_MULTIFRAME_RX_PAYLOAD_HEAD_SIZE * 8 + 1, 1)); // 64 from beginning, 48 bits from head, 16 bits from the middle - ASSERT_EQ(0b0101101001011010101001011010010110100101101001011010010110100101ULL, read(&transfer, 0, 64)); + REQUIRE(0b0101101001011010101001011010010110100101101001011010010110100101ULL == read(&transfer, 0, 64)); // 64 from two middle blocks, 32 from the first, 32 from the second - ASSERT_EQ(0b1100110011001100110011001100110001011010010110100101101001011010ULL, - read(&transfer, - CANARD_MULTIFRAME_RX_PAYLOAD_HEAD_SIZE * 8 + CANARD_BUFFER_BLOCK_DATA_SIZE * 8 - 32, 64)); + REQUIRE(0b1100110011001100110011001100110001011010010110100101101001011010ULL == + read(&transfer, + CANARD_MULTIFRAME_RX_PAYLOAD_HEAD_SIZE * 8 + CANARD_BUFFER_BLOCK_DATA_SIZE * 8 - 32, 64)); // Last 64 - ASSERT_EQ(0b0100010000110011001000100001000111001100110011001100110011001100ULL, - read(&transfer, transfer.payload_len * 8U - 64U, 64)); + REQUIRE(0b0100010000110011001000100001000111001100110011001100110011001100ULL == + read(&transfer, transfer.payload_len * 8U - 64U, 64)); /* * Testing without the middle @@ -182,43 +183,43 @@ TEST(ScalarDecode, MultiFrame) transfer.payload_len = uint16_t(transfer.payload_len - CANARD_BUFFER_BLOCK_DATA_SIZE * 2U); // Last 64 - ASSERT_EQ(0b0100010000110011001000100001000110100101101001011010010110100101ULL, - read(&transfer, transfer.payload_len * 8U - 64U, 64)); + REQUIRE(0b0100010000110011001000100001000110100101101001011010010110100101ULL == + read(&transfer, transfer.payload_len * 8U - 64U, 64)); } -TEST(ScalarEncode, Basic) +TEST_CASE("ScalarEncode, Basic") { uint8_t buffer[32]; std::fill_n(std::begin(buffer), sizeof(buffer), 0); uint8_t u8 = 123; canardEncodeScalar(buffer, 0, 8, &u8); - ASSERT_EQ(123, buffer[0]); - ASSERT_EQ(0, buffer[1]); + REQUIRE(123 == buffer[0]); + REQUIRE(0 == buffer[1]); u8 = 0b1111; canardEncodeScalar(buffer, 5, 4, &u8); - ASSERT_EQ(123U | 0b111U, buffer[0]); - ASSERT_EQ(0b10000000, buffer[1]); + REQUIRE((123U | 0b111U) == buffer[0]); + REQUIRE(0b10000000 == buffer[1]); int16_t s16 = -1; canardEncodeScalar(buffer, 9, 15, &s16); - ASSERT_EQ(123U | 0b111U, buffer[0]); - ASSERT_EQ(0b11111111, buffer[1]); - ASSERT_EQ(0b11111111, buffer[2]); - ASSERT_EQ(0b00000000, buffer[3]); + REQUIRE((123U | 0b111U) == buffer[0]); + REQUIRE(0b11111111 == buffer[1]); + REQUIRE(0b11111111 == buffer[2]); + REQUIRE(0b00000000 == buffer[3]); auto s64 = int64_t(0b0000000100100011101111000110011110001001101010111100110111101111L); canardEncodeScalar(buffer, 16, 60, &s64); - ASSERT_EQ(123U | 0b111U, buffer[0]); // 0 - ASSERT_EQ(0b11111111, buffer[1]); // 8 - ASSERT_EQ(0b11101111, buffer[2]); // 16 - ASSERT_EQ(0b11001101, buffer[3]); - ASSERT_EQ(0b10101011, buffer[4]); - ASSERT_EQ(0b10001001, buffer[5]); - ASSERT_EQ(0b01100111, buffer[6]); - ASSERT_EQ(0b10111100, buffer[7]); - ASSERT_EQ(0b00100011, buffer[8]); - ASSERT_EQ(0b00010000, buffer[9]); + REQUIRE((123U | 0b111U) == buffer[0]); // 0 + REQUIRE(0b11111111 == buffer[1]); // 8 + REQUIRE(0b11101111 == buffer[2]); // 16 + REQUIRE(0b11001101 == buffer[3]); + REQUIRE(0b10101011 == buffer[4]); + REQUIRE(0b10001001 == buffer[5]); + REQUIRE(0b01100111 == buffer[6]); + REQUIRE(0b10111100 == buffer[7]); + REQUIRE(0b00100011 == buffer[8]); + REQUIRE(0b00010000 == buffer[9]); } From 274544497318960524b25fb01278c57c39b8f3a0 Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Sun, 20 May 2018 22:37:40 +0300 Subject: [PATCH 17/81] Okay Travis, check this out. Migrating to a better build matrix specification in order to add more compilers later. --- .travis.yml | 76 ++++++++++++++++++++++++++++++++++------------------- 1 file changed, 49 insertions(+), 27 deletions(-) diff --git a/.travis.yml b/.travis.yml index c8ee8b72..54efc530 100644 --- a/.travis.yml +++ b/.travis.yml @@ -1,32 +1,54 @@ sudo: required dist: trusty -language: cpp -compiler: - - clang - - gcc -addons: - apt: - packages: - - libgtest-dev - - g++-multilib - - gcc-multilib - - gcc-avr - - avr-libc +matrix: + include: + # + # Main GCC 7 test + # + - language: cpp + addons: + apt: + sources: + - ubuntu-toolchain-r-test + packages: + - g++-7 + - g++-7-multilib + - gcc-7-multilib + script: + - CC=gcc-7 && CXX=g++-7 && cd tests/ && cmake . && make + - ./run_tests --rng-seed time -env: - - CFLAGS="-Werror" CXXFLAGS="-Werror" + # + # Main Clang 5 test + # + - language: cpp + addons: + apt: + sources: + - ubuntu-toolchain-r-test + - llvm-toolchain-trusty-5.0 + packages: + - clang-5.0 + - libstdc++-7-dev # This package contains the C++ standard library used by Clang-5.0 + script: + - clang++-5.0 -E -x c++ - -v < /dev/null # Print the Clang configuration for troubleshooting purposes + - cd tests/ + - cmake -DCMAKE_C_COMPILER=clang-5.0 -DCMAKE_CXX_COMPILER=clang++-5.0 . + - make + - ./run_tests --rng-seed time -script: - # Building and running unit tests - - mkdir build - - cd build - - cmake ../tests - - make - - ./run_tests - - cd .. - # Building the AVR driver (TODO: skip this during Clang build) - - mkdir build-avr - - cd build-avr - - cmake ../drivers/avr - - make + # + # AVR driver test + # + - language: cpp + addons: + apt: + packages: + - gcc-avr + - avr-libc + script: + - mkdir build-avr + - cd build-avr + - cmake ../drivers/avr + - make From 355188dfa5760c5a27dc9dc7bab70aeb0006bf3e Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Sun, 20 May 2018 22:41:51 +0300 Subject: [PATCH 18/81] Nope. How about this. --- .travis.yml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/.travis.yml b/.travis.yml index 54efc530..375788c5 100644 --- a/.travis.yml +++ b/.travis.yml @@ -15,6 +15,7 @@ matrix: - g++-7 - g++-7-multilib - gcc-7-multilib + - linux-libc-dev:i386 script: - CC=gcc-7 && CXX=g++-7 && cd tests/ && cmake . && make - ./run_tests --rng-seed time @@ -31,6 +32,7 @@ matrix: packages: - clang-5.0 - libstdc++-7-dev # This package contains the C++ standard library used by Clang-5.0 + - linux-libc-dev:i386 script: - clang++-5.0 -E -x c++ - -v < /dev/null # Print the Clang configuration for troubleshooting purposes - cd tests/ From 547cb267bc4c44fd9ca13a5d580f0e22bb949f09 Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Sun, 20 May 2018 22:46:25 +0300 Subject: [PATCH 19/81] GCC works, only Clang remains broken. Come on Clang, you can do it! --- .travis.yml | 1 + 1 file changed, 1 insertion(+) diff --git a/.travis.yml b/.travis.yml index 375788c5..f58a4d5e 100644 --- a/.travis.yml +++ b/.travis.yml @@ -33,6 +33,7 @@ matrix: - clang-5.0 - libstdc++-7-dev # This package contains the C++ standard library used by Clang-5.0 - linux-libc-dev:i386 + - libc6-dev-i386 script: - clang++-5.0 -E -x c++ - -v < /dev/null # Print the Clang configuration for troubleshooting purposes - cd tests/ From 2a35fc4e4bf2748ecc3e8db3b9feeda234770307 Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Sun, 20 May 2018 23:15:27 +0300 Subject: [PATCH 20/81] Trying i386 stdlib to fix Clang --- .travis.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.travis.yml b/.travis.yml index f58a4d5e..31cde3da 100644 --- a/.travis.yml +++ b/.travis.yml @@ -31,7 +31,7 @@ matrix: - llvm-toolchain-trusty-5.0 packages: - clang-5.0 - - libstdc++-7-dev # This package contains the C++ standard library used by Clang-5.0 + - libstdc++-7-dev:i386 # This package contains the C++ standard library used by Clang-5.0 - linux-libc-dev:i386 - libc6-dev-i386 script: From 162010f1eefdc468547ee5f130cf67310bbbe6d8 Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Sun, 20 May 2018 23:19:31 +0300 Subject: [PATCH 21/81] Explanatory notes --- .travis.yml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/.travis.yml b/.travis.yml index 31cde3da..04a3b84f 100644 --- a/.travis.yml +++ b/.travis.yml @@ -12,6 +12,7 @@ matrix: sources: - ubuntu-toolchain-r-test packages: + # We need i386 packages because we compile libcanard in 32-bit mode, it doesn't support 64-bit platforms. - g++-7 - g++-7-multilib - gcc-7-multilib @@ -30,6 +31,7 @@ matrix: - ubuntu-toolchain-r-test - llvm-toolchain-trusty-5.0 packages: + # We need i386 packages because we compile libcanard in 32-bit mode, it doesn't support 64-bit platforms. - clang-5.0 - libstdc++-7-dev:i386 # This package contains the C++ standard library used by Clang-5.0 - linux-libc-dev:i386 From 16781404d9a98f1893c7e6572fc9fa14b38098ed Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Mon, 21 May 2018 11:12:54 +0300 Subject: [PATCH 22/81] Eliminated usage of plain integral types from the library --- canard.c | 107 ++++++++++++++++++++++++--------------------- canard.h | 46 ++++++++++--------- canard_internals.h | 28 ++++++------ 3 files changed, 95 insertions(+), 86 deletions(-) diff --git a/canard.c b/canard.c index 5c83c8d3..6e855a25 100644 --- a/canard.c +++ b/canard.c @@ -54,9 +54,14 @@ #define TRANSFER_ID_FROM_TAIL_BYTE(x) ((uint8_t)((x) & 0x1FU)) // The extra cast to unsigned is needed to squelch warnings from clang-tidy -#define IS_START_OF_TRANSFER(x) ((bool)(((unsigned)(x) >> 7U) & 0x1U)) -#define IS_END_OF_TRANSFER(x) ((bool)(((unsigned)(x) >> 6U) & 0x1U)) -#define TOGGLE_BIT(x) ((bool)(((unsigned)(x) >> 5U) & 0x1U)) +#define IS_START_OF_TRANSFER(x) ((bool)(((uint32_t)(x) >> 7U) & 0x1U)) +#define IS_END_OF_TRANSFER(x) ((bool)(((uint32_t)(x) >> 6U) & 0x1U)) +#define TOGGLE_BIT(x) ((bool)(((uint32_t)(x) >> 5U) & 0x1U)) + +// This is needed to prevent usage of plain integral types (MISRA 3-9-2) +#define int +#define unsigned +#define long struct CanardTxQueueItem @@ -131,13 +136,13 @@ uint8_t canardGetLocalNodeID(const CanardInstance* ins) return ins->node_id; } -int canardBroadcast(CanardInstance* ins, - uint64_t data_type_signature, - uint16_t data_type_id, - uint8_t* inout_transfer_id, - uint8_t priority, - const void* payload, - uint16_t payload_len) +int16_t canardBroadcast(CanardInstance* ins, + uint64_t data_type_signature, + uint16_t data_type_id, + uint8_t* inout_transfer_id, + uint8_t priority, + const void* payload, + uint16_t payload_len) { if (payload == NULL && payload_len > 0) { @@ -181,22 +186,22 @@ int canardBroadcast(CanardInstance* ins, } } - const int result = enqueueTxFrames(ins, can_id, inout_transfer_id, crc, payload, payload_len); + const int16_t result = enqueueTxFrames(ins, can_id, inout_transfer_id, crc, payload, payload_len); incrementTransferID(inout_transfer_id); return result; } -int canardRequestOrRespond(CanardInstance* ins, - uint8_t destination_node_id, - uint64_t data_type_signature, - uint8_t data_type_id, - uint8_t* inout_transfer_id, - uint8_t priority, - CanardRequestResponse kind, - const void* payload, - uint16_t payload_len) +int16_t canardRequestOrRespond(CanardInstance* ins, + uint8_t destination_node_id, + uint64_t data_type_signature, + uint8_t data_type_id, + uint8_t* inout_transfer_id, + uint8_t priority, + CanardRequestResponse kind, + const void* payload, + uint16_t payload_len) { if (payload == NULL && payload_len > 0) { @@ -222,7 +227,7 @@ int canardRequestOrRespond(CanardInstance* ins, crc = crcAdd(crc, payload, payload_len); } - const int result = enqueueTxFrames(ins, can_id, inout_transfer_id, crc, payload, payload_len); + const int16_t result = enqueueTxFrames(ins, can_id, inout_transfer_id, crc, payload, payload_len); if (kind == CanardRequest) // Response Transfer ID must not be altered { @@ -376,8 +381,8 @@ void canardHandleRxFrame(CanardInstance* ins, const CanardCANFrame* frame, uint6 // take off the crc and store the payload rx_state->timestamp_usec = timestamp_usec; - const int ret = bufferBlockPushBytes(&ins->allocator, rx_state, frame->data + 2, - (uint8_t) (frame->data_len - 3)); + const int16_t ret = bufferBlockPushBytes(&ins->allocator, rx_state, frame->data + 2, + (uint8_t) (frame->data_len - 3)); if (ret < 0) { releaseStatePayload(ins, rx_state); @@ -390,8 +395,8 @@ void canardHandleRxFrame(CanardInstance* ins, const CanardCANFrame* frame, uint6 } else if (!IS_START_OF_TRANSFER(tail_byte) && !IS_END_OF_TRANSFER(tail_byte)) // Middle of a multi-frame transfer { - const int ret = bufferBlockPushBytes(&ins->allocator, rx_state, frame->data, - (uint8_t) (frame->data_len - 1)); + const int16_t ret = bufferBlockPushBytes(&ins->allocator, rx_state, frame->data, + (uint8_t) (frame->data_len - 1)); if (ret < 0) { releaseStatePayload(ins, rx_state); @@ -506,11 +511,11 @@ void canardCleanupStaleTransfers(CanardInstance* ins, uint64_t current_time_usec } } -int canardDecodeScalar(const CanardRxTransfer* transfer, - uint32_t bit_offset, - uint8_t bit_length, - bool value_is_signed, - void* out_value) +int16_t canardDecodeScalar(const CanardRxTransfer* transfer, + uint32_t bit_offset, + uint8_t bit_length, + bool value_is_signed, + void* out_value) { if (transfer == NULL || out_value == NULL) { @@ -547,7 +552,7 @@ int canardDecodeScalar(const CanardRxTransfer* transfer, memset(&storage, 0, sizeof(storage)); // This is important - const int result = descatterTransferPayload(transfer, bit_offset, bit_length, &storage.bytes[0]); + const int16_t result = descatterTransferPayload(transfer, bit_offset, bit_length, &storage.bytes[0]); if (result <= 0) { return result; @@ -859,12 +864,12 @@ CANARD_INTERNAL void incrementTransferID(uint8_t* transfer_id) } } -CANARD_INTERNAL int enqueueTxFrames(CanardInstance* ins, - uint32_t can_id, - uint8_t* transfer_id, - uint16_t crc, - const uint8_t* payload, - uint16_t payload_len) +CANARD_INTERNAL int16_t enqueueTxFrames(CanardInstance* ins, + uint32_t can_id, + uint8_t* transfer_id, + uint16_t crc, + const uint8_t* payload, + uint16_t payload_len) { CANARD_ASSERT(ins != NULL); CANARD_ASSERT((can_id & CANARD_CAN_EXT_ID_MASK) == can_id); // Flags must be cleared @@ -879,7 +884,7 @@ CANARD_INTERNAL int enqueueTxFrames(CanardInstance* ins, return -CANARD_ERROR_INVALID_ARGUMENT; } - int result = 0; + int16_t result = 0; if (payload_len < CANARD_CAN_FRAME_MAX_DATA_LEN) // Single frame transfer { @@ -1211,15 +1216,15 @@ CANARD_INTERNAL uint64_t releaseStatePayload(CanardInstance* ins, CanardRxState* /** * pushes data into the rx state. Fills the buffer head, then appends data to buffer blocks */ -CANARD_INTERNAL int bufferBlockPushBytes(CanardPoolAllocator* allocator, - CanardRxState* state, - const uint8_t* data, - uint8_t data_len) +CANARD_INTERNAL int16_t bufferBlockPushBytes(CanardPoolAllocator* allocator, + CanardRxState* state, + const uint8_t* data, + uint8_t data_len) { uint16_t data_index = 0; // if head is not full, add data to head - if ((int) CANARD_MULTIFRAME_RX_PAYLOAD_HEAD_SIZE - (int) state->payload_len > 0) + if ((CANARD_MULTIFRAME_RX_PAYLOAD_HEAD_SIZE - state->payload_len) > 0) { for (uint16_t i = (uint16_t)state->payload_len; i < CANARD_MULTIFRAME_RX_PAYLOAD_HEAD_SIZE && data_index < data_len; @@ -1354,10 +1359,10 @@ void copyBitArray(const uint8_t* src, uint32_t src_offset, uint32_t src_len, } } -CANARD_INTERNAL int descatterTransferPayload(const CanardRxTransfer* transfer, - uint32_t bit_offset, - uint8_t bit_length, - void* output) +CANARD_INTERNAL int16_t descatterTransferPayload(const CanardRxTransfer* transfer, + uint32_t bit_offset, + uint8_t bit_length, + void* output) { CANARD_ASSERT(transfer != 0); @@ -1472,14 +1477,14 @@ CANARD_INTERNAL bool isBigEndian(void) #endif } -CANARD_INTERNAL void swapByteOrder(void* data, unsigned size) +CANARD_INTERNAL void swapByteOrder(void* data, size_t size) { CANARD_ASSERT(data != NULL); uint8_t* const bytes = (uint8_t*) data; - unsigned fwd = 0; - unsigned rev = size - 1; + size_t fwd = 0; + size_t rev = size - 1; while (fwd < rev) { @@ -1497,7 +1502,7 @@ CANARD_INTERNAL void swapByteOrder(void* data, unsigned size) CANARD_INTERNAL uint16_t crcAddByte(uint16_t crc_val, uint8_t byte) { crc_val ^= (uint16_t) ((uint16_t) (byte) << 8U); - for (int j = 0; j < 8; j++) + for (uint8_t j = 0; j < 8; j++) { if (crc_val & 0x8000U) { diff --git a/canard.h b/canard.h index 137edf1d..3f19b128 100644 --- a/canard.h +++ b/canard.h @@ -355,14 +355,16 @@ uint8_t canardGetLocalNodeID(const CanardInstance* ins); * Pointer to the Transfer ID should point to a persistent variable (e.g. static or heap allocated, not on the stack); * it will be updated by the library after every transmission. The Transfer ID value cannot be shared between * transfers that have different descriptors! More on this in the transport layer specification. + * + * Returns the number of frames enqueued, or negative error code. */ -int canardBroadcast(CanardInstance* ins, ///< Library instance - uint64_t data_type_signature, ///< See above - uint16_t data_type_id, ///< Refer to the specification - uint8_t* inout_transfer_id, ///< Pointer to a persistent variable containing the transfer ID - uint8_t priority, ///< Refer to definitions CANARD_TRANSFER_PRIORITY_* - const void* payload, ///< Transfer payload - uint16_t payload_len); ///< Length of the above, in bytes +int16_t canardBroadcast(CanardInstance* ins, ///< Library instance + uint64_t data_type_signature, ///< See above + uint16_t data_type_id, ///< Refer to the specification + uint8_t* inout_transfer_id, ///< Pointer to a persistent variable containing the transfer ID + uint8_t priority, ///< Refer to definitions CANARD_TRANSFER_PRIORITY_* + const void* payload, ///< Transfer payload + uint16_t payload_len); ///< Length of the above, in bytes /** * Sends a request or a response transfer. @@ -378,16 +380,18 @@ int canardBroadcast(CanardInstance* ins, ///< Library instance * * For Response transfers, the pointer to the Transfer ID will be treated as const (i.e. read-only), and normally it * should point to the transfer_id field of the structure CanardRxTransfer. + * + * Returns the number of frames enqueued, or negative error code. */ -int canardRequestOrRespond(CanardInstance* ins, ///< Library instance - uint8_t destination_node_id, ///< Node ID of the server/client - uint64_t data_type_signature, ///< See above - uint8_t data_type_id, ///< Refer to the specification - uint8_t* inout_transfer_id, ///< Pointer to a persistent variable with the transfer ID - uint8_t priority, ///< Refer to definitions CANARD_TRANSFER_PRIORITY_* - CanardRequestResponse kind, ///< Refer to CanardRequestResponse - const void* payload, ///< Transfer payload - uint16_t payload_len); ///< Length of the above, in bytes +int16_t canardRequestOrRespond(CanardInstance* ins, ///< Library instance + uint8_t destination_node_id, ///< Node ID of the server/client + uint64_t data_type_signature, ///< See above + uint8_t data_type_id, ///< Refer to the specification + uint8_t* inout_transfer_id, ///< Pointer to a persistent variable with transfer ID + uint8_t priority, ///< Refer to definitions CANARD_TRANSFER_PRIORITY_* + CanardRequestResponse kind, ///< Refer to CanardRequestResponse + const void* payload, ///< Transfer payload + uint16_t payload_len); ///< Length of the above, in bytes /** * Returns a pointer to the top priority frame in the TX queue. @@ -448,11 +452,11 @@ void canardCleanupStaleTransfers(CanardInstance* ins, * | [33, 64] | false | uint64_t | * | [33, 64] | true | int64_t, or 64-bit float | */ -int canardDecodeScalar(const CanardRxTransfer* transfer, ///< The RX transfer where the data will be copied from - uint32_t bit_offset, ///< Offset, in bits, from the beginning of the transfer - uint8_t bit_length, ///< Length of the value, in bits; see the table - bool value_is_signed, ///< True if the value can be negative; see the table - void* out_value); ///< Pointer to the output storage; see the table +int16_t canardDecodeScalar(const CanardRxTransfer* transfer, ///< The RX transfer where the data will be copied from + uint32_t bit_offset, ///< Offset, in bits, from the beginning of the transfer + uint8_t bit_length, ///< Length of the value, in bits; see the table + bool value_is_signed, ///< True if the value can be negative; see the table + void* out_value); ///< Pointer to the output storage; see the table /** * This function can be used to encode values for later transmission in a UAVCAN transfer. It encodes a scalar value - diff --git a/canard_internals.h b/canard_internals.h index eba1cf50..baf4b06e 100644 --- a/canard_internals.h +++ b/canard_internals.h @@ -56,10 +56,10 @@ CANARD_INTERNAL CanardRxState* prependRxState(CanardInstance* ins, CANARD_INTERNAL CanardRxState* findRxState(CanardRxState* state, uint32_t transfer_descriptor); -CANARD_INTERNAL int bufferBlockPushBytes(CanardPoolAllocator* allocator, - CanardRxState* state, - const uint8_t* data, - uint8_t data_len); +CANARD_INTERNAL int16_t bufferBlockPushBytes(CanardPoolAllocator* allocator, + CanardRxState* state, + const uint8_t* data, + uint8_t data_len); CANARD_INTERNAL CanardBufferBlock* createBufferBlock(CanardPoolAllocator* allocator); @@ -86,12 +86,12 @@ CANARD_INTERNAL uint64_t releaseStatePayload(CanardInstance* ins, CanardRxState* rxstate); /// Returns the number of frames enqueued -CANARD_INTERNAL int enqueueTxFrames(CanardInstance* ins, - uint32_t can_id, - uint8_t* transfer_id, - uint16_t crc, - const uint8_t* payload, - uint16_t payload_len); +CANARD_INTERNAL int16_t enqueueTxFrames(CanardInstance* ins, + uint32_t can_id, + uint8_t* transfer_id, + uint16_t crc, + const uint8_t* payload, + uint16_t payload_len); CANARD_INTERNAL void copyBitArray(const uint8_t* src, uint32_t src_offset, @@ -103,10 +103,10 @@ CANARD_INTERNAL void copyBitArray(const uint8_t* src, * Moves specified bits from the scattered transfer storage to a specified contiguous buffer. * Returns the number of bits copied, or negated error code. */ -CANARD_INTERNAL int descatterTransferPayload(const CanardRxTransfer* transfer, - uint32_t bit_offset, - uint8_t bit_length, - void* output); +CANARD_INTERNAL int16_t descatterTransferPayload(const CanardRxTransfer* transfer, + uint32_t bit_offset, + uint8_t bit_length, + void* output); CANARD_INTERNAL bool isBigEndian(void); From d6d086c597ce0bc69390f58a619fbda8e5c49a08 Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Mon, 21 May 2018 11:54:21 +0300 Subject: [PATCH 23/81] Eliminated usage of plain integral types from the SocketCAN driver and the demo application --- drivers/socketcan/socketcan.c | 69 +++++++++++++++++++++++++---------- drivers/socketcan/socketcan.h | 15 +++++--- tests/demo.c | 61 ++++++++++++++++--------------- 3 files changed, 92 insertions(+), 53 deletions(-) diff --git a/drivers/socketcan/socketcan.c b/drivers/socketcan/socketcan.c index 6f7ff3c3..c6d09b2d 100644 --- a/drivers/socketcan/socketcan.c +++ b/drivers/socketcan/socketcan.c @@ -1,5 +1,5 @@ /* - * Copyright (c) 2016 UAVCAN Team + * Copyright (c) 2016-2018 UAVCAN Team * * Distributed under the MIT License, available in the file LICENSE. * @@ -17,9 +17,32 @@ #include #include #include +#include +#include +/// Returns the current errno as negated int16_t +static int16_t getErrorCode() +{ + const int out = -abs(errno); + if (out < 0) + { + if (out >= INT16_MIN) + { + return (int16_t)out; + } + else + { + return INT16_MIN; + } + } + else + { + assert(false); // Requested an error when errno is zero? + return INT16_MIN; + } +} -int socketcanInit(SocketCANInstance* out_ins, const char* can_iface_name) +int16_t socketcanInit(SocketCANInstance* out_ins, const char* can_iface_name) { const size_t iface_name_size = strlen(can_iface_name) + 1; if (iface_name_size > IFNAMSIZ) @@ -58,19 +81,19 @@ int socketcanInit(SocketCANInstance* out_ins, const char* can_iface_name) return 0; fail1: - close(fd); + (void)close(fd); fail0: - return -1; + return getErrorCode(); } -int socketcanClose(SocketCANInstance* ins) +int16_t socketcanClose(SocketCANInstance* ins) { const int close_result = close(ins->fd); ins->fd = -1; - return close_result; + return (int16_t)((close_result == 0) ? 0 : getErrorCode()); } -int socketcanTransmit(SocketCANInstance* ins, const CanardCANFrame* frame, int timeout_msec) +int16_t socketcanTransmit(SocketCANInstance* ins, const CanardCANFrame* frame, int32_t timeout_msec) { struct pollfd fds; memset(&fds, 0, sizeof(fds)); @@ -80,15 +103,15 @@ int socketcanTransmit(SocketCANInstance* ins, const CanardCANFrame* frame, int t const int poll_result = poll(&fds, 1, timeout_msec); if (poll_result < 0) { - return -1; + return getErrorCode(); } if (poll_result == 0) { return 0; } - if ((fds.revents & POLLOUT) == 0) + if (((uint32_t)fds.revents & (uint32_t)POLLOUT) == 0) { - return -1; + return -EIO; } struct can_frame transmit_frame; @@ -98,15 +121,19 @@ int socketcanTransmit(SocketCANInstance* ins, const CanardCANFrame* frame, int t memcpy(transmit_frame.data, frame->data, frame->data_len); const ssize_t nbytes = write(ins->fd, &transmit_frame, sizeof(transmit_frame)); - if (nbytes < 0 || (size_t)nbytes != sizeof(transmit_frame)) + if (nbytes < 0) + { + return getErrorCode(); + } + if ((size_t)nbytes != sizeof(transmit_frame)) { - return -1; + return -EIO; } return 1; } -int socketcanReceive(SocketCANInstance* ins, CanardCANFrame* out_frame, int timeout_msec) +int16_t socketcanReceive(SocketCANInstance* ins, CanardCANFrame* out_frame, int32_t timeout_msec) { struct pollfd fds; memset(&fds, 0, sizeof(fds)); @@ -116,27 +143,31 @@ int socketcanReceive(SocketCANInstance* ins, CanardCANFrame* out_frame, int time const int poll_result = poll(&fds, 1, timeout_msec); if (poll_result < 0) { - return -1; + return getErrorCode(); } if (poll_result == 0) { return 0; } - if ((fds.revents & POLLIN) == 0) + if (((uint32_t)fds.revents & (uint32_t)POLLIN) == 0) { - return -1; + return -EIO; } struct can_frame receive_frame; const ssize_t nbytes = read(ins->fd, &receive_frame, sizeof(receive_frame)); - if (nbytes < 0 || (size_t)nbytes != sizeof(receive_frame)) + if (nbytes < 0) + { + return getErrorCode(); + } + if ((size_t)nbytes != sizeof(receive_frame)) { - return -1; + return -EIO; } if (receive_frame.can_dlc > CAN_MAX_DLEN) // Appeasing Coverity Scan { - return -1; + return -EIO; } out_frame->id = receive_frame.can_id; // TODO: Map flags properly diff --git a/drivers/socketcan/socketcan.h b/drivers/socketcan/socketcan.h index 5313ee4e..ff631229 100644 --- a/drivers/socketcan/socketcan.h +++ b/drivers/socketcan/socketcan.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2016 UAVCAN Team + * Copyright (c) 2016-2018 UAVCAN Team * * Distributed under the MIT License, available in the file LICENSE. * @@ -22,28 +22,33 @@ typedef struct /** * Initializes the SocketCAN instance. + * Returns 0 on success, negative on error. */ -int socketcanInit(SocketCANInstance* out_ins, const char* can_iface_name); +int16_t socketcanInit(SocketCANInstance* out_ins, const char* can_iface_name); /** * Deinitializes the SocketCAN instance. + * Returns 0 on success, negative on error. */ -int socketcanClose(SocketCANInstance* ins); +int16_t socketcanClose(SocketCANInstance* ins); /** * Transmits a CanardCANFrame to the CAN socket. * Use negative timeout to block infinitely. + * Returns 1 on successful transmission, 0 on timeout, negative on error. */ -int socketcanTransmit(SocketCANInstance* ins, const CanardCANFrame* frame, int timeout_msec); +int16_t socketcanTransmit(SocketCANInstance* ins, const CanardCANFrame* frame, int32_t timeout_msec); /** * Receives a CanardCANFrame from the CAN socket. * Use negative timeout to block infinitely. + * Returns 1 on successful reception, 0 on timeout, negative on error. */ -int socketcanReceive(SocketCANInstance* ins, CanardCANFrame* out_frame, int timeout_msec); +int16_t socketcanReceive(SocketCANInstance* ins, CanardCANFrame* out_frame, int32_t timeout_msec); /** * Returns the file descriptor of the CAN socket. + * Can be used for external IO multiplexing. */ int socketcanGetSocketFileDescriptor(const SocketCANInstance* ins); diff --git a/tests/demo.c b/tests/demo.c index c765d2cb..9fc376dd 100644 --- a/tests/demo.c +++ b/tests/demo.c @@ -52,7 +52,6 @@ #define UNIQUE_ID_LENGTH_BYTES 16 - /* * Library instance. * In simple applications it makes sense to make it static, but it is not necessary. @@ -95,7 +94,7 @@ static float getRandomFloat(void) if (!initialized) // This is not thread safe, but a race condition here is not harmful. { initialized = true; - srand((unsigned)time(NULL)); + srand((uint32_t) time(NULL)); } // coverity[dont_call] return (float)rand() / (float)RAND_MAX; @@ -163,7 +162,7 @@ static void onTransferReceived(CanardInstance* ins, } // Copying the unique ID from the message - static const unsigned UniqueIDBitOffset = 8; + static const uint8_t UniqueIDBitOffset = 8; uint8_t received_unique_id[UNIQUE_ID_LENGTH_BYTES]; uint8_t received_unique_id_len = 0; for (; received_unique_id_len < (transfer->payload_len - (UniqueIDBitOffset / 8U)); received_unique_id_len++) @@ -181,7 +180,7 @@ static void onTransferReceived(CanardInstance* ins, if (memcmp(received_unique_id, my_unique_id, received_unique_id_len) != 0) { printf("Mismatching allocation response from %d:", transfer->source_node_id); - for (int i = 0; i < received_unique_id_len; i++) + for (uint8_t i = 0; i < received_unique_id_len; i++) { printf(" %02x/%02x", received_unique_id[i], my_unique_id[i]); } @@ -245,15 +244,15 @@ static void onTransferReceived(CanardInstance* ins, /* * Transmitting; in this case we don't have to release the payload because it's empty anyway. */ - const int resp_res = canardRequestOrRespond(ins, - transfer->source_node_id, - UAVCAN_GET_NODE_INFO_DATA_TYPE_SIGNATURE, - UAVCAN_GET_NODE_INFO_DATA_TYPE_ID, - &transfer->transfer_id, - transfer->priority, - CanardResponse, - &buffer[0], - (uint16_t)total_size); + const int16_t resp_res = canardRequestOrRespond(ins, + transfer->source_node_id, + UAVCAN_GET_NODE_INFO_DATA_TYPE_SIGNATURE, + UAVCAN_GET_NODE_INFO_DATA_TYPE_ID, + &transfer->transfer_id, + transfer->priority, + CanardResponse, + &buffer[0], + (uint16_t)total_size); if (resp_res <= 0) { (void)fprintf(stderr, "Could not respond to GetNodeInfo; error %d\n", resp_res); @@ -318,7 +317,7 @@ static void process1HzTasks(uint64_t timestamp_usec) */ { const CanardPoolAllocatorStatistics stats = canardGetPoolAllocatorStatistics(&canard); - const unsigned peak_percent = 100U * stats.peak_usage_blocks / stats.capacity_blocks; + const uint16_t peak_percent = (uint16_t)(100U * stats.peak_usage_blocks / stats.capacity_blocks); printf("Memory pool stats: capacity %u blocks, usage %u blocks, peak usage %u blocks (%u%%)\n", stats.capacity_blocks, stats.current_usage_blocks, stats.peak_usage_blocks, peak_percent); @@ -340,11 +339,15 @@ static void process1HzTasks(uint64_t timestamp_usec) uint8_t buffer[UAVCAN_NODE_STATUS_MESSAGE_SIZE]; makeNodeStatusMessage(buffer); - static uint8_t transfer_id; + static uint8_t transfer_id; // Note that the transfer ID variable MUST BE STATIC (or heap-allocated)! - const int bc_res = canardBroadcast(&canard, UAVCAN_NODE_STATUS_DATA_TYPE_SIGNATURE, - UAVCAN_NODE_STATUS_DATA_TYPE_ID, &transfer_id, CANARD_TRANSFER_PRIORITY_LOW, - buffer, UAVCAN_NODE_STATUS_MESSAGE_SIZE); + const int16_t bc_res = canardBroadcast(&canard, + UAVCAN_NODE_STATUS_DATA_TYPE_SIGNATURE, + UAVCAN_NODE_STATUS_DATA_TYPE_ID, + &transfer_id, + CANARD_TRANSFER_PRIORITY_LOW, + buffer, + UAVCAN_NODE_STATUS_MESSAGE_SIZE); if (bc_res <= 0) { (void)fprintf(stderr, "Could not broadcast node status; error %d\n", bc_res); @@ -358,12 +361,12 @@ static void process1HzTasks(uint64_t timestamp_usec) /** * Transmits all frames from the TX queue, receives up to one frame. */ -static void processTxRxOnce(SocketCANInstance* socketcan, int timeout_msec) +static void processTxRxOnce(SocketCANInstance* socketcan, int32_t timeout_msec) { // Transmitting for (const CanardCANFrame* txf = NULL; (txf = canardPeekTxQueue(&canard)) != NULL;) { - const int tx_res = socketcanTransmit(socketcan, txf, 0); + const int32_t tx_res = socketcanTransmit(socketcan, txf, 0); if (tx_res < 0) // Failure - drop the frame and report { canardPopTxQueue(&canard); @@ -382,7 +385,7 @@ static void processTxRxOnce(SocketCANInstance* socketcan, int timeout_msec) // Receiving CanardCANFrame rx_frame; const uint64_t timestamp = getMonotonicTimestampUSec(); - const int rx_res = socketcanReceive(socketcan, &rx_frame, timeout_msec); + const int16_t rx_res = socketcanReceive(socketcan, &rx_frame, timeout_msec); if (rx_res < 0) // Failure - report { (void)fprintf(stderr, "Receive error %d, errno '%s'\n", rx_res, strerror(errno)); @@ -414,7 +417,7 @@ int main(int argc, char** argv) */ SocketCANInstance socketcan; const char* const can_iface_name = argv[1]; - int res = socketcanInit(&socketcan, can_iface_name); + int16_t res = socketcanInit(&socketcan, can_iface_name); if (res < 0) { (void)fprintf(stderr, "Failed to open CAN iface '%s'\n", can_iface_name); @@ -483,13 +486,13 @@ int main(int argc, char** argv) memmove(&allocation_request[1], &my_unique_id[node_id_allocation_unique_id_offset], uid_size); // Broadcasting the request - const int bcast_res = canardBroadcast(&canard, - UAVCAN_NODE_ID_ALLOCATION_DATA_TYPE_SIGNATURE, - UAVCAN_NODE_ID_ALLOCATION_DATA_TYPE_ID, - &node_id_allocation_transfer_id, - CANARD_TRANSFER_PRIORITY_LOW, - &allocation_request[0], - (uint16_t) (uid_size + 1)); + const int16_t bcast_res = canardBroadcast(&canard, + UAVCAN_NODE_ID_ALLOCATION_DATA_TYPE_SIGNATURE, + UAVCAN_NODE_ID_ALLOCATION_DATA_TYPE_ID, + &node_id_allocation_transfer_id, + CANARD_TRANSFER_PRIORITY_LOW, + &allocation_request[0], + (uint16_t) (uid_size + 1)); if (bcast_res < 0) { (void)fprintf(stderr, "Could not broadcast dynamic node ID allocation request; error %d\n", bcast_res); From 5287c52d479311918b886b6c3d750f78b4798b15 Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Tue, 22 May 2018 11:33:13 +0300 Subject: [PATCH 24/81] STM32: eliminated native integral types; fixed warnings from clang-tidy --- drivers/stm32/_internal_bxcan.h | 184 ++++++++++++++++---------------- drivers/stm32/canard_stm32.c | 88 +++++++-------- drivers/stm32/canard_stm32.h | 30 +++--- 3 files changed, 151 insertions(+), 151 deletions(-) diff --git a/drivers/stm32/_internal_bxcan.h b/drivers/stm32/_internal_bxcan.h index 33b05e22..13dd7b59 100644 --- a/drivers/stm32/_internal_bxcan.h +++ b/drivers/stm32/_internal_bxcan.h @@ -63,91 +63,91 @@ typedef struct /** * CANx instances */ -#define CANARD_STM32_CAN1 ((volatile CanardSTM32CANType*)0x40006400) -#define CANARD_STM32_CAN2 ((volatile CanardSTM32CANType*)0x40006800) +#define CANARD_STM32_CAN1 ((volatile CanardSTM32CANType*)0x40006400U) +#define CANARD_STM32_CAN2 ((volatile CanardSTM32CANType*)0x40006800U) // CAN master control register -#define CANARD_STM32_CAN_MCR_INRQ (1U << 0) // Bit 0: Initialization Request -#define CANARD_STM32_CAN_MCR_SLEEP (1U << 1) // Bit 1: Sleep Mode Request -#define CANARD_STM32_CAN_MCR_TXFP (1U << 2) // Bit 2: Transmit FIFO Priority -#define CANARD_STM32_CAN_MCR_RFLM (1U << 3) // Bit 3: Receive FIFO Locked Mode -#define CANARD_STM32_CAN_MCR_NART (1U << 4) // Bit 4: No Automatic Retransmission -#define CANARD_STM32_CAN_MCR_AWUM (1U << 5) // Bit 5: Automatic Wakeup Mode -#define CANARD_STM32_CAN_MCR_ABOM (1U << 6) // Bit 6: Automatic Bus-Off Management -#define CANARD_STM32_CAN_MCR_TTCM (1U << 7) // Bit 7: Time Triggered Communication Mode Enable -#define CANARD_STM32_CAN_MCR_RESET (1U << 15) // Bit 15: bxCAN software master reset -#define CANARD_STM32_CAN_MCR_DBF (1U << 16) // Bit 16: Debug freeze +#define CANARD_STM32_CAN_MCR_INRQ (1U << 0U) // Bit 0: Initialization Request +#define CANARD_STM32_CAN_MCR_SLEEP (1U << 1U) // Bit 1: Sleep Mode Request +#define CANARD_STM32_CAN_MCR_TXFP (1U << 2U) // Bit 2: Transmit FIFO Priority +#define CANARD_STM32_CAN_MCR_RFLM (1U << 3U) // Bit 3: Receive FIFO Locked Mode +#define CANARD_STM32_CAN_MCR_NART (1U << 4U) // Bit 4: No Automatic Retransmission +#define CANARD_STM32_CAN_MCR_AWUM (1U << 5U) // Bit 5: Automatic Wakeup Mode +#define CANARD_STM32_CAN_MCR_ABOM (1U << 6U) // Bit 6: Automatic Bus-Off Management +#define CANARD_STM32_CAN_MCR_TTCM (1U << 7U) // Bit 7: Time Triggered Communication Mode Enable +#define CANARD_STM32_CAN_MCR_RESET (1U << 15U) // Bit 15: bxCAN software master reset +#define CANARD_STM32_CAN_MCR_DBF (1U << 16U) // Bit 16: Debug freeze // CAN master status register -#define CANARD_STM32_CAN_MSR_INAK (1U << 0) // Bit 0: Initialization Acknowledge -#define CANARD_STM32_CAN_MSR_SLAK (1U << 1) // Bit 1: Sleep Acknowledge -#define CANARD_STM32_CAN_MSR_ERRI (1U << 2) // Bit 2: Error Interrupt -#define CANARD_STM32_CAN_MSR_WKUI (1U << 3) // Bit 3: Wakeup Interrupt -#define CANARD_STM32_CAN_MSR_SLAKI (1U << 4) // Bit 4: Sleep acknowledge interrupt -#define CANARD_STM32_CAN_MSR_TXM (1U << 8) // Bit 8: Transmit Mode -#define CANARD_STM32_CAN_MSR_RXM (1U << 9) // Bit 9: Receive Mode -#define CANARD_STM32_CAN_MSR_SAMP (1U << 10) // Bit 10: Last Sample Point -#define CANARD_STM32_CAN_MSR_RX (1U << 11) // Bit 11: CAN Rx Signal +#define CANARD_STM32_CAN_MSR_INAK (1U << 0U) // Bit 0: Initialization Acknowledge +#define CANARD_STM32_CAN_MSR_SLAK (1U << 1U) // Bit 1: Sleep Acknowledge +#define CANARD_STM32_CAN_MSR_ERRI (1U << 2U) // Bit 2: Error Interrupt +#define CANARD_STM32_CAN_MSR_WKUI (1U << 3U) // Bit 3: Wakeup Interrupt +#define CANARD_STM32_CAN_MSR_SLAKI (1U << 4U) // Bit 4: Sleep acknowledge interrupt +#define CANARD_STM32_CAN_MSR_TXM (1U << 8U) // Bit 8: Transmit Mode +#define CANARD_STM32_CAN_MSR_RXM (1U << 9U) // Bit 9: Receive Mode +#define CANARD_STM32_CAN_MSR_SAMP (1U << 10U) // Bit 10: Last Sample Point +#define CANARD_STM32_CAN_MSR_RX (1U << 11U) // Bit 11: CAN Rx Signal // CAN transmit status register -#define CANARD_STM32_CAN_TSR_RQCP0 (1U << 0) // Bit 0: Request Completed Mailbox 0 -#define CANARD_STM32_CAN_TSR_TXOK0 (1U << 1) // Bit 1 : Transmission OK of Mailbox 0 -#define CANARD_STM32_CAN_TSR_ALST0 (1U << 2) // Bit 2 : Arbitration Lost for Mailbox 0 -#define CANARD_STM32_CAN_TSR_TERR0 (1U << 3) // Bit 3 : Transmission Error of Mailbox 0 -#define CANARD_STM32_CAN_TSR_ABRQ0 (1U << 7) // Bit 7 : Abort Request for Mailbox 0 -#define CANARD_STM32_CAN_TSR_RQCP1 (1U << 8) // Bit 8 : Request Completed Mailbox 1 -#define CANARD_STM32_CAN_TSR_TXOK1 (1U << 9) // Bit 9 : Transmission OK of Mailbox 1 -#define CANARD_STM32_CAN_TSR_ALST1 (1U << 10) // Bit 10 : Arbitration Lost for Mailbox 1 -#define CANARD_STM32_CAN_TSR_TERR1 (1U << 11) // Bit 11 : Transmission Error of Mailbox 1 -#define CANARD_STM32_CAN_TSR_ABRQ1 (1U << 15) // Bit 15 : Abort Request for Mailbox 1 -#define CANARD_STM32_CAN_TSR_RQCP2 (1U << 16) // Bit 16 : Request Completed Mailbox 2 -#define CANARD_STM32_CAN_TSR_TXOK2 (1U << 17) // Bit 17 : Transmission OK of Mailbox 2 -#define CANARD_STM32_CAN_TSR_ALST2 (1U << 18) // Bit 18: Arbitration Lost for Mailbox 2 -#define CANARD_STM32_CAN_TSR_TERR2 (1U << 19) // Bit 19: Transmission Error of Mailbox 2 -#define CANARD_STM32_CAN_TSR_ABRQ2 (1U << 23) // Bit 23: Abort Request for Mailbox 2 -#define CANARD_STM32_CAN_TSR_CODE_SHIFT (24U) // Bits 25-24: Mailbox Code +#define CANARD_STM32_CAN_TSR_RQCP0 (1U << 0U) // Bit 0: Request Completed Mailbox 0 +#define CANARD_STM32_CAN_TSR_TXOK0 (1U << 1U) // Bit 1 : Transmission OK of Mailbox 0 +#define CANARD_STM32_CAN_TSR_ALST0 (1U << 2U) // Bit 2 : Arbitration Lost for Mailbox 0 +#define CANARD_STM32_CAN_TSR_TERR0 (1U << 3U) // Bit 3 : Transmission Error of Mailbox 0 +#define CANARD_STM32_CAN_TSR_ABRQ0 (1U << 7U) // Bit 7 : Abort Request for Mailbox 0 +#define CANARD_STM32_CAN_TSR_RQCP1 (1U << 8U) // Bit 8 : Request Completed Mailbox 1 +#define CANARD_STM32_CAN_TSR_TXOK1 (1U << 9U) // Bit 9 : Transmission OK of Mailbox 1 +#define CANARD_STM32_CAN_TSR_ALST1 (1U << 10U) // Bit 10 : Arbitration Lost for Mailbox 1 +#define CANARD_STM32_CAN_TSR_TERR1 (1U << 11U) // Bit 11 : Transmission Error of Mailbox 1 +#define CANARD_STM32_CAN_TSR_ABRQ1 (1U << 15U) // Bit 15 : Abort Request for Mailbox 1 +#define CANARD_STM32_CAN_TSR_RQCP2 (1U << 16U) // Bit 16 : Request Completed Mailbox 2 +#define CANARD_STM32_CAN_TSR_TXOK2 (1U << 17U) // Bit 17 : Transmission OK of Mailbox 2 +#define CANARD_STM32_CAN_TSR_ALST2 (1U << 18U) // Bit 18: Arbitration Lost for Mailbox 2 +#define CANARD_STM32_CAN_TSR_TERR2 (1U << 19U) // Bit 19: Transmission Error of Mailbox 2 +#define CANARD_STM32_CAN_TSR_ABRQ2 (1U << 23U) // Bit 23: Abort Request for Mailbox 2 +#define CANARD_STM32_CAN_TSR_CODE_SHIFT (24U) // Bits 25-24: Mailbox Code #define CANARD_STM32_CAN_TSR_CODE_MASK (3U << CANARD_STM32_CAN_TSR_CODE_SHIFT) -#define CANARD_STM32_CAN_TSR_TME0 (1U << 26) // Bit 26: Transmit Mailbox 0 Empty -#define CANARD_STM32_CAN_TSR_TME1 (1U << 27) // Bit 27: Transmit Mailbox 1 Empty -#define CANARD_STM32_CAN_TSR_TME2 (1U << 28) // Bit 28: Transmit Mailbox 2 Empty -#define CANARD_STM32_CAN_TSR_LOW0 (1U << 29) // Bit 29: Lowest Priority Flag for Mailbox 0 -#define CANARD_STM32_CAN_TSR_LOW1 (1U << 30) // Bit 30: Lowest Priority Flag for Mailbox 1 -#define CANARD_STM32_CAN_TSR_LOW2 (1U << 31) // Bit 31: Lowest Priority Flag for Mailbox 2 +#define CANARD_STM32_CAN_TSR_TME0 (1U << 26U) // Bit 26: Transmit Mailbox 0 Empty +#define CANARD_STM32_CAN_TSR_TME1 (1U << 27U) // Bit 27: Transmit Mailbox 1 Empty +#define CANARD_STM32_CAN_TSR_TME2 (1U << 28U) // Bit 28: Transmit Mailbox 2 Empty +#define CANARD_STM32_CAN_TSR_LOW0 (1U << 29U) // Bit 29: Lowest Priority Flag for Mailbox 0 +#define CANARD_STM32_CAN_TSR_LOW1 (1U << 30U) // Bit 30: Lowest Priority Flag for Mailbox 1 +#define CANARD_STM32_CAN_TSR_LOW2 (1U << 31U) // Bit 31: Lowest Priority Flag for Mailbox 2 // CAN receive FIFO 0/1 registers -#define CANARD_STM32_CAN_RFR_FMP_SHIFT (0U) // Bits 1-0: FIFO Message Pending +#define CANARD_STM32_CAN_RFR_FMP_SHIFT (0U) // Bits 1-0: FIFO Message Pending #define CANARD_STM32_CAN_RFR_FMP_MASK (3U << CANARD_STM32_CAN_RFR_FMP_SHIFT) -#define CANARD_STM32_CAN_RFR_FULL (1U << 3) // Bit 3: FIFO 0 Full -#define CANARD_STM32_CAN_RFR_FOVR (1U << 4) // Bit 4: FIFO 0 Overrun -#define CANARD_STM32_CAN_RFR_RFOM (1U << 5) // Bit 5: Release FIFO 0 Output Mailbox +#define CANARD_STM32_CAN_RFR_FULL (1U << 3U) // Bit 3: FIFO 0 Full +#define CANARD_STM32_CAN_RFR_FOVR (1U << 4U) // Bit 4: FIFO 0 Overrun +#define CANARD_STM32_CAN_RFR_RFOM (1U << 5U) // Bit 5: Release FIFO 0 Output Mailbox // CAN interrupt enable register -#define CANARD_STM32_CAN_IER_TMEIE (1U << 0) // Bit 0: Transmit Mailbox Empty Interrupt Enable -#define CANARD_STM32_CAN_IER_FMPIE0 (1U << 1) // Bit 1: FIFO Message Pending Interrupt Enable -#define CANARD_STM32_CAN_IER_FFIE0 (1U << 2) // Bit 2: FIFO Full Interrupt Enable -#define CANARD_STM32_CAN_IER_FOVIE0 (1U << 3) // Bit 3: FIFO Overrun Interrupt Enable -#define CANARD_STM32_CAN_IER_FMPIE1 (1U << 4) // Bit 4: FIFO Message Pending Interrupt Enable -#define CANARD_STM32_CAN_IER_FFIE1 (1U << 5) // Bit 5: FIFO Full Interrupt Enable -#define CANARD_STM32_CAN_IER_FOVIE1 (1U << 6) // Bit 6: FIFO Overrun Interrupt Enable -#define CANARD_STM32_CAN_IER_EWGIE (1U << 8) // Bit 8: Error Warning Interrupt Enable -#define CANARD_STM32_CAN_IER_EPVIE (1U << 9) // Bit 9: Error Passive Interrupt Enable -#define CANARD_STM32_CAN_IER_BOFIE (1U << 10) // Bit 10: Bus-Off Interrupt Enable -#define CANARD_STM32_CAN_IER_LECIE (1U << 11) // Bit 11: Last Error Code Interrupt Enable -#define CANARD_STM32_CAN_IER_ERRIE (1U << 15) // Bit 15: Error Interrupt Enable -#define CANARD_STM32_CAN_IER_WKUIE (1U << 16) // Bit 16: Wakeup Interrupt Enable -#define CANARD_STM32_CAN_IER_SLKIE (1U << 17) // Bit 17: Sleep Interrupt Enable +#define CANARD_STM32_CAN_IER_TMEIE (1U << 0U) // Bit 0: Transmit Mailbox Empty Interrupt Enable +#define CANARD_STM32_CAN_IER_FMPIE0 (1U << 1U) // Bit 1: FIFO Message Pending Interrupt Enable +#define CANARD_STM32_CAN_IER_FFIE0 (1U << 2U) // Bit 2: FIFO Full Interrupt Enable +#define CANARD_STM32_CAN_IER_FOVIE0 (1U << 3U) // Bit 3: FIFO Overrun Interrupt Enable +#define CANARD_STM32_CAN_IER_FMPIE1 (1U << 4U) // Bit 4: FIFO Message Pending Interrupt Enable +#define CANARD_STM32_CAN_IER_FFIE1 (1U << 5U) // Bit 5: FIFO Full Interrupt Enable +#define CANARD_STM32_CAN_IER_FOVIE1 (1U << 6U) // Bit 6: FIFO Overrun Interrupt Enable +#define CANARD_STM32_CAN_IER_EWGIE (1U << 8U) // Bit 8: Error Warning Interrupt Enable +#define CANARD_STM32_CAN_IER_EPVIE (1U << 9U) // Bit 9: Error Passive Interrupt Enable +#define CANARD_STM32_CAN_IER_BOFIE (1U << 10U) // Bit 10: Bus-Off Interrupt Enable +#define CANARD_STM32_CAN_IER_LECIE (1U << 11U) // Bit 11: Last Error Code Interrupt Enable +#define CANARD_STM32_CAN_IER_ERRIE (1U << 15U) // Bit 15: Error Interrupt Enable +#define CANARD_STM32_CAN_IER_WKUIE (1U << 16U) // Bit 16: Wakeup Interrupt Enable +#define CANARD_STM32_CAN_IER_SLKIE (1U << 17U) // Bit 17: Sleep Interrupt Enable // CAN error status register -#define CANARD_STM32_CAN_ESR_EWGF (1U << 0) // Bit 0: Error Warning Flag -#define CANARD_STM32_CAN_ESR_EPVF (1U << 1) // Bit 1: Error Passive Flag -#define CANARD_STM32_CAN_ESR_BOFF (1U << 2) // Bit 2: Bus-Off Flag -#define CANARD_STM32_CAN_ESR_LEC_SHIFT (4U) // Bits 6-4: Last Error Code +#define CANARD_STM32_CAN_ESR_EWGF (1U << 0U) // Bit 0: Error Warning Flag +#define CANARD_STM32_CAN_ESR_EPVF (1U << 1U) // Bit 1: Error Passive Flag +#define CANARD_STM32_CAN_ESR_BOFF (1U << 2U) // Bit 2: Bus-Off Flag +#define CANARD_STM32_CAN_ESR_LEC_SHIFT (4U) // Bits 6-4: Last Error Code #define CANARD_STM32_CAN_ESR_LEC_MASK (7U << CANARD_STM32_CAN_ESR_LEC_SHIFT) #define CANARD_STM32_CAN_ESR_NOERROR (0U << CANARD_STM32_CAN_ESR_LEC_SHIFT) // 000: No Error #define CANARD_STM32_CAN_ESR_STUFFERROR (1U << CANARD_STM32_CAN_ESR_LEC_SHIFT) // 001: Stuff Error @@ -157,66 +157,66 @@ typedef struct #define CANARD_STM32_CAN_ESR_BDOMERROR (5U << CANARD_STM32_CAN_ESR_LEC_SHIFT) // 101: Bit dominant Error #define CANARD_STM32_CAN_ESR_CRCERRPR (6U << CANARD_STM32_CAN_ESR_LEC_SHIFT) // 110: CRC Error #define CANARD_STM32_CAN_ESR_SWERROR (7U << CANARD_STM32_CAN_ESR_LEC_SHIFT) // 111: Set by software -#define CANARD_STM32_CAN_ESR_TEC_SHIFT (16U) // Bits 23-16: LS byte of the 9-bit Transmit Error Counter +#define CANARD_STM32_CAN_ESR_TEC_SHIFT (16U) // Bits 23-16: LS byte of the 9-bit Transmit Error Counter #define CANARD_STM32_CAN_ESR_TEC_MASK (0xFFU << CANARD_STM32_CAN_ESR_TEC_SHIFT) -#define CANARD_STM32_CAN_ESR_REC_SHIFT (24U) // Bits 31-24: Receive Error Counter +#define CANARD_STM32_CAN_ESR_REC_SHIFT (24U) // Bits 31-24: Receive Error Counter #define CANARD_STM32_CAN_ESR_REC_MASK (0xFFU << CANARD_STM32_CAN_ESR_REC_SHIFT) // CAN bit timing register -#define CANARD_STM32_CAN_BTR_BRP_SHIFT (0U) // Bits 9-0: Baud Rate Prescaler +#define CANARD_STM32_CAN_BTR_BRP_SHIFT (0U) // Bits 9-0: Baud Rate Prescaler #define CANARD_STM32_CAN_BTR_BRP_MASK (0x03FFU << CANARD_STM32_CAN_BTR_BRP_SHIFT) -#define CANARD_STM32_CAN_BTR_TS1_SHIFT (16U) // Bits 19-16: Time Segment 1 +#define CANARD_STM32_CAN_BTR_TS1_SHIFT (16U) // Bits 19-16: Time Segment 1 #define CANARD_STM32_CAN_BTR_TS1_MASK (0x0FU << CANARD_STM32_CAN_BTR_TS1_SHIFT) -#define CANARD_STM32_CAN_BTR_TS2_SHIFT (20U) // Bits 22-20: Time Segment 2 +#define CANARD_STM32_CAN_BTR_TS2_SHIFT (20U) // Bits 22-20: Time Segment 2 #define CANARD_STM32_CAN_BTR_TS2_MASK (7U << CANARD_STM32_CAN_BTR_TS2_SHIFT) -#define CANARD_STM32_CAN_BTR_SJW_SHIFT (24U) // Bits 25-24: Resynchronization Jump Width +#define CANARD_STM32_CAN_BTR_SJW_SHIFT (24U) // Bits 25-24: Resynchronization Jump Width #define CANARD_STM32_CAN_BTR_SJW_MASK (3U << CANARD_STM32_CAN_BTR_SJW_SHIFT) -#define CANARD_STM32_CAN_BTR_LBKM (1U << 30) // Bit 30: Loop Back Mode (Debug); -#define CANARD_STM32_CAN_BTR_SILM (1U << 31) // Bit 31: Silent Mode (Debug); +#define CANARD_STM32_CAN_BTR_LBKM (1U << 30U) // Bit 30: Loop Back Mode (Debug); +#define CANARD_STM32_CAN_BTR_SILM (1U << 31U) // Bit 31: Silent Mode (Debug); -#define CANARD_STM32_CAN_BTR_BRP_MAX (1024U) // Maximum BTR value (without decrement); -#define CANARD_STM32_CAN_BTR_TSEG1_MAX (16U) // Maximum TSEG1 value (without decrement); -#define CANARD_STM32_CAN_BTR_TSEG2_MAX (8U) // Maximum TSEG2 value (without decrement); +#define CANARD_STM32_CAN_BTR_BRP_MAX (1024U) // Maximum BTR value (without decrement); +#define CANARD_STM32_CAN_BTR_TSEG1_MAX (16U) // Maximum TSEG1 value (without decrement); +#define CANARD_STM32_CAN_BTR_TSEG2_MAX (8U) // Maximum TSEG2 value (without decrement); // TX mailbox identifier register -#define CANARD_STM32_CAN_TIR_TXRQ (1U << 0) // Bit 0: Transmit Mailbox Request -#define CANARD_STM32_CAN_TIR_RTR (1U << 1) // Bit 1: Remote Transmission Request -#define CANARD_STM32_CAN_TIR_IDE (1U << 2) // Bit 2: Identifier Extension -#define CANARD_STM32_CAN_TIR_EXID_SHIFT (3U) // Bit 3-31: Extended Identifier +#define CANARD_STM32_CAN_TIR_TXRQ (1U << 0U) // Bit 0: Transmit Mailbox Request +#define CANARD_STM32_CAN_TIR_RTR (1U << 1U) // Bit 1: Remote Transmission Request +#define CANARD_STM32_CAN_TIR_IDE (1U << 2U) // Bit 2: Identifier Extension +#define CANARD_STM32_CAN_TIR_EXID_SHIFT (3U) // Bit 3-31: Extended Identifier #define CANARD_STM32_CAN_TIR_EXID_MASK (0x1FFFFFFFU << CANARD_STM32_CAN_TIR_EXID_SHIFT) -#define CANARD_STM32_CAN_TIR_STID_SHIFT (21U) // Bits 21-31: Standard Identifier +#define CANARD_STM32_CAN_TIR_STID_SHIFT (21U) // Bits 21-31: Standard Identifier #define CANARD_STM32_CAN_TIR_STID_MASK (0x07FFU << CANARD_STM32_CAN_TIR_STID_SHIFT) // Mailbox data length control and time stamp register -#define CANARD_STM32_CAN_TDTR_DLC_SHIFT (0U) // Bits 3:0: Data Length Code +#define CANARD_STM32_CAN_TDTR_DLC_SHIFT (0U) // Bits 3:0: Data Length Code #define CANARD_STM32_CAN_TDTR_DLC_MASK (0x0FU << CANARD_STM32_CAN_TDTR_DLC_SHIFT) -#define CANARD_STM32_CAN_TDTR_TGT (1U << 8) // Bit 8: Transmit Global Time -#define CANARD_STM32_CAN_TDTR_TIME_SHIFT (16U) // Bits 31:16: Message Time Stamp +#define CANARD_STM32_CAN_TDTR_TGT (1U << 8U) // Bit 8: Transmit Global Time +#define CANARD_STM32_CAN_TDTR_TIME_SHIFT (16U) // Bits 31:16: Message Time Stamp #define CANARD_STM32_CAN_TDTR_TIME_MASK (0xFFFFU << CANARD_STM32_CAN_TDTR_TIME_SHIFT) // Rx FIFO mailbox identifier register -#define CANARD_STM32_CAN_RIR_RTR (1U << 1) // Bit 1: Remote Transmission Request -#define CANARD_STM32_CAN_RIR_IDE (1U << 2) // Bit 2: Identifier Extension -#define CANARD_STM32_CAN_RIR_EXID_SHIFT (3U) // Bit 3-31: Extended Identifier +#define CANARD_STM32_CAN_RIR_RTR (1U << 1U) // Bit 1: Remote Transmission Request +#define CANARD_STM32_CAN_RIR_IDE (1U << 2U) // Bit 2: Identifier Extension +#define CANARD_STM32_CAN_RIR_EXID_SHIFT (3U) // Bit 3-31: Extended Identifier #define CANARD_STM32_CAN_RIR_EXID_MASK (0x1FFFFFFFU << CANARD_STM32_CAN_RIR_EXID_SHIFT) -#define CANARD_STM32_CAN_RIR_STID_SHIFT (21U) // Bits 21-31: Standard Identifier +#define CANARD_STM32_CAN_RIR_STID_SHIFT (21U) // Bits 21-31: Standard Identifier #define CANARD_STM32_CAN_RIR_STID_MASK (0x07FFU << CANARD_STM32_CAN_RIR_STID_SHIFT) // Receive FIFO mailbox data length control and time stamp register -#define CANARD_STM32_CAN_RDTR_DLC_SHIFT (0U) // Bits 3:0: Data Length Code +#define CANARD_STM32_CAN_RDTR_DLC_SHIFT (0U) // Bits 3:0: Data Length Code #define CANARD_STM32_CAN_RDTR_DLC_MASK (0x0FU << CANARD_STM32_CAN_RDTR_DLC_SHIFT) -#define CANARD_STM32_CAN_RDTR_FM_SHIFT (8U) // Bits 15-8: Filter Match Index +#define CANARD_STM32_CAN_RDTR_FM_SHIFT (8U) // Bits 15-8: Filter Match Index #define CANARD_STM32_CAN_RDTR_FM_MASK (0xFFU << CANARD_STM32_CAN_RDTR_FM_SHIFT) -#define CANARD_STM32_CAN_RDTR_TIME_SHIFT (16U) // Bits 31:16: Message Time Stamp +#define CANARD_STM32_CAN_RDTR_TIME_SHIFT (16U) // Bits 31:16: Message Time Stamp #define CANARD_STM32_CAN_RDTR_TIME_MASK (0xFFFFU << CANARD_STM32_CAN_RDTR_TIME_SHIFT) // CAN filter master register -#define CANARD_STM32_CAN_FMR_FINIT (1U << 0) // Bit 0: Filter Init Mode +#define CANARD_STM32_CAN_FMR_FINIT (1U << 0U) // Bit 0: Filter Init Mode #endif // CANARD_STM32_BXCAN_H diff --git a/drivers/stm32/canard_stm32.c b/drivers/stm32/canard_stm32.c index 85bc4401..9ffbf383 100644 --- a/drivers/stm32/canard_stm32.c +++ b/drivers/stm32/canard_stm32.c @@ -37,8 +37,8 @@ static bool isFramePriorityHigher(uint32_t a, uint32_t b) const bool ext_b = (b & CANARD_CAN_FRAME_EFF) != 0; if (ext_a != ext_b) { - const uint32_t arb11_a = ext_a ? (clean_a >> 18) : clean_a; - const uint32_t arb11_b = ext_b ? (clean_b >> 18) : clean_b; + const uint32_t arb11_a = ext_a ? (clean_a >> 18U) : clean_a; + const uint32_t arb11_b = ext_b ? (clean_b >> 18U) : clean_b; if (arb11_a != arb11_b) { return arb11_a < arb11_b; @@ -72,11 +72,11 @@ static uint32_t convertFrameIDCanardToRegister(const uint32_t id) if (id & CANARD_CAN_FRAME_EFF) { - out = ((id & CANARD_CAN_EXT_ID_MASK) << 3) | CANARD_STM32_CAN_TIR_IDE; + out = ((id & CANARD_CAN_EXT_ID_MASK) << 3U) | CANARD_STM32_CAN_TIR_IDE; } else { - out = ((id & CANARD_CAN_STD_ID_MASK) << 21); + out = ((id & CANARD_CAN_STD_ID_MASK) << 21U); } if (id & CANARD_CAN_FRAME_RTR) @@ -99,11 +99,11 @@ static uint32_t convertFrameIDRegisterToCanard(const uint32_t id) if ((id & CANARD_STM32_CAN_RIR_IDE) == 0) { - out = (CANARD_CAN_STD_ID_MASK & (id >> 21)); + out = (CANARD_CAN_STD_ID_MASK & (id >> 21U)); } else { - out = (CANARD_CAN_EXT_ID_MASK & (id >> 3)) | CANARD_CAN_FRAME_EFF; + out = (CANARD_CAN_EXT_ID_MASK & (id >> 3U)) | CANARD_CAN_FRAME_EFF; } if ((id & CANARD_STM32_CAN_RIR_RTR) != 0) @@ -125,9 +125,9 @@ static bool waitMSRINAKBitStateChange(volatile const CanardSTM32CANType* const b * 3 bit - inter frame space * This adds up to 11; therefore, it is not really necessary to wait longer than a few frame TX intervals. */ - static const unsigned TimeoutMilliseconds = 1000; + static const uint16_t TimeoutMilliseconds = 1000; - for (unsigned wait_ack = 0; wait_ack < TimeoutMilliseconds; wait_ack++) + for (uint16_t wait_ack = 0; wait_ack < TimeoutMilliseconds; wait_ack++) { const bool state = (bxcan->MSR & CANARD_STM32_CAN_MSR_INAK) != 0; if (state == target_state) @@ -165,8 +165,8 @@ static void processErrorStatus(void) } -int canardSTM32Init(const CanardSTM32CANTimings* const timings, - const CanardSTM32IfaceMode iface_mode) +int16_t canardSTM32Init(const CanardSTM32CANTimings* const timings, + const CanardSTM32IfaceMode iface_mode) { /* * Paranoia time. @@ -223,10 +223,10 @@ int canardSTM32Init(const CanardSTM32CANTimings* const timings, */ BXCAN->MCR = CANARD_STM32_CAN_MCR_ABOM | CANARD_STM32_CAN_MCR_AWUM | CANARD_STM32_CAN_MCR_INRQ; // RM page 648 - BXCAN->BTR = (((timings->max_resynchronization_jump_width - 1) & 3U) << 24) | - (((timings->bit_segment_1 - 1) & 15U) << 16) | - (((timings->bit_segment_2 - 1) & 7U) << 20) | - ((timings->bit_rate_prescaler - 1) & 1023U) | + BXCAN->BTR = (((timings->max_resynchronization_jump_width - 1U) & 3U) << 24U) | + (((timings->bit_segment_1 - 1U) & 15U) << 16U) | + (((timings->bit_segment_2 - 1U) & 7U) << 20U) | + ((timings->bit_rate_prescaler - 1U) & 1023U) | ((iface_mode == CanardSTM32IfaceModeSilent) ? CANARD_STM32_CAN_BTR_SILM : 0); CANARD_ASSERT(0 == BXCAN->IER); // Making sure the iterrupts are indeed disabled @@ -246,12 +246,12 @@ int canardSTM32Init(const CanardSTM32CANTimings* const timings, * MCU within the STM32 family. */ { - uint32_t fmr = CANARD_STM32_CAN1->FMR & 0xFFFFC0F1; - fmr |= CANARD_STM32_NUM_ACCEPTANCE_FILTERS << 8; // CAN2 start bank = 14 (if CAN2 is present) + uint32_t fmr = CANARD_STM32_CAN1->FMR & 0xFFFFC0F1U; + fmr |= CANARD_STM32_NUM_ACCEPTANCE_FILTERS << 8U; // CAN2 start bank = 14 (if CAN2 is present) CANARD_STM32_CAN1->FMR = fmr | CANARD_STM32_CAN_FMR_FINIT; } - CANARD_ASSERT(((CANARD_STM32_CAN1->FMR >> 8) & 0x3F) == CANARD_STM32_NUM_ACCEPTANCE_FILTERS); + CANARD_ASSERT(((CANARD_STM32_CAN1->FMR >> 8U) & 0x3FU) == CANARD_STM32_NUM_ACCEPTANCE_FILTERS); CANARD_STM32_CAN1->FM1R = 0; // Indentifier Mask mode CANARD_STM32_CAN1->FS1R = 0x0FFFFFFF; // All 32-bit @@ -278,7 +278,7 @@ int canardSTM32Init(const CanardSTM32CANTimings* const timings, } -int canardSTM32Transmit(const CanardCANFrame* const frame) +int16_t canardSTM32Transmit(const CanardCANFrame* const frame) { if (frame == NULL) { @@ -366,14 +366,14 @@ int canardSTM32Transmit(const CanardCANFrame* const frame) mb->TDTR = frame->data_len; // DLC equals data length except in CAN FD - mb->TDHR = (((uint32_t)frame->data[7]) << 24) | - (((uint32_t)frame->data[6]) << 16) | - (((uint32_t)frame->data[5]) << 8) | - (((uint32_t)frame->data[4]) << 0); - mb->TDLR = (((uint32_t)frame->data[3]) << 24) | - (((uint32_t)frame->data[2]) << 16) | - (((uint32_t)frame->data[1]) << 8) | - (((uint32_t)frame->data[0]) << 0); + mb->TDHR = (((uint32_t)frame->data[7]) << 24U) | + (((uint32_t)frame->data[6]) << 16U) | + (((uint32_t)frame->data[5]) << 8U) | + (((uint32_t)frame->data[4]) << 0U); + mb->TDLR = (((uint32_t)frame->data[3]) << 24U) | + (((uint32_t)frame->data[2]) << 16U) | + (((uint32_t)frame->data[1]) << 8U) | + (((uint32_t)frame->data[0]) << 0U); mb->TIR = convertFrameIDCanardToRegister(frame->id) | CANARD_STM32_CAN_TIR_TXRQ; // Go. @@ -384,7 +384,7 @@ int canardSTM32Transmit(const CanardCANFrame* const frame) } -int canardSTM32Receive(CanardCANFrame* const out_frame) +int16_t canardSTM32Receive(CanardCANFrame* const out_frame) { if (out_frame == NULL) { @@ -424,14 +424,14 @@ int canardSTM32Receive(CanardCANFrame* const out_frame) const uint32_t rdlr = mb->RDLR; const uint32_t rdhr = mb->RDHR; - out_frame->data[0] = (uint8_t)(0xFF & (rdlr >> 0)); - out_frame->data[1] = (uint8_t)(0xFF & (rdlr >> 8)); - out_frame->data[2] = (uint8_t)(0xFF & (rdlr >> 16)); - out_frame->data[3] = (uint8_t)(0xFF & (rdlr >> 24)); - out_frame->data[4] = (uint8_t)(0xFF & (rdhr >> 0)); - out_frame->data[5] = (uint8_t)(0xFF & (rdhr >> 8)); - out_frame->data[6] = (uint8_t)(0xFF & (rdhr >> 16)); - out_frame->data[7] = (uint8_t)(0xFF & (rdhr >> 24)); + out_frame->data[0] = (uint8_t)(0xFFU & (rdlr >> 0U)); + out_frame->data[1] = (uint8_t)(0xFFU & (rdlr >> 8U)); + out_frame->data[2] = (uint8_t)(0xFFU & (rdlr >> 16U)); + out_frame->data[3] = (uint8_t)(0xFFU & (rdlr >> 24U)); + out_frame->data[4] = (uint8_t)(0xFFU & (rdhr >> 0U)); + out_frame->data[5] = (uint8_t)(0xFFU & (rdhr >> 8U)); + out_frame->data[6] = (uint8_t)(0xFFU & (rdhr >> 16U)); + out_frame->data[7] = (uint8_t)(0xFFU & (rdhr >> 24U)); // Release FIFO entry we just read *RFxR[i] = CANARD_STM32_CAN_RFR_RFOM | CANARD_STM32_CAN_RFR_FOVR | CANARD_STM32_CAN_RFR_FULL; @@ -446,8 +446,8 @@ int canardSTM32Receive(CanardCANFrame* const out_frame) } -int canardSTM32ConfigureAcceptanceFilters(const CanardSTM32AcceptanceFilterConfiguration* const filter_configs, - const unsigned num_filter_configs) +int16_t canardSTM32ConfigureAcceptanceFilters(const CanardSTM32AcceptanceFilterConfiguration* const filter_configs, + const uint8_t num_filter_configs) { // Note that num_filter_configs = 0 is a valid configuration, which rejects all frames. if ((filter_configs == NULL) || @@ -466,7 +466,7 @@ int canardSTM32ConfigureAcceptanceFilters(const CanardSTM32AcceptanceFilterConfi * Having filters disabled we can update the configuration. * Register mapping: FR1 - ID, FR2 - Mask */ - for (unsigned i = 0; i < num_filter_configs; i++) + for (uint8_t i = 0; i < num_filter_configs; i++) { /* * Converting the ID and the Mask into the representation that can be chewed by the hardware. @@ -518,14 +518,14 @@ int canardSTM32ConfigureAcceptanceFilters(const CanardSTM32AcceptanceFilterConfi if ((cfg->id & CANARD_CAN_FRAME_EFF) || !(cfg->mask & CANARD_CAN_FRAME_EFF)) { - id = (cfg->id & CANARD_CAN_EXT_ID_MASK) << 3; - mask = (cfg->mask & CANARD_CAN_EXT_ID_MASK) << 3; + id = (cfg->id & CANARD_CAN_EXT_ID_MASK) << 3U; + mask = (cfg->mask & CANARD_CAN_EXT_ID_MASK) << 3U; id |= CANARD_STM32_CAN_RIR_IDE; } else { - id = (cfg->id & CANARD_CAN_STD_ID_MASK) << 21; - mask = (cfg->mask & CANARD_CAN_STD_ID_MASK) << 21; + id = (cfg->id & CANARD_CAN_STD_ID_MASK) << 21U; + mask = (cfg->mask & CANARD_CAN_STD_ID_MASK) << 21U; } if (cfg->id & CANARD_CAN_FRAME_RTR) @@ -546,9 +546,9 @@ int canardSTM32ConfigureAcceptanceFilters(const CanardSTM32AcceptanceFilterConfi /* * Applying the converted representation to the registers. */ - const unsigned filter_index = + const uint8_t filter_index = #if CANARD_STM32_USE_CAN2 - i + CANARD_STM32_NUM_ACCEPTANCE_FILTERS; + (uint8_t)(i + CANARD_STM32_NUM_ACCEPTANCE_FILTERS); #else i; #endif diff --git a/drivers/stm32/canard_stm32.h b/drivers/stm32/canard_stm32.h index a64f9b8a..87e1a6e7 100644 --- a/drivers/stm32/canard_stm32.h +++ b/drivers/stm32/canard_stm32.h @@ -51,7 +51,7 @@ extern "C" * which is a number from 1 to 27 inclusive. Seeing as the start bank cannot be set to 0, CAN2 has one filter less * to use. */ -#define CANARD_STM32_NUM_ACCEPTANCE_FILTERS 14 +#define CANARD_STM32_NUM_ACCEPTANCE_FILTERS 14U /** * The interface can be initialized in either of these modes. @@ -128,8 +128,8 @@ typedef struct * @retval 0 Success * @retval negative Error */ -int canardSTM32Init(const CanardSTM32CANTimings* const timings, - const CanardSTM32IfaceMode iface_mode); +int16_t canardSTM32Init(const CanardSTM32CANTimings* const timings, + const CanardSTM32IfaceMode iface_mode); /** * Pushes one frame into the TX buffer, if there is space. @@ -140,7 +140,7 @@ int canardSTM32Init(const CanardSTM32CANTimings* const timings, * @retval 0 No space in the buffer * @retval negative Error */ -int canardSTM32Transmit(const CanardCANFrame* const frame); +int16_t canardSTM32Transmit(const CanardCANFrame* const frame); /** * Reads one frame from the hardware RX FIFO, unless all FIFO are empty. @@ -150,7 +150,7 @@ int canardSTM32Transmit(const CanardCANFrame* const frame); * @retval 0 The buffer is empty * @retval negative Error */ -int canardSTM32Receive(CanardCANFrame* const out_frame); +int16_t canardSTM32Receive(CanardCANFrame* const out_frame); /** * Sets up acceptance filters according to the provided list of ID and masks. @@ -163,11 +163,11 @@ int canardSTM32Receive(CanardCANFrame* const out_frame); * @retval 0 Success * @retval negative Error */ -int canardSTM32ConfigureAcceptanceFilters(const CanardSTM32AcceptanceFilterConfiguration* const filter_configs, - const unsigned num_filter_configs); +int16_t canardSTM32ConfigureAcceptanceFilters(const CanardSTM32AcceptanceFilterConfiguration* const filter_configs, + const uint8_t num_filter_configs); /** - * Returns the runnning interface statistics. + * Returns the running interface statistics. */ CanardSTM32Stats canardSTM32GetStats(void); @@ -187,9 +187,9 @@ CanardSTM32Stats canardSTM32GetStats(void); * @retval negative Solution could not be found for the provided inputs. */ static inline -int canardSTM32ComputeCANTimings(const uint32_t peripheral_clock_rate, - const uint32_t target_bitrate, - CanardSTM32CANTimings* const out_timings) +int16_t canardSTM32ComputeCANTimings(const uint32_t peripheral_clock_rate, + const uint32_t target_bitrate, + CanardSTM32CANTimings* const out_timings) { if (target_bitrate < 1000) { @@ -202,8 +202,8 @@ int canardSTM32ComputeCANTimings(const uint32_t peripheral_clock_rate, /* * Hardware configuration */ - static const int MaxBS1 = 16; - static const int MaxBS2 = 8; + static const uint8_t MaxBS1 = 16; + static const uint8_t MaxBS2 = 8; /* * Ref. "Automatic Baudrate Detection in CANopen Networks", U. Koppe, MicroControl GmbH & Co. KG @@ -216,10 +216,10 @@ int canardSTM32ComputeCANTimings(const uint32_t peripheral_clock_rate, * 250 kbps 16 17 * 125 kbps 16 17 */ - const int max_quanta_per_bit = (target_bitrate >= 1000000) ? 10 : 17; + const uint8_t max_quanta_per_bit = (uint8_t)((target_bitrate >= 1000000) ? 10 : 17); CANARD_ASSERT(max_quanta_per_bit <= (MaxBS1 + MaxBS2)); - static const int MaxSamplePointLocationPermill = 900; + static const uint16_t MaxSamplePointLocationPermill = 900; /* * Computing (prescaler * BS): From f8f3a65ccfafe006895b89b8097f699ad0031b2f Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Tue, 22 May 2018 11:38:30 +0300 Subject: [PATCH 25/81] Removed temporary poison for int/unsigned/long in order to appease Clang - we don't need it anymore --- canard.c | 5 ----- 1 file changed, 5 deletions(-) diff --git a/canard.c b/canard.c index 6e855a25..4efd01c6 100644 --- a/canard.c +++ b/canard.c @@ -58,11 +58,6 @@ #define IS_END_OF_TRANSFER(x) ((bool)(((uint32_t)(x) >> 6U) & 0x1U)) #define TOGGLE_BIT(x) ((bool)(((uint32_t)(x) >> 5U) & 0x1U)) -// This is needed to prevent usage of plain integral types (MISRA 3-9-2) -#define int -#define unsigned -#define long - struct CanardTxQueueItem { From efaa02d0aa12147d3bb17d9bc50b147278298c0e Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Tue, 22 May 2018 11:38:40 +0300 Subject: [PATCH 26/81] Minor mistake --- tests/demo.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tests/demo.c b/tests/demo.c index 9fc376dd..7a3253cc 100644 --- a/tests/demo.c +++ b/tests/demo.c @@ -366,7 +366,7 @@ static void processTxRxOnce(SocketCANInstance* socketcan, int32_t timeout_msec) // Transmitting for (const CanardCANFrame* txf = NULL; (txf = canardPeekTxQueue(&canard)) != NULL;) { - const int32_t tx_res = socketcanTransmit(socketcan, txf, 0); + const int16_t tx_res = socketcanTransmit(socketcan, txf, 0); if (tx_res < 0) // Failure - drop the frame and report { canardPopTxQueue(&canard); From 931fcd0c7fb4f41317c1ebd007b5996ffa83d1aa Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Tue, 22 May 2018 12:23:07 +0300 Subject: [PATCH 27/81] Clang-tidy warning suppression hints --- drivers/socketcan/socketcan.c | 2 +- drivers/stm32/canard_stm32.h | 16 ++++++++-------- 2 files changed, 9 insertions(+), 9 deletions(-) diff --git a/drivers/socketcan/socketcan.c b/drivers/socketcan/socketcan.c index c6d09b2d..448c4de5 100644 --- a/drivers/socketcan/socketcan.c +++ b/drivers/socketcan/socketcan.c @@ -50,7 +50,7 @@ int16_t socketcanInit(SocketCANInstance* out_ins, const char* can_iface_name) goto fail0; } - const int fd = socket(PF_CAN, SOCK_RAW | SOCK_NONBLOCK, CAN_RAW); + const int fd = socket(PF_CAN, SOCK_RAW | SOCK_NONBLOCK, CAN_RAW); // NOLINT if (fd < 0) { goto fail0; diff --git a/drivers/stm32/canard_stm32.h b/drivers/stm32/canard_stm32.h index 87e1a6e7..7b8414c3 100644 --- a/drivers/stm32/canard_stm32.h +++ b/drivers/stm32/canard_stm32.h @@ -10,7 +10,7 @@ #define CANARD_STM32_H #include -#include +#include // NOLINT #ifdef __cplusplus @@ -196,7 +196,7 @@ int16_t canardSTM32ComputeCANTimings(const uint32_t peripheral_clock_rate, return -CANARD_STM32_ERROR_UNSUPPORTED_BIT_RATE; } - CANARD_ASSERT(out_timings != NULL); + CANARD_ASSERT(out_timings != NULL); // NOLINT memset(out_timings, 0, sizeof(*out_timings)); /* @@ -216,7 +216,7 @@ int16_t canardSTM32ComputeCANTimings(const uint32_t peripheral_clock_rate, * 250 kbps 16 17 * 125 kbps 16 17 */ - const uint8_t max_quanta_per_bit = (uint8_t)((target_bitrate >= 1000000) ? 10 : 17); + const uint8_t max_quanta_per_bit = (uint8_t)((target_bitrate >= 1000000) ? 10 : 17); // NOLINT CANARD_ASSERT(max_quanta_per_bit <= (MaxBS1 + MaxBS2)); static const uint16_t MaxSamplePointLocationPermill = 900; @@ -236,7 +236,7 @@ int16_t canardSTM32ComputeCANTimings(const uint32_t peripheral_clock_rate, /* * Searching for such prescaler value so that the number of quanta per bit is highest. */ - uint8_t bs1_bs2_sum = (uint8_t)(max_quanta_per_bit - 1); + uint8_t bs1_bs2_sum = (uint8_t)(max_quanta_per_bit - 1); // NOLINT while ((prescaler_bs % (1U + bs1_bs2_sum)) != 0) { @@ -272,12 +272,12 @@ int16_t canardSTM32ComputeCANTimings(const uint32_t peripheral_clock_rate, * - With rounding to nearest * - With rounding to zero */ - uint8_t bs1 = (uint8_t)(((7 * bs1_bs2_sum - 1) + 4) / 8); // Trying rounding to nearest first - uint8_t bs2 = (uint8_t)(bs1_bs2_sum - bs1); + uint8_t bs1 = (uint8_t)(((7 * bs1_bs2_sum - 1) + 4) / 8); // Trying rounding to nearest first // NOLINT + uint8_t bs2 = (uint8_t)(bs1_bs2_sum - bs1); // NOLINT CANARD_ASSERT(bs1_bs2_sum > bs1); { - const uint16_t sample_point_permill = (uint16_t)(1000U * (1U + bs1) / (1U + bs1 + bs2)); + const uint16_t sample_point_permill = (uint16_t)(1000U * (1U + bs1) / (1U + bs1 + bs2)); // NOLINT if (sample_point_permill > MaxSamplePointLocationPermill) // Strictly more! { @@ -300,7 +300,7 @@ int16_t canardSTM32ComputeCANTimings(const uint32_t peripheral_clock_rate, !valid) { // This actually means that the algorithm has a logic error, hence assert(0). - CANARD_ASSERT(0); + CANARD_ASSERT(0); // NOLINT return -CANARD_STM32_ERROR_UNSUPPORTED_BIT_RATE; } From ce2f90afb5cfb836f86e5c8211fb406957b5450b Mon Sep 17 00:00:00 2001 From: "Torola, Sami" Date: Tue, 29 May 2018 13:37:48 +0300 Subject: [PATCH 28/81] Fixed assert sizeof compatibility issue Fixed compatibility issue when checking struct size in assert https://github.com/UAVCAN/libcanard/issues/51 --- canard.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/canard.h b/canard.h index 3f19b128..745911a7 100644 --- a/canard.h +++ b/canard.h @@ -235,7 +235,7 @@ struct CanardRxState uint8_t buffer_head[]; }; -CANARD_STATIC_ASSERT(sizeof(CanardRxState) <= 28, "Invalid memory layout"); +CANARD_STATIC_ASSERT(offsetof(CanardRxState, buffer_head) <= 28, "Invalid memory layout"); CANARD_STATIC_ASSERT(CANARD_MULTIFRAME_RX_PAYLOAD_HEAD_SIZE >= 4, "Invalid memory layout"); /** From 0104f016beec593056d635d468806598c8aa965a Mon Sep 17 00:00:00 2001 From: "Torola, Sami" Date: Fri, 29 Jun 2018 13:20:59 +0300 Subject: [PATCH 29/81] Implemented DSDL compiler for the libcanard. --- .gitmodules | 3 + dsdl_compiler/README.md | 108 ++ dsdl_compiler/libcanard_dsdl_compiler/LICENSE | 23 + .../libcanard_dsdl_compiler/__init__.py | 429 ++++++ .../code_type_template.tmpl | 228 +++ .../data_type_template.tmpl | 128 ++ .../libcanard_dsdl_compiler/pyratemp.py | 1238 +++++++++++++++++ dsdl_compiler/libcanard_dsdlc | 68 + dsdl_compiler/pyuavcan | 1 + 9 files changed, 2226 insertions(+) create mode 100644 dsdl_compiler/README.md create mode 100644 dsdl_compiler/libcanard_dsdl_compiler/LICENSE create mode 100644 dsdl_compiler/libcanard_dsdl_compiler/__init__.py create mode 100644 dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl create mode 100644 dsdl_compiler/libcanard_dsdl_compiler/data_type_template.tmpl create mode 100644 dsdl_compiler/libcanard_dsdl_compiler/pyratemp.py create mode 100755 dsdl_compiler/libcanard_dsdlc create mode 160000 dsdl_compiler/pyuavcan diff --git a/.gitmodules b/.gitmodules index 225ac104..2de853e4 100644 --- a/.gitmodules +++ b/.gitmodules @@ -1,3 +1,6 @@ [submodule "drivers/avr/avr-can-lib"] path = drivers/avr/avr-can-lib url = https://github.com/rennerm/avr-can-lib +[submodule "dsdl_compiler/pyuavcan"] + path = dsdl_compiler/pyuavcan + url = https://github.com/UAVCAN/pyuavcan diff --git a/dsdl_compiler/README.md b/dsdl_compiler/README.md new file mode 100644 index 00000000..fdc87d67 --- /dev/null +++ b/dsdl_compiler/README.md @@ -0,0 +1,108 @@ +# UAVCAN DSDL compiler for the libcanard + +## Overview +Libcanard_dsdlc is a tool to generate UAVCAN DSDL definitions to libcanard compatible message c-modules. + +Modules have: defines, enums, unions, structs, and encoding and decoding functions as defined in UAVCAN DSDL. Encoding and decoding functions use the decode and encode functions of libcanard for bit packing / unpacking. + +In c there is no namespace, so all the generated #define and function names are long having full folder path included. This is made to prevent the collision with each other and to the rest of the system. + +## Install & Integration +To get libcanard from the git, make sure all the submodules are fetched too. + +`git submodules update --init --recursive` + +### Generating files +`python3 libcanard_dsdlc --outdir ` + +NOTE: If python2 is used, monotonic library is needed. + +`pip install monolith` + +### Using generated c-modules +Include all or only selected message c-files to your compiler script (e.g. Makefile). Add include path to root of the . + +NOTE: compiled *.o files can't be compiled into to flat "build" directory as some files in DSDL have the same name. + +### Float16 +Generated structs in modules use float16 type when so specified in DSDL. +In c-modules float16 is defined as uint16_t which can be overridden by defining FLOAT16 to something else e.g. __fp16. + +e.g. in Makefile + +` +CFLAGS += -DFLOAT16=__fp16 +` + +## Using generated modules + +#### Encode NodeStatus-broadcast message +``` + #include "uavcan/protocol/NodeStatus.h" + + /* Reserve memory and struct for messages */ + uint8_t packed_uavcan_msg_buf[UAVCAN_PROTOCOL_NODESTATUS_MAX_SIZE]; + /* MAX_SIZE comes from module header as pre-calculated */ + uavcan_protocol_NodeStatus msg; + + msg.uptime_sec = GetUptime(); + + msg.health = HEALTH_OK; + msg.mode = MODE_OPERATIONAL; + + msg.sub_mode = sub_mode; + msg.vendor_specific_status_code = vendor_status_code; + + /* Encode filled struct to packed_uavcan_msg_buf, ready to be send */ + uint32_t len_of_packed_msg = uavcan_protocol_NodeStatusEncode(&msg, packed_uavcan_msg_buf, 0, 1); + + canardBroadcast(&g_canard, + UAVCAN_PROTOCOL_NODESTATUS_SIGNATURE, + UAVCAN_PROTOCOL_NODESTATUS_ID, + &g_bc_node_status_transfer_id, + CANARD_TRANSFER_PRIORITY_MEDIUM, + packed_uavcan_msg_buf, + len_of_packed_msg); +``` + +All the *Encode calls need to have offset given as 0 and root item as 1 as parameters. This is needed, as the generated code may use offset and root item info in following *Encode calls. +*Dynamic Array* all the dynamic arrays have also _len field, which contain the info of how many data items have been stored in to dynamic array pointer. + +#### Decode GetSet-request + +``` + /* include header */ + #include "uavcan/protocol/param/GetSet.h" + + #define GETSETREQ_NAME_MAX_SIZE 96 // max size needed for the dynamic arrays + /* Reserve some memory for the dynamic arrays from the stack */ + uint8_t buff[GETSETREQ_NAME_MAX_SIZE]; + uint8_t *dyn_buf_ptr = buff; + + /* Reserve struct */ + uavcan_protocol_param_GetSetRequest get_set_req; + + /* Clearing the struct is necessary! Decoding does not guarantee + clearing all the bytes in fields in struct. */ + memset(&get_set_req, 0x00, sizeof(uavcan_protocol_param_GetSetRequest)); + + uavcan_protocol_param_GetSetRequestDecode(transfer, + (uint16_t)transfer->payload_len, + &get_set_req, + &dyn_buf_ptr, + 0); + + /* Now struct get_set_req "object" is ready to be used */ +``` + +*Dynamic Arrays* dyn_buf_ptr is a way to give allocated memory to *Decode function, to use that space to store dynamic arrays into it, and store the pointer to struct pointer. + +NOTE: There is no check whether dynamic memory allocation is big enough. + +## License + +Released under MIT license, check LICENSE + + + + diff --git a/dsdl_compiler/libcanard_dsdl_compiler/LICENSE b/dsdl_compiler/libcanard_dsdl_compiler/LICENSE new file mode 100644 index 00000000..496703fd --- /dev/null +++ b/dsdl_compiler/libcanard_dsdl_compiler/LICENSE @@ -0,0 +1,23 @@ +pyratemp was written by Roland Koebler , +and is published under the following license: + +Copyright (c) Roland Koebler, 2007-2013 + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in +all copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING +FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS +IN THE SOFTWARE. + diff --git a/dsdl_compiler/libcanard_dsdl_compiler/__init__.py b/dsdl_compiler/libcanard_dsdl_compiler/__init__.py new file mode 100644 index 00000000..50ad6543 --- /dev/null +++ b/dsdl_compiler/libcanard_dsdl_compiler/__init__.py @@ -0,0 +1,429 @@ +# +# UAVCAN DSDL compiler for libcanard +# +# This code is written by Pavel Kirienko for libuavcan DSDL generator +# copied and modified for the libcanard use +# +# Copyright (C) 2014 Pavel Kirienko +# Copyright (C) 2018 Intel Corporation +# + +''' +This module implements the core functionality of the UAVCAN DSDL compiler for libcanard. +Supported Python versions: 3.2+, 2.7. +It accepts a list of root namespaces and produces the set of C header files and souce files for libcanard. +It is based on the DSDL parsing package from pyuavcan. +''' + +from __future__ import division, absolute_import, print_function, unicode_literals +import sys, os, logging, errno, re +from .pyratemp import Template +from uavcan import dsdl + +# Python 2.7 compatibility +try: + str = unicode +except NameError: + pass + +OUTPUT_HEADER_FILE_EXTENSION = 'h' +OUTPUT_CODE_FILE_EXTENSION = 'c' +OUTPUT_FILE_PERMISSIONS = 0o444 # Read only for all +HEADER_TEMPLATE_FILENAME = os.path.join(os.path.dirname(__file__), 'data_type_template.tmpl') +CODE_TEMPLATE_FILENAME = os.path.join(os.path.dirname(__file__), 'code_type_template.tmpl') + +__all__ = ['run', 'logger', 'DsdlCompilerException'] + +class DsdlCompilerException(Exception): + pass + +logger = logging.getLogger(__name__) + +def run(source_dirs, include_dirs, output_dir): + ''' + This function takes a list of root namespace directories (containing DSDL definition files to parse), a + possibly empty list of search directories (containing DSDL definition files that can be referenced from the types + that are going to be parsed), and the output directory path (possibly nonexistent) where the generated C++ + header files will be stored. + + Note that this module features lazy write, i.e. if an output file does already exist and its content is not going + to change, it will not be overwritten. This feature allows to avoid unnecessary recompilation of dependent object + files. + + Args: + source_dirs List of root namespace directories to parse. + include_dirs List of root namespace directories with referenced types (possibly empty). This list is + automaitcally extended with source_dirs. + output_dir Output directory path. Will be created if doesn't exist. + ''' + assert isinstance(source_dirs, list) + assert isinstance(include_dirs, list) + output_dir = str(output_dir) + + types = run_parser(source_dirs, include_dirs + source_dirs) + if not types: + die('No type definitions were found') + + logger.info('%d types total', len(types)) + run_generator(types, output_dir) + +# ----------------- + +def pretty_filename(filename): + try: + a = os.path.abspath(filename) + r = os.path.relpath(filename) + return a if '..' in r else r + except ValueError: + return filename + +# get the CamelCase prefix from the current filename +def get_name_space_prefix(t): + return t.full_name.replace('.', '_') + +def type_output_filename(t, extension = OUTPUT_HEADER_FILE_EXTENSION): + assert t.category == t.CATEGORY_COMPOUND + return t.full_name.replace('.', os.path.sep) + '.' + extension + +def makedirs(path): + try: + try: + os.makedirs(path, exist_ok=True) # May throw "File exists" when executed as root, which is wrong + except TypeError: + os.makedirs(path) # Python 2.7 compatibility + except OSError as ex: + if ex.errno != errno.EEXIST: # http://stackoverflow.com/questions/12468022 + raise + +def die(text): + raise DsdlCompilerException(str(text)) + +def run_parser(source_dirs, search_dirs): + try: + types = dsdl.parse_namespaces(source_dirs, search_dirs) + except dsdl.DsdlException as ex: + logger.info('Parser failure', exc_info=True) + die(ex) + return types + +def run_generator(types, dest_dir): + try: + header_template_expander = make_template_expander(HEADER_TEMPLATE_FILENAME) + code_template_expander = make_template_expander(CODE_TEMPLATE_FILENAME) + dest_dir = os.path.abspath(dest_dir) # Removing '..' + makedirs(dest_dir) + for t in types: + logger.info('Generating type %s', t.full_name) + header_path_file_name = os.path.join(dest_dir, type_output_filename(t, OUTPUT_HEADER_FILE_EXTENSION)) + code_filename = os.path.join(dest_dir, type_output_filename(t, OUTPUT_CODE_FILE_EXTENSION)) + t.header_filename = type_output_filename(t, OUTPUT_HEADER_FILE_EXTENSION) + t.name_space_prefix = get_name_space_prefix(t) + header_text = generate_one_type(header_template_expander, t) + code_text = generate_one_type(code_template_expander, t) + write_generated_data(header_path_file_name, header_text) + write_generated_data(code_filename, code_text) + except Exception as ex: + logger.info('Generator failure', exc_info=True) + die(ex) + +def write_generated_data(filename, data): + dirname = os.path.dirname(filename) + makedirs(dirname) + + # Lazy update - file will not be rewritten if its content is not going to change + if os.path.exists(filename): + with open(filename) as f: + existing_data = f.read() + if data == existing_data: + logger.info('Up to date [%s]', pretty_filename(filename)) + return + logger.info('Rewriting [%s]', pretty_filename(filename)) + os.remove(filename) + else: + logger.info('Creating [%s]', pretty_filename(filename)) + + # Full rewrite + with open(filename, 'w') as f: + f.write(data) + try: + os.chmod(filename, OUTPUT_FILE_PERMISSIONS) + except (OSError, IOError) as ex: + logger.warning('Failed to set permissions for %s: %s', pretty_filename(filename), ex) + +def expand_to_next_full(size): + if size <= 8: + return 8 + elif size <= 16: + return 16 + elif size <= 32: + return 32 + elif size <=64: + return 64 + +def get_max_size(bits, unsigned): + if unsigned: + return (2 ** bits) -1 + else: + return (2 ** (bits-1)) -1 + +def strip_name(name): + return name.split('.')[-1] + +def type_to_c_type(t): + if t.category == t.CATEGORY_PRIMITIVE: + saturate = { + t.CAST_MODE_SATURATED: True, + t.CAST_MODE_TRUNCATED: False, + }[t.cast_mode] + cast_mode = { + t.CAST_MODE_SATURATED: 'Saturate', + t.CAST_MODE_TRUNCATED: 'Truncate', + }[t.cast_mode] + if t.kind == t.KIND_FLOAT: + float_type = { + 16: 'float16', + 32: 'float', + 64: 'double', + }[t.bitlen] + return {'cpp_type':'%s' % (float_type), + 'post_cpp_type':'', + 'cpp_type_comment':'float%d %s' % (t.bitlen, cast_mode, ), + 'bitlen':t.bitlen, + 'max_size':get_max_size(t.bitlen, False), + 'signedness':'false', + 'saturate':False} # do not saturate floats + else: + c_type = { + t.KIND_BOOLEAN: 'bool', + t.KIND_UNSIGNED_INT: 'uint', + t.KIND_SIGNED_INT: 'int', + }[t.kind] + signedness = { + t.KIND_BOOLEAN: 'false', + t.KIND_UNSIGNED_INT: 'false', + t.KIND_SIGNED_INT: 'true', + }[t.kind] + + if t.kind == t.KIND_BOOLEAN: + return {'cpp_type':'%s' % (c_type), + 'post_cpp_type':'', + 'cpp_type_comment':'bit len %d' % (t.bitlen, ), + 'bitlen':t.bitlen, + 'max_size':get_max_size(t.bitlen, False), + 'signedness':signedness, + 'saturate':saturate} + else: + if saturate: + # Do not staturate if struct field length is equal bitlen + if (expand_to_next_full(t.bitlen) == t.bitlen): + saturate = False + return {'cpp_type':'%s%d_t' % (c_type, expand_to_next_full(t.bitlen)), + 'post_cpp_type':'', + 'cpp_type_comment':'bit len %d' % (t.bitlen, ), + 'bitlen':t.bitlen, + 'max_size':get_max_size(t.bitlen, t.kind == t.KIND_UNSIGNED_INT), + 'signedness':signedness, + 'saturate':saturate} + + elif t.category == t.CATEGORY_ARRAY: + values = type_to_c_type(t.value_type) + mode = { + t.MODE_STATIC: 'Static Array', + t.MODE_DYNAMIC: 'Dynamic Array', + }[t.mode] + return {'cpp_type':'%s' % (values['cpp_type'], ), + 'cpp_type_category': t.value_type.category, + 'post_cpp_type':'[%d]' % (t.max_size,), + 'cpp_type_comment':'%s %dbit[%d] max items' % (mode, values['bitlen'], t.max_size, ), + 'bitlen':values['bitlen'], + 'array_max_size_bit_len':t.max_size.bit_length(), + 'max_size':values['max_size'], + 'signedness':values['signedness'], + 'saturate':values['saturate'], + 'dynamic_array': t.mode == t.MODE_DYNAMIC, + } + elif t.category == t.CATEGORY_COMPOUND: + return { + 'cpp_type':t.full_name.replace('.','_'), + 'post_cpp_type':'', + 'cpp_type_comment':'', + 'bitlen':t.get_max_bitlen(), + 'max_size':0, + 'signedness':'false', + 'saturate':False} + elif t.category == t.CATEGORY_VOID: + return {'cpp_type':'', + 'post_cpp_type':'', + 'cpp_type_comment':'void%d' % t.bitlen, + 'bitlen':t.bitlen, + 'max_size':0, + 'signedness':'false', + 'saturate':False} + else: + raise DsdlCompilerException('Unknown type category: %s' % t.category) + +def generate_one_type(template_expander, t): + t.name_space_type_name = get_name_space_prefix(t) + t.cpp_full_type_name = '::' + t.full_name.replace('.', '::') + t.include_guard = '__' + t.full_name.replace('.', '_').upper() + t.macro_name = t.full_name.replace('.', '_').upper() + + # Dependencies (no duplicates) + def fields_includes(fields): + def detect_include(t): + if t.category == t.CATEGORY_COMPOUND: + return type_output_filename(t) + if t.category == t.CATEGORY_ARRAY: + return detect_include(t.value_type) + return list(sorted(set(filter(None, [detect_include(x.type) for x in fields])))) + + if t.kind == t.KIND_MESSAGE: + t.cpp_includes = fields_includes(t.fields) + else: + t.cpp_includes = fields_includes(t.request_fields + t.response_fields) + + t.cpp_namespace_components = t.full_name.split('.')[:-1] + t.has_default_dtid = t.default_dtid is not None + + # Attribute types + def inject_cpp_types(attributes): + length = len(attributes) + count = 0 + has_array = False + for a in attributes: + count = count + 1 + a.last_item = False + if (count == length): + a.last_item = True + + data = type_to_c_type(a.type) + for key, value in data.items(): + setattr(a, key, value) + + if a.type.category == t.CATEGORY_ARRAY: + a.array_size = a.type.max_size + has_array = True + + a.type_category = a.type.category + a.void = a.type.category == a.type.CATEGORY_VOID + if a.void: + assert not a.name + a.name = '' + return has_array + + if t.kind == t.KIND_MESSAGE: + t.has_array = inject_cpp_types(t.fields) + inject_cpp_types(t.constants) + t.all_attributes = t.fields + t.constants + t.union = t.union and len(t.fields) + if t.union: + t.union = len(t.fields).bit_length() + else: + t.request_has_array = inject_cpp_types(t.request_fields) + inject_cpp_types(t.request_constants) + t.response_has_array = inject_cpp_types(t.response_fields) + inject_cpp_types(t.response_constants) + t.all_attributes = t.request_fields + t.request_constants + t.response_fields + t.response_constants + t.request_union = t.request_union and len(t.request_fields) + t.response_union = t.response_union and len(t.response_fields) + if t.request_union: + t.request_union = len(t.request_fields).bit_length() + if t.response_union: + t.response_union = len(t.response_fields).bit_length() + + # Constant properties + def inject_constant_info(constants): + for c in constants: + if c.type.kind == c.type.KIND_FLOAT: + float(c.string_value) # Making sure that this is a valid float literal + c.cpp_value = c.string_value + else: + int(c.string_value) # Making sure that this is a valid integer literal + c.cpp_value = c.string_value + if c.type.kind == c.type.KIND_UNSIGNED_INT: + c.cpp_value += 'U' + + if t.kind == t.KIND_MESSAGE: + inject_constant_info(t.constants) + else: + inject_constant_info(t.request_constants) + inject_constant_info(t.response_constants) + + # Data type kind + t.cpp_kind = { + t.KIND_MESSAGE: '::uavcan::DataTypeKindMessage', + t.KIND_SERVICE: '::uavcan::DataTypeKindService', + }[t.kind] + + # Generation + text = template_expander(t=t) # t for Type + text = '\n'.join(x.rstrip() for x in text.splitlines()) + text = text.replace('\n\n\n\n\n', '\n\n').replace('\n\n\n\n', '\n\n').replace('\n\n\n', '\n\n') + text = text.replace('{\n\n ', '{\n ') + return text + +def make_template_expander(filename): + ''' + Templating is based on pyratemp (http://www.simple-is-better.org/template/pyratemp.html). + The pyratemp's syntax is rather verbose and not so human friendly, so we define some + custom extensions to make it easier to read and write. + The resulting syntax somewhat resembles Mako (which was used earlier instead of pyratemp): + Substitution: + ${expression} + Line joining through backslash (replaced with a single space): + ${foo(bar(very_long_arument=42, \ + second_line=72))} + Blocks: + % for a in range(10): + % if a == 5: + ${foo()} + % endif + % endfor + The extended syntax is converted into pyratemp's through regexp substitution. + ''' + with open(filename) as f: + template_text = f.read() + + # Backslash-newline elimination + template_text = re.sub(r'\\\r{0,1}\n\ *', r' ', template_text) + + # Substitution syntax transformation: ${foo} ==> $!foo!$ + template_text = re.sub(r'([^\$]{0,1})\$\{([^\}]+)\}', r'\1$!\2!$', template_text) + + # Flow control expression transformation: % foo: ==> + template_text = re.sub(r'(?m)^(\ *)\%\ *(.+?):{0,1}$', r'\1', template_text) + + # Block termination transformation: ==> + template_text = re.sub(r'\<\!--\(end[a-z]+\)--\>', r'', template_text) + + # Pyratemp workaround. + # The problem is that if there's no empty line after a macro declaration, first line will be doubly indented. + # Workaround: + # 1. Remove trailing comments + # 2. Add a newline after each macro declaration + template_text = re.sub(r'\ *\#\!.*', '', template_text) + template_text = re.sub(r'(\<\!--\(macro\ [a-zA-Z0-9_]+\)--\>.*?)', r'\1\n', template_text) + + # Preprocessed text output for debugging +# with open(filename + '.d', 'w') as f: +# f.write(template_text) + + template = Template(template_text) + + def expand(**args): + # This function adds one indentation level (4 spaces); it will be used from the template + args['indent'] = lambda text, idnt = ' ': idnt + text.replace('\n', '\n' + idnt) + # This function works like enumerate(), telling you whether the current item is the last one + def enum_last_value(iterable, start=0): + it = iter(iterable) + count = start + last = next(it) + for val in it: + yield count, False, last + last = val + count += 1 + yield count, True, last + args['enum_last_value'] = enum_last_value + return template(**args) + + return expand diff --git a/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl b/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl new file mode 100644 index 00000000..39442108 --- /dev/null +++ b/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl @@ -0,0 +1,228 @@ +/* + * UAVCAN data structure definition for libcanard. + * + * Autogenerated, do not edit. + * + * Source file: ${t.source_file} + */ + +#include "${t.header_filename}" +#include "canard.h" + + #! type_name, service, max_bitlen, fields, constants, union, has_array + + %if max_bitlen +/** + * @brief ${type_name}Encode + * @param source : Pointer to source data struct + * @param msg_buf: Pointer to msg storage + * @param offset: Call with 0, bit offset to msg storage + * @param root_item: Call with 1, this for internal use + * @retval returns message length as bytes (when root_item == 1) + */ +uint32_t ${type_name}Encode(${type_name} *source, void *msg_buf, uint32_t offset, uint8_t root_item) { + %if union + /* Max Union Tag Value */ + //assert(source->union_tag > ${(len(fields) - 1)}); + %endif + %if has_array: + uint32_t c = 0; + %endif + + %if union: + /* Union Tag ${union} bits */ + canardEncodeScalar(msg_buf, offset, ${union}, (void*)&source->union_tag); // ${union} bits + offset += ${union}; + $!setvar("union_index", "0")!$ + %endif + + % for f in fields: + %if union: + ${'if' if not union_index else 'else if'} (source->union_tag == ${union_index}) { + $!setvar("union_index", "union_index + 1")!$ + %endif + %if f.type_category == t.CATEGORY_ARRAY + %if f.dynamic_array == True + + /* Dynamic Array (${f.name})*/ + %if f.last_item + %if f.bitlen < 8 + ${f.array_max_size_bit_len} + /* - Add array length, last item, but bitlen < 8. */ + canardEncodeScalar(msg_buf, offset, ${f.array_max_size_bit_len}, (void*)&source->${'%s' % ((f.name + '_len'))}); + offset += ${f.array_max_size_bit_len}; + %else + if (! root_item) { + /* - Add array length */ + canardEncodeScalar(msg_buf, offset, ${f.array_max_size_bit_len}, (void*)&source->${'%s' % ((f.name + '_len'))}); + offset += ${f.array_max_size_bit_len}; + } + %endif + %else + /* - Add array length */ + canardEncodeScalar(msg_buf, offset, ${f.array_max_size_bit_len}, (void*)&source->${'%s' % ((f.name + '_len'))}); + offset += ${f.array_max_size_bit_len}; + %endif + /* - Add array items */ + for (c = 0; c < source->${'%s' % ((f.name + '_len'))}; c++) { + %if f.cpp_type_category == t.CATEGORY_COMPOUND: + offset += ${f.cpp_type}Encode((void*)&source->${f.name}[c], msg_buf, offset, 0); + %else + canardEncodeScalar(msg_buf, offset, ${f.bitlen}, (void*)(source->${f.name} + c)); // ${f.max_size} + offset += ${f.bitlen}; + %endif + } + %else + /* Static array (${f.name}) */ + for (c = 0; c < ${f.array_size}; c++) { + canardEncodeScalar(msg_buf, offset, ${f.bitlen}, (void*)(source->${f.name} + c)); // ${f.max_size} + offset += ${f.bitlen}; + } + %endif + + %elif f.type_category == t.CATEGORY_VOID: + + /* Void${f.bitlen} */ + offset += ${f.bitlen}; + %elif f.type_category == t.CATEGORY_COMPOUND: + + /* Compound */ + offset = ${f.cpp_type}Encode((void*)&source->${f.name}, msg_buf, offset, 0); + %else + %if f.saturate + source->${f.name} = SATURATE(source->${f.name}, ${f.max_size}) + %endif + canardEncodeScalar(msg_buf, offset, ${f.bitlen}, (void*)&source->${f.name}); // ${f.max_size} + offset += ${f.bitlen}; + + %endif + %if union: + } + %endif + % endfor + if (root_item) { + return (offset + 7 ) / 8; + } + + return offset; +} + +/** + * @brief ${type_name}Decode + * @param transfer: Pointer to CanardRxTransfer transfer + * @param payload_len: Payload message length + * @param dest: Pointer to destination struct + * @param dyn_arr_buf: NULL or Pointer to memory storage to be used for dynamic arrays + * ${type_name} dyn memory will point to dyn_arr_buf memory. + * NULL will ignore dynamic arrays decoding. + * @param offset: Call with 0, bit offset to msg storage + * @retval + */ +uint32_t ${type_name}Decode(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name} *dest, uint8_t **dyn_arr_buf, uint32_t offset) { + %if has_array + uint32_t c = 0; + %endif + + %if union: + /* Get Union Tag */ + canardDecodeScalar(transfer, offset, ${union}, false, (void*)&dest->union_tag); // ${union} + offset += ${union}; + $!setvar("union_index", "0")!$ + %endif + + % for f in fields: + %if union: + ${'if' if not union_index else 'else if'} (dest->union_tag == ${union_index}) { + $!setvar("union_index", "union_index + 1")!$ + %endif + %if f.type_category == t.CATEGORY_ARRAY + %if f.dynamic_array == True + + /* Dynamic Array (${f.name})*/ + %if f.last_item + %if f.bitlen > 7 + /* - Last item in struct & Root item & (Array Size > 8 bit), tail array optimization */ + if (payload_len) { + /* - Calculate Array length from MSG length */ + dest->${'%s' % ((f.name + '_len'))} = ((payload_len * 8) - offset ) / ${f.bitlen}; // ${f.bitlen} bit array item size + } else { + /* - Array length ${f.array_max_size_bit_len} bits */ + canardDecodeScalar(transfer, offset, ${f.array_max_size_bit_len}, false, (void*)&dest->${'%s' % ((f.name + '_len'))}); // ${f.max_size} + offset += ${f.array_max_size_bit_len}; + } + %else + canardDecodeScalar(transfer, offset, ${f.array_max_size_bit_len}, false, (void*)&dest->${'%s' % ((f.name + '_len'))}); // ${f.max_size} + offset += ${f.array_max_size_bit_len}; + %endif + %else + /* - Array length, not last item ${f.array_max_size_bit_len} bits*/ + canardDecodeScalar(transfer, offset, ${f.array_max_size_bit_len}, false, (void*)&dest->${'%s' % ((f.name + '_len'))}); // ${f.max_size} + offset += ${f.array_max_size_bit_len}; + %endif + /* - Get Array */ + if (dyn_arr_buf) { + dest->${f.name} = (${f.cpp_type}*)*dyn_arr_buf; + } + for (c = 0; c < dest->${'%s' % ((f.name + '_len'))}; c++) { + %if f.cpp_type_category == t.CATEGORY_COMPOUND: + offset += ${f.cpp_type}Decode(transfer, 0, (void*)&dest->${f.name}[c], dyn_arr_buf, offset); + %else + if (dyn_arr_buf) { + canardDecodeScalar(transfer, offset, ${f.bitlen}, ${f.signedness}, (void*)*dyn_arr_buf); // ${f.max_size} + *dyn_arr_buf = (uint8_t *)(((${f.cpp_type}*)*dyn_arr_buf) + 1); + } + offset += ${f.bitlen}; + %endif + } + %else + + /* Static array (${f.name}) */ + for (c = 0; c < ${f.array_size}; c++) { + canardDecodeScalar(transfer, offset, ${f.bitlen}, ${f.signedness}, (void*)(dest->${f.name} + c)); + offset += ${f.bitlen}; + } + %endif + %elif f.type_category == t.CATEGORY_VOID: + + /* Void${f.bitlen} */ + offset += ${f.bitlen}; + %elif f.type_category == t.CATEGORY_COMPOUND: + + /* Compound */ + offset = ${f.cpp_type}Decode(transfer, 0, (void*)&dest->${f.name}, dyn_arr_buf, offset); + %else + + canardDecodeScalar(transfer, offset, ${f.bitlen}, ${f.signedness}, (void*)&dest->${f.name}); + offset += ${f.bitlen}; + %endif + %if union: + } + %endif + % endfor + return offset; +} + %else +uint32_t ${type_name}Encode(${type_name} *source, void *msg_buf, uint32_t offset, uint8_t root_item) { + if (root_item) { + return (offset + 7 ) / 8; + } + return offset; +} +uint32_t ${type_name}Decode(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name} *dest, uint8_t **dyn_arr_buf, uint32_t offset) { + return offset; +} + %endif + + +% if t.kind == t.KIND_SERVICE: +${generate_primary_body(type_name=t.name_space_type_name+'Request', service='_REQUEST', max_bitlen=t.get_max_bitlen_request(), \ + fields=t.request_fields, constants=t.request_constants, \ + union=t.request_union, has_array=t.request_has_array)} + +${generate_primary_body(type_name=t.name_space_type_name+'Response', service='_RESPONSE', max_bitlen=t.get_max_bitlen_response(), \ + fields=t.response_fields, constants=t.response_constants, \ + union=t.response_union, has_array=t.response_has_array)} +% else: +${generate_primary_body(type_name=t.name_space_type_name, service='', max_bitlen=t.get_max_bitlen(), \ + fields=t.fields, constants=t.constants, union=t.union, has_array=t.has_array)} +% endif diff --git a/dsdl_compiler/libcanard_dsdl_compiler/data_type_template.tmpl b/dsdl_compiler/libcanard_dsdl_compiler/data_type_template.tmpl new file mode 100644 index 00000000..7d7192b8 --- /dev/null +++ b/dsdl_compiler/libcanard_dsdl_compiler/data_type_template.tmpl @@ -0,0 +1,128 @@ +/* + * UAVCAN data structure definition for libcanard. + * + * Autogenerated, do not edit. + * + * Source file: ${t.source_file} + */ + +#ifndef ${t.include_guard} +#define ${t.include_guard} + +#include +#include "canard.h" + +#ifndef FLOAT16 +typedef uint16_t float16; +#else +typedef FLOAT16 float16; +#endif + +#ifndef SATURATE +#define SATURATE(x, max) ( ((x) > max) ? max : ( (-(x) > max) ? (-max) : (x) ) ); +#endif + +#ifdef __cplusplus +extern "C" { +#endif + +% for inc in t.cpp_includes: +#include <${inc}> +% endfor + +/******************************* Source text ********************************** +% for line in t.source_text.strip().splitlines(): +${line} +% endfor +******************************************************************************/ + +/********************* DSDL signature source definition *********************** +% for line in t.get_dsdl_signature_source_definition().splitlines(): +${line} +% endfor +******************************************************************************/ + +%if t.default_dtid != None: +#define ${'%-50s' % (t.macro_name + '_ID')} ${t.default_dtid} +%endif +#define ${'%-50s' % (t.macro_name + '_NAME')} "${t.full_name}" +#define ${'%-50s' % (t.macro_name + '_SIGNATURE')} (${'0x%08X' % t.get_data_type_signature()}ULL) + + #! type_name, service, max_bitlen, fields, constants, union, has_array + +#define ${'%-50s' % (t.macro_name + service + '_MAX_SIZE')} ((${'%d' % max_bitlen} + 7)/8) + + %if max_bitlen + +// Constants + % for a in constants: +#define ${'%-60s %10s' % (t.macro_name + '_' + a.name, a.init_expression, )} // ${a.init_expression} + % endfor + + %if union +typedef enum { + % for idx,last,a in enum_last_value(fields): + ${type_name.upper()}_${a.name.upper()}${',' if not last else ''} + % endfor +} ${type_name}_ENUM; + %endif + +typedef struct { + %if union: + ${type_name}_ENUM union_tag; // union_tag indicates what field the data structure is holding + + union { + %endif + #! group_name, attrs + /* ${group_name} */ + % for a in attrs: + %if a.type_category == t.CATEGORY_ARRAY + %if a.dynamic_array == True + struct { + ${'uint8_t %-26s // %s' % ((a.name + '_len;'), 'TODO what size this should be?' )} + ${'%-10s %-26s // %s' % (a.cpp_type, ('*' + a.name + ';'), a.cpp_type_comment, )} + }; + %else + ${'%-10s %-30s // %s' % (a.cpp_type, (a.name + a.post_cpp_type + ';'), a.cpp_type_comment, )} + %endif + %elif a.type_category == t.CATEGORY_VOID: + /* ${a.cpp_type_comment} */ + %else + ${'%-10s %-30s // %s' % (a.cpp_type, (a.name + a.post_cpp_type + ';'), a.cpp_type_comment, )} + %endif + % endfor + + ${expand_attr_types(group_name='FieldTypes', attrs=fields)} + %if union: + }; + %endif +} ${type_name}; + +extern uint32_t ${type_name}Encode(${type_name} *source, void *msg_buf, uint32_t offset, uint8_t root_item); +extern uint32_t ${type_name}Decode(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name} *dest, uint8_t **dyn_arr_buf, uint32_t offset); + %else +typedef struct { + uint8_t empty; +} ${type_name}; + + extern uint32_t ${type_name}Encode(${type_name} *source, void *msg_buf, uint32_t offset, uint8_t root_item); + extern uint32_t ${type_name}Decode(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name} *dest, uint8_t **dyn_arr_buf, uint32_t offset); + %endif + + +% if t.kind == t.KIND_SERVICE: +${generate_primary_body(type_name=t.name_space_type_name+'Request', service='_REQUEST', max_bitlen=t.get_max_bitlen_request(), \ + fields=t.request_fields, constants=t.request_constants, \ + union=t.request_union, has_array=t.request_has_array)} + +${generate_primary_body(type_name=t.name_space_type_name+'Response', service='_RESPONSE', max_bitlen=t.get_max_bitlen_response(), \ + fields=t.response_fields, constants=t.response_constants, \ + union=t.response_union, has_array=t.response_has_array)} +% else: +${generate_primary_body(type_name=t.name_space_type_name, service='', max_bitlen=t.get_max_bitlen(), \ + fields=t.fields, constants=t.constants, union=t.union, has_array=t.has_array)} +% endif +#ifdef __cplusplus +} /* extern "C" */ +#endif +#endif // ${t.include_guard} diff --git a/dsdl_compiler/libcanard_dsdl_compiler/pyratemp.py b/dsdl_compiler/libcanard_dsdl_compiler/pyratemp.py new file mode 100644 index 00000000..eb4c1286 --- /dev/null +++ b/dsdl_compiler/libcanard_dsdl_compiler/pyratemp.py @@ -0,0 +1,1238 @@ +#!/usr/bin/env python +# -*- coding: utf-8 -*- +""" +Small, simple and powerful template-engine for Python. + +A template-engine for Python, which is very simple, easy to use, small, +fast, powerful, modular, extensible, well documented and pythonic. + +See documentation for a list of features, template-syntax etc. + +:Version: 0.3.2 +:Requires: Python >=2.6 / 3.x + +:Usage: + see class ``Template`` and examples below. + +:Example: + + Note that the examples are in Python 2; they also work in + Python 3 if you replace u"..." by "...", unicode() by str() + and partly "..." by b"...". + + quickstart:: + >>> t = Template("hello @!name!@") + >>> print(t(name="marvin")) + hello marvin + + quickstart with a template-file:: + # >>> t = Template(filename="mytemplate.tmpl") + # >>> print(t(name="marvin")) + # hello marvin + + generic usage:: + >>> t = Template(u"output is in Unicode \\xe4\\xf6\\xfc\\u20ac") + >>> t #doctest: +ELLIPSIS + <...Template instance at 0x...> + >>> t() + u'output is in Unicode \\xe4\\xf6\\xfc\\u20ac' + >>> unicode(t) + u'output is in Unicode \\xe4\\xf6\\xfc\\u20ac' + + with data:: + >>> t = Template("hello @!name!@", data={"name":"world"}) + >>> t() + u'hello world' + >>> t(name="worlds") + u'hello worlds' + + # >>> t(note="data must be Unicode or ASCII", name=u"\\xe4") + # u'hello \\xe4' + + escaping:: + >>> t = Template("hello escaped: @!name!@, unescaped: $!name!$") + >>> t(name='''<>&'"''') + u'hello escaped: <>&'", unescaped: <>&\\'"' + + result-encoding:: + # encode the unicode-object to your encoding with encode() + >>> t = Template(u"hello \\xe4\\xf6\\xfc\\u20ac") + >>> result = t() + >>> result + u'hello \\xe4\\xf6\\xfc\\u20ac' + >>> result.encode("utf-8") + 'hello \\xc3\\xa4\\xc3\\xb6\\xc3\\xbc\\xe2\\x82\\xac' + >>> result.encode("ascii") + Traceback (most recent call last): + ... + UnicodeEncodeError: 'ascii' codec can't encode characters in position 6-9: ordinal not in range(128) + >>> result.encode("ascii", 'xmlcharrefreplace') + 'hello äöü€' + + Python-expressions:: + >>> Template('formatted: @! "%8.5f" % value !@')(value=3.141592653) + u'formatted: 3.14159' + >>> Template("hello --@!name.upper().center(20)!@--")(name="world") + u'hello -- WORLD --' + >>> Template("calculate @!var*5+7!@")(var=7) + u'calculate 42' + + blocks (if/for/macros/...):: + >>> t = Template("barbazunknown(@!foo!@)") + >>> t(foo=2) + u'baz' + >>> t(foo=5) + u'unknown(5)' + + >>> t = Template("@!i!@ (empty)") + >>> t(mylist=[]) + u'(empty)' + >>> t(mylist=[1,2,3]) + u'1 2 3 ' + + >>> t = Template(" - @!i!@: @!elem!@") + >>> t(mylist=["a","b","c"]) + u' - 0: a - 1: b - 2: c' + + >>> t = Template('hello @!name!@ @!greetings(name=user)!@') + >>> t(user="monty") + u' hello monty' + + exists:: + >>> t = Template('YESNO') + >>> t() + u'NO' + >>> t(foo=1) + u'YES' + >>> t(foo=None) # note this difference to 'default()' + u'YES' + + default-values:: + # non-existing variables raise an error + >>> Template('hi @!optional!@')() + Traceback (most recent call last): + ... + TemplateRenderError: Cannot eval expression 'optional'. (NameError: name 'optional' is not defined) + + >>> t = Template('hi @!default("optional","anyone")!@') + >>> t() + u'hi anyone' + >>> t(optional=None) + u'hi anyone' + >>> t(optional="there") + u'hi there' + + # the 1st parameter can be any eval-expression + >>> t = Template('@!default("5*var1+var2","missing variable")!@') + >>> t(var1=10) + u'missing variable' + >>> t(var1=10, var2=2) + u'52' + + # also in blocks + >>> t = Template('yesno') + >>> t() + u'no' + >>> t(opt1=23, opt2=42) + u'yes' + + >>> t = Template('@!i!@') + >>> t() + u'' + >>> t(optional_list=[1,2,3]) + u'123' + + + # but make sure to put the expression in quotation marks, otherwise: + >>> Template('@!default(optional,"fallback")!@')() + Traceback (most recent call last): + ... + TemplateRenderError: Cannot eval expression 'default(optional,"fallback")'. (NameError: name 'optional' is not defined) + + setvar:: + >>> t = Template('$!setvar("i", "i+1")!$@!i!@') + >>> t(i=6) + u'7' + + >>> t = Template('''$!setvar("s", '"\\\\\\\\n".join(s)')!$@!s!@''') + >>> t(isinstance=isinstance, s="123") + u'123' + >>> t(isinstance=isinstance, s=["123", "456"]) + u'123\\n456' + +:Author: Roland Koebler (rk at simple-is-better dot org) +:Copyright: Roland Koebler +:License: MIT/X11-like, see __license__ + +:RCS: $Id: pyratemp.py,v 1.22 2013/09/17 07:44:13 rk Exp $ +""" +from __future__ import unicode_literals + +__version__ = "0.3.2" +__author__ = "Roland Koebler " +__license__ = """Copyright (c) Roland Koebler, 2007-2013 + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in +all copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING +FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS +IN THE SOFTWARE.""" + +#========================================= + +import os, re, sys, types +if sys.version_info[0] >= 3: + import builtins + unicode = str + long = int +else: + import __builtin__ as builtins + from codecs import open + +#========================================= +# some useful functions + +#---------------------- +# string-position: i <-> row,col + +def srow(string, i): + """Get line numer of ``string[i]`` in `string`. + + :Returns: row, starting at 1 + :Note: This works for text-strings with ``\\n`` or ``\\r\\n``. + """ + return string.count('\n', 0, max(0, i)) + 1 + +def scol(string, i): + """Get column number of ``string[i]`` in `string`. + + :Returns: column, starting at 1 (but may be <1 if i<0) + :Note: This works for text-strings with ``\\n`` or ``\\r\\n``. + """ + return i - string.rfind('\n', 0, max(0, i)) + +def sindex(string, row, col): + """Get index of the character at `row`/`col` in `string`. + + :Parameters: + - `row`: row number, starting at 1. + - `col`: column number, starting at 1. + :Returns: ``i``, starting at 0 (but may be <1 if row/col<0) + :Note: This works for text-strings with '\\n' or '\\r\\n'. + """ + n = 0 + for _ in range(row-1): + n = string.find('\n', n) + 1 + return n+col-1 + +#---------------------- + +def dictkeyclean(d): + """Convert all keys of the dict `d` to strings. + """ + new_d = {} + for k, v in d.items(): + new_d[str(k)] = v + return new_d + +#---------------------- + +def dummy(*_, **__): + """Dummy function, doing nothing. + """ + pass + +def dummy_raise(exception, value): + """Create an exception-raising dummy function. + + :Returns: dummy function, raising ``exception(value)`` + """ + def mydummy(*_, **__): + raise exception(value) + return mydummy + +#========================================= +# escaping + +(NONE, HTML, LATEX, MAIL_HEADER) = range(0, 4) +ESCAPE_SUPPORTED = {"NONE":None, "HTML":HTML, "LATEX":LATEX, "MAIL_HEADER":MAIL_HEADER} + +def escape(s, format=HTML): + """Replace special characters by their escape sequence. + + :Parameters: + - `s`: unicode-string to escape + - `format`: + + - `NONE`: nothing is replaced + - `HTML`: replace &<>'" by &...; + - `LATEX`: replace \#$%&_{}~^ + - `MAIL_HEADER`: escape non-ASCII mail-header-contents + :Returns: + the escaped string in unicode + :Exceptions: + - `ValueError`: if `format` is invalid. + + :Uses: + MAIL_HEADER uses module email + """ + #Note: If you have to make sure that every character gets replaced + # only once (and if you cannot achieve this with the following code), + # use something like "".join([replacedict.get(c,c) for c in s]) + # which is about 2-3 times slower (but maybe needs less memory). + #Note: This is one of the most time-consuming parts of the template. + if format is None or format == NONE: + pass + elif format == HTML: + s = s.replace("&", "&") # must be done first! + s = s.replace("<", "<") + s = s.replace(">", ">") + s = s.replace('"', """) + s = s.replace("'", "'") + elif format == LATEX: + s = s.replace("\\", "\\x") #must be done first! + s = s.replace("#", "\\#") + s = s.replace("$", "\\$") + s = s.replace("%", "\\%") + s = s.replace("&", "\\&") + s = s.replace("_", "\\_") + s = s.replace("{", "\\{") + s = s.replace("}", "\\}") + s = s.replace("\\x","\\textbackslash{}") + s = s.replace("~", "\\textasciitilde{}") + s = s.replace("^", "\\textasciicircum{}") + elif format == MAIL_HEADER: + import email.header + try: + s.encode("ascii") + return s + except UnicodeEncodeError: + return email.header.make_header([(s, "utf-8")]).encode() + else: + raise ValueError('Invalid format (only None, HTML, LATEX and MAIL_HEADER are supported).') + return s + +#========================================= + +#----------------------------------------- +# Exceptions + +class TemplateException(Exception): + """Base class for template-exceptions.""" + pass + +class TemplateParseError(TemplateException): + """Template parsing failed.""" + def __init__(self, err, errpos): + """ + :Parameters: + - `err`: error-message or exception to wrap + - `errpos`: ``(filename,row,col)`` where the error occured. + """ + self.err = err + self.filename, self.row, self.col = errpos + TemplateException.__init__(self) + def __str__(self): + if not self.filename: + return "line %d, col %d: %s" % (self.row, self.col, str(self.err)) + else: + return "file %s, line %d, col %d: %s" % (self.filename, self.row, self.col, str(self.err)) + +class TemplateSyntaxError(TemplateParseError, SyntaxError): + """Template syntax-error.""" + pass + +class TemplateIncludeError(TemplateParseError): + """Template 'include' failed.""" + pass + +class TemplateRenderError(TemplateException): + """Template rendering failed.""" + pass + +#----------------------------------------- +# Loader + +class LoaderString: + """Load template from a string/unicode. + + Note that 'include' is not possible in such templates. + """ + def __init__(self, encoding='utf-8'): + self.encoding = encoding + + def load(self, s): + """Return template-string as unicode. + """ + if isinstance(s, unicode): + u = s + else: + u = s.decode(self.encoding) + return u + +class LoaderFile: + """Load template from a file. + + When loading a template from a file, it's possible to including other + templates (by using 'include' in the template). But for simplicity + and security, all included templates have to be in the same directory! + (see ``allowed_path``) + """ + def __init__(self, allowed_path=None, encoding='utf-8'): + """Init the loader. + + :Parameters: + - `allowed_path`: path of the template-files + - `encoding`: encoding of the template-files + :Exceptions: + - `ValueError`: if `allowed_path` is not a directory + """ + if allowed_path and not os.path.isdir(allowed_path): + raise ValueError("'allowed_path' has to be a directory.") + self.path = allowed_path + self.encoding = encoding + + def load(self, filename): + """Load a template from a file. + + Check if filename is allowed and return its contens in unicode. + + :Parameters: + - `filename`: filename of the template without path + :Returns: + the contents of the template-file in unicode + :Exceptions: + - `ValueError`: if `filename` contains a path + """ + if filename != os.path.basename(filename): + raise ValueError("No path allowed in filename. (%s)" %(filename)) + filename = os.path.join(self.path, filename) + + f = open(filename, 'r', encoding=self.encoding) + u = f.read() + f.close() + + return u + +#----------------------------------------- +# Parser + +class Parser(object): + """Parse a template into a parse-tree. + + Includes a syntax-check, an optional expression-check and verbose + error-messages. + + See documentation for a description of the parse-tree. + """ + # template-syntax + _comment_start = "#!" + _comment_end = "!#" + _sub_start = "$!" + _sub_end = "!$" + _subesc_start = "@!" + _subesc_end = "!@" + _block_start = "" + + # build regexps + # comment + # single-line, until end-tag or end-of-line. + _strComment = r"""%s(?P.*?)(?P%s|\n|$)""" \ + % (re.escape(_comment_start), re.escape(_comment_end)) + _reComment = re.compile(_strComment, re.M) + + # escaped or unescaped substitution + # single-line ("|$" is needed to be able to generate good error-messges) + _strSubstitution = r""" + ( + %s\s*(?P.*?)\s*(?P%s|$) #substitution + | + %s\s*(?P.*?)\s*(?P%s|$) #escaped substitution + ) + """ % (re.escape(_sub_start), re.escape(_sub_end), + re.escape(_subesc_start), re.escape(_subesc_end)) + _reSubstitution = re.compile(_strSubstitution, re.X|re.M) + + # block + # - single-line, no nesting. + # or + # - multi-line, nested by whitespace indentation: + # * start- and end-tag of a block must have exactly the same indentation. + # * start- and end-tags of *nested* blocks should have a greater indentation. + # NOTE: A single-line block must not start at beginning of the line with + # the same indentation as the enclosing multi-line blocks! + # Note that " " and "\t" are different, although they may + # look the same in an editor! + _s = re.escape(_block_start) + _e = re.escape(_block_end) + _strBlock = r""" + ^(?P[ \t]*)%send%s(?P.*)\r?\n? # multi-line end (^ IGNORED_TEXT\n) + | + (?P)%send%s # single-line end () + | + (?P[ \t]*) # single-line tag (no nesting) + %s(?P\w+)[ \t]*(?P.*?)%s + (?P.*?) + (?=(?:%s.*?%s.*?)??%send%s) # (match until end or i.e. ) + | + # multi-line tag, nested by whitespace indentation + ^(?P[ \t]*) # save indentation of start tag + %s(?P\w+)\s*(?P.*?)%s(?P.*)\r?\n + (?P(?:.*\n)*?) + (?=(?P=indent)%s(?:.|\s)*?%s) # match indentation + """ % (_s, _e, + _s, _e, + _s, _e, _s, _e, _s, _e, + _s, _e, _s, _e) + _reBlock = re.compile(_strBlock, re.X|re.M) + + # "for"-block parameters: "var(,var)* in ..." + _strForParam = r"""^(?P\w+(?:\s*,\s*\w+)*)\s+in\s+(?P.+)$""" + _reForParam = re.compile(_strForParam) + + # allowed macro-names + _reMacroParam = re.compile(r"""^\w+$""") + + + def __init__(self, loadfunc=None, testexpr=None, escape=HTML): + """Init the parser. + + :Parameters: + - `loadfunc`: function to load included templates + (i.e. ``LoaderFile(...).load``) + - `testexpr`: function to test if a template-expressions is valid + (i.e. ``EvalPseudoSandbox().compile``) + - `escape`: default-escaping (may be modified by the template) + :Exceptions: + - `ValueError`: if `testexpr` or `escape` is invalid. + """ + if loadfunc is None: + self._load = dummy_raise(NotImplementedError, "'include' not supported, since no 'loadfunc' was given.") + else: + self._load = loadfunc + + if testexpr is None: + self._testexprfunc = dummy + else: + try: # test if testexpr() works + testexpr("i==1") + except Exception as err: + raise ValueError("Invalid 'testexpr'. (%s)" %(err)) + self._testexprfunc = testexpr + + if escape not in ESCAPE_SUPPORTED.values(): + raise ValueError("Unsupported 'escape'. (%s)" %(escape)) + self.escape = escape + self._includestack = [] + + def parse(self, template): + """Parse a template. + + :Parameters: + - `template`: template-unicode-string + :Returns: the resulting parse-tree + :Exceptions: + - `TemplateSyntaxError`: for template-syntax-errors + - `TemplateIncludeError`: if template-inclusion failed + - `TemplateException` + """ + self._includestack = [(None, template)] # for error-messages (_errpos) + return self._parse(template) + + def _errpos(self, fpos): + """Convert `fpos` to ``(filename,row,column)`` for error-messages.""" + filename, string = self._includestack[-1] + return filename, srow(string, fpos), scol(string, fpos) + + def _testexpr(self, expr, fpos=0): + """Test a template-expression to detect errors.""" + try: + self._testexprfunc(expr) + except SyntaxError as err: + raise TemplateSyntaxError(err, self._errpos(fpos)) + + def _parse_sub(self, parsetree, text, fpos=0): + """Parse substitutions, and append them to the parse-tree. + + Additionally, remove comments. + """ + curr = 0 + for match in self._reSubstitution.finditer(text): + start = match.start() + if start > curr: + parsetree.append(("str", self._reComment.sub('', text[curr:start]))) + + if match.group("sub") is not None: + if not match.group("end"): + raise TemplateSyntaxError("Missing closing tag '%s' for '%s'." + % (self._sub_end, match.group()), self._errpos(fpos+start)) + if len(match.group("sub")) > 0: + self._testexpr(match.group("sub"), fpos+start) + parsetree.append(("sub", match.group("sub"))) + else: + assert(match.group("escsub") is not None) + if not match.group("escend"): + raise TemplateSyntaxError("Missing closing tag '%s' for '%s'." + % (self._subesc_end, match.group()), self._errpos(fpos+start)) + if len(match.group("escsub")) > 0: + self._testexpr(match.group("escsub"), fpos+start) + parsetree.append(("esc", self.escape, match.group("escsub"))) + + curr = match.end() + + if len(text) > curr: + parsetree.append(("str", self._reComment.sub('', text[curr:]))) + + def _parse(self, template, fpos=0): + """Recursive part of `parse()`. + + :Parameters: + - template + - fpos: position of ``template`` in the complete template (for error-messages) + """ + # blank out comments + # (So that its content does not collide with other syntax, and + # because removing them completely would falsify the character- + # position ("match.start()") of error-messages) + template = self._reComment.sub(lambda match: self._comment_start+" "*len(match.group(1))+match.group(2), template) + + # init parser + parsetree = [] + curr = 0 # current position (= end of previous block) + block_type = None # block type: if,for,macro,raw,... + block_indent = None # None: single-line, >=0: multi-line + + # find blocks + for match in self._reBlock.finditer(template): + start = match.start() + # process template-part before this block + if start > curr: + self._parse_sub(parsetree, template[curr:start], fpos) + + # analyze block syntax (incl. error-checking and -messages) + keyword = None + block = match.groupdict() + pos__ = fpos + start # shortcut + if block["sKeyw"] is not None: # single-line block tag + block_indent = None + keyword = block["sKeyw"] + param = block["sParam"] + content = block["sContent"] + if block["sSpace"]: # restore spaces before start-tag + if len(parsetree) > 0 and parsetree[-1][0] == "str": + parsetree[-1] = ("str", parsetree[-1][1] + block["sSpace"]) + else: + parsetree.append(("str", block["sSpace"])) + pos_p = fpos + match.start("sParam") # shortcuts + pos_c = fpos + match.start("sContent") + elif block["mKeyw"] is not None: # multi-line block tag + block_indent = len(block["indent"]) + keyword = block["mKeyw"] + param = block["mParam"] + content = block["mContent"] + pos_p = fpos + match.start("mParam") + pos_c = fpos + match.start("mContent") + ignored = block["mIgnored"].strip() + if ignored and ignored != self._comment_start: + raise TemplateSyntaxError("No code allowed after block-tag.", self._errpos(fpos+match.start("mIgnored"))) + elif block["mEnd"] is not None: # multi-line block end + if block_type is None: + raise TemplateSyntaxError("No block to end here/invalid indent.", self._errpos(pos__) ) + if block_indent != len(block["mEnd"]): + raise TemplateSyntaxError("Invalid indent for end-tag.", self._errpos(pos__) ) + ignored = block["meIgnored"].strip() + if ignored and ignored != self._comment_start: + raise TemplateSyntaxError("No code allowed after end-tag.", self._errpos(fpos+match.start("meIgnored"))) + block_type = None + elif block["sEnd"] is not None: # single-line block end + if block_type is None: + raise TemplateSyntaxError("No block to end here/invalid indent.", self._errpos(pos__)) + if block_indent is not None: + raise TemplateSyntaxError("Invalid indent for end-tag.", self._errpos(pos__)) + block_type = None + else: + raise TemplateException("FATAL: Block regexp error. Please contact the author. (%s)" % match.group()) + + # analyze block content (mainly error-checking and -messages) + if keyword: + keyword = keyword.lower() + if 'for' == keyword: + if block_type is not None: + raise TemplateSyntaxError("Missing block-end-tag before new block at '%s'." %(match.group()), self._errpos(pos__)) + block_type = 'for' + cond = self._reForParam.match(param) + if cond is None: + raise TemplateSyntaxError("Invalid 'for ...' at '%s'." %(param), self._errpos(pos_p)) + names = tuple(n.strip() for n in cond.group("names").split(",")) + self._testexpr(cond.group("iter"), pos_p+cond.start("iter")) + parsetree.append(("for", names, cond.group("iter"), self._parse(content, pos_c))) + elif 'if' == keyword: + if block_type is not None: + raise TemplateSyntaxError("Missing block-end-tag before new block at '%s'." %(match.group()), self._errpos(pos__)) + if not param: + raise TemplateSyntaxError("Missing condition for 'if' at '%s'." %(match.group()), self._errpos(pos__)) + block_type = 'if' + self._testexpr(param, pos_p) + parsetree.append(("if", param, self._parse(content, pos_c))) + elif 'elif' == keyword: + if block_type != 'if': + raise TemplateSyntaxError("'elif' may only appear after 'if' at '%s'." %(match.group()), self._errpos(pos__)) + if not param: + raise TemplateSyntaxError("Missing condition for 'elif' at '%s'." %(match.group()), self._errpos(pos__)) + self._testexpr(param, pos_p) + parsetree.append(("elif", param, self._parse(content, pos_c))) + elif 'else' == keyword: + if block_type not in ('if', 'for'): + raise TemplateSyntaxError("'else' may only appear after 'if' or 'for' at '%s'." %(match.group()), self._errpos(pos__)) + if param: + raise TemplateSyntaxError("'else' may not have parameters at '%s'." %(match.group()), self._errpos(pos__)) + parsetree.append(("else", self._parse(content, pos_c))) + elif 'macro' == keyword: + if block_type is not None: + raise TemplateSyntaxError("Missing block-end-tag before new block '%s'." %(match.group()), self._errpos(pos__)) + block_type = 'macro' + # make sure param is "\w+" (instead of ".+") + if not param: + raise TemplateSyntaxError("Missing name for 'macro' at '%s'." %(match.group()), self._errpos(pos__)) + if not self._reMacroParam.match(param): + raise TemplateSyntaxError("Invalid name for 'macro' at '%s'." %(match.group()), self._errpos(pos__)) + #remove last newline + if len(content) > 0 and content[-1] == '\n': + content = content[:-1] + if len(content) > 0 and content[-1] == '\r': + content = content[:-1] + parsetree.append(("macro", param, self._parse(content, pos_c))) + + # parser-commands + elif 'raw' == keyword: + if block_type is not None: + raise TemplateSyntaxError("Missing block-end-tag before new block '%s'." %(match.group()), self._errpos(pos__)) + if param: + raise TemplateSyntaxError("'raw' may not have parameters at '%s'." %(match.group()), self._errpos(pos__)) + block_type = 'raw' + parsetree.append(("str", content)) + elif 'include' == keyword: + if block_type is not None: + raise TemplateSyntaxError("Missing block-end-tag before new block '%s'." %(match.group()), self._errpos(pos__)) + if param: + raise TemplateSyntaxError("'include' may not have parameters at '%s'." %(match.group()), self._errpos(pos__)) + block_type = 'include' + try: + u = self._load(content.strip()) + except Exception as err: + raise TemplateIncludeError(err, self._errpos(pos__)) + self._includestack.append((content.strip(), u)) # current filename/template for error-msg. + p = self._parse(u) + self._includestack.pop() + parsetree.extend(p) + elif 'set_escape' == keyword: + if block_type is not None: + raise TemplateSyntaxError("Missing block-end-tag before new block '%s'." %(match.group()), self._errpos(pos__)) + if param: + raise TemplateSyntaxError("'set_escape' may not have parameters at '%s'." %(match.group()), self._errpos(pos__)) + block_type = 'set_escape' + esc = content.strip().upper() + if esc not in ESCAPE_SUPPORTED: + raise TemplateSyntaxError("Unsupported escape '%s'." %(esc), self._errpos(pos__)) + self.escape = ESCAPE_SUPPORTED[esc] + else: + raise TemplateSyntaxError("Invalid keyword '%s'." %(keyword), self._errpos(pos__)) + curr = match.end() + + if block_type is not None: + raise TemplateSyntaxError("Missing end-tag.", self._errpos(pos__)) + + if len(template) > curr: # process template-part after last block + self._parse_sub(parsetree, template[curr:], fpos+curr) + + return parsetree + +#----------------------------------------- +# Evaluation + +# some checks +assert len(eval("dir()", {'__builtins__':{'dir':dir}})) == 1, \ + "FATAL: 'eval' does not work as expected (%s)." +assert compile("0 .__class__", "", "eval").co_names == ('__class__',), \ + "FATAL: 'compile' does not work as expected." + +class EvalPseudoSandbox: + """An eval-pseudo-sandbox. + + The pseudo-sandbox restricts the available functions/objects, so the + code can only access: + + - some of the builtin Python-functions, which are considered "safe" + (see safe_builtins) + - some additional functions (exists(), default(), setvar(), escape()) + - the passed objects incl. their methods. + + Additionally, names beginning with "_" are forbidden. + This is to prevent things like '0 .__class__', with which you could + easily break out of a "sandbox". + + Be careful to only pass "safe" objects/functions to the template, + because any unsafe function/method could break the sandbox! + For maximum security, restrict the access to as few objects/functions + as possible! + + :Warning: + Note that this is no real sandbox! (And although I don't know any + way to break out of the sandbox without passing-in an unsafe object, + I cannot guarantee that there is no such way. So use with care.) + + Take care if you want to use it for untrusted code!! + """ + + safe_builtins = { + "True" : True, + "False" : False, + "None" : None, + + "abs" : builtins.abs, + "chr" : builtins.chr, + "divmod" : builtins.divmod, + "hash" : builtins.hash, + "hex" : builtins.hex, + "isinstance": builtins.isinstance, + "len" : builtins.len, + "max" : builtins.max, + "min" : builtins.min, + "oct" : builtins.oct, + "ord" : builtins.ord, + "pow" : builtins.pow, + "range" : builtins.range, + "round" : builtins.round, + "sorted" : builtins.sorted, + "sum" : builtins.sum, + "unichr" : builtins.chr, + "zip" : builtins.zip, + + "bool" : builtins.bool, + "bytes" : builtins.bytes, + "complex" : builtins.complex, + "dict" : builtins.dict, + "enumerate" : builtins.enumerate, + "float" : builtins.float, + "int" : builtins.int, + "list" : builtins.list, + "long" : long, + "reversed" : builtins.reversed, + "set" : builtins.set, + "str" : builtins.str, + "tuple" : builtins.tuple, + "unicode" : unicode, + + "dir" : builtins.dir, + } + if sys.version_info[0] < 3: + safe_builtins["unichr"] = builtins.unichr + + def __init__(self): + self._compile_cache = {} + self.vars_ptr = None + self.eval_allowed_builtins = self.safe_builtins.copy() + self.register("__import__", self.f_import) + self.register("exists", self.f_exists) + self.register("default", self.f_default) + self.register("setvar", self.f_setvar) + self.register("escape", self.f_escape) + + def register(self, name, obj): + """Add an object to the "allowed eval-builtins". + + Mainly useful to add user-defined functions to the pseudo-sandbox. + """ + self.eval_allowed_builtins[name] = obj + + def _check_code_names(self, code, expr): + """Check if the code tries to access names beginning with "_". + + Used to prevent sandbox-breakouts via new-style-classes, like + ``"".__class__.__base__.__subclasses__()``. + + :Raises: + NameError if expression contains forbidden names. + """ + for name in code.co_names: + if name[0] == '_' and name != '_[1]': # _[1] is necessary for [x for x in y] + raise NameError("Name '%s' is not allowed in '%s'." % (name, expr)) + # recursively check sub-codes (e.g. lambdas) + for const in code.co_consts: + if isinstance(const, types.CodeType): + self._check_code_names(const, expr) + + def compile(self, expr): + """Compile a Python-eval-expression. + + - Use a compile-cache. + - Raise a `NameError` if `expr` contains a name beginning with ``_``. + + :Returns: the compiled `expr` + :Exceptions: + - `SyntaxError`: for compile-errors + - `NameError`: if expr contains a name beginning with ``_`` + """ + if expr not in self._compile_cache: + c = compile(expr, "", "eval") + self._check_code_names(c, expr) + self._compile_cache[expr] = c + return self._compile_cache[expr] + + def eval(self, expr, variables): + """Eval a Python-eval-expression. + + Sets ``self.vars_ptr`` to ``variables`` and compiles the code + before evaluating. + """ + sav = self.vars_ptr + self.vars_ptr = variables + + try: + x = eval(self.compile(expr), {"__builtins__": self.eval_allowed_builtins}, variables) + except NameError: + # workaround for lambdas like ``sorted(..., key=lambda x: my_f(x))`` + vars2 = {"__builtins__": self.eval_allowed_builtins} + vars2.update(variables) + x = eval(self.compile(expr), vars2) + + self.vars_ptr = sav + return x + + def f_import(self, name, *_, **__): + """``import``/``__import__()`` for the sandboxed code. + + Since "import" is insecure, the PseudoSandbox does not allow to + import other modules. But since some functions need to import + other modules (e.g. "datetime.datetime.strftime" imports "time"), + this function replaces the builtin "import" and allows to use + modules which are already accessible by the sandboxed code. + + :Note: + - This probably only works for rather simple imports. + - For security, it may be better to avoid such (complex) modules + which import other modules. (e.g. use time.localtime and + time.strftime instead of datetime.datetime.strftime, + or write a small wrapper.) + + :Example: + + >>> from datetime import datetime + >>> import pyratemp + >>> t = pyratemp.Template('@!mytime.strftime("%H:%M:%S")!@') + + # >>> print(t(mytime=datetime.now())) + # Traceback (most recent call last): + # ... + # ImportError: import not allowed in pseudo-sandbox; try to import 'time' yourself and pass it to the sandbox/template + + >>> import time + >>> print(t(mytime=datetime.strptime("13:40:54", "%H:%M:%S"), time=time)) + 13:40:54 + + # >>> print(t(mytime=datetime.now(), time=time)) + # 13:40:54 + """ + if self.vars_ptr is not None and name in self.vars_ptr and isinstance(self.vars_ptr[name], types.ModuleType): + return self.vars_ptr[name] + else: + raise ImportError("import not allowed in pseudo-sandbox; try to import '%s' yourself (and maybe pass it to the sandbox/template)" % name) + + def f_exists(self, varname): + """``exists()`` for the sandboxed code. + + Test if the variable `varname` exists in the current namespace. + + This only works for single variable names. If you want to test + complicated expressions, use i.e. `default`. + (i.e. `default("expr",False)`) + + :Note: the variable-name has to be quoted! (like in eval) + :Example: see module-docstring + """ + return (varname in self.vars_ptr) + + def f_default(self, expr, default=None): + """``default()`` for the sandboxed code. + + Try to evaluate an expression and return the result or a + fallback-/default-value; the `default`-value is used + if `expr` does not exist/is invalid/results in None. + + This is very useful for optional data. + + :Parameter: + - expr: "eval-expression" + - default: fallback-value if eval(expr) fails or is None. + :Returns: + the eval-result or the "fallback"-value. + + :Note: the eval-expression has to be quoted! (like in eval) + :Example: see module-docstring + """ + try: + r = self.eval(expr, self.vars_ptr) + if r is None: + return default + return r + #TODO: which exceptions should be catched here? + except (NameError, LookupError, TypeError, AttributeError): + return default + + def f_setvar(self, name, expr): + """``setvar()`` for the sandboxed code. + + Set a variable. + + :Example: see module-docstring + """ + self.vars_ptr[name] = self.eval(expr, self.vars_ptr) + return "" + + def f_escape(self, s, format="HTML"): + """``escape()`` for the sandboxed code. + """ + if isinstance(format, (str, unicode)): + format = ESCAPE_SUPPORTED[format.upper()] + return escape(unicode(s), format) + +#----------------------------------------- +# basic template / subtemplate + +class TemplateBase: + """Basic template-class. + + Used both for the template itself and for 'macro's ("subtemplates") in + the template. + """ + + def __init__(self, parsetree, renderfunc, data=None): + """Create the Template/Subtemplate/Macro. + + :Parameters: + - `parsetree`: parse-tree of the template/subtemplate/macro + - `renderfunc`: render-function + - `data`: data to fill into the template by default (dictionary). + This data may later be overridden when rendering the template. + :Exceptions: + - `TypeError`: if `data` is not a dictionary + """ + #TODO: parameter-checking? + self.parsetree = parsetree + if isinstance(data, dict): + self.data = data + elif data is None: + self.data = {} + else: + raise TypeError('"data" must be a dict (or None).') + self.current_data = data + self._render = renderfunc + + def __call__(self, **override): + """Fill out/render the template. + + :Parameters: + - `override`: objects to add to the data-namespace, overriding + the "default"-data. + :Returns: the filled template (in unicode) + :Note: This is also called when invoking macros + (i.e. ``$!mymacro()!$``). + """ + self.current_data = self.data.copy() + self.current_data.update(override) + u = "".join(self._render(self.parsetree, self.current_data)) + self.current_data = self.data # restore current_data + return _dontescape(u) # (see class _dontescape) + + def __unicode__(self): + """Alias for __call__().""" + return self.__call__() + def __str__(self): + """Alias for __call__().""" + return self.__call__() + +#----------------------------------------- +# Renderer + +class _dontescape(unicode): + """Unicode-string which should not be escaped. + + If ``isinstance(object,_dontescape)``, then don't escape the object in + ``@!...!@``. It's useful for not double-escaping macros, and it's + automatically used for macros/subtemplates. + + :Note: This only works if the object is used on its own in ``@!...!@``. + It i.e. does not work in ``@!object*2!@`` or ``@!object + "hi"!@``. + """ + __slots__ = [] + + +class Renderer(object): + """Render a template-parse-tree. + + :Uses: `TemplateBase` for macros + """ + + def __init__(self, evalfunc, escapefunc): + """Init the renderer. + + :Parameters: + - `evalfunc`: function for template-expression-evaluation + (i.e. ``EvalPseudoSandbox().eval``) + - `escapefunc`: function for escaping special characters + (i.e. `escape`) + """ + #TODO: test evalfunc + self.evalfunc = evalfunc + self.escapefunc = escapefunc + + def _eval(self, expr, data): + """evalfunc with error-messages""" + try: + return self.evalfunc(expr, data) + #TODO: any other errors to catch here? + except (TypeError, NameError, LookupError, AttributeError, SyntaxError) as err: + raise TemplateRenderError("Cannot eval expression '%s'. (%s: %s)" %(expr, err.__class__.__name__, err)) + + def render(self, parsetree, data): + """Render a parse-tree of a template. + + :Parameters: + - `parsetree`: the parse-tree + - `data`: the data to fill into the template (dictionary) + :Returns: the rendered output-unicode-string + :Exceptions: + - `TemplateRenderError` + """ + _eval = self._eval # shortcut + output = [] + do_else = False # use else/elif-branch? + + if parsetree is None: + return "" + for elem in parsetree: + if "str" == elem[0]: + output.append(elem[1]) + elif "sub" == elem[0]: + output.append(unicode(_eval(elem[1], data))) + elif "esc" == elem[0]: + obj = _eval(elem[2], data) + #prevent double-escape + if isinstance(obj, _dontescape) or isinstance(obj, TemplateBase): + output.append(unicode(obj)) + else: + output.append(self.escapefunc(unicode(obj), elem[1])) + elif "for" == elem[0]: + do_else = True + (names, iterable) = elem[1:3] + try: + loop_iter = iter(_eval(iterable, data)) + except TypeError: + raise TemplateRenderError("Cannot loop over '%s'." % iterable) + for i in loop_iter: + do_else = False + if len(names) == 1: + data[names[0]] = i + else: + data.update(zip(names, i)) #"for a,b,.. in list" + output.extend(self.render(elem[3], data)) + elif "if" == elem[0]: + do_else = True + if _eval(elem[1], data): + do_else = False + output.extend(self.render(elem[2], data)) + elif "elif" == elem[0]: + if do_else and _eval(elem[1], data): + do_else = False + output.extend(self.render(elem[2], data)) + elif "else" == elem[0]: + if do_else: + do_else = False + output.extend(self.render(elem[1], data)) + elif "macro" == elem[0]: + data[elem[1]] = TemplateBase(elem[2], self.render, data) + else: + raise TemplateRenderError("Invalid parse-tree (%s)." %(elem)) + + return output + +#----------------------------------------- +# template user-interface (putting it all together) + +class Template(TemplateBase): + """Template-User-Interface. + + :Usage: + :: + t = Template(...) (<- see __init__) + output = t(...) (<- see TemplateBase.__call__) + + :Example: + see module-docstring + """ + + def __init__(self, string=None,filename=None,parsetree=None, encoding='utf-8', data=None, escape=HTML, + loader_class=LoaderFile, + parser_class=Parser, + renderer_class=Renderer, + eval_class=EvalPseudoSandbox, + escape_func=escape): + """Load (+parse) a template. + + :Parameters: + - `string,filename,parsetree`: a template-string, + filename of a template to load, + or a template-parsetree. + (only one of these 3 is allowed) + - `encoding`: encoding of the template-files (only used for "filename") + - `data`: data to fill into the template by default (dictionary). + This data may later be overridden when rendering the template. + - `escape`: default-escaping for the template, may be overwritten by the template! + - `loader_class` + - `parser_class` + - `renderer_class` + - `eval_class` + - `escapefunc` + """ + if [string, filename, parsetree].count(None) != 2: + raise ValueError('Exactly 1 of string,filename,parsetree is necessary.') + + tmpl = None + # load template + if filename is not None: + incl_load = loader_class(os.path.dirname(filename), encoding).load + tmpl = incl_load(os.path.basename(filename)) + if string is not None: + incl_load = dummy_raise(NotImplementedError, "'include' not supported for template-strings.") + tmpl = LoaderString(encoding).load(string) + + # eval (incl. compile-cache) + templateeval = eval_class() + + # parse + if tmpl is not None: + p = parser_class(loadfunc=incl_load, testexpr=templateeval.compile, escape=escape) + parsetree = p.parse(tmpl) + del p + + # renderer + renderfunc = renderer_class(templateeval.eval, escape_func).render + + #create template + TemplateBase.__init__(self, parsetree, renderfunc, data) + + +#========================================= diff --git a/dsdl_compiler/libcanard_dsdlc b/dsdl_compiler/libcanard_dsdlc new file mode 100755 index 00000000..5e46e443 --- /dev/null +++ b/dsdl_compiler/libcanard_dsdlc @@ -0,0 +1,68 @@ +#!/usr/bin/env python +# +# UAVCAN DSDL compiler for libcanard +# Supported Python versions: 3.2+, 2.7. +# +# This code is written by Pavel Kirienko for libuavcan DSDL generator +# copied and modified for the libcanard use +# +# Copyright (C) 2014 Pavel Kirienko +# Copyright (C) 2018 Intel Corporation +# + +from __future__ import division, absolute_import, print_function, unicode_literals +import os, sys, logging, argparse + +# This trickery allows to use the compiler even if pyuavcan is not installed in the system. +# This is extremely important, as it makes the compiler (and therefore libcanard in general) +# totally dependency-free, except for the Python interpreter itself. +SCRIPT_DIR = os.path.dirname(os.path.abspath(__file__)) +LOCAL_PYUAVCAN_DIR = os.path.join(SCRIPT_DIR, 'pyuavcan') +RUNNING_FROM_SRC_DIR = os.path.isdir(LOCAL_PYUAVCAN_DIR) +if RUNNING_FROM_SRC_DIR: + sys.path.insert(0, SCRIPT_DIR) + sys.path.insert(0, LOCAL_PYUAVCAN_DIR) + +def configure_logging(verbosity): + fmt = '%(message)s' + level = { 0: logging.WARNING, 1: logging.INFO, 2: logging.DEBUG }.get(verbosity or 0, logging.DEBUG) + logging.basicConfig(stream=sys.stderr, level=level, format=fmt) + +def die(text): + print(text, file=sys.stderr) + exit(1) + +DEFAULT_OUTDIR = 'dsdlc_generated' + +DESCRIPTION = '''UAVCAN DSDL compiler for the libcanard. +Takes an input directory/directories that contains an hierarchy of DSDL +definitions and converts it into C header and source files for the libcanard. +This script can be used directly from the source directory, no installation required! +Supported Python versions: 3.2+, 2.7. +''' + +argparser = argparse.ArgumentParser(description=DESCRIPTION) +argparser.add_argument('source_dir', nargs='+', help='source directory with DSDL definitions') +argparser.add_argument('--verbose', '-v', action='count', help='verbosity level (-v, -vv)') +argparser.add_argument('--outdir', '-O', default=DEFAULT_OUTDIR, help='output directory, default %s' % DEFAULT_OUTDIR) +argparser.add_argument('--incdir', '-I', default=[], action='append', help= +'''nested type namespaces, one path per argument. Can be also specified through the environment variable +UAVCAN_DSDL_INCLUDE_PATH, where the path entries are separated by colons ":"''') +args = argparser.parse_args() + +configure_logging(args.verbose) + +try: + extra_incdir = os.environ['UAVCAN_DSDL_INCLUDE_PATH'].split(':') + logging.info('Additional include directories: %s', extra_incdir) + args.incdir += extra_incdir +except KeyError: + pass + +from libcanard_dsdl_compiler import run as dsdlc_run + +try: + dsdlc_run(args.source_dir, args.incdir, args.outdir) +except Exception as ex: + logging.error('Compiler failure', exc_info=True) + die(str(ex)) diff --git a/dsdl_compiler/pyuavcan b/dsdl_compiler/pyuavcan new file mode 160000 index 00000000..7a149d6b --- /dev/null +++ b/dsdl_compiler/pyuavcan @@ -0,0 +1 @@ +Subproject commit 7a149d6b106cf6ec6c170acf93f5bfd1ce88d779 From 66856787aebe8841c8de04004c8cb94bfe920339 Mon Sep 17 00:00:00 2001 From: "Torola, Sami" Date: Tue, 3 Jul 2018 15:21:15 +0300 Subject: [PATCH 30/81] Code review changes - FLOAT16 define changed to CANARD_FLOAT16 - Monolith typo fixed to monotonic - Using ```cpp in code sections - Encode and Decode API split to two. One without offset & root_item and _internal API which has those. - memset (for) added to Decode functions to clear struct before decode - SATURATE changed to c-files not to export those outside - canardDecodeScalar return values checked and carried out of Decode functions - Assert added to union checking - Zubax coding style changes Fixed TODO - Dynamic array len size was fixed to uint8_t which may not be always enough. Array max size is checked and uint16_t used if needed. TODO - TAO - Object name conflict --- dsdl_compiler/README.md | 26 +-- .../libcanard_dsdl_compiler/__init__.py | 3 +- .../code_type_template.tmpl | 214 +++++++++++++----- .../data_type_template.tmpl | 54 +++-- 4 files changed, 203 insertions(+), 94 deletions(-) diff --git a/dsdl_compiler/README.md b/dsdl_compiler/README.md index fdc87d67..d2b4f438 100644 --- a/dsdl_compiler/README.md +++ b/dsdl_compiler/README.md @@ -17,7 +17,7 @@ To get libcanard from the git, make sure all the submodules are fetched too. NOTE: If python2 is used, monotonic library is needed. -`pip install monolith` +`pip install monotonic` ### Using generated c-modules Include all or only selected message c-files to your compiler script (e.g. Makefile). Add include path to root of the . @@ -25,19 +25,18 @@ Include all or only selected message c-files to your compiler script (e.g. Makef NOTE: compiled *.o files can't be compiled into to flat "build" directory as some files in DSDL have the same name. ### Float16 -Generated structs in modules use float16 type when so specified in DSDL. -In c-modules float16 is defined as uint16_t which can be overridden by defining FLOAT16 to something else e.g. __fp16. +Generated structs in modules use canard_float16 type when specified float16 in DSDL. Canard_float16 has to be defined as CANARD_FLOAT16 to something e.g. __fp16. e.g. in Makefile ` -CFLAGS += -DFLOAT16=__fp16 +CFLAGS += -DCANARD_FLOAT16=__fp16 ` ## Using generated modules #### Encode NodeStatus-broadcast message -``` +```cpp #include "uavcan/protocol/NodeStatus.h" /* Reserve memory and struct for messages */ @@ -47,14 +46,14 @@ CFLAGS += -DFLOAT16=__fp16 msg.uptime_sec = GetUptime(); - msg.health = HEALTH_OK; - msg.mode = MODE_OPERATIONAL; + msg.health = UAVCAN_PROTOCOL_NODESTATUS_HEALTH_OK; + msg.mode = UAVCAN_PROTOCOL_NODESTATUS_MODE_OPERATIONAL; msg.sub_mode = sub_mode; msg.vendor_specific_status_code = vendor_status_code; /* Encode filled struct to packed_uavcan_msg_buf, ready to be send */ - uint32_t len_of_packed_msg = uavcan_protocol_NodeStatusEncode(&msg, packed_uavcan_msg_buf, 0, 1); + uint32_t len_of_packed_msg = uavcan_protocol_NodeStatusEncode(&msg, packed_uavcan_msg_buf); canardBroadcast(&g_canard, UAVCAN_PROTOCOL_NODESTATUS_SIGNATURE, @@ -65,12 +64,11 @@ CFLAGS += -DFLOAT16=__fp16 len_of_packed_msg); ``` -All the *Encode calls need to have offset given as 0 and root item as 1 as parameters. This is needed, as the generated code may use offset and root item info in following *Encode calls. *Dynamic Array* all the dynamic arrays have also _len field, which contain the info of how many data items have been stored in to dynamic array pointer. #### Decode GetSet-request -``` +```cpp /* include header */ #include "uavcan/protocol/param/GetSet.h" @@ -82,15 +80,11 @@ All the *Encode calls need to have offset given as 0 and root item as 1 as param /* Reserve struct */ uavcan_protocol_param_GetSetRequest get_set_req; - /* Clearing the struct is necessary! Decoding does not guarantee - clearing all the bytes in fields in struct. */ - memset(&get_set_req, 0x00, sizeof(uavcan_protocol_param_GetSetRequest)); - + /* NOTE get_set_req struct will be cleared in Decode function first */ uavcan_protocol_param_GetSetRequestDecode(transfer, (uint16_t)transfer->payload_len, &get_set_req, - &dyn_buf_ptr, - 0); + &dyn_buf_ptr); /* Now struct get_set_req "object" is ready to be used */ ``` diff --git a/dsdl_compiler/libcanard_dsdl_compiler/__init__.py b/dsdl_compiler/libcanard_dsdl_compiler/__init__.py index 50ad6543..49264c4c 100644 --- a/dsdl_compiler/libcanard_dsdl_compiler/__init__.py +++ b/dsdl_compiler/libcanard_dsdl_compiler/__init__.py @@ -181,7 +181,7 @@ def type_to_c_type(t): }[t.cast_mode] if t.kind == t.KIND_FLOAT: float_type = { - 16: 'float16', + 16: 'canard_float16', 32: 'float', 64: 'double', }[t.bitlen] @@ -241,6 +241,7 @@ def type_to_c_type(t): 'signedness':values['signedness'], 'saturate':values['saturate'], 'dynamic_array': t.mode == t.MODE_DYNAMIC, + 'max_array_elements': t.max_size, } elif t.category == t.CATEGORY_COMPOUND: return { diff --git a/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl b/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl index 39442108..b023ed84 100644 --- a/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl +++ b/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl @@ -9,28 +9,50 @@ #include "${t.header_filename}" #include "canard.h" +#ifndef SATURATE +#define SATURATE(x, max) ( ((x) > max) ? max : ( (-(x) > max) ? (-max) : (x) ) ); +#endif + #! type_name, service, max_bitlen, fields, constants, union, has_array %if max_bitlen + /** * @brief ${type_name}Encode * @param source : Pointer to source data struct * @param msg_buf: Pointer to msg storage - * @param offset: Call with 0, bit offset to msg storage - * @param root_item: Call with 1, this for internal use - * @retval returns message length as bytes (when root_item == 1) + * @retval returns message length as bytes + */ +uint32_t ${type_name}Encode(${type_name} *source, void *msg_buf) +{ + uint32_t offset = 0; + + offset = ${type_name}Encode_internal(source, msg_buf, offset, 1); + + return (offset + 7 ) / 8; +} + +/** + * @brief ${type_name}Encode_internal + * @details [long description] + * @param source : pointer to source data struct + * @param msg_buf: pointer to msg storage + * @param offset: bit offset to msg storage + * @param root_item: for detecting if TAO should be used + * @retval returns offset */ -uint32_t ${type_name}Encode(${type_name} *source, void *msg_buf, uint32_t offset, uint8_t root_item) { +uint32_t ${type_name}Encode_internal(${type_name} *source, void *msg_buf, uint32_t offset, uint8_t root_item) +{ %if union - /* Max Union Tag Value */ - //assert(source->union_tag > ${(len(fields) - 1)}); + // Max Union Tag Value + CANARD_ASSERT(source->union_tag <= ${(len(fields) - 1)}); %endif %if has_array: uint32_t c = 0; %endif %if union: - /* Union Tag ${union} bits */ + // Union Tag ${union} bits canardEncodeScalar(msg_buf, offset, ${union}, (void*)&source->union_tag); // ${union} bits offset += ${union}; $!setvar("union_index", "0")!$ @@ -44,37 +66,40 @@ uint32_t ${type_name}Encode(${type_name} *source, void *msg_buf, uint32_t offset %if f.type_category == t.CATEGORY_ARRAY %if f.dynamic_array == True - /* Dynamic Array (${f.name})*/ + // Dynamic Array (${f.name}) %if f.last_item %if f.bitlen < 8 ${f.array_max_size_bit_len} - /* - Add array length, last item, but bitlen < 8. */ + // - Add array length, last item, but bitlen < 8. canardEncodeScalar(msg_buf, offset, ${f.array_max_size_bit_len}, (void*)&source->${'%s' % ((f.name + '_len'))}); offset += ${f.array_max_size_bit_len}; %else - if (! root_item) { - /* - Add array length */ + if (! root_item) + { + // - Add array length canardEncodeScalar(msg_buf, offset, ${f.array_max_size_bit_len}, (void*)&source->${'%s' % ((f.name + '_len'))}); offset += ${f.array_max_size_bit_len}; } %endif %else - /* - Add array length */ + // - Add array length canardEncodeScalar(msg_buf, offset, ${f.array_max_size_bit_len}, (void*)&source->${'%s' % ((f.name + '_len'))}); offset += ${f.array_max_size_bit_len}; %endif - /* - Add array items */ - for (c = 0; c < source->${'%s' % ((f.name + '_len'))}; c++) { + // - Add array items + for (c = 0; c < source->${'%s' % ((f.name + '_len'))}; c++) + { %if f.cpp_type_category == t.CATEGORY_COMPOUND: - offset += ${f.cpp_type}Encode((void*)&source->${f.name}[c], msg_buf, offset, 0); + offset += ${f.cpp_type}Encode_internal((void*)&source->${f.name}[c], msg_buf, offset, 0); %else canardEncodeScalar(msg_buf, offset, ${f.bitlen}, (void*)(source->${f.name} + c)); // ${f.max_size} offset += ${f.bitlen}; %endif } %else - /* Static array (${f.name}) */ - for (c = 0; c < ${f.array_size}; c++) { + // Static array (${f.name}) + for (c = 0; c < ${f.array_size}; c++) + { canardEncodeScalar(msg_buf, offset, ${f.bitlen}, (void*)(source->${f.name} + c)); // ${f.max_size} offset += ${f.bitlen}; } @@ -82,12 +107,12 @@ uint32_t ${type_name}Encode(${type_name} *source, void *msg_buf, uint32_t offset %elif f.type_category == t.CATEGORY_VOID: - /* Void${f.bitlen} */ + // Void${f.bitlen} offset += ${f.bitlen}; %elif f.type_category == t.CATEGORY_COMPOUND: - /* Compound */ - offset = ${f.cpp_type}Encode((void*)&source->${f.name}, msg_buf, offset, 0); + // Compound + offset = ${f.cpp_type}Encode_internal((void*)&source->${f.name}, msg_buf, offset, 0); %else %if f.saturate source->${f.name} = SATURATE(source->${f.name}, ${f.max_size}) @@ -100,9 +125,6 @@ uint32_t ${type_name}Encode(${type_name} *source, void *msg_buf, uint32_t offset } %endif % endfor - if (root_item) { - return (offset + 7 ) / 8; - } return offset; } @@ -115,60 +137,107 @@ uint32_t ${type_name}Encode(${type_name} *source, void *msg_buf, uint32_t offset * @param dyn_arr_buf: NULL or Pointer to memory storage to be used for dynamic arrays * ${type_name} dyn memory will point to dyn_arr_buf memory. * NULL will ignore dynamic arrays decoding. + * @retval offset or ERROR value if < 0 + */ +int32_t ${type_name}Decode(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name} *dest, uint8_t **dyn_arr_buf) +{ + for (uint32_t c = 0; c < sizeof(${type_name}); c++) + { + ((uint8_t*)dest)[c] = 0x00; + } + return ${type_name}Decode_internal(transfer, payload_len, dest, dyn_arr_buf, 0); +} + +/** + * @brief ${type_name}Decode_internal + * @param transfer: Pointer to CanardRxTransfer transfer + * @param payload_len: Payload message length + * @param dest: Pointer to destination struct + * @param dyn_arr_buf: NULL or Pointer to memory storage to be used for dynamic arrays + * ${type_name} dyn memory will point to dyn_arr_buf memory. + * NULL will ignore dynamic arrays decoding. * @param offset: Call with 0, bit offset to msg storage - * @retval + * @retval offset or ERROR value if < 0 */ -uint32_t ${type_name}Decode(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name} *dest, uint8_t **dyn_arr_buf, uint32_t offset) { +int32_t ${type_name}Decode_internal(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name} *dest, uint8_t **dyn_arr_buf, int32_t offset) +{ + int32_t ret = 0; %if has_array uint32_t c = 0; %endif %if union: - /* Get Union Tag */ - canardDecodeScalar(transfer, offset, ${union}, false, (void*)&dest->union_tag); // ${union} + // Get Union Tag + ret = canardDecodeScalar(transfer, offset, ${union}, false, (void*)&dest->union_tag); // ${union} + if (ret != ${union}) + { + goto ${type_name}_error_exit; + } offset += ${union}; $!setvar("union_index", "0")!$ %endif % for f in fields: %if union: - ${'if' if not union_index else 'else if'} (dest->union_tag == ${union_index}) { + ${'if' if not union_index else 'else if'} (dest->union_tag == ${union_index}) + { $!setvar("union_index", "union_index + 1")!$ %endif %if f.type_category == t.CATEGORY_ARRAY %if f.dynamic_array == True - /* Dynamic Array (${f.name})*/ + // Dynamic Array (${f.name}) %if f.last_item %if f.bitlen > 7 - /* - Last item in struct & Root item & (Array Size > 8 bit), tail array optimization */ - if (payload_len) { - /* - Calculate Array length from MSG length */ + // - Last item in struct & Root item & (Array Size > 8 bit), tail array optimization + if (payload_len) + { + // - Calculate Array length from MSG length dest->${'%s' % ((f.name + '_len'))} = ((payload_len * 8) - offset ) / ${f.bitlen}; // ${f.bitlen} bit array item size - } else { - /* - Array length ${f.array_max_size_bit_len} bits */ - canardDecodeScalar(transfer, offset, ${f.array_max_size_bit_len}, false, (void*)&dest->${'%s' % ((f.name + '_len'))}); // ${f.max_size} + } else + { + // - Array length ${f.array_max_size_bit_len} bits + ret = canardDecodeScalar(transfer, offset, ${f.array_max_size_bit_len}, false, (void*)&dest->${'%s' % ((f.name + '_len'))}); // ${f.max_size} + if (ret != ${f.array_max_size_bit_len}) + { + goto ${type_name}_error_exit; + } offset += ${f.array_max_size_bit_len}; } %else - canardDecodeScalar(transfer, offset, ${f.array_max_size_bit_len}, false, (void*)&dest->${'%s' % ((f.name + '_len'))}); // ${f.max_size} + ret = canardDecodeScalar(transfer, offset, ${f.array_max_size_bit_len}, false, (void*)&dest->${'%s' % ((f.name + '_len'))}); // ${f.max_size} + if (ret != ${f.array_max_size_bit_len}) + { + goto ${type_name}_error_exit; + } offset += ${f.array_max_size_bit_len}; %endif %else - /* - Array length, not last item ${f.array_max_size_bit_len} bits*/ - canardDecodeScalar(transfer, offset, ${f.array_max_size_bit_len}, false, (void*)&dest->${'%s' % ((f.name + '_len'))}); // ${f.max_size} + // - Array length, not last item ${f.array_max_size_bit_len} bits + ret = canardDecodeScalar(transfer, offset, ${f.array_max_size_bit_len}, false, (void*)&dest->${'%s' % ((f.name + '_len'))}); // ${f.max_size} + if (ret != ${f.array_max_size_bit_len}) + { + goto ${type_name}_error_exit; + } offset += ${f.array_max_size_bit_len}; %endif - /* - Get Array */ - if (dyn_arr_buf) { + // - Get Array + if (dyn_arr_buf) + { dest->${f.name} = (${f.cpp_type}*)*dyn_arr_buf; } - for (c = 0; c < dest->${'%s' % ((f.name + '_len'))}; c++) { + for (c = 0; c < dest->${'%s' % ((f.name + '_len'))}; c++) + { %if f.cpp_type_category == t.CATEGORY_COMPOUND: - offset += ${f.cpp_type}Decode(transfer, 0, (void*)&dest->${f.name}[c], dyn_arr_buf, offset); + offset += ${f.cpp_type}Decode_internal(transfer, 0, (void*)&dest->${f.name}[c], dyn_arr_buf, offset); %else - if (dyn_arr_buf) { - canardDecodeScalar(transfer, offset, ${f.bitlen}, ${f.signedness}, (void*)*dyn_arr_buf); // ${f.max_size} + if (dyn_arr_buf) + { + ret = canardDecodeScalar(transfer, offset, ${f.bitlen}, ${f.signedness}, (void*)*dyn_arr_buf); // ${f.max_size} + if (ret != ${f.bitlen}) + { + goto ${type_name}_error_exit; + } *dyn_arr_buf = (uint8_t *)(((${f.cpp_type}*)*dyn_arr_buf) + 1); } offset += ${f.bitlen}; @@ -176,23 +245,37 @@ uint32_t ${type_name}Decode(const CanardRxTransfer* transfer, uint16_t payload_l } %else - /* Static array (${f.name}) */ - for (c = 0; c < ${f.array_size}; c++) { - canardDecodeScalar(transfer, offset, ${f.bitlen}, ${f.signedness}, (void*)(dest->${f.name} + c)); + // Static array (${f.name}) + for (c = 0; c < ${f.array_size}; c++) + { + ret = canardDecodeScalar(transfer, offset, ${f.bitlen}, ${f.signedness}, (void*)(dest->${f.name} + c)); + if (ret != ${f.bitlen}) + { + goto ${type_name}_error_exit; + } offset += ${f.bitlen}; } %endif %elif f.type_category == t.CATEGORY_VOID: - /* Void${f.bitlen} */ + // Void${f.bitlen} offset += ${f.bitlen}; %elif f.type_category == t.CATEGORY_COMPOUND: - /* Compound */ - offset = ${f.cpp_type}Decode(transfer, 0, (void*)&dest->${f.name}, dyn_arr_buf, offset); + // Compound + offset = ${f.cpp_type}Decode_internal(transfer, 0, (void*)&dest->${f.name}, dyn_arr_buf, offset); + if (offset < 0) + { + ret = offset; + goto ${type_name}_error_exit; + } %else - canardDecodeScalar(transfer, offset, ${f.bitlen}, ${f.signedness}, (void*)&dest->${f.name}); + ret = canardDecodeScalar(transfer, offset, ${f.bitlen}, ${f.signedness}, (void*)&dest->${f.name}); + if (ret != ${f.bitlen}) + { + goto ${type_name}_error_exit; + } offset += ${f.bitlen}; %endif %if union: @@ -200,15 +283,34 @@ uint32_t ${type_name}Decode(const CanardRxTransfer* transfer, uint16_t payload_l %endif % endfor return offset; + +${type_name}_error_exit: + if (ret < 0) + { + return ret; + } else + { + return -CANARD_ERROR_INTERNAL; + } } %else -uint32_t ${type_name}Encode(${type_name} *source, void *msg_buf, uint32_t offset, uint8_t root_item) { - if (root_item) { - return (offset + 7 ) / 8; - } +uint32_t ${type_name}Encode(${type_name} *source, void *msg_buf) +{ + return 0; +} + +uint32_t ${type_name}Encode_internal(${type_name} *source, void *msg_buf, uint32_t offset, uint8_t root_item) +{ return offset; } -uint32_t ${type_name}Decode(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name} *dest, uint8_t **dyn_arr_buf, uint32_t offset) { + +int32_t ${type_name}Decode(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name} *dest, uint8_t **dyn_arr_buf) +{ + return 0; +} + +int32_t ${type_name}Decode_internal(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name} *dest, uint8_t **dyn_arr_buf, int32_t offset) +{ return offset; } %endif diff --git a/dsdl_compiler/libcanard_dsdl_compiler/data_type_template.tmpl b/dsdl_compiler/libcanard_dsdl_compiler/data_type_template.tmpl index 7d7192b8..a7b361e6 100644 --- a/dsdl_compiler/libcanard_dsdl_compiler/data_type_template.tmpl +++ b/dsdl_compiler/libcanard_dsdl_compiler/data_type_template.tmpl @@ -12,18 +12,15 @@ #include #include "canard.h" -#ifndef FLOAT16 -typedef uint16_t float16; +#ifndef CANARD_FLOAT16 +#error "Please define CANARD_FLOAT16 to a relevant implementation for your platform, e.g. float or __fp16. See README.md for details" #else -typedef FLOAT16 float16; -#endif - -#ifndef SATURATE -#define SATURATE(x, max) ( ((x) > max) ? max : ( (-(x) > max) ? (-max) : (x) ) ); +typedef CANARD_FLOAT16 canard_float16; #endif #ifdef __cplusplus -extern "C" { +extern "C" +{ #endif % for inc in t.cpp_includes: @@ -60,33 +57,41 @@ ${line} % endfor %if union -typedef enum { +typedef enum +{ % for idx,last,a in enum_last_value(fields): ${type_name.upper()}_${a.name.upper()}${',' if not last else ''} % endfor } ${type_name}_ENUM; %endif -typedef struct { +typedef struct +{ %if union: ${type_name}_ENUM union_tag; // union_tag indicates what field the data structure is holding - union { + union + { %endif #! group_name, attrs - /* ${group_name} */ + // ${group_name} % for a in attrs: %if a.type_category == t.CATEGORY_ARRAY %if a.dynamic_array == True - struct { - ${'uint8_t %-26s // %s' % ((a.name + '_len;'), 'TODO what size this should be?' )} + struct + { + %if a.max_array_elements > 255 + ${'uint16_t %-26s // %s' % ((a.name + '_len;'), 'Dynamic array length')} + %else + ${'uint8_t %-26s // %s' % ((a.name + '_len;'), 'Dynamic array length')} + %endif ${'%-10s %-26s // %s' % (a.cpp_type, ('*' + a.name + ';'), a.cpp_type_comment, )} }; %else ${'%-10s %-30s // %s' % (a.cpp_type, (a.name + a.post_cpp_type + ';'), a.cpp_type_comment, )} %endif %elif a.type_category == t.CATEGORY_VOID: - /* ${a.cpp_type_comment} */ + // ${a.cpp_type_comment} %else ${'%-10s %-30s // %s' % (a.cpp_type, (a.name + a.post_cpp_type + ';'), a.cpp_type_comment, )} %endif @@ -98,15 +103,22 @@ typedef struct { %endif } ${type_name}; -extern uint32_t ${type_name}Encode(${type_name} *source, void *msg_buf, uint32_t offset, uint8_t root_item); -extern uint32_t ${type_name}Decode(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name} *dest, uint8_t **dyn_arr_buf, uint32_t offset); + +extern uint32_t ${type_name}Encode(${type_name} *source, void *msg_buf); +extern int32_t ${type_name}Decode(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name} *dest, uint8_t **dyn_arr_buf); + +extern uint32_t ${type_name}Encode_internal(${type_name} *source, void *msg_buf, uint32_t offset, uint8_t root_item); +extern int32_t ${type_name}Decode_internal(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name} *dest, uint8_t **dyn_arr_buf, int32_t offset); %else -typedef struct { +typedef struct +{ uint8_t empty; } ${type_name}; - extern uint32_t ${type_name}Encode(${type_name} *source, void *msg_buf, uint32_t offset, uint8_t root_item); - extern uint32_t ${type_name}Decode(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name} *dest, uint8_t **dyn_arr_buf, uint32_t offset); +extern uint32_t ${type_name}Encode(${type_name} *source, void *msg_buf); +extern int32_t ${type_name}Decode(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name} *dest, uint8_t **dyn_arr_buf); +extern uint32_t ${type_name}Encode_internal(${type_name} *source, void *msg_buf, uint32_t offset, uint8_t root_item); +extern int32_t ${type_name}Decode_internal(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name} *dest, uint8_t **dyn_arr_buf, int32_t offset); %endif @@ -123,6 +135,6 @@ ${generate_primary_body(type_name=t.name_space_type_name, service='', max_bitlen fields=t.fields, constants=t.constants, union=t.union, has_array=t.has_array)} % endif #ifdef __cplusplus -} /* extern "C" */ +} // extern "C" #endif #endif // ${t.include_guard} From 92778394f232feb8990ef26764eac24608de1567 Mon Sep 17 00:00:00 2001 From: "Torola, Sami" Date: Tue, 3 Jul 2018 18:23:44 +0300 Subject: [PATCH 31/81] Review changes part 3, TAO removal support - Decode function is now be backward compatible with future TAO removal - 1st messages decode is tried with TAO disabled - if failed 2nd round TAO enabled. --- .../code_type_template.tmpl | 51 +++++++++++++++---- .../data_type_template.tmpl | 4 +- 2 files changed, 44 insertions(+), 11 deletions(-) diff --git a/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl b/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl index b023ed84..9a8bbc67 100644 --- a/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl +++ b/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl @@ -13,6 +13,9 @@ #define SATURATE(x, max) ( ((x) > max) ? max : ( (-(x) > max) ? (-max) : (x) ) ); #endif +#define ENABLE_TAO ((uint8_t) 1) +#define DISABLE_TAO ((uint8_t) 0) + #! type_name, service, max_bitlen, fields, constants, union, has_array %if max_bitlen @@ -34,7 +37,6 @@ uint32_t ${type_name}Encode(${type_name} *source, void *msg_buf) /** * @brief ${type_name}Encode_internal - * @details [long description] * @param source : pointer to source data struct * @param msg_buf: pointer to msg storage * @param offset: bit offset to msg storage @@ -86,6 +88,7 @@ uint32_t ${type_name}Encode_internal(${type_name} *source, void *msg_buf, uint32 canardEncodeScalar(msg_buf, offset, ${f.array_max_size_bit_len}, (void*)&source->${'%s' % ((f.name + '_len'))}); offset += ${f.array_max_size_bit_len}; %endif + // - Add array items for (c = 0; c < source->${'%s' % ((f.name + '_len'))}; c++) { @@ -141,11 +144,38 @@ uint32_t ${type_name}Encode_internal(${type_name} *source, void *msg_buf, uint32 */ int32_t ${type_name}Decode(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name} *dest, uint8_t **dyn_arr_buf) { - for (uint32_t c = 0; c < sizeof(${type_name}); c++) + const int32_t offset = 0; + int32_t ret = 0; + + /* Backward compatibility support for removing TAO + * - first try to decode with TAO DISABLED + * - if it fails fall back to TAO ENABLED + */ + uint8_t tao = DISABLE_TAO; + + while (1) { - ((uint8_t*)dest)[c] = 0x00; + // Clear the destination struct + for (uint32_t c = 0; c < sizeof(${type_name}); c++) + { + ((uint8_t*)dest)[c] = 0x00; + } + + ret = ${type_name}Decode_internal(transfer, payload_len, dest, dyn_arr_buf, offset, tao); + + if (ret >= 0) + { + break; + } + + if (tao == ENABLE_TAO) + { + break; + } + tao = ENABLE_TAO; } - return ${type_name}Decode_internal(transfer, payload_len, dest, dyn_arr_buf, 0); + + return ret; } /** @@ -157,9 +187,10 @@ int32_t ${type_name}Decode(const CanardRxTransfer* transfer, uint16_t payload_le * ${type_name} dyn memory will point to dyn_arr_buf memory. * NULL will ignore dynamic arrays decoding. * @param offset: Call with 0, bit offset to msg storage + * @param tao: is tail array optimization used * @retval offset or ERROR value if < 0 */ -int32_t ${type_name}Decode_internal(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name} *dest, uint8_t **dyn_arr_buf, int32_t offset) +int32_t ${type_name}Decode_internal(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name} *dest, uint8_t **dyn_arr_buf, int32_t offset, uint8_t tao) { int32_t ret = 0; %if has_array @@ -190,7 +221,7 @@ int32_t ${type_name}Decode_internal(const CanardRxTransfer* transfer, uint16_t p %if f.last_item %if f.bitlen > 7 // - Last item in struct & Root item & (Array Size > 8 bit), tail array optimization - if (payload_len) + if (payload_len && tao == ENABLE_TAO) { // - Calculate Array length from MSG length dest->${'%s' % ((f.name + '_len'))} = ((payload_len * 8) - offset ) / ${f.bitlen}; // ${f.bitlen} bit array item size @@ -221,15 +252,17 @@ int32_t ${type_name}Decode_internal(const CanardRxTransfer* transfer, uint16_t p } offset += ${f.array_max_size_bit_len}; %endif + // - Get Array if (dyn_arr_buf) { dest->${f.name} = (${f.cpp_type}*)*dyn_arr_buf; } + for (c = 0; c < dest->${'%s' % ((f.name + '_len'))}; c++) { %if f.cpp_type_category == t.CATEGORY_COMPOUND: - offset += ${f.cpp_type}Decode_internal(transfer, 0, (void*)&dest->${f.name}[c], dyn_arr_buf, offset); + offset += ${f.cpp_type}Decode_internal(transfer, 0, (void*)&dest->${f.name}[c], dyn_arr_buf, offset, tao); %else if (dyn_arr_buf) { @@ -263,7 +296,7 @@ int32_t ${type_name}Decode_internal(const CanardRxTransfer* transfer, uint16_t p %elif f.type_category == t.CATEGORY_COMPOUND: // Compound - offset = ${f.cpp_type}Decode_internal(transfer, 0, (void*)&dest->${f.name}, dyn_arr_buf, offset); + offset = ${f.cpp_type}Decode_internal(transfer, 0, (void*)&dest->${f.name}, dyn_arr_buf, offset, tao); if (offset < 0) { ret = offset; @@ -309,7 +342,7 @@ int32_t ${type_name}Decode(const CanardRxTransfer* transfer, uint16_t payload_le return 0; } -int32_t ${type_name}Decode_internal(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name} *dest, uint8_t **dyn_arr_buf, int32_t offset) +int32_t ${type_name}Decode_internal(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name} *dest, uint8_t **dyn_arr_buf, int32_t offset, uint8_t tao) { return offset; } diff --git a/dsdl_compiler/libcanard_dsdl_compiler/data_type_template.tmpl b/dsdl_compiler/libcanard_dsdl_compiler/data_type_template.tmpl index a7b361e6..dea094c3 100644 --- a/dsdl_compiler/libcanard_dsdl_compiler/data_type_template.tmpl +++ b/dsdl_compiler/libcanard_dsdl_compiler/data_type_template.tmpl @@ -108,7 +108,7 @@ extern uint32_t ${type_name}Encode(${type_name} *source, void *msg_buf); extern int32_t ${type_name}Decode(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name} *dest, uint8_t **dyn_arr_buf); extern uint32_t ${type_name}Encode_internal(${type_name} *source, void *msg_buf, uint32_t offset, uint8_t root_item); -extern int32_t ${type_name}Decode_internal(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name} *dest, uint8_t **dyn_arr_buf, int32_t offset); +extern int32_t ${type_name}Decode_internal(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name} *dest, uint8_t **dyn_arr_buf, int32_t offset, uint8_t use_tao); %else typedef struct { @@ -118,7 +118,7 @@ typedef struct extern uint32_t ${type_name}Encode(${type_name} *source, void *msg_buf); extern int32_t ${type_name}Decode(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name} *dest, uint8_t **dyn_arr_buf); extern uint32_t ${type_name}Encode_internal(${type_name} *source, void *msg_buf, uint32_t offset, uint8_t root_item); -extern int32_t ${type_name}Decode_internal(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name} *dest, uint8_t **dyn_arr_buf, int32_t offset); +extern int32_t ${type_name}Decode_internal(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name} *dest, uint8_t **dyn_arr_buf, int32_t offset, uint8_t use_tao); %endif From d260757eacf1d01e0cc6f31469efa9ae0cbc1f06 Mon Sep 17 00:00:00 2001 From: "Torola, Sami" Date: Thu, 5 Jul 2018 13:37:13 +0300 Subject: [PATCH 32/81] Review changes 4, changed float strategy - Float16 will be promoted to float32 in structs and just converted to float16 before encoding or decoding back to float32 after receiving. --- dsdl_compiler/README.md | 9 +--- .../libcanard_dsdl_compiler/__init__.py | 12 ++++- .../code_type_template.tmpl | 50 +++++++++++++++++-- .../data_type_template.tmpl | 6 --- 4 files changed, 59 insertions(+), 18 deletions(-) diff --git a/dsdl_compiler/README.md b/dsdl_compiler/README.md index d2b4f438..8fed7212 100644 --- a/dsdl_compiler/README.md +++ b/dsdl_compiler/README.md @@ -25,13 +25,8 @@ Include all or only selected message c-files to your compiler script (e.g. Makef NOTE: compiled *.o files can't be compiled into to flat "build" directory as some files in DSDL have the same name. ### Float16 -Generated structs in modules use canard_float16 type when specified float16 in DSDL. Canard_float16 has to be defined as CANARD_FLOAT16 to something e.g. __fp16. - -e.g. in Makefile - -` -CFLAGS += -DCANARD_FLOAT16=__fp16 -` +Generated structs in modules use float type when specified float16 in DSDL. Float is converted to float16 using libcanard's canardConvertNativeFloatToFloat16 when Encoding. Calling Decode function after receive will convert float16 to float, using libcanard's canardConvertFloat16ToNativeFloat function. +Canard conversion functions can be replaced to compiler casting if wanted, e.g. #define CANARD_USE_FLOAT16_CAST e.g. __fp16. ## Using generated modules diff --git a/dsdl_compiler/libcanard_dsdl_compiler/__init__.py b/dsdl_compiler/libcanard_dsdl_compiler/__init__.py index 49264c4c..4428086d 100644 --- a/dsdl_compiler/libcanard_dsdl_compiler/__init__.py +++ b/dsdl_compiler/libcanard_dsdl_compiler/__init__.py @@ -181,7 +181,7 @@ def type_to_c_type(t): }[t.cast_mode] if t.kind == t.KIND_FLOAT: float_type = { - 16: 'canard_float16', + 16: 'float', 32: 'float', 64: 'double', }[t.bitlen] @@ -312,8 +312,16 @@ def inject_cpp_types(attributes): a.name = '' return has_array + def has_float16(attributes): + has_float16 = False + for a in attributes: + if a.type.category == t.CATEGORY_PRIMITIVE and a.type.kind == a.type.KIND_FLOAT and a.bitlen == 16: + has_float16 = True + return has_float16 + if t.kind == t.KIND_MESSAGE: t.has_array = inject_cpp_types(t.fields) + t.has_float16 = has_float16(t.fields) inject_cpp_types(t.constants) t.all_attributes = t.fields + t.constants t.union = t.union and len(t.fields) @@ -321,8 +329,10 @@ def inject_cpp_types(attributes): t.union = len(t.fields).bit_length() else: t.request_has_array = inject_cpp_types(t.request_fields) + t.request_has_float16 = has_float16(t.request_fields) inject_cpp_types(t.request_constants) t.response_has_array = inject_cpp_types(t.response_fields) + t.response_has_float16 = has_float16(t.response_fields) inject_cpp_types(t.response_constants) t.all_attributes = t.request_fields + t.request_constants + t.response_fields + t.response_constants t.request_union = t.request_union and len(t.request_fields) diff --git a/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl b/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl index 9a8bbc67..12562f4e 100644 --- a/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl +++ b/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl @@ -16,7 +16,7 @@ #define ENABLE_TAO ((uint8_t) 1) #define DISABLE_TAO ((uint8_t) 0) - #! type_name, service, max_bitlen, fields, constants, union, has_array + #! type_name, service, max_bitlen, fields, constants, union, has_array, has_float16 %if max_bitlen @@ -52,6 +52,13 @@ uint32_t ${type_name}Encode_internal(${type_name} *source, void *msg_buf, uint32 %if has_array: uint32_t c = 0; %endif + %if has_float16: +#ifndef CANARD_USE_FLOAT16_CAST + uint16_t tmp_float = 0; +#else + CANARD_USE_FLOAT16_CAST tmp_float = 0; +#endif + %endif %if union: // Union Tag ${union} bits @@ -116,6 +123,16 @@ uint32_t ${type_name}Encode_internal(${type_name} *source, void *msg_buf, uint32 // Compound offset = ${f.cpp_type}Encode_internal((void*)&source->${f.name}, msg_buf, offset, 0); + %elif f.type_category == t.CATEGORY_PRIMITIVE and f.cpp_type == "float" and f.bitlen == 16: + + // float16 special handling +#ifndef CANARD_USE_FLOAT16_CAST + tmp_float = canardConvertNativeFloatToFloat16(source->${f.name}); +#else + tmp_float = (CANARD_USE_FLOAT16_CAST)source->${f.name}; +#endif + canardEncodeScalar(msg_buf, offset, ${f.bitlen}, (void*)&tmp_float); // ${f.max_size} + offset += ${f.bitlen}; %else %if f.saturate source->${f.name} = SATURATE(source->${f.name}, ${f.max_size}) @@ -196,6 +213,13 @@ int32_t ${type_name}Decode_internal(const CanardRxTransfer* transfer, uint16_t p %if has_array uint32_t c = 0; %endif + %if has_float16: +#ifndef CANARD_USE_FLOAT16_CAST + uint16_t tmp_float = 0; +#else + CANARD_USE_FLOAT16_CAST tmp_float = 0; +#endif + %endif %if union: // Get Union Tag @@ -302,6 +326,21 @@ int32_t ${type_name}Decode_internal(const CanardRxTransfer* transfer, uint16_t p ret = offset; goto ${type_name}_error_exit; } + %elif f.type_category == t.CATEGORY_PRIMITIVE and f.cpp_type == "float" and f.bitlen == 16: + + // float16 special handling + ret = canardDecodeScalar(transfer, offset, ${f.bitlen}, ${f.signedness}, (void*)&tmp_float); + + if (ret != ${f.bitlen}) + { + goto ${type_name}_error_exit; + } +#ifndef CANARD_USE_FLOAT16_CAST + dest->${f.name} = canardConvertFloat16ToNativeFloat(tmp_float); +#else + dest->${f.name} = (float)tmp_float; +#endif + offset += ${f.bitlen}; %else ret = canardDecodeScalar(transfer, offset, ${f.bitlen}, ${f.signedness}, (void*)&dest->${f.name}); @@ -352,12 +391,15 @@ int32_t ${type_name}Decode_internal(const CanardRxTransfer* transfer, uint16_t p % if t.kind == t.KIND_SERVICE: ${generate_primary_body(type_name=t.name_space_type_name+'Request', service='_REQUEST', max_bitlen=t.get_max_bitlen_request(), \ fields=t.request_fields, constants=t.request_constants, \ - union=t.request_union, has_array=t.request_has_array)} + union=t.request_union, has_array=t.request_has_array, \ + has_float16=t.request_has_float16)} ${generate_primary_body(type_name=t.name_space_type_name+'Response', service='_RESPONSE', max_bitlen=t.get_max_bitlen_response(), \ fields=t.response_fields, constants=t.response_constants, \ - union=t.response_union, has_array=t.response_has_array)} + union=t.response_union, has_array=t.response_has_array, \ + has_float16=t.response_has_float16)} % else: ${generate_primary_body(type_name=t.name_space_type_name, service='', max_bitlen=t.get_max_bitlen(), \ - fields=t.fields, constants=t.constants, union=t.union, has_array=t.has_array)} + fields=t.fields, constants=t.constants, union=t.union, has_array=t.has_array, \ + has_float16=t.has_float16)} % endif diff --git a/dsdl_compiler/libcanard_dsdl_compiler/data_type_template.tmpl b/dsdl_compiler/libcanard_dsdl_compiler/data_type_template.tmpl index dea094c3..bf32b861 100644 --- a/dsdl_compiler/libcanard_dsdl_compiler/data_type_template.tmpl +++ b/dsdl_compiler/libcanard_dsdl_compiler/data_type_template.tmpl @@ -12,12 +12,6 @@ #include #include "canard.h" -#ifndef CANARD_FLOAT16 -#error "Please define CANARD_FLOAT16 to a relevant implementation for your platform, e.g. float or __fp16. See README.md for details" -#else -typedef CANARD_FLOAT16 canard_float16; -#endif - #ifdef __cplusplus extern "C" { From efd6308c89c1f05745eb500455cdb0c447a54b52 Mon Sep 17 00:00:00 2001 From: "Torola, Sami" Date: Thu, 5 Jul 2018 13:48:38 +0300 Subject: [PATCH 33/81] Review changes: Changed API names -Changed API names from Encode and Decode to _encode and _decode. --- .../code_type_template.tmpl | 36 +++++++++---------- .../data_type_template.tmpl | 16 ++++----- 2 files changed, 26 insertions(+), 26 deletions(-) diff --git a/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl b/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl index 12562f4e..22cbd18f 100644 --- a/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl +++ b/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl @@ -21,29 +21,29 @@ %if max_bitlen /** - * @brief ${type_name}Encode + * @brief ${type_name}_encode * @param source : Pointer to source data struct * @param msg_buf: Pointer to msg storage * @retval returns message length as bytes */ -uint32_t ${type_name}Encode(${type_name} *source, void *msg_buf) +uint32_t ${type_name}_encode(${type_name} *source, void *msg_buf) { uint32_t offset = 0; - offset = ${type_name}Encode_internal(source, msg_buf, offset, 1); + offset = ${type_name}_encode_internal(source, msg_buf, offset, 1); return (offset + 7 ) / 8; } /** - * @brief ${type_name}Encode_internal + * @brief ${type_name}_encode_internal * @param source : pointer to source data struct * @param msg_buf: pointer to msg storage * @param offset: bit offset to msg storage * @param root_item: for detecting if TAO should be used * @retval returns offset */ -uint32_t ${type_name}Encode_internal(${type_name} *source, void *msg_buf, uint32_t offset, uint8_t root_item) +uint32_t ${type_name}_encode_internal(${type_name} *source, void *msg_buf, uint32_t offset, uint8_t root_item) { %if union // Max Union Tag Value @@ -100,7 +100,7 @@ uint32_t ${type_name}Encode_internal(${type_name} *source, void *msg_buf, uint32 for (c = 0; c < source->${'%s' % ((f.name + '_len'))}; c++) { %if f.cpp_type_category == t.CATEGORY_COMPOUND: - offset += ${f.cpp_type}Encode_internal((void*)&source->${f.name}[c], msg_buf, offset, 0); + offset += ${f.cpp_type}_encode_internal((void*)&source->${f.name}[c], msg_buf, offset, 0); %else canardEncodeScalar(msg_buf, offset, ${f.bitlen}, (void*)(source->${f.name} + c)); // ${f.max_size} offset += ${f.bitlen}; @@ -122,7 +122,7 @@ uint32_t ${type_name}Encode_internal(${type_name} *source, void *msg_buf, uint32 %elif f.type_category == t.CATEGORY_COMPOUND: // Compound - offset = ${f.cpp_type}Encode_internal((void*)&source->${f.name}, msg_buf, offset, 0); + offset = ${f.cpp_type}_encode_internal((void*)&source->${f.name}, msg_buf, offset, 0); %elif f.type_category == t.CATEGORY_PRIMITIVE and f.cpp_type == "float" and f.bitlen == 16: // float16 special handling @@ -150,7 +150,7 @@ uint32_t ${type_name}Encode_internal(${type_name} *source, void *msg_buf, uint32 } /** - * @brief ${type_name}Decode + * @brief ${type_name}_decode * @param transfer: Pointer to CanardRxTransfer transfer * @param payload_len: Payload message length * @param dest: Pointer to destination struct @@ -159,7 +159,7 @@ uint32_t ${type_name}Encode_internal(${type_name} *source, void *msg_buf, uint32 * NULL will ignore dynamic arrays decoding. * @retval offset or ERROR value if < 0 */ -int32_t ${type_name}Decode(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name} *dest, uint8_t **dyn_arr_buf) +int32_t ${type_name}_decode(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name} *dest, uint8_t **dyn_arr_buf) { const int32_t offset = 0; int32_t ret = 0; @@ -178,7 +178,7 @@ int32_t ${type_name}Decode(const CanardRxTransfer* transfer, uint16_t payload_le ((uint8_t*)dest)[c] = 0x00; } - ret = ${type_name}Decode_internal(transfer, payload_len, dest, dyn_arr_buf, offset, tao); + ret = ${type_name}_decode_internal(transfer, payload_len, dest, dyn_arr_buf, offset, tao); if (ret >= 0) { @@ -196,7 +196,7 @@ int32_t ${type_name}Decode(const CanardRxTransfer* transfer, uint16_t payload_le } /** - * @brief ${type_name}Decode_internal + * @brief ${type_name}_decode_internal * @param transfer: Pointer to CanardRxTransfer transfer * @param payload_len: Payload message length * @param dest: Pointer to destination struct @@ -207,7 +207,7 @@ int32_t ${type_name}Decode(const CanardRxTransfer* transfer, uint16_t payload_le * @param tao: is tail array optimization used * @retval offset or ERROR value if < 0 */ -int32_t ${type_name}Decode_internal(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name} *dest, uint8_t **dyn_arr_buf, int32_t offset, uint8_t tao) +int32_t ${type_name}_decode_internal(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name} *dest, uint8_t **dyn_arr_buf, int32_t offset, uint8_t tao) { int32_t ret = 0; %if has_array @@ -286,7 +286,7 @@ int32_t ${type_name}Decode_internal(const CanardRxTransfer* transfer, uint16_t p for (c = 0; c < dest->${'%s' % ((f.name + '_len'))}; c++) { %if f.cpp_type_category == t.CATEGORY_COMPOUND: - offset += ${f.cpp_type}Decode_internal(transfer, 0, (void*)&dest->${f.name}[c], dyn_arr_buf, offset, tao); + offset += ${f.cpp_type}_decode_internal(transfer, 0, (void*)&dest->${f.name}[c], dyn_arr_buf, offset, tao); %else if (dyn_arr_buf) { @@ -320,7 +320,7 @@ int32_t ${type_name}Decode_internal(const CanardRxTransfer* transfer, uint16_t p %elif f.type_category == t.CATEGORY_COMPOUND: // Compound - offset = ${f.cpp_type}Decode_internal(transfer, 0, (void*)&dest->${f.name}, dyn_arr_buf, offset, tao); + offset = ${f.cpp_type}_decode_internal(transfer, 0, (void*)&dest->${f.name}, dyn_arr_buf, offset, tao); if (offset < 0) { ret = offset; @@ -366,22 +366,22 @@ ${type_name}_error_exit: } } %else -uint32_t ${type_name}Encode(${type_name} *source, void *msg_buf) +uint32_t ${type_name}_encode(${type_name} *source, void *msg_buf) { return 0; } -uint32_t ${type_name}Encode_internal(${type_name} *source, void *msg_buf, uint32_t offset, uint8_t root_item) +uint32_t ${type_name}_encode_internal(${type_name} *source, void *msg_buf, uint32_t offset, uint8_t root_item) { return offset; } -int32_t ${type_name}Decode(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name} *dest, uint8_t **dyn_arr_buf) +int32_t ${type_name}_decode(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name} *dest, uint8_t **dyn_arr_buf) { return 0; } -int32_t ${type_name}Decode_internal(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name} *dest, uint8_t **dyn_arr_buf, int32_t offset, uint8_t tao) +int32_t ${type_name}_decode_internal(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name} *dest, uint8_t **dyn_arr_buf, int32_t offset, uint8_t tao) { return offset; } diff --git a/dsdl_compiler/libcanard_dsdl_compiler/data_type_template.tmpl b/dsdl_compiler/libcanard_dsdl_compiler/data_type_template.tmpl index bf32b861..72abc3a2 100644 --- a/dsdl_compiler/libcanard_dsdl_compiler/data_type_template.tmpl +++ b/dsdl_compiler/libcanard_dsdl_compiler/data_type_template.tmpl @@ -98,21 +98,21 @@ typedef struct } ${type_name}; -extern uint32_t ${type_name}Encode(${type_name} *source, void *msg_buf); -extern int32_t ${type_name}Decode(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name} *dest, uint8_t **dyn_arr_buf); +extern uint32_t ${type_name}_encode(${type_name} *source, void *msg_buf); +extern int32_t ${type_name}_decode(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name} *dest, uint8_t **dyn_arr_buf); -extern uint32_t ${type_name}Encode_internal(${type_name} *source, void *msg_buf, uint32_t offset, uint8_t root_item); -extern int32_t ${type_name}Decode_internal(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name} *dest, uint8_t **dyn_arr_buf, int32_t offset, uint8_t use_tao); +extern uint32_t ${type_name}_encode_internal(${type_name} *source, void *msg_buf, uint32_t offset, uint8_t root_item); +extern int32_t ${type_name}_decode_internal(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name} *dest, uint8_t **dyn_arr_buf, int32_t offset, uint8_t tao); %else typedef struct { uint8_t empty; } ${type_name}; -extern uint32_t ${type_name}Encode(${type_name} *source, void *msg_buf); -extern int32_t ${type_name}Decode(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name} *dest, uint8_t **dyn_arr_buf); -extern uint32_t ${type_name}Encode_internal(${type_name} *source, void *msg_buf, uint32_t offset, uint8_t root_item); -extern int32_t ${type_name}Decode_internal(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name} *dest, uint8_t **dyn_arr_buf, int32_t offset, uint8_t use_tao); +extern uint32_t ${type_name}_encode(${type_name} *source, void *msg_buf); +extern int32_t ${type_name}_decode(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name} *dest, uint8_t **dyn_arr_buf); +extern uint32_t ${type_name}_encode_internal(${type_name} *source, void *msg_buf, uint32_t offset, uint8_t root_item); +extern int32_t ${type_name}_decode_internal(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name} *dest, uint8_t **dyn_arr_buf, int32_t offset, uint8_t tao); %endif From 1a8e2c87f6058e8263f25af02901e9d167a81404 Mon Sep 17 00:00:00 2001 From: "Torola, Sami" Date: Thu, 5 Jul 2018 14:48:08 +0300 Subject: [PATCH 34/81] Review proposal: c-file naming -C-files have not folder_ before their real name to make them unique. --- dsdl_compiler/libcanard_dsdl_compiler/__init__.py | 9 ++++++++- 1 file changed, 8 insertions(+), 1 deletion(-) diff --git a/dsdl_compiler/libcanard_dsdl_compiler/__init__.py b/dsdl_compiler/libcanard_dsdl_compiler/__init__.py index 4428086d..7c3c5430 100644 --- a/dsdl_compiler/libcanard_dsdl_compiler/__init__.py +++ b/dsdl_compiler/libcanard_dsdl_compiler/__init__.py @@ -83,7 +83,14 @@ def get_name_space_prefix(t): def type_output_filename(t, extension = OUTPUT_HEADER_FILE_EXTENSION): assert t.category == t.CATEGORY_COMPOUND - return t.full_name.replace('.', os.path.sep) + '.' + extension + folder_name = t.full_name.split('.')[-2] + if extension == OUTPUT_CODE_FILE_EXTENSION: + name_list = t.full_name.split('.') + if len(folder_name): + name_list[-1] = str(folder_name) + '_' + str(name_list[-1]) + return os.path.sep.join(name_list) + '.' + extension + else: + return t.full_name.replace('.', os.path.sep) + '.' + extension def makedirs(path): try: From c3822b37d4dcd690d4d85fe5330b0880c9b9f57c Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Sun, 19 Aug 2018 11:27:52 +0300 Subject: [PATCH 35/81] STM32 driver README update The driver is tested against STM32F446 --- drivers/stm32/README.md | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/drivers/stm32/README.md b/drivers/stm32/README.md index 8cde50e8..685cfa0c 100644 --- a/drivers/stm32/README.md +++ b/drivers/stm32/README.md @@ -7,9 +7,10 @@ and can be used with virtually any operating system or on bare metal In theory, the entire family of STM32 should be supported by this driver, since they all share the same CAN controller IP known as bxCAN. -So far this driver has been tested with the following MCU: +So far this driver has been tested at least with the following MCU: * STM32F105 - both CAN1 and CAN2 +* STM32F446 * Please extend this list if you used it with other MCU. ## Features From c50dcebb03d6080aa0ea83ce4ac9162d30de4e1c Mon Sep 17 00:00:00 2001 From: "Torola, Sami" Date: Mon, 24 Sep 2018 15:56:39 +0300 Subject: [PATCH 36/81] Added support for generating header only library. When using libcanard_dsdlc generator with --header_only flag it will generate header only version from the UAVCAN message library. --- .../libcanard_dsdl_compiler/__init__.py | 47 +++---- .../code_type_template.tmpl | 127 +++++++++--------- .../data_type_template.tmpl | 28 ++-- dsdl_compiler/libcanard_dsdlc | 3 +- 4 files changed, 112 insertions(+), 93 deletions(-) diff --git a/dsdl_compiler/libcanard_dsdl_compiler/__init__.py b/dsdl_compiler/libcanard_dsdl_compiler/__init__.py index 7c3c5430..9b661280 100644 --- a/dsdl_compiler/libcanard_dsdl_compiler/__init__.py +++ b/dsdl_compiler/libcanard_dsdl_compiler/__init__.py @@ -39,7 +39,7 @@ class DsdlCompilerException(Exception): logger = logging.getLogger(__name__) -def run(source_dirs, include_dirs, output_dir): +def run(source_dirs, include_dirs, output_dir, header_only): ''' This function takes a list of root namespace directories (containing DSDL definition files to parse), a possibly empty list of search directories (containing DSDL definition files that can be referenced from the types @@ -55,6 +55,7 @@ def run(source_dirs, include_dirs, output_dir): include_dirs List of root namespace directories with referenced types (possibly empty). This list is automaitcally extended with source_dirs. output_dir Output directory path. Will be created if doesn't exist. + header_only Weather to generated as header only library. ''' assert isinstance(source_dirs, list) assert isinstance(include_dirs, list) @@ -65,7 +66,7 @@ def run(source_dirs, include_dirs, output_dir): die('No type definitions were found') logger.info('%d types total', len(types)) - run_generator(types, output_dir) + run_generator(types, output_dir, header_only) # ----------------- @@ -113,7 +114,7 @@ def run_parser(source_dirs, search_dirs): die(ex) return types -def run_generator(types, dest_dir): +def run_generator(types, dest_dir, header_only): try: header_template_expander = make_template_expander(HEADER_TEMPLATE_FILENAME) code_template_expander = make_template_expander(CODE_TEMPLATE_FILENAME) @@ -125,37 +126,37 @@ def run_generator(types, dest_dir): code_filename = os.path.join(dest_dir, type_output_filename(t, OUTPUT_CODE_FILE_EXTENSION)) t.header_filename = type_output_filename(t, OUTPUT_HEADER_FILE_EXTENSION) t.name_space_prefix = get_name_space_prefix(t) + t.header_only = header_only header_text = generate_one_type(header_template_expander, t) code_text = generate_one_type(code_template_expander, t) - write_generated_data(header_path_file_name, header_text) - write_generated_data(code_filename, code_text) + write_generated_data(header_path_file_name, header_text, header_only) + if header_only: + code_text = "\r\n" + code_text + write_generated_data(header_path_file_name, code_text, header_only, True) + else: + write_generated_data(code_filename, code_text, header_only) except Exception as ex: logger.info('Generator failure', exc_info=True) die(ex) -def write_generated_data(filename, data): +def write_generated_data(filename, data, header_only, append_file=False): dirname = os.path.dirname(filename) makedirs(dirname) - # Lazy update - file will not be rewritten if its content is not going to change - if os.path.exists(filename): - with open(filename) as f: - existing_data = f.read() - if data == existing_data: - logger.info('Up to date [%s]', pretty_filename(filename)) - return - logger.info('Rewriting [%s]', pretty_filename(filename)) - os.remove(filename) + if append_file: + with open(filename, 'a') as f: + f.write(data) else: - logger.info('Creating [%s]', pretty_filename(filename)) + if os.path.exists(filename): + os.remove(filename) + with open(filename, 'w') as f: + f.write(data) - # Full rewrite - with open(filename, 'w') as f: - f.write(data) - try: - os.chmod(filename, OUTPUT_FILE_PERMISSIONS) - except (OSError, IOError) as ex: - logger.warning('Failed to set permissions for %s: %s', pretty_filename(filename), ex) + if not header_only or header_only and append_file: + try: + os.chmod(filename, OUTPUT_FILE_PERMISSIONS) + except (OSError, IOError) as ex: + logger.warning('Failed to set permissions for %s: %s', pretty_filename(filename), ex) def expand_to_next_full(size): if size <= 8: diff --git a/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl b/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl index 22cbd18f..b2858227 100644 --- a/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl +++ b/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl @@ -5,9 +5,10 @@ * * Source file: ${t.source_file} */ - +%if not t.header_only #include "${t.header_filename}" #include "canard.h" +%endif #ifndef SATURATE #define SATURATE(x, max) ( ((x) > max) ? max : ( (-(x) > max) ? (-max) : (x) ) ); @@ -20,21 +21,6 @@ %if max_bitlen -/** - * @brief ${type_name}_encode - * @param source : Pointer to source data struct - * @param msg_buf: Pointer to msg storage - * @retval returns message length as bytes - */ -uint32_t ${type_name}_encode(${type_name} *source, void *msg_buf) -{ - uint32_t offset = 0; - - offset = ${type_name}_encode_internal(source, msg_buf, offset, 1); - - return (offset + 7 ) / 8; -} - /** * @brief ${type_name}_encode_internal * @param source : pointer to source data struct @@ -150,49 +136,18 @@ uint32_t ${type_name}_encode_internal(${type_name} *source, void *msg_buf, uint3 } /** - * @brief ${type_name}_decode - * @param transfer: Pointer to CanardRxTransfer transfer - * @param payload_len: Payload message length - * @param dest: Pointer to destination struct - * @param dyn_arr_buf: NULL or Pointer to memory storage to be used for dynamic arrays - * ${type_name} dyn memory will point to dyn_arr_buf memory. - * NULL will ignore dynamic arrays decoding. - * @retval offset or ERROR value if < 0 + * @brief ${type_name}_encode + * @param source : Pointer to source data struct + * @param msg_buf: Pointer to msg storage + * @retval returns message length as bytes */ -int32_t ${type_name}_decode(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name} *dest, uint8_t **dyn_arr_buf) +uint32_t ${type_name}_encode(${type_name} *source, void *msg_buf) { - const int32_t offset = 0; - int32_t ret = 0; - - /* Backward compatibility support for removing TAO - * - first try to decode with TAO DISABLED - * - if it fails fall back to TAO ENABLED - */ - uint8_t tao = DISABLE_TAO; - - while (1) - { - // Clear the destination struct - for (uint32_t c = 0; c < sizeof(${type_name}); c++) - { - ((uint8_t*)dest)[c] = 0x00; - } - - ret = ${type_name}_decode_internal(transfer, payload_len, dest, dyn_arr_buf, offset, tao); - - if (ret >= 0) - { - break; - } + uint32_t offset = 0; - if (tao == ENABLE_TAO) - { - break; - } - tao = ENABLE_TAO; - } + offset = ${type_name}_encode_internal(source, msg_buf, offset, 1); - return ret; + return (offset + 7 ) / 8; } /** @@ -365,18 +320,59 @@ ${type_name}_error_exit: return -CANARD_ERROR_INTERNAL; } } - %else -uint32_t ${type_name}_encode(${type_name} *source, void *msg_buf) + +/** + * @brief ${type_name}_decode + * @param transfer: Pointer to CanardRxTransfer transfer + * @param payload_len: Payload message length + * @param dest: Pointer to destination struct + * @param dyn_arr_buf: NULL or Pointer to memory storage to be used for dynamic arrays + * ${type_name} dyn memory will point to dyn_arr_buf memory. + * NULL will ignore dynamic arrays decoding. + * @retval offset or ERROR value if < 0 + */ +int32_t ${type_name}_decode(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name} *dest, uint8_t **dyn_arr_buf) { - return 0; -} + const int32_t offset = 0; + int32_t ret = 0; + + /* Backward compatibility support for removing TAO + * - first try to decode with TAO DISABLED + * - if it fails fall back to TAO ENABLED + */ + uint8_t tao = DISABLE_TAO; + + while (1) + { + // Clear the destination struct + for (uint32_t c = 0; c < sizeof(${type_name}); c++) + { + ((uint8_t*)dest)[c] = 0x00; + } + + ret = ${type_name}_decode_internal(transfer, payload_len, dest, dyn_arr_buf, offset, tao); + + if (ret >= 0) + { + break; + } + + if (tao == ENABLE_TAO) + { + break; + } + tao = ENABLE_TAO; + } + return ret; +} + %else uint32_t ${type_name}_encode_internal(${type_name} *source, void *msg_buf, uint32_t offset, uint8_t root_item) { return offset; } -int32_t ${type_name}_decode(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name} *dest, uint8_t **dyn_arr_buf) +uint32_t ${type_name}_encode(${type_name} *source, void *msg_buf) { return 0; } @@ -385,6 +381,11 @@ int32_t ${type_name}_decode_internal(const CanardRxTransfer* transfer, uint16_t { return offset; } + +int32_t ${type_name}_decode(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name} *dest, uint8_t **dyn_arr_buf) +{ + return 0; +} %endif @@ -403,3 +404,9 @@ ${generate_primary_body(type_name=t.name_space_type_name, service='', max_bitlen fields=t.fields, constants=t.constants, union=t.union, has_array=t.has_array, \ has_float16=t.has_float16)} % endif +%if t.header_only +#ifdef __cplusplus +} // extern "C" +#endif +#endif // ${t.include_guard} +%endif \ No newline at end of file diff --git a/dsdl_compiler/libcanard_dsdl_compiler/data_type_template.tmpl b/dsdl_compiler/libcanard_dsdl_compiler/data_type_template.tmpl index 72abc3a2..3a2a5d4c 100644 --- a/dsdl_compiler/libcanard_dsdl_compiler/data_type_template.tmpl +++ b/dsdl_compiler/libcanard_dsdl_compiler/data_type_template.tmpl @@ -21,6 +21,15 @@ extern "C" #include <${inc}> % endfor + + + %if t.header_only +static inline + %else +extern + %endif + + /******************************* Source text ********************************** % for line in t.source_text.strip().splitlines(): ${line} @@ -97,22 +106,21 @@ typedef struct %endif } ${type_name}; +@!storage_class!@uint32_t ${type_name}_encode(${type_name} *source, void *msg_buf); +@!storage_class!@int32_t ${type_name}_decode(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name} *dest, uint8_t **dyn_arr_buf); -extern uint32_t ${type_name}_encode(${type_name} *source, void *msg_buf); -extern int32_t ${type_name}_decode(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name} *dest, uint8_t **dyn_arr_buf); - -extern uint32_t ${type_name}_encode_internal(${type_name} *source, void *msg_buf, uint32_t offset, uint8_t root_item); -extern int32_t ${type_name}_decode_internal(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name} *dest, uint8_t **dyn_arr_buf, int32_t offset, uint8_t tao); +@!storage_class!@uint32_t ${type_name}_encode_internal(${type_name} *source, void *msg_buf, uint32_t offset, uint8_t root_item); +@!storage_class!@int32_t ${type_name}_decode_internal(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name} *dest, uint8_t **dyn_arr_buf, int32_t offset, uint8_t tao); %else typedef struct { uint8_t empty; } ${type_name}; +@!storage_class!@uint32_t ${type_name}_encode(${type_name} *source, void *msg_buf); +@!storage_class!@int32_t ${type_name}_decode(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name} *dest, uint8_t **dyn_arr_buf); +@!storage_class!@uint32_t ${type_name}_encode_internal(${type_name} *source, void *msg_buf, uint32_t offset, uint8_t root_item); +@!storage_class!@int32_t ${type_name}_decode_internal(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name} *dest, uint8_t **dyn_arr_buf, int32_t offset, uint8_t tao); -extern uint32_t ${type_name}_encode(${type_name} *source, void *msg_buf); -extern int32_t ${type_name}_decode(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name} *dest, uint8_t **dyn_arr_buf); -extern uint32_t ${type_name}_encode_internal(${type_name} *source, void *msg_buf, uint32_t offset, uint8_t root_item); -extern int32_t ${type_name}_decode_internal(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name} *dest, uint8_t **dyn_arr_buf, int32_t offset, uint8_t tao); %endif @@ -128,7 +136,9 @@ ${generate_primary_body(type_name=t.name_space_type_name+'Response', service='_R ${generate_primary_body(type_name=t.name_space_type_name, service='', max_bitlen=t.get_max_bitlen(), \ fields=t.fields, constants=t.constants, union=t.union, has_array=t.has_array)} % endif +%if not t.header_only #ifdef __cplusplus } // extern "C" #endif #endif // ${t.include_guard} +%endif \ No newline at end of file diff --git a/dsdl_compiler/libcanard_dsdlc b/dsdl_compiler/libcanard_dsdlc index 5e46e443..dacb6d91 100755 --- a/dsdl_compiler/libcanard_dsdlc +++ b/dsdl_compiler/libcanard_dsdlc @@ -43,6 +43,7 @@ Supported Python versions: 3.2+, 2.7. argparser = argparse.ArgumentParser(description=DESCRIPTION) argparser.add_argument('source_dir', nargs='+', help='source directory with DSDL definitions') +argparser.add_argument('--header_only', '-ho', action='store_true', help='Generate as header only library') argparser.add_argument('--verbose', '-v', action='count', help='verbosity level (-v, -vv)') argparser.add_argument('--outdir', '-O', default=DEFAULT_OUTDIR, help='output directory, default %s' % DEFAULT_OUTDIR) argparser.add_argument('--incdir', '-I', default=[], action='append', help= @@ -62,7 +63,7 @@ except KeyError: from libcanard_dsdl_compiler import run as dsdlc_run try: - dsdlc_run(args.source_dir, args.incdir, args.outdir) + dsdlc_run(args.source_dir, args.incdir, args.outdir, args.header_only) except Exception as ex: logging.error('Compiler failure', exc_info=True) die(str(ex)) From ada6692093c2d14d0eccbdb1cc3c5ff632acbdf6 Mon Sep 17 00:00:00 2001 From: "Torola, Sami" Date: Mon, 24 Sep 2018 16:20:10 +0300 Subject: [PATCH 37/81] Added longer names for exported defines. Added longer names for exported defines to prevent collision when using library as header only. --- .../code_type_template.tmpl | 18 +++++++++--------- 1 file changed, 9 insertions(+), 9 deletions(-) diff --git a/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl b/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl index b2858227..aedf2422 100644 --- a/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl +++ b/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl @@ -10,12 +10,12 @@ #include "canard.h" %endif -#ifndef SATURATE -#define SATURATE(x, max) ( ((x) > max) ? max : ( (-(x) > max) ? (-max) : (x) ) ); +#ifndef _UAVCAN_INTERNAL_SATURATE +#define _UAVCAN_INTERNAL_SATURATE(x, max) ( ((x) > max) ? max : ( (-(x) > max) ? (-max) : (x) ) ); #endif -#define ENABLE_TAO ((uint8_t) 1) -#define DISABLE_TAO ((uint8_t) 0) +#define _UAVCAN_INTERNAL_ENABLE_TAO ((uint8_t) 1) +#define _UAVCAN_INTERNAL_DISABLE_TAO ((uint8_t) 0) #! type_name, service, max_bitlen, fields, constants, union, has_array, has_float16 @@ -121,7 +121,7 @@ uint32_t ${type_name}_encode_internal(${type_name} *source, void *msg_buf, uint3 offset += ${f.bitlen}; %else %if f.saturate - source->${f.name} = SATURATE(source->${f.name}, ${f.max_size}) + source->${f.name} = _UAVCAN_INTERNAL_SATURATE(source->${f.name}, ${f.max_size}) %endif canardEncodeScalar(msg_buf, offset, ${f.bitlen}, (void*)&source->${f.name}); // ${f.max_size} offset += ${f.bitlen}; @@ -200,7 +200,7 @@ int32_t ${type_name}_decode_internal(const CanardRxTransfer* transfer, uint16_t %if f.last_item %if f.bitlen > 7 // - Last item in struct & Root item & (Array Size > 8 bit), tail array optimization - if (payload_len && tao == ENABLE_TAO) + if (payload_len && tao == _UAVCAN_INTERNAL_ENABLE_TAO) { // - Calculate Array length from MSG length dest->${'%s' % ((f.name + '_len'))} = ((payload_len * 8) - offset ) / ${f.bitlen}; // ${f.bitlen} bit array item size @@ -340,7 +340,7 @@ int32_t ${type_name}_decode(const CanardRxTransfer* transfer, uint16_t payload_l * - first try to decode with TAO DISABLED * - if it fails fall back to TAO ENABLED */ - uint8_t tao = DISABLE_TAO; + uint8_t tao = _UAVCAN_INTERNAL_DISABLE_TAO; while (1) { @@ -357,11 +357,11 @@ int32_t ${type_name}_decode(const CanardRxTransfer* transfer, uint16_t payload_l break; } - if (tao == ENABLE_TAO) + if (tao == _UAVCAN_INTERNAL_ENABLE_TAO) { break; } - tao = ENABLE_TAO; + tao = _UAVCAN_INTERNAL_ENABLE_TAO; } return ret; From a8b3237d22f366b3fb05cd1c8d7e626f2596bbfd Mon Sep 17 00:00:00 2001 From: "Torola, Sami" Date: Tue, 25 Sep 2018 07:39:54 +0300 Subject: [PATCH 38/81] Preview change: exposed define prefix changed to CANARD_ --- .../code_type_template.tmpl | 18 +++++++++--------- 1 file changed, 9 insertions(+), 9 deletions(-) diff --git a/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl b/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl index aedf2422..9b07a83f 100644 --- a/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl +++ b/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl @@ -10,12 +10,12 @@ #include "canard.h" %endif -#ifndef _UAVCAN_INTERNAL_SATURATE -#define _UAVCAN_INTERNAL_SATURATE(x, max) ( ((x) > max) ? max : ( (-(x) > max) ? (-max) : (x) ) ); +#ifndef CANARD_INTERNAL_SATURATE +#define CANARD_INTERNAL_SATURATE(x, max) ( ((x) > max) ? max : ( (-(x) > max) ? (-max) : (x) ) ); #endif -#define _UAVCAN_INTERNAL_ENABLE_TAO ((uint8_t) 1) -#define _UAVCAN_INTERNAL_DISABLE_TAO ((uint8_t) 0) +#define CANARD_INTERNAL_ENABLE_TAO ((uint8_t) 1) +#define CANARD_INTERNAL_DISABLE_TAO ((uint8_t) 0) #! type_name, service, max_bitlen, fields, constants, union, has_array, has_float16 @@ -121,7 +121,7 @@ uint32_t ${type_name}_encode_internal(${type_name} *source, void *msg_buf, uint3 offset += ${f.bitlen}; %else %if f.saturate - source->${f.name} = _UAVCAN_INTERNAL_SATURATE(source->${f.name}, ${f.max_size}) + source->${f.name} = CANARD_INTERNAL_SATURATE(source->${f.name}, ${f.max_size}) %endif canardEncodeScalar(msg_buf, offset, ${f.bitlen}, (void*)&source->${f.name}); // ${f.max_size} offset += ${f.bitlen}; @@ -200,7 +200,7 @@ int32_t ${type_name}_decode_internal(const CanardRxTransfer* transfer, uint16_t %if f.last_item %if f.bitlen > 7 // - Last item in struct & Root item & (Array Size > 8 bit), tail array optimization - if (payload_len && tao == _UAVCAN_INTERNAL_ENABLE_TAO) + if (payload_len && tao == CANARD_INTERNAL_ENABLE_TAO) { // - Calculate Array length from MSG length dest->${'%s' % ((f.name + '_len'))} = ((payload_len * 8) - offset ) / ${f.bitlen}; // ${f.bitlen} bit array item size @@ -340,7 +340,7 @@ int32_t ${type_name}_decode(const CanardRxTransfer* transfer, uint16_t payload_l * - first try to decode with TAO DISABLED * - if it fails fall back to TAO ENABLED */ - uint8_t tao = _UAVCAN_INTERNAL_DISABLE_TAO; + uint8_t tao = CANARD_INTERNAL_DISABLE_TAO; while (1) { @@ -357,11 +357,11 @@ int32_t ${type_name}_decode(const CanardRxTransfer* transfer, uint16_t payload_l break; } - if (tao == _UAVCAN_INTERNAL_ENABLE_TAO) + if (tao == CANARD_INTERNAL_ENABLE_TAO) { break; } - tao = _UAVCAN_INTERNAL_ENABLE_TAO; + tao = CANARD_INTERNAL_ENABLE_TAO; } return ret; From afa1fc6ab44549e823092c9e60d75a646855bd32 Mon Sep 17 00:00:00 2001 From: "Torola, Sami" Date: Mon, 1 Oct 2018 13:41:19 +0300 Subject: [PATCH 39/81] Code review changes. - Added info about header only code generation. - Removed info about the python monotonic library. - Some README re-formating. - Added new-lines to the end of template files. --- dsdl_compiler/README.md | 103 +++++++++--------- .../code_type_template.tmpl | 2 +- .../data_type_template.tmpl | 2 +- .../{LICENSE => pyratemp_LICENSE} | 0 4 files changed, 54 insertions(+), 53 deletions(-) rename dsdl_compiler/libcanard_dsdl_compiler/{LICENSE => pyratemp_LICENSE} (100%) diff --git a/dsdl_compiler/README.md b/dsdl_compiler/README.md index 8fed7212..bdfbc842 100644 --- a/dsdl_compiler/README.md +++ b/dsdl_compiler/README.md @@ -1,7 +1,7 @@ # UAVCAN DSDL compiler for the libcanard ## Overview -Libcanard_dsdlc is a tool to generate UAVCAN DSDL definitions to libcanard compatible message c-modules. +Libcanard_dsdlc is a tool to generate UAVCAN DSDL definitions to libcanard compatible message c-modules or to header only library with command line flag. Modules have: defines, enums, unions, structs, and encoding and decoding functions as defined in UAVCAN DSDL. Encoding and decoding functions use the decode and encode functions of libcanard for bit packing / unpacking. @@ -12,17 +12,17 @@ To get libcanard from the git, make sure all the submodules are fetched too. `git submodules update --init --recursive` -### Generating files -`python3 libcanard_dsdlc --outdir ` - -NOTE: If python2 is used, monotonic library is needed. +### Generating and using library -`pip install monotonic` +### When using c-modules +`python3 libcanard_dsdlc --outdir ` -### Using generated c-modules Include all or only selected message c-files to your compiler script (e.g. Makefile). Add include path to root of the . -NOTE: compiled *.o files can't be compiled into to flat "build" directory as some files in DSDL have the same name. +### When using as header only library +`python3 libcanard_dsdlc --header_only --outdir ` + +Include wanted message header(s) into your code. Add include path to root of the . ### Float16 Generated structs in modules use float type when specified float16 in DSDL. Float is converted to float16 using libcanard's canardConvertNativeFloatToFloat16 when Encoding. Calling Decode function after receive will convert float16 to float, using libcanard's canardConvertFloat16ToNativeFloat function. @@ -32,31 +32,32 @@ Canard conversion functions can be replaced to compiler casting if wanted, e.g. #### Encode NodeStatus-broadcast message ```cpp - #include "uavcan/protocol/NodeStatus.h" - - /* Reserve memory and struct for messages */ - uint8_t packed_uavcan_msg_buf[UAVCAN_PROTOCOL_NODESTATUS_MAX_SIZE]; - /* MAX_SIZE comes from module header as pre-calculated */ - uavcan_protocol_NodeStatus msg; - - msg.uptime_sec = GetUptime(); - - msg.health = UAVCAN_PROTOCOL_NODESTATUS_HEALTH_OK; - msg.mode = UAVCAN_PROTOCOL_NODESTATUS_MODE_OPERATIONAL; - - msg.sub_mode = sub_mode; - msg.vendor_specific_status_code = vendor_status_code; - - /* Encode filled struct to packed_uavcan_msg_buf, ready to be send */ - uint32_t len_of_packed_msg = uavcan_protocol_NodeStatusEncode(&msg, packed_uavcan_msg_buf); - - canardBroadcast(&g_canard, - UAVCAN_PROTOCOL_NODESTATUS_SIGNATURE, - UAVCAN_PROTOCOL_NODESTATUS_ID, - &g_bc_node_status_transfer_id, - CANARD_TRANSFER_PRIORITY_MEDIUM, - packed_uavcan_msg_buf, - len_of_packed_msg); +#include "uavcan/protocol/NodeStatus.h" + +/* Reserve memory and struct for messages */ +uint8_t packed_uavcan_msg_buf[UAVCAN_PROTOCOL_NODESTATUS_MAX_SIZE]; +/* MAX_SIZE comes from module header as pre-calculated */ +uavcan_protocol_NodeStatus msg; + +msg.uptime_sec = GetUptime(); + +msg.health = UAVCAN_PROTOCOL_NODESTATUS_HEALTH_OK; +msg.mode = UAVCAN_PROTOCOL_NODESTATUS_MODE_OPERATIONAL; + +msg.sub_mode = sub_mode; +msg.vendor_specific_status_code = vendor_status_code; + +/* Encode filled struct to packed_uavcan_msg_buf, ready to be send */ +uint32_t len_of_packed_msg = uavcan_protocol_NodeStatusEncode(&msg, + packed_uavcan_msg_buf); + +canardBroadcast(&g_canard, + UAVCAN_PROTOCOL_NODESTATUS_SIGNATURE, + UAVCAN_PROTOCOL_NODESTATUS_ID, + &g_bc_node_status_transfer_id, + CANARD_TRANSFER_PRIORITY_MEDIUM, + packed_uavcan_msg_buf, + len_of_packed_msg); ``` *Dynamic Array* all the dynamic arrays have also _len field, which contain the info of how many data items have been stored in to dynamic array pointer. @@ -64,24 +65,24 @@ Canard conversion functions can be replaced to compiler casting if wanted, e.g. #### Decode GetSet-request ```cpp - /* include header */ - #include "uavcan/protocol/param/GetSet.h" - - #define GETSETREQ_NAME_MAX_SIZE 96 // max size needed for the dynamic arrays - /* Reserve some memory for the dynamic arrays from the stack */ - uint8_t buff[GETSETREQ_NAME_MAX_SIZE]; - uint8_t *dyn_buf_ptr = buff; - - /* Reserve struct */ - uavcan_protocol_param_GetSetRequest get_set_req; - - /* NOTE get_set_req struct will be cleared in Decode function first */ - uavcan_protocol_param_GetSetRequestDecode(transfer, - (uint16_t)transfer->payload_len, - &get_set_req, - &dyn_buf_ptr); - - /* Now struct get_set_req "object" is ready to be used */ +/* include header */ +#include "uavcan/protocol/param/GetSet.h" + +#define GETSETREQ_NAME_MAX_SIZE 96 // max size needed for the dynamic arrays +/* Reserve some memory for the dynamic arrays from the stack */ +uint8_t buff[GETSETREQ_NAME_MAX_SIZE]; +uint8_t *dyn_buf_ptr = buff; + +/* Reserve struct */ +uavcan_protocol_param_GetSetRequest get_set_req; + +/* NOTE get_set_req struct will be cleared in Decode function first */ +uavcan_protocol_param_GetSetRequestDecode(transfer, + (uint16_t)transfer->payload_len, + &get_set_req, + &dyn_buf_ptr); + +/* Now struct get_set_req "object" is ready to be used */ ``` *Dynamic Arrays* dyn_buf_ptr is a way to give allocated memory to *Decode function, to use that space to store dynamic arrays into it, and store the pointer to struct pointer. diff --git a/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl b/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl index 9b07a83f..2d91a43a 100644 --- a/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl +++ b/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl @@ -409,4 +409,4 @@ ${generate_primary_body(type_name=t.name_space_type_name, service='', max_bitlen } // extern "C" #endif #endif // ${t.include_guard} -%endif \ No newline at end of file +%endif diff --git a/dsdl_compiler/libcanard_dsdl_compiler/data_type_template.tmpl b/dsdl_compiler/libcanard_dsdl_compiler/data_type_template.tmpl index 3a2a5d4c..f902b958 100644 --- a/dsdl_compiler/libcanard_dsdl_compiler/data_type_template.tmpl +++ b/dsdl_compiler/libcanard_dsdl_compiler/data_type_template.tmpl @@ -141,4 +141,4 @@ ${generate_primary_body(type_name=t.name_space_type_name, service='', max_bitlen } // extern "C" #endif #endif // ${t.include_guard} -%endif \ No newline at end of file +%endif diff --git a/dsdl_compiler/libcanard_dsdl_compiler/LICENSE b/dsdl_compiler/libcanard_dsdl_compiler/pyratemp_LICENSE similarity index 100% rename from dsdl_compiler/libcanard_dsdl_compiler/LICENSE rename to dsdl_compiler/libcanard_dsdl_compiler/pyratemp_LICENSE From 23e09030ead04b061607aa31278e448dc6e4e4a6 Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Thu, 4 Oct 2018 15:51:23 +0300 Subject: [PATCH 40/81] Minor corrections to the DSDL compiler: README fixes, code style fixes --- dsdl_compiler/README.md | 103 ++++++++++-------- .../code_type_template.tmpl | 18 +-- .../data_type_template.tmpl | 16 +-- 3 files changed, 77 insertions(+), 60 deletions(-) diff --git a/dsdl_compiler/README.md b/dsdl_compiler/README.md index bdfbc842..7100702c 100644 --- a/dsdl_compiler/README.md +++ b/dsdl_compiler/README.md @@ -1,68 +1,88 @@ -# UAVCAN DSDL compiler for the libcanard +# DSDL compiler for libcanard ## Overview -Libcanard_dsdlc is a tool to generate UAVCAN DSDL definitions to libcanard compatible message c-modules or to header only library with command line flag. -Modules have: defines, enums, unions, structs, and encoding and decoding functions as defined in UAVCAN DSDL. Encoding and decoding functions use the decode and encode functions of libcanard for bit packing / unpacking. +Libcanard_dsdlc is a tool for converting UAVCAN DSDL definitions into libcanard-compatible C source files or headers. -In c there is no namespace, so all the generated #define and function names are long having full folder path included. This is made to prevent the collision with each other and to the rest of the system. +Modules have: defines, enums, unions, structs, and encoding/decoding functions as defined in UAVCAN DSDL. +Encoding and decoding functions use the encode and decode functions of libcanard for bit packing/unpacking. -## Install & Integration -To get libcanard from the git, make sure all the submodules are fetched too. +In C there is no namespace, so all the generated `#define` and function names are long having full folder path included. +This is made to prevent collisions with each other and with the rest of the system. -`git submodules update --init --recursive` +## Installation & integration -### Generating and using library +To get libcanard from git, make sure all the submodules are fetched too. + +``` +git submodules update --init --recursive +``` + +## Compilation ### When using c-modules -`python3 libcanard_dsdlc --outdir ` -Include all or only selected message c-files to your compiler script (e.g. Makefile). Add include path to root of the . +``` +python3 libcanard_dsdlc --outdir +``` + +Add all or only selected message C-files to your build script (e.g. Makefile). +Add `` to your include paths. ### When using as header only library -`python3 libcanard_dsdlc --header_only --outdir ` -Include wanted message header(s) into your code. Add include path to root of the . +``` +python3 libcanard_dsdlc --header_only --outdir +``` + +Include wanted message header(s) into your code. +Add `` to your include paths. + +### Notes -### Float16 -Generated structs in modules use float type when specified float16 in DSDL. Float is converted to float16 using libcanard's canardConvertNativeFloatToFloat16 when Encoding. Calling Decode function after receive will convert float16 to float, using libcanard's canardConvertFloat16ToNativeFloat function. -Canard conversion functions can be replaced to compiler casting if wanted, e.g. #define CANARD_USE_FLOAT16_CAST e.g. __fp16. +#### Float16 + +Generated structs use the native `float` type for `float16`. +The native `float` is converted to `float16` using libcanard's `canardConvertNativeFloatToFloat16()` when encoding. +Calling decode function after reception will convert `float16` to the native `float` using the libcanard's +`canardConvertFloat16ToNativeFloat()` function. +Libcanard conversion functions can be replaced to compiler casting if wanted, +e.g. `#define CANARD_USE_FLOAT16_CAST __fp16`. ## Using generated modules -#### Encode NodeStatus-broadcast message +### Encode NodeStatus message + ```cpp #include "uavcan/protocol/NodeStatus.h" - + /* Reserve memory and struct for messages */ uint8_t packed_uavcan_msg_buf[UAVCAN_PROTOCOL_NODESTATUS_MAX_SIZE]; /* MAX_SIZE comes from module header as pre-calculated */ uavcan_protocol_NodeStatus msg; msg.uptime_sec = GetUptime(); - msg.health = UAVCAN_PROTOCOL_NODESTATUS_HEALTH_OK; msg.mode = UAVCAN_PROTOCOL_NODESTATUS_MODE_OPERATIONAL; - msg.sub_mode = sub_mode; msg.vendor_specific_status_code = vendor_status_code; -/* Encode filled struct to packed_uavcan_msg_buf, ready to be send */ -uint32_t len_of_packed_msg = uavcan_protocol_NodeStatusEncode(&msg, - packed_uavcan_msg_buf); - -canardBroadcast(&g_canard, - UAVCAN_PROTOCOL_NODESTATUS_SIGNATURE, - UAVCAN_PROTOCOL_NODESTATUS_ID, - &g_bc_node_status_transfer_id, - CANARD_TRANSFER_PRIORITY_MEDIUM, - packed_uavcan_msg_buf, - len_of_packed_msg); +/* Encode the filled struct into packed_uavcan_msg_buf, ready to be sent */ +const uint32_t len_of_packed_msg = uavcan_protocol_NodeStatusEncode(&msg, packed_uavcan_msg_buf); + +(void) canardBroadcast(&g_canard, + UAVCAN_PROTOCOL_NODESTATUS_SIGNATURE, + UAVCAN_PROTOCOL_NODESTATUS_ID, + &g_bc_node_status_transfer_id, + CANARD_TRANSFER_PRIORITY_MEDIUM, + packed_uavcan_msg_buf, + len_of_packed_msg); ``` -*Dynamic Array* all the dynamic arrays have also _len field, which contain the info of how many data items have been stored in to dynamic array pointer. +Dynamic arrays also have the `_len` field, +which specifies how many data items are accessible via the dynamic array pointer. -#### Decode GetSet-request +#### Decode GetSet request ```cpp /* include header */ @@ -70,29 +90,26 @@ canardBroadcast(&g_canard, #define GETSETREQ_NAME_MAX_SIZE 96 // max size needed for the dynamic arrays /* Reserve some memory for the dynamic arrays from the stack */ -uint8_t buff[GETSETREQ_NAME_MAX_SIZE]; -uint8_t *dyn_buf_ptr = buff; +uint8_t buff[GETSETREQ_NAME_MAX_SIZE]; +uint8_t* dyn_buf_ptr = buff; /* Reserve struct */ uavcan_protocol_param_GetSetRequest get_set_req; -/* NOTE get_set_req struct will be cleared in Decode function first */ +/* NOTE get_set_req struct will be cleared in the Decode function first */ uavcan_protocol_param_GetSetRequestDecode(transfer, (uint16_t)transfer->payload_len, &get_set_req, &dyn_buf_ptr); -/* Now struct get_set_req "object" is ready to be used */ +/* Now the struct get_set_req "object" is ready to be used */ ``` -*Dynamic Arrays* dyn_buf_ptr is a way to give allocated memory to *Decode function, to use that space to store dynamic arrays into it, and store the pointer to struct pointer. +`dyn_buf_ptr` is a way to give allocated memory to the Decode function, +to use that space to store dynamic arrays into it, and store the pointer to struct pointer. -NOTE: There is no check whether dynamic memory allocation is big enough. +NOTE: There is no check whether dynamic memory allocation is sufficient. ## License -Released under MIT license, check LICENSE - - - - +Released under the MIT license, check the file LICENSE. diff --git a/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl b/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl index 2d91a43a..8abdd1c5 100644 --- a/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl +++ b/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl @@ -29,7 +29,7 @@ * @param root_item: for detecting if TAO should be used * @retval returns offset */ -uint32_t ${type_name}_encode_internal(${type_name} *source, void *msg_buf, uint32_t offset, uint8_t root_item) +uint32_t ${type_name}_encode_internal(${type_name}* source, void* msg_buf, uint32_t offset, uint8_t root_item) { %if union // Max Union Tag Value @@ -141,7 +141,7 @@ uint32_t ${type_name}_encode_internal(${type_name} *source, void *msg_buf, uint3 * @param msg_buf: Pointer to msg storage * @retval returns message length as bytes */ -uint32_t ${type_name}_encode(${type_name} *source, void *msg_buf) +uint32_t ${type_name}_encode(${type_name}* source, void* msg_buf) { uint32_t offset = 0; @@ -162,7 +162,7 @@ uint32_t ${type_name}_encode(${type_name} *source, void *msg_buf) * @param tao: is tail array optimization used * @retval offset or ERROR value if < 0 */ -int32_t ${type_name}_decode_internal(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name} *dest, uint8_t **dyn_arr_buf, int32_t offset, uint8_t tao) +int32_t ${type_name}_decode_internal(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name}* dest, uint8_t** dyn_arr_buf, int32_t offset, uint8_t tao) { int32_t ret = 0; %if has_array @@ -250,7 +250,7 @@ int32_t ${type_name}_decode_internal(const CanardRxTransfer* transfer, uint16_t { goto ${type_name}_error_exit; } - *dyn_arr_buf = (uint8_t *)(((${f.cpp_type}*)*dyn_arr_buf) + 1); + *dyn_arr_buf = (uint8_t*)(((${f.cpp_type}*)*dyn_arr_buf) + 1); } offset += ${f.bitlen}; %endif @@ -331,7 +331,7 @@ ${type_name}_error_exit: * NULL will ignore dynamic arrays decoding. * @retval offset or ERROR value if < 0 */ -int32_t ${type_name}_decode(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name} *dest, uint8_t **dyn_arr_buf) +int32_t ${type_name}_decode(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name}* dest, uint8_t** dyn_arr_buf) { const int32_t offset = 0; int32_t ret = 0; @@ -367,22 +367,22 @@ int32_t ${type_name}_decode(const CanardRxTransfer* transfer, uint16_t payload_l return ret; } %else -uint32_t ${type_name}_encode_internal(${type_name} *source, void *msg_buf, uint32_t offset, uint8_t root_item) +uint32_t ${type_name}_encode_internal(${type_name}* source, void* msg_buf, uint32_t offset, uint8_t root_item) { return offset; } -uint32_t ${type_name}_encode(${type_name} *source, void *msg_buf) +uint32_t ${type_name}_encode(${type_name}* source, void* msg_buf) { return 0; } -int32_t ${type_name}_decode_internal(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name} *dest, uint8_t **dyn_arr_buf, int32_t offset, uint8_t tao) +int32_t ${type_name}_decode_internal(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name}* dest, uint8_t** dyn_arr_buf, int32_t offset, uint8_t tao) { return offset; } -int32_t ${type_name}_decode(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name} *dest, uint8_t **dyn_arr_buf) +int32_t ${type_name}_decode(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name}* dest, uint8_t** dyn_arr_buf) { return 0; } diff --git a/dsdl_compiler/libcanard_dsdl_compiler/data_type_template.tmpl b/dsdl_compiler/libcanard_dsdl_compiler/data_type_template.tmpl index f902b958..65023552 100644 --- a/dsdl_compiler/libcanard_dsdl_compiler/data_type_template.tmpl +++ b/dsdl_compiler/libcanard_dsdl_compiler/data_type_template.tmpl @@ -106,20 +106,20 @@ typedef struct %endif } ${type_name}; -@!storage_class!@uint32_t ${type_name}_encode(${type_name} *source, void *msg_buf); -@!storage_class!@int32_t ${type_name}_decode(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name} *dest, uint8_t **dyn_arr_buf); +@!storage_class!@uint32_t ${type_name}_encode(${type_name}* source, void* msg_buf); +@!storage_class!@int32_t ${type_name}_decode(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name}* dest, uint8_t** dyn_arr_buf); -@!storage_class!@uint32_t ${type_name}_encode_internal(${type_name} *source, void *msg_buf, uint32_t offset, uint8_t root_item); -@!storage_class!@int32_t ${type_name}_decode_internal(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name} *dest, uint8_t **dyn_arr_buf, int32_t offset, uint8_t tao); +@!storage_class!@uint32_t ${type_name}_encode_internal(${type_name}* source, void* msg_buf, uint32_t offset, uint8_t root_item); +@!storage_class!@int32_t ${type_name}_decode_internal(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name}* dest, uint8_t** dyn_arr_buf, int32_t offset, uint8_t tao); %else typedef struct { uint8_t empty; } ${type_name}; -@!storage_class!@uint32_t ${type_name}_encode(${type_name} *source, void *msg_buf); -@!storage_class!@int32_t ${type_name}_decode(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name} *dest, uint8_t **dyn_arr_buf); -@!storage_class!@uint32_t ${type_name}_encode_internal(${type_name} *source, void *msg_buf, uint32_t offset, uint8_t root_item); -@!storage_class!@int32_t ${type_name}_decode_internal(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name} *dest, uint8_t **dyn_arr_buf, int32_t offset, uint8_t tao); +@!storage_class!@uint32_t ${type_name}_encode(${type_name}* source, void* msg_buf); +@!storage_class!@int32_t ${type_name}_decode(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name}* dest, uint8_t** dyn_arr_buf); +@!storage_class!@uint32_t ${type_name}_encode_internal(${type_name}* source, void* msg_buf, uint32_t offset, uint8_t root_item); +@!storage_class!@int32_t ${type_name}_decode_internal(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name}* dest, uint8_t** dyn_arr_buf, int32_t offset, uint8_t tao); %endif From da7a4374244812830c95e818b435dd1d75d3162b Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Thu, 4 Oct 2018 15:56:23 +0300 Subject: [PATCH 41/81] Fixed the examples --- dsdl_compiler/README.md | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/dsdl_compiler/README.md b/dsdl_compiler/README.md index 7100702c..6a265dfa 100644 --- a/dsdl_compiler/README.md +++ b/dsdl_compiler/README.md @@ -61,14 +61,14 @@ uint8_t packed_uavcan_msg_buf[UAVCAN_PROTOCOL_NODESTATUS_MAX_SIZE]; /* MAX_SIZE comes from module header as pre-calculated */ uavcan_protocol_NodeStatus msg; -msg.uptime_sec = GetUptime(); +msg.uptime_sec = getUptime(); msg.health = UAVCAN_PROTOCOL_NODESTATUS_HEALTH_OK; msg.mode = UAVCAN_PROTOCOL_NODESTATUS_MODE_OPERATIONAL; msg.sub_mode = sub_mode; msg.vendor_specific_status_code = vendor_status_code; /* Encode the filled struct into packed_uavcan_msg_buf, ready to be sent */ -const uint32_t len_of_packed_msg = uavcan_protocol_NodeStatusEncode(&msg, packed_uavcan_msg_buf); +const uint32_t len_of_packed_msg = uavcan_protocol_NodeStatus_encode(&msg, packed_uavcan_msg_buf); (void) canardBroadcast(&g_canard, UAVCAN_PROTOCOL_NODESTATUS_SIGNATURE, @@ -97,10 +97,10 @@ uint8_t* dyn_buf_ptr = buff; uavcan_protocol_param_GetSetRequest get_set_req; /* NOTE get_set_req struct will be cleared in the Decode function first */ -uavcan_protocol_param_GetSetRequestDecode(transfer, - (uint16_t)transfer->payload_len, - &get_set_req, - &dyn_buf_ptr); +(void) uavcan_protocol_param_GetSetRequest_decode(transfer, + (uint16_t)transfer->payload_len, + &get_set_req, + &dyn_buf_ptr); /* Now the struct get_set_req "object" is ready to be used */ ``` From e0123c0f6f1f356637af0a7434415a128e02c3df Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Thu, 4 Oct 2018 16:03:42 +0300 Subject: [PATCH 42/81] Code style fixes --- .../libcanard_dsdl_compiler/code_type_template.tmpl | 6 ++++-- .../libcanard_dsdl_compiler/data_type_template.tmpl | 2 +- 2 files changed, 5 insertions(+), 3 deletions(-) diff --git a/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl b/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl index 8abdd1c5..4e8bd2ce 100644 --- a/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl +++ b/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl @@ -204,7 +204,8 @@ int32_t ${type_name}_decode_internal(const CanardRxTransfer* transfer, uint16_t { // - Calculate Array length from MSG length dest->${'%s' % ((f.name + '_len'))} = ((payload_len * 8) - offset ) / ${f.bitlen}; // ${f.bitlen} bit array item size - } else + } + else { // - Array length ${f.array_max_size_bit_len} bits ret = canardDecodeScalar(transfer, offset, ${f.array_max_size_bit_len}, false, (void*)&dest->${'%s' % ((f.name + '_len'))}); // ${f.max_size} @@ -315,7 +316,8 @@ ${type_name}_error_exit: if (ret < 0) { return ret; - } else + } + else { return -CANARD_ERROR_INTERNAL; } diff --git a/dsdl_compiler/libcanard_dsdl_compiler/data_type_template.tmpl b/dsdl_compiler/libcanard_dsdl_compiler/data_type_template.tmpl index 65023552..c16651d7 100644 --- a/dsdl_compiler/libcanard_dsdl_compiler/data_type_template.tmpl +++ b/dsdl_compiler/libcanard_dsdl_compiler/data_type_template.tmpl @@ -88,7 +88,7 @@ typedef struct %else ${'uint8_t %-26s // %s' % ((a.name + '_len;'), 'Dynamic array length')} %endif - ${'%-10s %-26s // %s' % (a.cpp_type, ('*' + a.name + ';'), a.cpp_type_comment, )} + ${'%-10s %-26s // %s' % ((a.cpp_type + '*'), (a.name + ';'), a.cpp_type_comment, )} }; %else ${'%-10s %-30s // %s' % (a.cpp_type, (a.name + a.post_cpp_type + ';'), a.cpp_type_comment, )} From 09c228fe1f917f5e0014056c6a960ccb8f90f047 Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Thu, 4 Oct 2018 16:04:55 +0300 Subject: [PATCH 43/81] Ignoring generated DSDL files --- .gitignore | 3 +++ 1 file changed, 3 insertions(+) diff --git a/.gitignore b/.gitignore index 2cee413a..b65856db 100644 --- a/.gitignore +++ b/.gitignore @@ -43,3 +43,6 @@ cmake-build-*/ .cproject .pydevproject .gdbinit + +# Generated files +dsdlc_generated/ From 9d2e2904d25c0df10dc78a17ba915cdb13d54292 Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Sat, 6 Oct 2018 19:24:25 +0300 Subject: [PATCH 44/81] Link to the new forum --- README.md | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/README.md b/README.md index a2bd1806..03fc8cd1 100644 --- a/README.md +++ b/README.md @@ -5,9 +5,7 @@ Minimal implementation of the UAVCAN protocol stack in C for resource constrained applications. -Links: - -* **[DISCUSSION GROUP](https://groups.google.com/forum/#!forum/uavcan)** +Get help on the **[UAVCAN Forum](https://forum.uavcan.org)**. ## Usage From 5bd2c32a9baae9bd2dec3a92e1707c97d8b37ee6 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?=C3=85smund=20Eek?= Date: Thu, 18 Oct 2018 10:53:29 +0200 Subject: [PATCH 45/81] Added constants for length of arrays in header files. --- .gitignore | 3 +++ .../libcanard_dsdl_compiler/data_type_template.tmpl | 10 ++++++++++ 2 files changed, 13 insertions(+) diff --git a/.gitignore b/.gitignore index b65856db..0641d8d6 100644 --- a/.gitignore +++ b/.gitignore @@ -46,3 +46,6 @@ cmake-build-*/ # Generated files dsdlc_generated/ + +# Pycache +__pycache__/ diff --git a/dsdl_compiler/libcanard_dsdl_compiler/data_type_template.tmpl b/dsdl_compiler/libcanard_dsdl_compiler/data_type_template.tmpl index c16651d7..b1a0d541 100644 --- a/dsdl_compiler/libcanard_dsdl_compiler/data_type_template.tmpl +++ b/dsdl_compiler/libcanard_dsdl_compiler/data_type_template.tmpl @@ -59,6 +59,16 @@ ${line} #define ${'%-60s %10s' % (t.macro_name + '_' + a.name, a.init_expression, )} // ${a.init_expression} % endfor + % for a in fields: + %if a.type_category == t.CATEGORY_ARRAY + %if a.dynamic_array == True +#define ${'%-80s' % (t.macro_name + service + '_' + a.name.upper() + '_MAX_LENGTH')} ${a.type.max_size} + %else +#define ${'%-80s' % (t.macro_name + service + '_' + a.name.upper() + '_LENGTH')} ${a.type.max_size} + %endif + %endif + % endfor + %if union typedef enum { From 1355a0ce483c695da5935382ceb9d6bd4c222bec Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?=C3=85smund=20Eek?= Date: Thu, 18 Oct 2018 20:56:55 +0200 Subject: [PATCH 46/81] Changed from unnamed to named structs to prevent errors during compiling with c99 and -pedantic. --- .../code_type_template.tmpl | 20 +++++++++---------- .../data_type_template.tmpl | 8 ++++---- 2 files changed, 14 insertions(+), 14 deletions(-) diff --git a/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl b/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl index 4e8bd2ce..62492566 100644 --- a/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl +++ b/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl @@ -66,29 +66,29 @@ uint32_t ${type_name}_encode_internal(${type_name}* source, void* msg_buf, uint3 %if f.bitlen < 8 ${f.array_max_size_bit_len} // - Add array length, last item, but bitlen < 8. - canardEncodeScalar(msg_buf, offset, ${f.array_max_size_bit_len}, (void*)&source->${'%s' % ((f.name + '_len'))}); + canardEncodeScalar(msg_buf, offset, ${f.array_max_size_bit_len}, (void*)&source->${'%s' % ((f.name + '.len'))}); offset += ${f.array_max_size_bit_len}; %else if (! root_item) { // - Add array length - canardEncodeScalar(msg_buf, offset, ${f.array_max_size_bit_len}, (void*)&source->${'%s' % ((f.name + '_len'))}); + canardEncodeScalar(msg_buf, offset, ${f.array_max_size_bit_len}, (void*)&source->${'%s' % ((f.name + '.len'))}); offset += ${f.array_max_size_bit_len}; } %endif %else // - Add array length - canardEncodeScalar(msg_buf, offset, ${f.array_max_size_bit_len}, (void*)&source->${'%s' % ((f.name + '_len'))}); + canardEncodeScalar(msg_buf, offset, ${f.array_max_size_bit_len}, (void*)&source->${'%s' % ((f.name + '.len'))}); offset += ${f.array_max_size_bit_len}; %endif // - Add array items - for (c = 0; c < source->${'%s' % ((f.name + '_len'))}; c++) + for (c = 0; c < source->${'%s' % ((f.name + '.len'))}; c++) { %if f.cpp_type_category == t.CATEGORY_COMPOUND: offset += ${f.cpp_type}_encode_internal((void*)&source->${f.name}[c], msg_buf, offset, 0); %else - canardEncodeScalar(msg_buf, offset, ${f.bitlen}, (void*)(source->${f.name} + c)); // ${f.max_size} + canardEncodeScalar(msg_buf, offset, ${f.bitlen}, (void*)(source->${'%s' % ((f.name + '.data'))} + c));// ${f.max_size} offset += ${f.bitlen}; %endif } @@ -203,12 +203,12 @@ int32_t ${type_name}_decode_internal(const CanardRxTransfer* transfer, uint16_t if (payload_len && tao == CANARD_INTERNAL_ENABLE_TAO) { // - Calculate Array length from MSG length - dest->${'%s' % ((f.name + '_len'))} = ((payload_len * 8) - offset ) / ${f.bitlen}; // ${f.bitlen} bit array item size + dest->${'%s' % ((f.name + '.len'))} = ((payload_len * 8) - offset ) / ${f.bitlen}; // ${f.bitlen} bit array item size } else { // - Array length ${f.array_max_size_bit_len} bits - ret = canardDecodeScalar(transfer, offset, ${f.array_max_size_bit_len}, false, (void*)&dest->${'%s' % ((f.name + '_len'))}); // ${f.max_size} + ret = canardDecodeScalar(transfer, offset, ${f.array_max_size_bit_len}, false, (void*)&dest->${'%s' % ((f.name + '.len'))}); // ${f.max_size} if (ret != ${f.array_max_size_bit_len}) { goto ${type_name}_error_exit; @@ -216,7 +216,7 @@ int32_t ${type_name}_decode_internal(const CanardRxTransfer* transfer, uint16_t offset += ${f.array_max_size_bit_len}; } %else - ret = canardDecodeScalar(transfer, offset, ${f.array_max_size_bit_len}, false, (void*)&dest->${'%s' % ((f.name + '_len'))}); // ${f.max_size} + ret = canardDecodeScalar(transfer, offset, ${f.array_max_size_bit_len}, false, (void*)&dest->${'%s' % ((f.name + '.len'))}); // ${f.max_size} if (ret != ${f.array_max_size_bit_len}) { goto ${type_name}_error_exit; @@ -236,10 +236,10 @@ int32_t ${type_name}_decode_internal(const CanardRxTransfer* transfer, uint16_t // - Get Array if (dyn_arr_buf) { - dest->${f.name} = (${f.cpp_type}*)*dyn_arr_buf; + dest->${'%s' % ((f.name + '.data'))} = (${f.cpp_type}*)*dyn_arr_buf; } - for (c = 0; c < dest->${'%s' % ((f.name + '_len'))}; c++) + for (c = 0; c < dest->${'%s' % ((f.name + '.len'))}; c++) { %if f.cpp_type_category == t.CATEGORY_COMPOUND: offset += ${f.cpp_type}_decode_internal(transfer, 0, (void*)&dest->${f.name}[c], dyn_arr_buf, offset, tao); diff --git a/dsdl_compiler/libcanard_dsdl_compiler/data_type_template.tmpl b/dsdl_compiler/libcanard_dsdl_compiler/data_type_template.tmpl index b1a0d541..91916666 100644 --- a/dsdl_compiler/libcanard_dsdl_compiler/data_type_template.tmpl +++ b/dsdl_compiler/libcanard_dsdl_compiler/data_type_template.tmpl @@ -94,12 +94,12 @@ typedef struct struct { %if a.max_array_elements > 255 - ${'uint16_t %-26s // %s' % ((a.name + '_len;'), 'Dynamic array length')} + ${'uint16_t %-26s // %s' % (('len;'), 'Dynamic array length')} %else - ${'uint8_t %-26s // %s' % ((a.name + '_len;'), 'Dynamic array length')} + ${'uint8_t %-26s // %s' % (('len;'), 'Dynamic array length')} %endif - ${'%-10s %-26s // %s' % ((a.cpp_type + '*'), (a.name + ';'), a.cpp_type_comment, )} - }; + ${'%-10s %-26s // %s' % ((a.cpp_type + '*'), ('data;'), a.cpp_type_comment, )} + } ${a.name}; %else ${'%-10s %-30s // %s' % (a.cpp_type, (a.name + a.post_cpp_type + ';'), a.cpp_type_comment, )} %endif From 1d7fe17f90b41a25969c9a4af23a3f7a91ad6a32 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?=C3=85smund=20Eek?= Date: Sat, 20 Oct 2018 19:42:13 +0200 Subject: [PATCH 47/81] Fixed bug where some parts of the template weren't updated --- .../libcanard_dsdl_compiler/code_type_template.tmpl | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl b/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl index 62492566..7d38ae15 100644 --- a/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl +++ b/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl @@ -86,7 +86,7 @@ uint32_t ${type_name}_encode_internal(${type_name}* source, void* msg_buf, uint3 for (c = 0; c < source->${'%s' % ((f.name + '.len'))}; c++) { %if f.cpp_type_category == t.CATEGORY_COMPOUND: - offset += ${f.cpp_type}_encode_internal((void*)&source->${f.name}[c], msg_buf, offset, 0); + offset += ${f.cpp_type}_encode_internal((void*)&source->${'%s' % ((f.name + '.data'))}[c], msg_buf, offset, 0); %else canardEncodeScalar(msg_buf, offset, ${f.bitlen}, (void*)(source->${'%s' % ((f.name + '.data'))} + c));// ${f.max_size} offset += ${f.bitlen}; @@ -225,7 +225,7 @@ int32_t ${type_name}_decode_internal(const CanardRxTransfer* transfer, uint16_t %endif %else // - Array length, not last item ${f.array_max_size_bit_len} bits - ret = canardDecodeScalar(transfer, offset, ${f.array_max_size_bit_len}, false, (void*)&dest->${'%s' % ((f.name + '_len'))}); // ${f.max_size} + ret = canardDecodeScalar(transfer, offset, ${f.array_max_size_bit_len}, false, (void*)&dest->${'%s' % ((f.name + '.len'))}); // ${f.max_size} if (ret != ${f.array_max_size_bit_len}) { goto ${type_name}_error_exit; @@ -242,7 +242,7 @@ int32_t ${type_name}_decode_internal(const CanardRxTransfer* transfer, uint16_t for (c = 0; c < dest->${'%s' % ((f.name + '.len'))}; c++) { %if f.cpp_type_category == t.CATEGORY_COMPOUND: - offset += ${f.cpp_type}_decode_internal(transfer, 0, (void*)&dest->${f.name}[c], dyn_arr_buf, offset, tao); + offset += ${f.cpp_type}_decode_internal(transfer, 0, (void*)&dest->${'%s' % ((f.name + '.data'))}[c], dyn_arr_buf, offset, tao); %else if (dyn_arr_buf) { From a98d345e87d519c829d40d71d6e60fef6539b893 Mon Sep 17 00:00:00 2001 From: Damien Espitallier Date: Thu, 1 Nov 2018 11:28:56 +0100 Subject: [PATCH 48/81] remove unused warnings on generated files --- .../code_type_template.tmpl | 18 ++++++++++++------ 1 file changed, 12 insertions(+), 6 deletions(-) diff --git a/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl b/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl index 7d38ae15..03349e7e 100644 --- a/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl +++ b/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl @@ -17,6 +17,12 @@ #define CANARD_INTERNAL_ENABLE_TAO ((uint8_t) 1) #define CANARD_INTERNAL_DISABLE_TAO ((uint8_t) 0) +#if defined(__GNUC__) +# define CANARD_MAYBE_UNUSED(x) x __attribute__((unused)) +#else +# define CANARD_MAYBE_UNUSED(x) x +#endif + #! type_name, service, max_bitlen, fields, constants, union, has_array, has_float16 %if max_bitlen @@ -29,7 +35,7 @@ * @param root_item: for detecting if TAO should be used * @retval returns offset */ -uint32_t ${type_name}_encode_internal(${type_name}* source, void* msg_buf, uint32_t offset, uint8_t root_item) +uint32_t ${type_name}_encode_internal(${type_name}* source, void* msg_buf, uint32_t offset, uint8_t CANARD_MAYBE_UNUSED(root_item)) { %if union // Max Union Tag Value @@ -162,7 +168,7 @@ uint32_t ${type_name}_encode(${type_name}* source, void* msg_buf) * @param tao: is tail array optimization used * @retval offset or ERROR value if < 0 */ -int32_t ${type_name}_decode_internal(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name}* dest, uint8_t** dyn_arr_buf, int32_t offset, uint8_t tao) +int32_t ${type_name}_decode_internal(const CanardRxTransfer* transfer, uint16_t CANARD_MAYBE_UNUSED(payload_len), ${type_name}* dest, uint8_t** CANARD_MAYBE_UNUSED(dyn_arr_buf), int32_t offset, uint8_t CANARD_MAYBE_UNUSED(tao)) { int32_t ret = 0; %if has_array @@ -369,22 +375,22 @@ int32_t ${type_name}_decode(const CanardRxTransfer* transfer, uint16_t payload_l return ret; } %else -uint32_t ${type_name}_encode_internal(${type_name}* source, void* msg_buf, uint32_t offset, uint8_t root_item) +uint32_t ${type_name}_encode_internal(${type_name}* CANARD_MAYBE_UNUSED(source), void* CANARD_MAYBE_UNUSED(msg_buf), uint32_t offset, uint8_t CANARD_MAYBE_UNUSED(root_item)) { return offset; } -uint32_t ${type_name}_encode(${type_name}* source, void* msg_buf) +uint32_t ${type_name}_encode(${type_name}* CANARD_MAYBE_UNUSED(source), void* CANARD_MAYBE_UNUSED(msg_buf)) { return 0; } -int32_t ${type_name}_decode_internal(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name}* dest, uint8_t** dyn_arr_buf, int32_t offset, uint8_t tao) +int32_t ${type_name}_decode_internal(const CanardRxTransfer* CANARD_MAYBE_UNUSED(transfer), uint16_t CANARD_MAYBE_UNUSED(payload_len), ${type_name}* CANARD_MAYBE_UNUSED(dest), uint8_t** CANARD_MAYBE_UNUSED(dyn_arr_buf), int32_t offset, uint8_t CANARD_MAYBE_UNUSED(tao)) { return offset; } -int32_t ${type_name}_decode(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name}* dest, uint8_t** dyn_arr_buf) +int32_t ${type_name}_decode(const CanardRxTransfer* CANARD_MAYBE_UNUSED(transfer), uint16_t CANARD_MAYBE_UNUSED(payload_len), ${type_name}* CANARD_MAYBE_UNUSED(dest), uint8_t** CANARD_MAYBE_UNUSED(dyn_arr_buf)) { return 0; } From 673cb367c5b40b8653164d7ac3226e9134367c92 Mon Sep 17 00:00:00 2001 From: Damien Espitallier Date: Thu, 1 Nov 2018 11:29:24 +0100 Subject: [PATCH 49/81] remove signess issues on generated files --- .../libcanard_dsdl_compiler/code_type_template.tmpl | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl b/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl index 03349e7e..2deefa22 100644 --- a/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl +++ b/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl @@ -14,6 +14,11 @@ #define CANARD_INTERNAL_SATURATE(x, max) ( ((x) > max) ? max : ( (-(x) > max) ? (-max) : (x) ) ); #endif +#ifndef CANARD_INTERNAL_SATURATE_UNSIGNED +#define CANARD_INTERNAL_SATURATE_UNSIGNED(x, max) ( ((x) > max) ? max : (x) ); +#endif + + #define CANARD_INTERNAL_ENABLE_TAO ((uint8_t) 1) #define CANARD_INTERNAL_DISABLE_TAO ((uint8_t) 0) @@ -127,7 +132,11 @@ uint32_t ${type_name}_encode_internal(${type_name}* source, void* msg_buf, uint3 offset += ${f.bitlen}; %else %if f.saturate + %if f.signedness == 'true' source->${f.name} = CANARD_INTERNAL_SATURATE(source->${f.name}, ${f.max_size}) + %else + source->${f.name} = CANARD_INTERNAL_SATURATE_UNSIGNED(source->${f.name}, ${f.max_size}) + %endif %endif canardEncodeScalar(msg_buf, offset, ${f.bitlen}, (void*)&source->${f.name}); // ${f.max_size} offset += ${f.bitlen}; From 00f4f6713462ec61cf098f7444b8bd4b91ac55fb Mon Sep 17 00:00:00 2001 From: Damien Espitallier Date: Thu, 1 Nov 2018 11:57:31 +0100 Subject: [PATCH 50/81] Fix issue with service constants in dsdl compiler --- dsdl_compiler/libcanard_dsdl_compiler/data_type_template.tmpl | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/dsdl_compiler/libcanard_dsdl_compiler/data_type_template.tmpl b/dsdl_compiler/libcanard_dsdl_compiler/data_type_template.tmpl index 91916666..50a1738c 100644 --- a/dsdl_compiler/libcanard_dsdl_compiler/data_type_template.tmpl +++ b/dsdl_compiler/libcanard_dsdl_compiler/data_type_template.tmpl @@ -56,7 +56,7 @@ ${line} // Constants % for a in constants: -#define ${'%-60s %10s' % (t.macro_name + '_' + a.name, a.init_expression, )} // ${a.init_expression} +#define ${'%-60s %10s' % (t.macro_name + service + '_' + a.name, a.init_expression, )} // ${a.init_expression} % endfor % for a in fields: From e257a5482b81fe958f9164b535db3468793323e0 Mon Sep 17 00:00:00 2001 From: Damien Espitallier Date: Sat, 3 Nov 2018 08:54:47 +0100 Subject: [PATCH 51/81] remove extra blank line --- dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl | 1 - 1 file changed, 1 deletion(-) diff --git a/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl b/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl index 2deefa22..3c860bcf 100644 --- a/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl +++ b/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl @@ -18,7 +18,6 @@ #define CANARD_INTERNAL_SATURATE_UNSIGNED(x, max) ( ((x) > max) ? max : (x) ); #endif - #define CANARD_INTERNAL_ENABLE_TAO ((uint8_t) 1) #define CANARD_INTERNAL_DISABLE_TAO ((uint8_t) 0) From e1e8bcbada74e4c25619154b9dc7ce6eebcbe183 Mon Sep 17 00:00:00 2001 From: Damien Espitallier Date: Sat, 3 Nov 2018 09:06:28 +0100 Subject: [PATCH 52/81] format template code for 120 lines maximum --- .../code_type_template.tmpl | 77 +++++++++++++++---- 1 file changed, 63 insertions(+), 14 deletions(-) diff --git a/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl b/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl index 3c860bcf..f9cb82e8 100644 --- a/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl +++ b/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl @@ -39,7 +39,10 @@ * @param root_item: for detecting if TAO should be used * @retval returns offset */ -uint32_t ${type_name}_encode_internal(${type_name}* source, void* msg_buf, uint32_t offset, uint8_t CANARD_MAYBE_UNUSED(root_item)) +uint32_t ${type_name}_encode_internal(${type_name}* source, + void* msg_buf, + uint32_t offset, + uint8_t CANARD_MAYBE_UNUSED(root_item)) { %if union // Max Union Tag Value @@ -98,7 +101,10 @@ uint32_t ${type_name}_encode_internal(${type_name}* source, void* msg_buf, uint3 %if f.cpp_type_category == t.CATEGORY_COMPOUND: offset += ${f.cpp_type}_encode_internal((void*)&source->${'%s' % ((f.name + '.data'))}[c], msg_buf, offset, 0); %else - canardEncodeScalar(msg_buf, offset, ${f.bitlen}, (void*)(source->${'%s' % ((f.name + '.data'))} + c));// ${f.max_size} + canardEncodeScalar(msg_buf, + offset, + ${f.bitlen}, + (void*)(source->${'%s' % ((f.name + '.data'))} + c));// ${f.max_size} offset += ${f.bitlen}; %endif } @@ -176,7 +182,13 @@ uint32_t ${type_name}_encode(${type_name}* source, void* msg_buf) * @param tao: is tail array optimization used * @retval offset or ERROR value if < 0 */ -int32_t ${type_name}_decode_internal(const CanardRxTransfer* transfer, uint16_t CANARD_MAYBE_UNUSED(payload_len), ${type_name}* dest, uint8_t** CANARD_MAYBE_UNUSED(dyn_arr_buf), int32_t offset, uint8_t CANARD_MAYBE_UNUSED(tao)) +int32_t ${type_name}_decode_internal( + const CanardRxTransfer* transfer, + uint16_t CANARD_MAYBE_UNUSED(payload_len), + ${type_name}* dest, + uint8_t** CANARD_MAYBE_UNUSED(dyn_arr_buf), + int32_t offset, + uint8_t CANARD_MAYBE_UNUSED(tao)) { int32_t ret = 0; %if has_array @@ -222,7 +234,11 @@ int32_t ${type_name}_decode_internal(const CanardRxTransfer* transfer, uint16_t else { // - Array length ${f.array_max_size_bit_len} bits - ret = canardDecodeScalar(transfer, offset, ${f.array_max_size_bit_len}, false, (void*)&dest->${'%s' % ((f.name + '.len'))}); // ${f.max_size} + ret = canardDecodeScalar(transfer, + offset, + ${f.array_max_size_bit_len}, + false, + (void*)&dest->${'%s' % ((f.name + '.len'))}); // ${f.max_size} if (ret != ${f.array_max_size_bit_len}) { goto ${type_name}_error_exit; @@ -230,7 +246,11 @@ int32_t ${type_name}_decode_internal(const CanardRxTransfer* transfer, uint16_t offset += ${f.array_max_size_bit_len}; } %else - ret = canardDecodeScalar(transfer, offset, ${f.array_max_size_bit_len}, false, (void*)&dest->${'%s' % ((f.name + '.len'))}); // ${f.max_size} + ret = canardDecodeScalar(transfer, + offset, + ${f.array_max_size_bit_len}, + false, + (void*)&dest->${'%s' % ((f.name + '.len'))}); // ${f.max_size} if (ret != ${f.array_max_size_bit_len}) { goto ${type_name}_error_exit; @@ -239,7 +259,11 @@ int32_t ${type_name}_decode_internal(const CanardRxTransfer* transfer, uint16_t %endif %else // - Array length, not last item ${f.array_max_size_bit_len} bits - ret = canardDecodeScalar(transfer, offset, ${f.array_max_size_bit_len}, false, (void*)&dest->${'%s' % ((f.name + '.len'))}); // ${f.max_size} + ret = canardDecodeScalar(transfer, + offset, + ${f.array_max_size_bit_len}, + false, + (void*)&dest->${'%s' % ((f.name + '.len'))}); // ${f.max_size} if (ret != ${f.array_max_size_bit_len}) { goto ${type_name}_error_exit; @@ -256,11 +280,20 @@ int32_t ${type_name}_decode_internal(const CanardRxTransfer* transfer, uint16_t for (c = 0; c < dest->${'%s' % ((f.name + '.len'))}; c++) { %if f.cpp_type_category == t.CATEGORY_COMPOUND: - offset += ${f.cpp_type}_decode_internal(transfer, 0, (void*)&dest->${'%s' % ((f.name + '.data'))}[c], dyn_arr_buf, offset, tao); + offset += ${f.cpp_type}_decode_internal(transfer, + 0, + (void*)&dest->${'%s' % ((f.name + '.data'))}[c], + dyn_arr_buf, + offset, + tao); %else if (dyn_arr_buf) { - ret = canardDecodeScalar(transfer, offset, ${f.bitlen}, ${f.signedness}, (void*)*dyn_arr_buf); // ${f.max_size} + ret = canardDecodeScalar(transfer, + offset, + ${f.bitlen}, + ${f.signedness}, + (void*)*dyn_arr_buf); // ${f.max_size} if (ret != ${f.bitlen}) { goto ${type_name}_error_exit; @@ -347,7 +380,10 @@ ${type_name}_error_exit: * NULL will ignore dynamic arrays decoding. * @retval offset or ERROR value if < 0 */ -int32_t ${type_name}_decode(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name}* dest, uint8_t** dyn_arr_buf) +int32_t ${type_name}_decode(const CanardRxTransfer* transfer, + uint16_t payload_len, + ${type_name}* dest, + uint8_t** dyn_arr_buf) { const int32_t offset = 0; int32_t ret = 0; @@ -383,7 +419,10 @@ int32_t ${type_name}_decode(const CanardRxTransfer* transfer, uint16_t payload_l return ret; } %else -uint32_t ${type_name}_encode_internal(${type_name}* CANARD_MAYBE_UNUSED(source), void* CANARD_MAYBE_UNUSED(msg_buf), uint32_t offset, uint8_t CANARD_MAYBE_UNUSED(root_item)) +uint32_t ${type_name}_encode_internal(${type_name}* CANARD_MAYBE_UNUSED(source), + void* CANARD_MAYBE_UNUSED(msg_buf), + uint32_t offset, + uint8_t CANARD_MAYBE_UNUSED(root_item)) { return offset; } @@ -393,12 +432,20 @@ uint32_t ${type_name}_encode(${type_name}* CANARD_MAYBE_UNUSED(source), void* CA return 0; } -int32_t ${type_name}_decode_internal(const CanardRxTransfer* CANARD_MAYBE_UNUSED(transfer), uint16_t CANARD_MAYBE_UNUSED(payload_len), ${type_name}* CANARD_MAYBE_UNUSED(dest), uint8_t** CANARD_MAYBE_UNUSED(dyn_arr_buf), int32_t offset, uint8_t CANARD_MAYBE_UNUSED(tao)) +int32_t ${type_name}_decode_internal(const CanardRxTransfer* CANARD_MAYBE_UNUSED(transfer), + uint16_t CANARD_MAYBE_UNUSED(payload_len), + ${type_name}* CANARD_MAYBE_UNUSED(dest), + uint8_t** CANARD_MAYBE_UNUSED(dyn_arr_buf), + int32_t offset, + uint8_t CANARD_MAYBE_UNUSED(tao)) { return offset; } -int32_t ${type_name}_decode(const CanardRxTransfer* CANARD_MAYBE_UNUSED(transfer), uint16_t CANARD_MAYBE_UNUSED(payload_len), ${type_name}* CANARD_MAYBE_UNUSED(dest), uint8_t** CANARD_MAYBE_UNUSED(dyn_arr_buf)) +int32_t ${type_name}_decode(const CanardRxTransfer* CANARD_MAYBE_UNUSED(transfer), + uint16_t CANARD_MAYBE_UNUSED(payload_len), + ${type_name}* CANARD_MAYBE_UNUSED(dest), + uint8_t** CANARD_MAYBE_UNUSED(dyn_arr_buf)) { return 0; } @@ -406,12 +453,14 @@ int32_t ${type_name}_decode(const CanardRxTransfer* CANARD_MAYBE_UNUSED(transfer % if t.kind == t.KIND_SERVICE: -${generate_primary_body(type_name=t.name_space_type_name+'Request', service='_REQUEST', max_bitlen=t.get_max_bitlen_request(), \ +${generate_primary_body(type_name=t.name_space_type_name+'Request',\ + service='_REQUEST', imax_bitlen=t.get_max_bitlen_request(), \ fields=t.request_fields, constants=t.request_constants, \ union=t.request_union, has_array=t.request_has_array, \ has_float16=t.request_has_float16)} -${generate_primary_body(type_name=t.name_space_type_name+'Response', service='_RESPONSE', max_bitlen=t.get_max_bitlen_response(), \ +${generate_primary_body(type_name=t.name_space_type_name+'Response',\ + service='_RESPONSE', max_bitlen=t.get_max_bitlen_response(), \ fields=t.response_fields, constants=t.response_constants, \ union=t.response_union, has_array=t.response_has_array, \ has_float16=t.response_has_float16)} From c4fabe28ddad0e73e9c2290606faa067cf7e6212 Mon Sep 17 00:00:00 2001 From: Damien Espitallier Date: Sat, 3 Nov 2018 09:08:31 +0100 Subject: [PATCH 53/81] fix typo on max_bitlen --- dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl b/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl index f9cb82e8..0177011f 100644 --- a/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl +++ b/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl @@ -454,7 +454,7 @@ int32_t ${type_name}_decode(const CanardRxTransfer* CANARD_MAYBE_UNUSED(transfer % if t.kind == t.KIND_SERVICE: ${generate_primary_body(type_name=t.name_space_type_name+'Request',\ - service='_REQUEST', imax_bitlen=t.get_max_bitlen_request(), \ + service='_REQUEST', max_bitlen=t.get_max_bitlen_request(), \ fields=t.request_fields, constants=t.request_constants, \ union=t.request_union, has_array=t.request_has_array, \ has_float16=t.request_has_float16)} From b35c32a794b4dfe09946af5ac091bc915df33b0a Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Adolfo=20E=2E=20Garc=C3=ADa?= Date: Mon, 10 Dec 2018 15:57:03 -0600 Subject: [PATCH 54/81] Add the option to allow the user to provide an overrides header file The user should define the "CANARD_ENABLE_CUSTOM_BUILD_CONFIG" flag and provide the file "canard_build_config.h". --- README.md | 2 ++ canard.h | 7 ++++++- 2 files changed, 8 insertions(+), 1 deletion(-) diff --git a/README.md b/README.md index 03fc8cd1..6e073dc9 100644 --- a/README.md +++ b/README.md @@ -30,6 +30,8 @@ and you're ready to roll. Also you may want to use one of the available drivers for various CAN backends that are distributed with Libcanard - check out the `drivers/` directory to find out more. +If you wish to override some of the default options, e.g., assert macros' definition, use the `-D CANARD_ENABLE_CUSTOM_BUILD_CONFIG` flag and provide your implementation in a file named `canard_build_config.h`. + Example for Make: ```make diff --git a/canard.h b/canard.h index 745911a7..bb96d142 100644 --- a/canard.h +++ b/canard.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2016-2017 UAVCAN Team + * Copyright (c) 2016-2018 UAVCAN Team * * Permission is hereby granted, free of charge, to any person obtaining a copy * of this software and associated documentation files (the "Software"), to deal @@ -32,6 +32,11 @@ #include #include +/// Build configuration header. Use it to provide your overrides. +#ifdef CANARD_ENABLE_CUSTOM_BUILD_CONFIG +# include "canard_build_config.h" +#endif + #ifdef __cplusplus extern "C" { #endif From c307f1920c02e1b6c269788597771c650e47d3f1 Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Tue, 11 Dec 2018 14:40:18 +0200 Subject: [PATCH 55/81] README update; CANARD_ENABLE_CUSTOM_BUILD_CONFIG check replaced with #if --- README.md | 7 +++++-- canard.h | 2 +- 2 files changed, 6 insertions(+), 3 deletions(-) diff --git a/README.md b/README.md index 6e073dc9..277387c0 100644 --- a/README.md +++ b/README.md @@ -1,7 +1,7 @@ # Libcanard +[![Forum](https://img.shields.io/discourse/https/forum.uavcan.org/users.svg)](https://forum.uavcan.org) [![Build Status](https://travis-ci.org/UAVCAN/libcanard.svg?branch=master)](https://travis-ci.org/UAVCAN/libcanard) [![Coverity Scan](https://scan.coverity.com/projects/uavcan-libcanard/badge.svg)](https://scan.coverity.com/projects/uavcan-libcanard) -[![Gitter](https://img.shields.io/badge/gitter-join%20chat-green.svg)](https://gitter.im/UAVCAN/general) Minimal implementation of the UAVCAN protocol stack in C for resource constrained applications. @@ -30,7 +30,10 @@ and you're ready to roll. Also you may want to use one of the available drivers for various CAN backends that are distributed with Libcanard - check out the `drivers/` directory to find out more. -If you wish to override some of the default options, e.g., assert macros' definition, use the `-D CANARD_ENABLE_CUSTOM_BUILD_CONFIG` flag and provide your implementation in a file named `canard_build_config.h`. +If you wish to override some of the default options, e.g., assert macros' definition, +define the macro `CANARD_ENABLE_CUSTOM_BUILD_CONFIG` as a non-zero value +(e.g. for GCC or Clang: `-DCANARD_ENABLE_CUSTOM_BUILD_CONFIG=1`) +and provide your implementation in a file named `canard_build_config.h`. Example for Make: diff --git a/canard.h b/canard.h index bb96d142..9edd9abf 100644 --- a/canard.h +++ b/canard.h @@ -33,7 +33,7 @@ #include /// Build configuration header. Use it to provide your overrides. -#ifdef CANARD_ENABLE_CUSTOM_BUILD_CONFIG +#if CANARD_ENABLE_CUSTOM_BUILD_CONFIG # include "canard_build_config.h" #endif From 65ea2be5343e83c6327d20ee5c82d03f4b22d55a Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Tue, 11 Dec 2018 17:17:50 +0200 Subject: [PATCH 56/81] Warning fix & CI fix --- canard.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/canard.h b/canard.h index 9edd9abf..dcdbd5dc 100644 --- a/canard.h +++ b/canard.h @@ -33,7 +33,7 @@ #include /// Build configuration header. Use it to provide your overrides. -#if CANARD_ENABLE_CUSTOM_BUILD_CONFIG +#if defined(CANARD_ENABLE_CUSTOM_BUILD_CONFIG) && CANARD_ENABLE_CUSTOM_BUILD_CONFIG # include "canard_build_config.h" #endif From 067898534469a8511c8e480959eb47cfe9e80a8e Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 5 Jan 2019 15:32:13 +1100 Subject: [PATCH 57/81] dsdlc_compiler: fixed building of headers with C++ this removes the void* cast when calling encode_internal and decode_internal for compounts. The void* cast causes a -fpermissive error when built with C++ --- dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl b/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl index 0177011f..83ec47e6 100644 --- a/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl +++ b/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl @@ -124,7 +124,7 @@ uint32_t ${type_name}_encode_internal(${type_name}* source, %elif f.type_category == t.CATEGORY_COMPOUND: // Compound - offset = ${f.cpp_type}_encode_internal((void*)&source->${f.name}, msg_buf, offset, 0); + offset = ${f.cpp_type}_encode_internal(&source->${f.name}, msg_buf, offset, 0); %elif f.type_category == t.CATEGORY_PRIMITIVE and f.cpp_type == "float" and f.bitlen == 16: // float16 special handling @@ -323,7 +323,7 @@ int32_t ${type_name}_decode_internal( %elif f.type_category == t.CATEGORY_COMPOUND: // Compound - offset = ${f.cpp_type}_decode_internal(transfer, 0, (void*)&dest->${f.name}, dyn_arr_buf, offset, tao); + offset = ${f.cpp_type}_decode_internal(transfer, 0, &dest->${f.name}, dyn_arr_buf, offset, tao); if (offset < 0) { ret = offset; From 1714dd491379d5e5a1b988c460b8aed485f3cbd6 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 15 Jan 2019 11:34:26 +1100 Subject: [PATCH 58/81] dsdl_compiler: removed non-TAO v0 support --- .../code_type_template.tmpl | 47 ++++--------------- .../data_type_template.tmpl | 4 +- 2 files changed, 12 insertions(+), 39 deletions(-) diff --git a/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl b/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl index 83ec47e6..b917f3df 100644 --- a/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl +++ b/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl @@ -18,9 +18,6 @@ #define CANARD_INTERNAL_SATURATE_UNSIGNED(x, max) ( ((x) > max) ? max : (x) ); #endif -#define CANARD_INTERNAL_ENABLE_TAO ((uint8_t) 1) -#define CANARD_INTERNAL_DISABLE_TAO ((uint8_t) 0) - #if defined(__GNUC__) # define CANARD_MAYBE_UNUSED(x) x __attribute__((unused)) #else @@ -179,7 +176,6 @@ uint32_t ${type_name}_encode(${type_name}* source, void* msg_buf) * ${type_name} dyn memory will point to dyn_arr_buf memory. * NULL will ignore dynamic arrays decoding. * @param offset: Call with 0, bit offset to msg storage - * @param tao: is tail array optimization used * @retval offset or ERROR value if < 0 */ int32_t ${type_name}_decode_internal( @@ -187,8 +183,7 @@ int32_t ${type_name}_decode_internal( uint16_t CANARD_MAYBE_UNUSED(payload_len), ${type_name}* dest, uint8_t** CANARD_MAYBE_UNUSED(dyn_arr_buf), - int32_t offset, - uint8_t CANARD_MAYBE_UNUSED(tao)) + int32_t offset) { int32_t ret = 0; %if has_array @@ -226,7 +221,7 @@ int32_t ${type_name}_decode_internal( %if f.last_item %if f.bitlen > 7 // - Last item in struct & Root item & (Array Size > 8 bit), tail array optimization - if (payload_len && tao == CANARD_INTERNAL_ENABLE_TAO) + if (payload_len) { // - Calculate Array length from MSG length dest->${'%s' % ((f.name + '.len'))} = ((payload_len * 8) - offset ) / ${f.bitlen}; // ${f.bitlen} bit array item size @@ -284,8 +279,7 @@ int32_t ${type_name}_decode_internal( 0, (void*)&dest->${'%s' % ((f.name + '.data'))}[c], dyn_arr_buf, - offset, - tao); + offset); %else if (dyn_arr_buf) { @@ -323,7 +317,7 @@ int32_t ${type_name}_decode_internal( %elif f.type_category == t.CATEGORY_COMPOUND: // Compound - offset = ${f.cpp_type}_decode_internal(transfer, 0, &dest->${f.name}, dyn_arr_buf, offset, tao); + offset = ${f.cpp_type}_decode_internal(transfer, 0, &dest->${f.name}, dyn_arr_buf, offset); if (offset < 0) { ret = offset; @@ -388,34 +382,14 @@ int32_t ${type_name}_decode(const CanardRxTransfer* transfer, const int32_t offset = 0; int32_t ret = 0; - /* Backward compatibility support for removing TAO - * - first try to decode with TAO DISABLED - * - if it fails fall back to TAO ENABLED - */ - uint8_t tao = CANARD_INTERNAL_DISABLE_TAO; - - while (1) + // Clear the destination struct + for (uint32_t c = 0; c < sizeof(${type_name}); c++) { - // Clear the destination struct - for (uint32_t c = 0; c < sizeof(${type_name}); c++) - { - ((uint8_t*)dest)[c] = 0x00; - } - - ret = ${type_name}_decode_internal(transfer, payload_len, dest, dyn_arr_buf, offset, tao); - - if (ret >= 0) - { - break; - } - - if (tao == CANARD_INTERNAL_ENABLE_TAO) - { - break; - } - tao = CANARD_INTERNAL_ENABLE_TAO; + ((uint8_t*)dest)[c] = 0x00; } + ret = ${type_name}_decode_internal(transfer, payload_len, dest, dyn_arr_buf, offset); + return ret; } %else @@ -436,8 +410,7 @@ int32_t ${type_name}_decode_internal(const CanardRxTransfer* CANARD_MAYBE_UNUSED uint16_t CANARD_MAYBE_UNUSED(payload_len), ${type_name}* CANARD_MAYBE_UNUSED(dest), uint8_t** CANARD_MAYBE_UNUSED(dyn_arr_buf), - int32_t offset, - uint8_t CANARD_MAYBE_UNUSED(tao)) + int32_t offset) { return offset; } diff --git a/dsdl_compiler/libcanard_dsdl_compiler/data_type_template.tmpl b/dsdl_compiler/libcanard_dsdl_compiler/data_type_template.tmpl index 50a1738c..c4006e4f 100644 --- a/dsdl_compiler/libcanard_dsdl_compiler/data_type_template.tmpl +++ b/dsdl_compiler/libcanard_dsdl_compiler/data_type_template.tmpl @@ -120,7 +120,7 @@ typedef struct @!storage_class!@int32_t ${type_name}_decode(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name}* dest, uint8_t** dyn_arr_buf); @!storage_class!@uint32_t ${type_name}_encode_internal(${type_name}* source, void* msg_buf, uint32_t offset, uint8_t root_item); -@!storage_class!@int32_t ${type_name}_decode_internal(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name}* dest, uint8_t** dyn_arr_buf, int32_t offset, uint8_t tao); +@!storage_class!@int32_t ${type_name}_decode_internal(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name}* dest, uint8_t** dyn_arr_buf, int32_t offset); %else typedef struct { @@ -129,7 +129,7 @@ typedef struct @!storage_class!@uint32_t ${type_name}_encode(${type_name}* source, void* msg_buf); @!storage_class!@int32_t ${type_name}_decode(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name}* dest, uint8_t** dyn_arr_buf); @!storage_class!@uint32_t ${type_name}_encode_internal(${type_name}* source, void* msg_buf, uint32_t offset, uint8_t root_item); -@!storage_class!@int32_t ${type_name}_decode_internal(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name}* dest, uint8_t** dyn_arr_buf, int32_t offset, uint8_t tao); +@!storage_class!@int32_t ${type_name}_decode_internal(const CanardRxTransfer* transfer, uint16_t payload_len, ${type_name}* dest, uint8_t** dyn_arr_buf, int32_t offset); %endif From fc763e4fef122f70c118676ce7bda1c89ac63794 Mon Sep 17 00:00:00 2001 From: David Lenfesty <6893214+davidlenfesty@users.noreply.github.com> Date: Thu, 31 Jan 2019 12:58:53 -0700 Subject: [PATCH 59/81] Added STM32F303 as a tested MCU. I have personally verified CAN1 to be fully functional on the F303 series. --- drivers/stm32/README.md | 1 + 1 file changed, 1 insertion(+) diff --git a/drivers/stm32/README.md b/drivers/stm32/README.md index 685cfa0c..9f821823 100644 --- a/drivers/stm32/README.md +++ b/drivers/stm32/README.md @@ -11,6 +11,7 @@ So far this driver has been tested at least with the following MCU: * STM32F105 - both CAN1 and CAN2 * STM32F446 +* STM32F303 - Only CAN1 verified * Please extend this list if you used it with other MCU. ## Features From 016a6efd80f1c1842154141852bc6f6d2cd41568 Mon Sep 17 00:00:00 2001 From: spiremike Date: Sun, 3 Feb 2019 12:20:24 +0000 Subject: [PATCH 60/81] Calculate max size of boolean as unsigned --- dsdl_compiler/libcanard_dsdl_compiler/__init__.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/dsdl_compiler/libcanard_dsdl_compiler/__init__.py b/dsdl_compiler/libcanard_dsdl_compiler/__init__.py index 9b661280..f4411716 100644 --- a/dsdl_compiler/libcanard_dsdl_compiler/__init__.py +++ b/dsdl_compiler/libcanard_dsdl_compiler/__init__.py @@ -217,7 +217,7 @@ def type_to_c_type(t): 'post_cpp_type':'', 'cpp_type_comment':'bit len %d' % (t.bitlen, ), 'bitlen':t.bitlen, - 'max_size':get_max_size(t.bitlen, False), + 'max_size':get_max_size(t.bitlen, True), 'signedness':signedness, 'saturate':saturate} else: From 08286a350f6d2a2a80475f4c24348b9db830675f Mon Sep 17 00:00:00 2001 From: spiremike Date: Sun, 3 Feb 2019 12:21:20 +0000 Subject: [PATCH 61/81] Update saturations macro to use >= for comparison to avoid compiler warning --- dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl b/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl index b917f3df..9810f0e5 100644 --- a/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl +++ b/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl @@ -15,7 +15,7 @@ #endif #ifndef CANARD_INTERNAL_SATURATE_UNSIGNED -#define CANARD_INTERNAL_SATURATE_UNSIGNED(x, max) ( ((x) > max) ? max : (x) ); +#define CANARD_INTERNAL_SATURATE_UNSIGNED(x, max) ( ((x) >= max) ? max : (x) ); #endif #if defined(__GNUC__) From 58e676f905f28e6b7da09ce62e023f5bb0305697 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Adolfo=20E=2E=20Garc=C3=ADa?= Date: Mon, 4 Feb 2019 00:09:18 -0600 Subject: [PATCH 62/81] Add explicit cast to silence compiler warning --- .../code_type_template.tmpl | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl b/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl index 9810f0e5..034075e3 100644 --- a/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl +++ b/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl @@ -199,7 +199,7 @@ int32_t ${type_name}_decode_internal( %if union: // Get Union Tag - ret = canardDecodeScalar(transfer, offset, ${union}, false, (void*)&dest->union_tag); // ${union} + ret = canardDecodeScalar(transfer, (uint32_t)offset, ${union}, false, (void*)&dest->union_tag); // ${union} if (ret != ${union}) { goto ${type_name}_error_exit; @@ -230,7 +230,7 @@ int32_t ${type_name}_decode_internal( { // - Array length ${f.array_max_size_bit_len} bits ret = canardDecodeScalar(transfer, - offset, + (uint32_t)offset, ${f.array_max_size_bit_len}, false, (void*)&dest->${'%s' % ((f.name + '.len'))}); // ${f.max_size} @@ -242,7 +242,7 @@ int32_t ${type_name}_decode_internal( } %else ret = canardDecodeScalar(transfer, - offset, + (uint32_t)offset, ${f.array_max_size_bit_len}, false, (void*)&dest->${'%s' % ((f.name + '.len'))}); // ${f.max_size} @@ -255,7 +255,7 @@ int32_t ${type_name}_decode_internal( %else // - Array length, not last item ${f.array_max_size_bit_len} bits ret = canardDecodeScalar(transfer, - offset, + (uint32_t)offset, ${f.array_max_size_bit_len}, false, (void*)&dest->${'%s' % ((f.name + '.len'))}); // ${f.max_size} @@ -284,7 +284,7 @@ int32_t ${type_name}_decode_internal( if (dyn_arr_buf) { ret = canardDecodeScalar(transfer, - offset, + (uint32_t)offset, ${f.bitlen}, ${f.signedness}, (void*)*dyn_arr_buf); // ${f.max_size} @@ -302,7 +302,7 @@ int32_t ${type_name}_decode_internal( // Static array (${f.name}) for (c = 0; c < ${f.array_size}; c++) { - ret = canardDecodeScalar(transfer, offset, ${f.bitlen}, ${f.signedness}, (void*)(dest->${f.name} + c)); + ret = canardDecodeScalar(transfer, (uint32_t)offset, ${f.bitlen}, ${f.signedness}, (void*)(dest->${f.name} + c)); if (ret != ${f.bitlen}) { goto ${type_name}_error_exit; @@ -326,7 +326,7 @@ int32_t ${type_name}_decode_internal( %elif f.type_category == t.CATEGORY_PRIMITIVE and f.cpp_type == "float" and f.bitlen == 16: // float16 special handling - ret = canardDecodeScalar(transfer, offset, ${f.bitlen}, ${f.signedness}, (void*)&tmp_float); + ret = canardDecodeScalar(transfer, (uint32_t)offset, ${f.bitlen}, ${f.signedness}, (void*)&tmp_float); if (ret != ${f.bitlen}) { @@ -340,7 +340,7 @@ int32_t ${type_name}_decode_internal( offset += ${f.bitlen}; %else - ret = canardDecodeScalar(transfer, offset, ${f.bitlen}, ${f.signedness}, (void*)&dest->${f.name}); + ret = canardDecodeScalar(transfer, (uint32_t)offset, ${f.bitlen}, ${f.signedness}, (void*)&dest->${f.name}); if (ret != ${f.bitlen}) { goto ${type_name}_error_exit; From 30f789532f9ac5c316f8bec3ab07cebc9076916d Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Adolfo=20E=2E=20Garc=C3=ADa?= Date: Mon, 4 Feb 2019 00:10:28 -0600 Subject: [PATCH 63/81] Add STM32F091 to the list of supported MCUs --- drivers/stm32/README.md | 1 + 1 file changed, 1 insertion(+) diff --git a/drivers/stm32/README.md b/drivers/stm32/README.md index 9f821823..db53b250 100644 --- a/drivers/stm32/README.md +++ b/drivers/stm32/README.md @@ -9,6 +9,7 @@ In theory, the entire family of STM32 should be supported by this driver, since they all share the same CAN controller IP known as bxCAN. So far this driver has been tested at least with the following MCU: +* STM32F091 * STM32F105 - both CAN1 and CAN2 * STM32F446 * STM32F303 - Only CAN1 verified From 16abaffc8918bba83a08ed59098f8cd9617b9fa0 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?=C3=85smund=20Eek?= Date: Thu, 21 Feb 2019 14:56:55 +0100 Subject: [PATCH 64/81] Fix bug with decoding of compound structs --- dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl b/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl index 034075e3..bf5476d4 100644 --- a/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl +++ b/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl @@ -317,7 +317,7 @@ int32_t ${type_name}_decode_internal( %elif f.type_category == t.CATEGORY_COMPOUND: // Compound - offset = ${f.cpp_type}_decode_internal(transfer, 0, &dest->${f.name}, dyn_arr_buf, offset); + offset = ${f.cpp_type}_decode_internal(transfer, transfer_len, &dest->${f.name}, dyn_arr_buf, offset); if (offset < 0) { ret = offset; From 03bb805ec2742f120c1f26a0d40a38cd47dc8e7d Mon Sep 17 00:00:00 2001 From: aasmune Date: Mon, 25 Feb 2019 19:49:32 +0100 Subject: [PATCH 65/81] Fixed bug introduced in last commit where an undeclared variable were used in auto generation of code. --- dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl b/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl index bf5476d4..ca8c09fb 100644 --- a/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl +++ b/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl @@ -317,7 +317,7 @@ int32_t ${type_name}_decode_internal( %elif f.type_category == t.CATEGORY_COMPOUND: // Compound - offset = ${f.cpp_type}_decode_internal(transfer, transfer_len, &dest->${f.name}, dyn_arr_buf, offset); + offset = ${f.cpp_type}_decode_internal(transfer, payload_len, &dest->${f.name}, dyn_arr_buf, offset); if (offset < 0) { ret = offset; From e928aef4b1d6f8968147d422c26ca4dc01e54368 Mon Sep 17 00:00:00 2001 From: mike7c2 Date: Thu, 28 Feb 2019 20:35:43 +0000 Subject: [PATCH 66/81] Add error reporting for canardHandleRxFrame, address comments from #90 --- canard.c | 41 +++-- canard.h | 22 ++- tests/test_rxerr.cpp | 374 +++++++++++++++++++++++++++++++++++++++++++ 3 files changed, 415 insertions(+), 22 deletions(-) create mode 100644 tests/test_rxerr.cpp diff --git a/canard.c b/canard.c index 4efd01c6..ece6c42c 100644 --- a/canard.c +++ b/canard.c @@ -248,7 +248,7 @@ void canardPopTxQueue(CanardInstance* ins) freeBlock(&ins->allocator, item); } -void canardHandleRxFrame(CanardInstance* ins, const CanardCANFrame* frame, uint64_t timestamp_usec) +int16_t canardHandleRxFrame(CanardInstance* ins, const CanardCANFrame* frame, uint64_t timestamp_usec) { const CanardTransferType transfer_type = extractTransferType(frame->id); const uint8_t destination_node_id = (transfer_type == CanardTransferTypeBroadcast) ? @@ -262,13 +262,13 @@ void canardHandleRxFrame(CanardInstance* ins, const CanardCANFrame* frame, uint6 (frame->id & CANARD_CAN_FRAME_ERR) != 0 || (frame->data_len < 1)) { - return; // Unsupported frame, not UAVCAN - ignore + return -CANARD_ERROR_RX_INCOMPATIBLE_PACKET; } if (transfer_type != CanardTransferTypeBroadcast && destination_node_id != canardGetLocalNodeID(ins)) { - return; // Address mismatch + return -CANARD_ERROR_RX_WRONG_ADDRESS; } const uint8_t priority = PRIORITY_FROM_ID(frame->id); @@ -291,14 +291,14 @@ void canardHandleRxFrame(CanardInstance* ins, const CanardCANFrame* frame, uint6 if(rx_state == NULL) { - return; // No allocator room for this frame + return -CANARD_ERROR_OUT_OF_MEMORY; } rx_state->calculated_crc = crcAddSignature(0xFFFFU, data_type_signature); } else { - return; // The application doesn't want this transfer + return -CANARD_ERROR_RX_NOT_WANTED; } } else @@ -307,7 +307,7 @@ void canardHandleRxFrame(CanardInstance* ins, const CanardCANFrame* frame, uint6 if (rx_state == NULL) { - return; + return -CANARD_ERROR_RX_MISSED_START; } } @@ -330,10 +330,10 @@ void canardHandleRxFrame(CanardInstance* ins, const CanardCANFrame* frame, uint6 rx_state->transfer_id = TRANSFER_ID_FROM_TAIL_BYTE(tail_byte); rx_state->next_toggle = 0; releaseStatePayload(ins, rx_state); - if (!IS_START_OF_TRANSFER(tail_byte)) // missed the first frame + if (!IS_START_OF_TRANSFER(tail_byte)) { rx_state->transfer_id++; - return; + return -CANARD_ERROR_RX_MISSED_START; } } @@ -354,24 +354,24 @@ void canardHandleRxFrame(CanardInstance* ins, const CanardCANFrame* frame, uint6 ins->on_reception(ins, &rx_transfer); prepareForNextTransfer(rx_state); - return; + return CANARD_OK; } if (TOGGLE_BIT(tail_byte) != rx_state->next_toggle) { - return; // wrong toggle + return -CANARD_ERROR_RX_WRONG_TOGGLE; } if (TRANSFER_ID_FROM_TAIL_BYTE(tail_byte) != rx_state->transfer_id) { - return; // unexpected tid + return -CANARD_ERROR_RX_UNEXPECTED_TID; } if (IS_START_OF_TRANSFER(tail_byte) && !IS_END_OF_TRANSFER(tail_byte)) // Beginning of multi frame transfer { if (frame->data_len <= 3) { - return; // Not enough data + return -CANARD_ERROR_RX_SHORT_FRAME; } // take off the crc and store the payload @@ -382,7 +382,7 @@ void canardHandleRxFrame(CanardInstance* ins, const CanardCANFrame* frame, uint6 { releaseStatePayload(ins, rx_state); prepareForNextTransfer(rx_state); - return; + return CANARD_ERROR_OUT_OF_MEMORY; } rx_state->payload_crc = (uint16_t)(((uint16_t) frame->data[0]) | (uint16_t)((uint16_t) frame->data[1] << 8U)); rx_state->calculated_crc = crcAdd((uint16_t)rx_state->calculated_crc, @@ -396,7 +396,7 @@ void canardHandleRxFrame(CanardInstance* ins, const CanardCANFrame* frame, uint6 { releaseStatePayload(ins, rx_state); prepareForNextTransfer(rx_state); - return; + return CANARD_ERROR_OUT_OF_MEMORY; } rx_state->calculated_crc = crcAdd((uint16_t)rx_state->calculated_crc, frame->data, (uint8_t)(frame->data_len - 1)); @@ -468,10 +468,19 @@ void canardHandleRxFrame(CanardInstance* ins, const CanardCANFrame* frame, uint6 // Making sure the payload is released even if the application didn't bother with it canardReleaseRxTransferPayload(ins, &rx_transfer); prepareForNextTransfer(rx_state); - return; + + if (rx_state->calculated_crc == rx_state->payload_crc) + { + return CANARD_OK; + } + else + { + return CANARD_ERROR_RX_BAD_CRC; + } } rx_state->next_toggle = rx_state->next_toggle ? 0 : 1; + return CANARD_OK; } void canardCleanupStaleTransfers(CanardInstance* ins, uint64_t current_time_usec) @@ -1120,7 +1129,7 @@ CANARD_INTERNAL CanardRxState* traverseRxStates(CanardInstance* ins, uint32_t tr if (states == NULL) // initialize CanardRxStates { states = createRxState(&ins->allocator, transfer_descriptor); - + if(states == NULL) { return NULL; diff --git a/canard.h b/canard.h index dcdbd5dc..ff8f8140 100644 --- a/canard.h +++ b/canard.h @@ -65,12 +65,20 @@ extern "C" { #endif /// Error code definitions; inverse of these values may be returned from API calls. -#define CANARD_OK 0 +#define CANARD_OK 0 // Value 1 is omitted intentionally, since -1 is often used in 3rd party code -#define CANARD_ERROR_INVALID_ARGUMENT 2 -#define CANARD_ERROR_OUT_OF_MEMORY 3 -#define CANARD_ERROR_NODE_ID_NOT_SET 4 -#define CANARD_ERROR_INTERNAL 9 +#define CANARD_ERROR_INVALID_ARGUMENT 2 +#define CANARD_ERROR_OUT_OF_MEMORY 3 +#define CANARD_ERROR_NODE_ID_NOT_SET 4 +#define CANARD_ERROR_INTERNAL 9 +#define CANARD_ERROR_RX_INCOMPATIBLE_PACKET 10 +#define CANARD_ERROR_RX_WRONG_ADDRESS 11 +#define CANARD_ERROR_RX_NOT_WANTED 12 +#define CANARD_ERROR_RX_MISSED_START 13 +#define CANARD_ERROR_RX_WRONG_TOGGLE 14 +#define CANARD_ERROR_RX_UNEXPECTED_TID 15 +#define CANARD_ERROR_RX_SHORT_FRAME 16 +#define CANARD_ERROR_RX_BAD_CRC 17 /// The size of a memory block in bytes. #define CANARD_MEM_BLOCK_SIZE 32U @@ -417,8 +425,10 @@ void canardPopTxQueue(CanardInstance* ins); /** * Processes a received CAN frame with a timestamp. * The application will call this function when it receives a new frame from the CAN bus. + * + * Return value will report any errors in decoding packets. */ -void canardHandleRxFrame(CanardInstance* ins, +int16_t canardHandleRxFrame(CanardInstance* ins, const CanardCANFrame* frame, uint64_t timestamp_usec); diff --git a/tests/test_rxerr.cpp b/tests/test_rxerr.cpp new file mode 100644 index 00000000..74850edf --- /dev/null +++ b/tests/test_rxerr.cpp @@ -0,0 +1,374 @@ +/* + * Copyright (c) 2016 UAVCAN Team + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in all + * copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE + * SOFTWARE. + * + * Contributors: https://github.com/UAVCAN/libcanard/contributors + */ + +#include +#include + +//Independent implementation of ID layout from https://uavcan.org/Specification/4._CAN_bus_transport_layer/ +#define CONSTRUCT_PRIO(prio) (((prio) & 0x1F) << 23) +#define CONSTRUCT_MTID(mtid) (((mtid) & 0xFFFF) << 8) +#define CONSTRUCT_SID(sid) (((sid) & 0x7F)) +#define CONSTRUCT_DISC(disc) (((disc) & 0x3FFF) << 10) +#define CONSTRUCT_DISC_MTID(mtid) (((mtid) & 0x3) << 8) +#define CONSTRUCT_STID(stid) (((stid) & 0xFF) << 16) +#define CONSTRUCT_DID(did) (((did) & 0x7F) << 8) +#define CONSTRUCT_REQUEST(request) (((request) & 0x1) << 15) + +#define CONSTRUCT_SNM_BIT (1 << 7) + +#define CONSTRUCT_ANON_MSG_ID(prio, disc, mtid, sid) (CONSTRUCT_PRIO(prio) | \ + CONSTRUCT_DISC_MTID(mtid) | \ + CONSTRUCT_DISC(disc) | \ + CONSTRUCT_SID(sid) \ + CANARD_CAN_FRAME_EFF) + +#define CONSTRUCT_MSG_ID(prio, mtid, sid) (CONSTRUCT_PRIO(prio) | \ + CONSTRUCT_MTID(mtid) | \ + CONSTRUCT_SID(sid) | \ + CANARD_CAN_FRAME_EFF) + +#define CONSTRUCT_SVC_ID(prio, stid, request, did, sid) (CONSTRUCT_PRIO(prio) | \ + CONSTRUCT_STID(stid) | \ + CONSTRUCT_REQUEST(request) | \ + CONSTRUCT_DID(did) | \ + CONSTRUCT_SID(sid) | \ + CONSTRUCT_SNM_BIT | \ + CANARD_CAN_FRAME_EFF) + +#define CONSTRUCT_START(start) (((start) & 0x1) << 7) +#define CONSTRUCT_END(end) (((end) & 0x1) << 6) +#define CONSTRUCT_TOGGLE(toggle) (((toggle) & 0x1) << 5) +#define CONSTRUCT_TID(tid) (((tid) & 0x1F)) + +#define CONSTRUCT_TAIL_BYTE(start, end, toggle, tid) (CONSTRUCT_START(start) | \ + CONSTRUCT_END(end) | \ + CONSTRUCT_TOGGLE(toggle) | \ + CONSTRUCT_TID(tid)) + +static bool g_should_accept = true; + +/** + * This callback is invoked by the library when a new message or request or response is received. + */ +static void onTransferReceived(CanardInstance* ins, + CanardRxTransfer* transfer) +{ + (void)ins; + (void)transfer; +} + +static bool shouldAcceptTransfer(const CanardInstance* ins, + uint64_t* out_data_type_signature, + uint16_t data_type_id, + CanardTransferType transfer_type, + uint8_t source_node_id) +{ + (void)ins; + (void)out_data_type_signature; + (void)data_type_id; + (void)transfer_type; + (void)source_node_id; + return g_should_accept; +} + +TEST_CASE("canardHandleRxFrame incompatible packet handling, Correctness") +{ + uint8_t canard_memory_pool[1024]; + CanardInstance canard; + CanardCANFrame frame; + int16_t err; + + //Setup frame data to be single frame transfer + frame.data[0] = CONSTRUCT_TAIL_BYTE(1, 1, 0, 0); + + canardInit(&canard, canard_memory_pool, sizeof(canard_memory_pool), + onTransferReceived, shouldAcceptTransfer, &canard); + g_should_accept = true; + + //Frame with good RTR/ERR/data_len bad EFF + frame.id = 0; + frame.data_len = 1; + err = canardHandleRxFrame(&canard, &frame, 1); + REQUIRE(-CANARD_ERROR_RX_INCOMPATIBLE_PACKET == err); + + //Frame with good EFF/ERR/data_len, bad RTR + frame.id = 0 | CANARD_CAN_FRAME_RTR | CANARD_CAN_FRAME_EFF; + frame.data_len = 1; + err = canardHandleRxFrame(&canard, &frame, 1); + REQUIRE(-CANARD_ERROR_RX_INCOMPATIBLE_PACKET == err); + + //Frame with good EFF/RTR/data_len, bad ERR + frame.id = 0 | CANARD_CAN_FRAME_ERR | CANARD_CAN_FRAME_EFF; + frame.data_len = 1; + err = canardHandleRxFrame(&canard, &frame, 1); + REQUIRE(-CANARD_ERROR_RX_INCOMPATIBLE_PACKET == err); + + //Frame with good EFF/RTR/ERR, bad data_len + frame.id = 0 | CANARD_CAN_FRAME_EFF; + frame.data_len = 0; + err = canardHandleRxFrame(&canard, &frame, 1); + REQUIRE(-CANARD_ERROR_RX_INCOMPATIBLE_PACKET == err); + + //Frame with good EFF/RTR/ERR/data_len + frame.id = 0 | CANARD_CAN_FRAME_EFF; + frame.data_len = 1; + err = canardHandleRxFrame(&canard, &frame, 1); + REQUIRE(CANARD_OK == err); +} + +TEST_CASE("canardHandleRxFrame wrong address handling, Correctness") +{ + uint8_t canard_memory_pool[1024]; + CanardInstance canard; + CanardCANFrame frame; + int16_t err; + + //Setup frame data to be single frame transfer + frame.data[0] = CONSTRUCT_TAIL_BYTE(1, 1, 0, 0); + + //Open canard to accept all transfers with a node ID of 20 + canardInit(&canard, canard_memory_pool, sizeof(canard_memory_pool), + onTransferReceived, shouldAcceptTransfer, &canard); + canardSetLocalNodeID(&canard, 20); + g_should_accept = true; + + //Send package with ID 24, should not be wanted + frame.id = CONSTRUCT_SVC_ID(0, 0, 1, 24, 0); + frame.data_len = 1; + err = canardHandleRxFrame(&canard, &frame, 1); + REQUIRE(-CANARD_ERROR_RX_WRONG_ADDRESS == err); + + //Send package with ID 20, should be OK + frame.id = 0 | CANARD_CAN_FRAME_EFF; //Set EFF + frame.id = CONSTRUCT_SVC_ID(0, 0, 1, 20, 0); + frame.data_len = 1; + err = canardHandleRxFrame(&canard, &frame, 1); + REQUIRE(CANARD_OK == err); +} + +TEST_CASE("canardHandleRxFrame shouldAccept handling, Correctness") +{ + uint8_t canard_memory_pool[1024]; + CanardInstance canard; + CanardCANFrame frame; + int16_t err; + + //Setup frame data to be single frame transfer + frame.data[0] = CONSTRUCT_TAIL_BYTE(1, 1, 0, 0); + + //Open canard to accept all transfers with a node ID of 20 + canardInit(&canard, canard_memory_pool, sizeof(canard_memory_pool), + onTransferReceived, shouldAcceptTransfer, &canard); + canardSetLocalNodeID(&canard, 20); + + //Send packet, don't accept + g_should_accept = false; + frame.id = CONSTRUCT_SVC_ID(0, 0, 1, 20, 0); + frame.data_len = 1; + err = canardHandleRxFrame(&canard, &frame, 1); + REQUIRE(-CANARD_ERROR_RX_NOT_WANTED == err); + + //Send packet, accept + g_should_accept = true; + frame.id = CONSTRUCT_SVC_ID(0, 0, 1, 20, 0); + frame.data_len = 1; + err = canardHandleRxFrame(&canard, &frame, 1); + REQUIRE(CANARD_OK == err); +} + +TEST_CASE("canardHandleRxFrame no state handling, Correctness") +{ + uint8_t canard_memory_pool[1024]; + CanardInstance canard; + CanardCANFrame frame; + int16_t err; + + g_should_accept = true; + + //Open canard to accept all transfers with a node ID of 20 + canardInit(&canard, canard_memory_pool, sizeof(canard_memory_pool), + onTransferReceived, shouldAcceptTransfer, &canard); + canardSetLocalNodeID(&canard, 20); + + //Not start or end of packet, should fail + frame.data[0] = CONSTRUCT_TAIL_BYTE(0, 0, 0, 0); + frame.id = CONSTRUCT_SVC_ID(0, 0, 1, 20, 0); + frame.data_len = 1; + err = canardHandleRxFrame(&canard, &frame, 1); + REQUIRE(-CANARD_ERROR_RX_MISSED_START == err); + + //End of packet, should fail + frame.data[0] = CONSTRUCT_TAIL_BYTE(0, 1, 0, 0); + frame.id = CONSTRUCT_SVC_ID(0, 0, 1, 20, 0); + frame.data_len = 1; + err = canardHandleRxFrame(&canard, &frame, 1); + REQUIRE(-CANARD_ERROR_RX_MISSED_START == err); + + //1 Frame packet, should pass + frame.data[0] = CONSTRUCT_TAIL_BYTE(1, 1, 0, 0); + frame.id = CONSTRUCT_SVC_ID(0, 0, 1, 20, 0); + frame.data_len = 1; + err = canardHandleRxFrame(&canard, &frame, 1); + REQUIRE(CANARD_OK == err); + + //Send a start packet, should pass + frame.data[7] = CONSTRUCT_TAIL_BYTE(1, 0, 0, 1); + + frame.id = CONSTRUCT_SVC_ID(0, 0, 1, 20, 0); + frame.data_len = 8; //Data length MUST be full packet + err = canardHandleRxFrame(&canard, &frame, 1); + REQUIRE(CANARD_OK == err); + + //Send a middle packet, from the same ID, but don't toggle + frame.data[0] = CONSTRUCT_TAIL_BYTE(0, 0, 0, 1); + frame.id = CONSTRUCT_SVC_ID(0, 0, 1, 20, 0); + frame.data_len = 1; + err = canardHandleRxFrame(&canard, &frame, 1); + REQUIRE(-CANARD_ERROR_RX_WRONG_TOGGLE == err); + + //Send a middle packet, toggle, but use wrong ID + frame.data[7] = CONSTRUCT_TAIL_BYTE(0, 0, 1, 2); + frame.id = CONSTRUCT_SVC_ID(0, 0, 1, 20, 0); + frame.data_len = 8; + err = canardHandleRxFrame(&canard, &frame, 1); + REQUIRE(-CANARD_ERROR_RX_UNEXPECTED_TID == err); + + //Send a middle packet, toggle, and use correct ID + frame.data[7] = CONSTRUCT_TAIL_BYTE(0, 0, 1, 1); + frame.id = CONSTRUCT_SVC_ID(0, 0, 1, 20, 0); + frame.data_len = 8; + err = canardHandleRxFrame(&canard, &frame, 1); + REQUIRE(CANARD_OK == err); + +} + +TEST_CASE("canardHandleRxFrame missed start handling, Correctness") +{ + uint8_t canard_memory_pool[1024]; + CanardInstance canard; + CanardCANFrame frame; + int16_t err; + + g_should_accept = true; + + //Open canard to accept all transfers with a node ID of 20 + canardInit(&canard, canard_memory_pool, sizeof(canard_memory_pool), + onTransferReceived, shouldAcceptTransfer, &canard); + canardSetLocalNodeID(&canard, 20); + + //Send a start packet, should pass + frame.data[7] = CONSTRUCT_TAIL_BYTE(1, 0, 0, 1); + + frame.id = CONSTRUCT_SVC_ID(0, 0, 1, 20, 0); + frame.data_len = 8; //Data length MUST be full packet + err = canardHandleRxFrame(&canard, &frame, 1); + REQUIRE(CANARD_OK == err); + + //Send a middle packet, toggle, and use correct ID - but timeout + frame.data[7] = CONSTRUCT_TAIL_BYTE(0, 0, 1, 1); + frame.id = CONSTRUCT_SVC_ID(0, 0, 1, 20, 0); + frame.data_len = 8; + err = canardHandleRxFrame(&canard, &frame, 4000000); + REQUIRE(-CANARD_ERROR_RX_MISSED_START == err); + + //Send a start packet, should pass + frame.data[7] = CONSTRUCT_TAIL_BYTE(1, 0, 0, 1); + frame.id = CONSTRUCT_SVC_ID(0, 0, 1, 20, 0); + frame.data_len = 8; //Data length MUST be full packet + err = canardHandleRxFrame(&canard, &frame, 1); + REQUIRE(CANARD_OK == err); + + //Send a middle packet, toggle, and use correct ID - but timestamp 0 + frame.data[7] = CONSTRUCT_TAIL_BYTE(0, 0, 1, 1); + frame.id = CONSTRUCT_SVC_ID(0, 0, 1, 20, 0); + frame.data_len = 8; + err = canardHandleRxFrame(&canard, &frame, 0); + REQUIRE(-CANARD_ERROR_RX_MISSED_START == err); + + //Send a start packet, should pass + frame.data[7] = CONSTRUCT_TAIL_BYTE(1, 0, 0, 1); + frame.id = CONSTRUCT_SVC_ID(0, 0, 1, 20, 0); + frame.data_len = 8; //Data length MUST be full packet + err = canardHandleRxFrame(&canard, &frame, 1); + REQUIRE(CANARD_OK == err); + + //Send a middle packet, toggle, and use an incorrect TID + frame.data[7] = CONSTRUCT_TAIL_BYTE(0, 0, 1, 3); + frame.data[7] = 0 | 3 | (1<<5); + frame.id = CONSTRUCT_SVC_ID(0, 0, 1, 20, 0); + frame.data_len = 8; + err = canardHandleRxFrame(&canard, &frame, 0); + REQUIRE(-CANARD_ERROR_RX_MISSED_START == err); +} + +TEST_CASE("canardHandleRxFrame short frame handling, Correctness") +{ + uint8_t canard_memory_pool[1024]; + CanardInstance canard; + CanardCANFrame frame; + int16_t err; + + g_should_accept = true; + + //Open canard to accept all transfers with a node ID of 20 + canardInit(&canard, canard_memory_pool, sizeof(canard_memory_pool), + onTransferReceived, shouldAcceptTransfer, &canard); + canardSetLocalNodeID(&canard, 20); + + //Send a start packet which is short, should fail + frame.data[1] = CONSTRUCT_TAIL_BYTE(1, 0, 0, 1); + frame.id = CONSTRUCT_SVC_ID(0, 0, 1, 20, 0); + frame.data_len = 2; //Data length MUST be full packet + err = canardHandleRxFrame(&canard, &frame, 1); + REQUIRE(-CANARD_ERROR_RX_SHORT_FRAME == err); + + //Send a start packet which is short, should fail + frame.data[2] = CONSTRUCT_TAIL_BYTE(1, 0, 0, 1); + frame.id = CONSTRUCT_SVC_ID(0, 0, 1, 20, 0); + frame.data_len = 3; //Data length MUST be full packet + err = canardHandleRxFrame(&canard, &frame, 1); + REQUIRE(-CANARD_ERROR_RX_SHORT_FRAME == err); +} + +TEST_CASE("canardHandleRxFrame OOM handling, Correctness") +{ + uint8_t dummy_buf; + CanardInstance canard; + CanardCANFrame frame; + int16_t err; + + g_should_accept = true; + + //Open canard to accept all transfers with a node ID of 20 + canardInit(&canard, &dummy_buf, 0, + onTransferReceived, shouldAcceptTransfer, &canard); + canardSetLocalNodeID(&canard, 20); + + //Send a start packet - we shouldn't have any memory + frame.data[7] = CONSTRUCT_TAIL_BYTE(1, 0, 0, 1); + frame.id = CONSTRUCT_SVC_ID(0, 0, 1, 20, 0); + frame.data_len = 8; //Data length MUST be full packet + err = canardHandleRxFrame(&canard, &frame, 1); + REQUIRE(-CANARD_ERROR_OUT_OF_MEMORY == err); +} \ No newline at end of file From ec99817f39da9e19eb6738d49b42b089bc8fd0f4 Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Fri, 1 Mar 2019 15:10:23 +0200 Subject: [PATCH 67/81] Formatting and copyright updates; no logical changes --- canard.c | 2 +- canard.h | 6 ++--- tests/test_rxerr.cpp | 52 ++++++++++++++++++++++---------------------- 3 files changed, 30 insertions(+), 30 deletions(-) diff --git a/canard.c b/canard.c index ece6c42c..ae9077ca 100644 --- a/canard.c +++ b/canard.c @@ -1,5 +1,5 @@ /* - * Copyright (c) 2016-2017 UAVCAN Team + * Copyright (c) 2016-2019 UAVCAN Team * * Permission is hereby granted, free of charge, to any person obtaining a copy * of this software and associated documentation files (the "Software"), to deal diff --git a/canard.h b/canard.h index ff8f8140..58532d8f 100644 --- a/canard.h +++ b/canard.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2016-2018 UAVCAN Team + * Copyright (c) 2016-2019 UAVCAN Team * * Permission is hereby granted, free of charge, to any person obtaining a copy * of this software and associated documentation files (the "Software"), to deal @@ -429,8 +429,8 @@ void canardPopTxQueue(CanardInstance* ins); * Return value will report any errors in decoding packets. */ int16_t canardHandleRxFrame(CanardInstance* ins, - const CanardCANFrame* frame, - uint64_t timestamp_usec); + const CanardCANFrame* frame, + uint64_t timestamp_usec); /** * Traverses the list of transfers and removes those that were last updated more than timeout_usec microseconds ago. diff --git a/tests/test_rxerr.cpp b/tests/test_rxerr.cpp index 74850edf..44f31f0e 100644 --- a/tests/test_rxerr.cpp +++ b/tests/test_rxerr.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2016 UAVCAN Team + * Copyright (c) 2016-2019 UAVCAN Team * * Permission is hereby granted, free of charge, to any person obtaining a copy * of this software and associated documentation files (the "Software"), to deal @@ -26,35 +26,35 @@ #include //Independent implementation of ID layout from https://uavcan.org/Specification/4._CAN_bus_transport_layer/ -#define CONSTRUCT_PRIO(prio) (((prio) & 0x1F) << 23) -#define CONSTRUCT_MTID(mtid) (((mtid) & 0xFFFF) << 8) -#define CONSTRUCT_SID(sid) (((sid) & 0x7F)) -#define CONSTRUCT_DISC(disc) (((disc) & 0x3FFF) << 10) -#define CONSTRUCT_DISC_MTID(mtid) (((mtid) & 0x3) << 8) -#define CONSTRUCT_STID(stid) (((stid) & 0xFF) << 16) -#define CONSTRUCT_DID(did) (((did) & 0x7F) << 8) -#define CONSTRUCT_REQUEST(request) (((request) & 0x1) << 15) +#define CONSTRUCT_PRIO(prio) (((prio) & 0x1F) << 23) +#define CONSTRUCT_MTID(mtid) (((mtid) & 0xFFFF) << 8) +#define CONSTRUCT_SID(sid) (((sid) & 0x7F)) +#define CONSTRUCT_DISC(disc) (((disc) & 0x3FFF) << 10) +#define CONSTRUCT_DISC_MTID(mtid) (((mtid) & 0x3) << 8) +#define CONSTRUCT_STID(stid) (((stid) & 0xFF) << 16) +#define CONSTRUCT_DID(did) (((did) & 0x7F) << 8) +#define CONSTRUCT_REQUEST(request) (((request) & 0x1) << 15) #define CONSTRUCT_SNM_BIT (1 << 7) #define CONSTRUCT_ANON_MSG_ID(prio, disc, mtid, sid) (CONSTRUCT_PRIO(prio) | \ - CONSTRUCT_DISC_MTID(mtid) | \ - CONSTRUCT_DISC(disc) | \ - CONSTRUCT_SID(sid) \ - CANARD_CAN_FRAME_EFF) + CONSTRUCT_DISC_MTID(mtid) | \ + CONSTRUCT_DISC(disc) | \ + CONSTRUCT_SID(sid) \ + CANARD_CAN_FRAME_EFF) #define CONSTRUCT_MSG_ID(prio, mtid, sid) (CONSTRUCT_PRIO(prio) | \ - CONSTRUCT_MTID(mtid) | \ - CONSTRUCT_SID(sid) | \ - CANARD_CAN_FRAME_EFF) + CONSTRUCT_MTID(mtid) | \ + CONSTRUCT_SID(sid) | \ + CANARD_CAN_FRAME_EFF) #define CONSTRUCT_SVC_ID(prio, stid, request, did, sid) (CONSTRUCT_PRIO(prio) | \ - CONSTRUCT_STID(stid) | \ - CONSTRUCT_REQUEST(request) | \ - CONSTRUCT_DID(did) | \ - CONSTRUCT_SID(sid) | \ - CONSTRUCT_SNM_BIT | \ - CANARD_CAN_FRAME_EFF) + CONSTRUCT_STID(stid) | \ + CONSTRUCT_REQUEST(request) | \ + CONSTRUCT_DID(did) | \ + CONSTRUCT_SID(sid) | \ + CONSTRUCT_SNM_BIT | \ + CANARD_CAN_FRAME_EFF) #define CONSTRUCT_START(start) (((start) & 0x1) << 7) #define CONSTRUCT_END(end) (((end) & 0x1) << 6) @@ -62,9 +62,9 @@ #define CONSTRUCT_TID(tid) (((tid) & 0x1F)) #define CONSTRUCT_TAIL_BYTE(start, end, toggle, tid) (CONSTRUCT_START(start) | \ - CONSTRUCT_END(end) | \ - CONSTRUCT_TOGGLE(toggle) | \ - CONSTRUCT_TID(tid)) + CONSTRUCT_END(end) | \ + CONSTRUCT_TOGGLE(toggle) | \ + CONSTRUCT_TID(tid)) static bool g_should_accept = true; @@ -371,4 +371,4 @@ TEST_CASE("canardHandleRxFrame OOM handling, Correctness") frame.data_len = 8; //Data length MUST be full packet err = canardHandleRxFrame(&canard, &frame, 1); REQUIRE(-CANARD_ERROR_OUT_OF_MEMORY == err); -} \ No newline at end of file +} From 75e593b9a1eadf1f2ebf85dc267ba490b0ddd537 Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Fri, 1 Mar 2019 15:11:56 +0200 Subject: [PATCH 68/81] Fixed a false-positive linter warning in canard.c --- canard.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/canard.c b/canard.c index ae9077ca..0f4e0954 100644 --- a/canard.c +++ b/canard.c @@ -345,7 +345,7 @@ int16_t canardHandleRxFrame(CanardInstance* ins, const CanardCANFrame* frame, ui .payload_head = frame->data, .payload_len = (uint8_t)(frame->data_len - 1U), .data_type_id = data_type_id, - .transfer_type = transfer_type, + .transfer_type = (uint8_t)transfer_type, .transfer_id = TRANSFER_ID_FROM_TAIL_BYTE(tail_byte), .priority = priority, .source_node_id = source_node_id @@ -450,7 +450,7 @@ int16_t canardHandleRxFrame(CanardInstance* ins, const CanardCANFrame* frame, ui .payload_tail = (tail_offset >= frame_payload_size) ? NULL : (&frame->data[tail_offset]), .payload_len = (uint16_t)(rx_state->payload_len + frame_payload_size), .data_type_id = data_type_id, - .transfer_type = transfer_type, + .transfer_type = (uint8_t)transfer_type, .transfer_id = TRANSFER_ID_FROM_TAIL_BYTE(tail_byte), .priority = priority, .source_node_id = source_node_id From ff5dea2eb570a2c9582132a52d3db757b98f226f Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Fri, 1 Mar 2019 15:17:38 +0200 Subject: [PATCH 69/81] Demo style fixes: added g_ to globals, no logical changes --- tests/demo.c | 79 ++++++++++++++++++++++++++++------------------------ 1 file changed, 42 insertions(+), 37 deletions(-) diff --git a/tests/demo.c b/tests/demo.c index 7a3253cc..0446c02b 100644 --- a/tests/demo.c +++ b/tests/demo.c @@ -56,21 +56,21 @@ * Library instance. * In simple applications it makes sense to make it static, but it is not necessary. */ -static CanardInstance canard; ///< The library instance -static uint8_t canard_memory_pool[1024]; ///< Arena for memory allocation, used by the library +static CanardInstance g_canard; ///< The library instance +static uint8_t g_canard_memory_pool[1024]; ///< Arena for memory allocation, used by the library /* * Variables used for dynamic node ID allocation. * RTFM at http://uavcan.org/Specification/6._Application_level_functions/#dynamic-node-id-allocation */ -static uint64_t send_next_node_id_allocation_request_at; ///< When the next node ID allocation request should be sent -static uint8_t node_id_allocation_unique_id_offset; ///< Depends on the stage of the next request +static uint64_t g_send_next_node_id_allocation_request_at; ///< When the next node ID allocation request should be sent +static uint8_t g_node_id_allocation_unique_id_offset; ///< Depends on the stage of the next request /* * Node status variables */ -static uint8_t node_health = UAVCAN_NODE_HEALTH_OK; -static uint8_t node_mode = UAVCAN_NODE_MODE_INITIALIZATION; +static uint8_t g_node_health = UAVCAN_NODE_HEALTH_OK; +static uint8_t g_node_mode = UAVCAN_NODE_MODE_INITIALIZATION; static uint64_t getMonotonicTimestampUSec(void) @@ -130,8 +130,8 @@ static void makeNodeStatusMessage(uint8_t buffer[UAVCAN_NODE_STATUS_MESSAGE_SIZE * encode the values manually. */ canardEncodeScalar(buffer, 0, 32, &uptime_sec); - canardEncodeScalar(buffer, 32, 2, &node_health); - canardEncodeScalar(buffer, 34, 3, &node_mode); + canardEncodeScalar(buffer, 32, 2, &g_node_health); + canardEncodeScalar(buffer, 34, 3, &g_node_mode); } @@ -150,14 +150,14 @@ static void onTransferReceived(CanardInstance* ins, (transfer->data_type_id == UAVCAN_NODE_ID_ALLOCATION_DATA_TYPE_ID)) { // Rule C - updating the randomized time interval - send_next_node_id_allocation_request_at = + g_send_next_node_id_allocation_request_at = getMonotonicTimestampUSec() + UAVCAN_NODE_ID_ALLOCATION_REQUEST_DELAY_OFFSET_USEC + (uint64_t)(getRandomFloat() * UAVCAN_NODE_ID_ALLOCATION_RANDOM_TIMEOUT_RANGE_USEC); if (transfer->source_node_id == CANARD_BROADCAST_NODE_ID) { puts("Allocation request from another allocatee"); - node_id_allocation_unique_id_offset = 0; + g_node_id_allocation_unique_id_offset = 0; return; } @@ -185,18 +185,18 @@ static void onTransferReceived(CanardInstance* ins, printf(" %02x/%02x", received_unique_id[i], my_unique_id[i]); } puts(""); - node_id_allocation_unique_id_offset = 0; + g_node_id_allocation_unique_id_offset = 0; return; // No match, return } if (received_unique_id_len < UNIQUE_ID_LENGTH_BYTES) { // The allocator has confirmed part of unique ID, switching to the next stage and updating the timeout. - node_id_allocation_unique_id_offset = received_unique_id_len; - send_next_node_id_allocation_request_at -= UAVCAN_NODE_ID_ALLOCATION_REQUEST_DELAY_OFFSET_USEC; + g_node_id_allocation_unique_id_offset = received_unique_id_len; + g_send_next_node_id_allocation_request_at -= UAVCAN_NODE_ID_ALLOCATION_REQUEST_DELAY_OFFSET_USEC; printf("Matching allocation response from %d offset %d\n", - transfer->source_node_id, node_id_allocation_unique_id_offset); + transfer->source_node_id, g_node_id_allocation_unique_id_offset); } else { @@ -310,13 +310,13 @@ static void process1HzTasks(uint64_t timestamp_usec) /* * Purging transfers that are no longer transmitted. This will occasionally free up some memory. */ - canardCleanupStaleTransfers(&canard, timestamp_usec); + canardCleanupStaleTransfers(&g_canard, timestamp_usec); /* * Printing the memory usage statistics. */ { - const CanardPoolAllocatorStatistics stats = canardGetPoolAllocatorStatistics(&canard); + const CanardPoolAllocatorStatistics stats = canardGetPoolAllocatorStatistics(&g_canard); const uint16_t peak_percent = (uint16_t)(100U * stats.peak_usage_blocks / stats.capacity_blocks); printf("Memory pool stats: capacity %u blocks, usage %u blocks, peak usage %u blocks (%u%%)\n", @@ -341,7 +341,7 @@ static void process1HzTasks(uint64_t timestamp_usec) static uint8_t transfer_id; // Note that the transfer ID variable MUST BE STATIC (or heap-allocated)! - const int16_t bc_res = canardBroadcast(&canard, + const int16_t bc_res = canardBroadcast(&g_canard, UAVCAN_NODE_STATUS_DATA_TYPE_SIGNATURE, UAVCAN_NODE_STATUS_DATA_TYPE_ID, &transfer_id, @@ -354,7 +354,7 @@ static void process1HzTasks(uint64_t timestamp_usec) } } - node_mode = UAVCAN_NODE_MODE_OPERATIONAL; + g_node_mode = UAVCAN_NODE_MODE_OPERATIONAL; } @@ -364,17 +364,17 @@ static void process1HzTasks(uint64_t timestamp_usec) static void processTxRxOnce(SocketCANInstance* socketcan, int32_t timeout_msec) { // Transmitting - for (const CanardCANFrame* txf = NULL; (txf = canardPeekTxQueue(&canard)) != NULL;) + for (const CanardCANFrame* txf = NULL; (txf = canardPeekTxQueue(&g_canard)) != NULL;) { const int16_t tx_res = socketcanTransmit(socketcan, txf, 0); if (tx_res < 0) // Failure - drop the frame and report { - canardPopTxQueue(&canard); + canardPopTxQueue(&g_canard); (void)fprintf(stderr, "Transmit error %d, frame dropped, errno '%s'\n", tx_res, strerror(errno)); } else if (tx_res > 0) // Success - just drop the frame { - canardPopTxQueue(&canard); + canardPopTxQueue(&g_canard); } else // Timeout - just exit and try again later { @@ -392,7 +392,7 @@ static void processTxRxOnce(SocketCANInstance* socketcan, int32_t timeout_msec) } else if (rx_res > 0) // Success - process the frame { - canardHandleRxFrame(&canard, &rx_frame, timestamp); + canardHandleRxFrame(&g_canard, &rx_frame, timestamp); } else { @@ -427,32 +427,37 @@ int main(int argc, char** argv) /* * Initializing the Libcanard instance. */ - canardInit(&canard, canard_memory_pool, sizeof(canard_memory_pool), onTransferReceived, shouldAcceptTransfer, NULL); + canardInit(&g_canard, + g_canard_memory_pool, + sizeof(g_canard_memory_pool), + onTransferReceived, + shouldAcceptTransfer, + NULL); /* * Performing the dynamic node ID allocation procedure. */ static const uint8_t PreferredNodeID = CANARD_BROADCAST_NODE_ID; ///< This can be made configurable, obviously - node_id_allocation_unique_id_offset = 0; + g_node_id_allocation_unique_id_offset = 0; uint8_t node_id_allocation_transfer_id = 0; - while (canardGetLocalNodeID(&canard) == CANARD_BROADCAST_NODE_ID) + while (canardGetLocalNodeID(&g_canard) == CANARD_BROADCAST_NODE_ID) { puts("Waiting for dynamic node ID allocation..."); - send_next_node_id_allocation_request_at = + g_send_next_node_id_allocation_request_at = getMonotonicTimestampUSec() + UAVCAN_NODE_ID_ALLOCATION_REQUEST_DELAY_OFFSET_USEC + (uint64_t)(getRandomFloat() * UAVCAN_NODE_ID_ALLOCATION_RANDOM_TIMEOUT_RANGE_USEC); - while ((getMonotonicTimestampUSec() < send_next_node_id_allocation_request_at) && - (canardGetLocalNodeID(&canard) == CANARD_BROADCAST_NODE_ID)) + while ((getMonotonicTimestampUSec() < g_send_next_node_id_allocation_request_at) && + (canardGetLocalNodeID(&g_canard) == CANARD_BROADCAST_NODE_ID)) { processTxRxOnce(&socketcan, 1); } - if (canardGetLocalNodeID(&canard) != CANARD_BROADCAST_NODE_ID) + if (canardGetLocalNodeID(&g_canard) != CANARD_BROADCAST_NODE_ID) { break; } @@ -462,7 +467,7 @@ int main(int argc, char** argv) uint8_t allocation_request[CANARD_CAN_FRAME_MAX_DATA_LEN - 1]; allocation_request[0] = (uint8_t)(PreferredNodeID << 1U); - if (node_id_allocation_unique_id_offset == 0) + if (g_node_id_allocation_unique_id_offset == 0) { allocation_request[0] |= 1; // First part of unique ID } @@ -471,22 +476,22 @@ int main(int argc, char** argv) readUniqueID(my_unique_id); static const uint8_t MaxLenOfUniqueIDInRequest = 6; - uint8_t uid_size = (uint8_t)(UNIQUE_ID_LENGTH_BYTES - node_id_allocation_unique_id_offset); + uint8_t uid_size = (uint8_t)(UNIQUE_ID_LENGTH_BYTES - g_node_id_allocation_unique_id_offset); if (uid_size > MaxLenOfUniqueIDInRequest) { uid_size = MaxLenOfUniqueIDInRequest; } // Paranoia time - assert(node_id_allocation_unique_id_offset < UNIQUE_ID_LENGTH_BYTES); + assert(g_node_id_allocation_unique_id_offset < UNIQUE_ID_LENGTH_BYTES); assert(uid_size <= MaxLenOfUniqueIDInRequest); assert(uid_size > 0); - assert((uid_size + node_id_allocation_unique_id_offset) <= UNIQUE_ID_LENGTH_BYTES); + assert((uid_size + g_node_id_allocation_unique_id_offset) <= UNIQUE_ID_LENGTH_BYTES); - memmove(&allocation_request[1], &my_unique_id[node_id_allocation_unique_id_offset], uid_size); + memmove(&allocation_request[1], &my_unique_id[g_node_id_allocation_unique_id_offset], uid_size); // Broadcasting the request - const int16_t bcast_res = canardBroadcast(&canard, + const int16_t bcast_res = canardBroadcast(&g_canard, UAVCAN_NODE_ID_ALLOCATION_DATA_TYPE_SIGNATURE, UAVCAN_NODE_ID_ALLOCATION_DATA_TYPE_ID, &node_id_allocation_transfer_id, @@ -499,10 +504,10 @@ int main(int argc, char** argv) } // Preparing for timeout; if response is received, this value will be updated from the callback. - node_id_allocation_unique_id_offset = 0; + g_node_id_allocation_unique_id_offset = 0; } - printf("Dynamic node ID allocation complete [%d]\n", canardGetLocalNodeID(&canard)); + printf("Dynamic node ID allocation complete [%d]\n", canardGetLocalNodeID(&g_canard)); /* * Running the main loop. From 4e0fcbb1d630f633dd7f17e7567092a47b2e2d44 Mon Sep 17 00:00:00 2001 From: Kjetil Kjeka Date: Sun, 10 Mar 2019 19:27:23 +0100 Subject: [PATCH 70/81] Bugfix priority field position in test --- tests/test_rxerr.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tests/test_rxerr.cpp b/tests/test_rxerr.cpp index 44f31f0e..9822c29d 100644 --- a/tests/test_rxerr.cpp +++ b/tests/test_rxerr.cpp @@ -26,7 +26,7 @@ #include //Independent implementation of ID layout from https://uavcan.org/Specification/4._CAN_bus_transport_layer/ -#define CONSTRUCT_PRIO(prio) (((prio) & 0x1F) << 23) +#define CONSTRUCT_PRIO(prio) (((prio) & 0x1F) << 24) #define CONSTRUCT_MTID(mtid) (((mtid) & 0xFFFF) << 8) #define CONSTRUCT_SID(sid) (((sid) & 0x7F)) #define CONSTRUCT_DISC(disc) (((disc) & 0x3FFF) << 10) From 83d75fa795636386358dd7248cf1bde98fcddf3c Mon Sep 17 00:00:00 2001 From: mike7c2 Date: Mon, 18 Mar 2019 16:48:19 +0000 Subject: [PATCH 71/81] Fix flake errors, assuming line length of 120 chars --- .../libcanard_dsdl_compiler/__init__.py | 129 +++++++++++------- .../libcanard_dsdl_compiler/pyratemp.py | 1 + dsdl_compiler/libcanard_dsdlc | 19 ++- show_data_type_info.py | 24 ++-- 4 files changed, 105 insertions(+), 68 deletions(-) diff --git a/dsdl_compiler/libcanard_dsdl_compiler/__init__.py b/dsdl_compiler/libcanard_dsdl_compiler/__init__.py index f4411716..ab45291c 100644 --- a/dsdl_compiler/libcanard_dsdl_compiler/__init__.py +++ b/dsdl_compiler/libcanard_dsdl_compiler/__init__.py @@ -16,7 +16,10 @@ ''' from __future__ import division, absolute_import, print_function, unicode_literals -import sys, os, logging, errno, re +import os +import logging +import errno +import re from .pyratemp import Template from uavcan import dsdl @@ -32,13 +35,17 @@ HEADER_TEMPLATE_FILENAME = os.path.join(os.path.dirname(__file__), 'data_type_template.tmpl') CODE_TEMPLATE_FILENAME = os.path.join(os.path.dirname(__file__), 'code_type_template.tmpl') + __all__ = ['run', 'logger', 'DsdlCompilerException'] + class DsdlCompilerException(Exception): pass + logger = logging.getLogger(__name__) + def run(source_dirs, include_dirs, output_dir, header_only): ''' This function takes a list of root namespace directories (containing DSDL definition files to parse), a @@ -70,6 +77,7 @@ def run(source_dirs, include_dirs, output_dir, header_only): # ----------------- + def pretty_filename(filename): try: a = os.path.abspath(filename) @@ -78,11 +86,13 @@ def pretty_filename(filename): except ValueError: return filename + # get the CamelCase prefix from the current filename def get_name_space_prefix(t): return t.full_name.replace('.', '_') -def type_output_filename(t, extension = OUTPUT_HEADER_FILE_EXTENSION): + +def type_output_filename(t, extension=OUTPUT_HEADER_FILE_EXTENSION): assert t.category == t.CATEGORY_COMPOUND folder_name = t.full_name.split('.')[-2] if extension == OUTPUT_CODE_FILE_EXTENSION: @@ -93,6 +103,7 @@ def type_output_filename(t, extension = OUTPUT_HEADER_FILE_EXTENSION): else: return t.full_name.replace('.', os.path.sep) + '.' + extension + def makedirs(path): try: try: @@ -103,9 +114,11 @@ def makedirs(path): if ex.errno != errno.EEXIST: # http://stackoverflow.com/questions/12468022 raise + def die(text): raise DsdlCompilerException(str(text)) + def run_parser(source_dirs, search_dirs): try: types = dsdl.parse_namespaces(source_dirs, search_dirs) @@ -114,6 +127,7 @@ def run_parser(source_dirs, search_dirs): die(ex) return types + def run_generator(types, dest_dir, header_only): try: header_template_expander = make_template_expander(HEADER_TEMPLATE_FILENAME) @@ -139,6 +153,7 @@ def run_generator(types, dest_dir, header_only): logger.info('Generator failure', exc_info=True) die(ex) + def write_generated_data(filename, data, header_only, append_file=False): dirname = os.path.dirname(filename) makedirs(dirname) @@ -158,6 +173,7 @@ def write_generated_data(filename, data, header_only, append_file=False): except (OSError, IOError) as ex: logger.warning('Failed to set permissions for %s: %s', pretty_filename(filename), ex) + def expand_to_next_full(size): if size <= 8: return 8 @@ -165,18 +181,21 @@ def expand_to_next_full(size): return 16 elif size <= 32: return 32 - elif size <=64: + elif size <= 64: return 64 + def get_max_size(bits, unsigned): if unsigned: - return (2 ** bits) -1 + return (2 ** bits) - 1 else: - return (2 ** (bits-1)) -1 + return (2 ** (bits - 1)) - 1 + def strip_name(name): return name.split('.')[-1] + def type_to_c_type(t): if t.category == t.CATEGORY_PRIMITIVE: saturate = { @@ -193,13 +212,14 @@ def type_to_c_type(t): 32: 'float', 64: 'double', }[t.bitlen] - return {'cpp_type':'%s' % (float_type), - 'post_cpp_type':'', - 'cpp_type_comment':'float%d %s' % (t.bitlen, cast_mode, ), - 'bitlen':t.bitlen, - 'max_size':get_max_size(t.bitlen, False), - 'signedness':'false', - 'saturate':False} # do not saturate floats + return { + 'cpp_type': '%s' % (float_type), + 'post_cpp_type': '', + 'cpp_type_comment': 'float%d %s' % (t.bitlen, cast_mode, ), + 'bitlen': t.bitlen, + 'max_size': get_max_size(t.bitlen, False), + 'signedness': 'false', + 'saturate': False} # do not saturate floats else: c_type = { t.KIND_BOOLEAN: 'bool', @@ -213,25 +233,27 @@ def type_to_c_type(t): }[t.kind] if t.kind == t.KIND_BOOLEAN: - return {'cpp_type':'%s' % (c_type), - 'post_cpp_type':'', - 'cpp_type_comment':'bit len %d' % (t.bitlen, ), - 'bitlen':t.bitlen, - 'max_size':get_max_size(t.bitlen, True), - 'signedness':signedness, - 'saturate':saturate} + return { + 'cpp_type': '%s' % (c_type), + 'post_cpp_type': '', + 'cpp_type_comment': 'bit len %d' % (t.bitlen, ), + 'bitlen': t.bitlen, + 'max_size': get_max_size(t.bitlen, True), + 'signedness': signedness, + 'saturate': saturate} else: if saturate: # Do not staturate if struct field length is equal bitlen if (expand_to_next_full(t.bitlen) == t.bitlen): saturate = False - return {'cpp_type':'%s%d_t' % (c_type, expand_to_next_full(t.bitlen)), - 'post_cpp_type':'', - 'cpp_type_comment':'bit len %d' % (t.bitlen, ), - 'bitlen':t.bitlen, - 'max_size':get_max_size(t.bitlen, t.kind == t.KIND_UNSIGNED_INT), - 'signedness':signedness, - 'saturate':saturate} + return { + 'cpp_type': '%s%d_t' % (c_type, expand_to_next_full(t.bitlen)), + 'post_cpp_type': '', + 'cpp_type_comment': 'bit len %d' % (t.bitlen, ), + 'bitlen': t.bitlen, + 'max_size': get_max_size(t.bitlen, t.kind == t.KIND_UNSIGNED_INT), + 'signedness': signedness, + 'saturate': saturate} elif t.category == t.CATEGORY_ARRAY: values = type_to_c_type(t.value_type) @@ -239,39 +261,41 @@ def type_to_c_type(t): t.MODE_STATIC: 'Static Array', t.MODE_DYNAMIC: 'Dynamic Array', }[t.mode] - return {'cpp_type':'%s' % (values['cpp_type'], ), + return { + 'cpp_type': '%s' % (values['cpp_type'], ), 'cpp_type_category': t.value_type.category, - 'post_cpp_type':'[%d]' % (t.max_size,), - 'cpp_type_comment':'%s %dbit[%d] max items' % (mode, values['bitlen'], t.max_size, ), - 'bitlen':values['bitlen'], - 'array_max_size_bit_len':t.max_size.bit_length(), - 'max_size':values['max_size'], - 'signedness':values['signedness'], - 'saturate':values['saturate'], + 'post_cpp_type': '[%d]' % (t.max_size,), + 'cpp_type_comment': '%s %dbit[%d] max items' % (mode, values['bitlen'], t.max_size, ), + 'bitlen': values['bitlen'], + 'array_max_size_bit_len': t.max_size.bit_length(), + 'max_size': values['max_size'], + 'signedness': values['signedness'], + 'saturate': values['saturate'], 'dynamic_array': t.mode == t.MODE_DYNAMIC, - 'max_array_elements': t.max_size, - } + 'max_array_elements': t.max_size} elif t.category == t.CATEGORY_COMPOUND: return { - 'cpp_type':t.full_name.replace('.','_'), - 'post_cpp_type':'', - 'cpp_type_comment':'', - 'bitlen':t.get_max_bitlen(), - 'max_size':0, - 'signedness':'false', - 'saturate':False} + 'cpp_type': t.full_name.replace('.', '_'), + 'post_cpp_type': '', + 'cpp_type_comment': '', + 'bitlen': t.get_max_bitlen(), + 'max_size': 0, + 'signedness': 'false', + 'saturate': False} elif t.category == t.CATEGORY_VOID: - return {'cpp_type':'', - 'post_cpp_type':'', - 'cpp_type_comment':'void%d' % t.bitlen, - 'bitlen':t.bitlen, - 'max_size':0, - 'signedness':'false', - 'saturate':False} + return { + 'cpp_type': '', + 'post_cpp_type': '', + 'cpp_type_comment': 'void%d' % t.bitlen, + 'bitlen': t.bitlen, + 'max_size': 0, + 'signedness': 'false', + 'saturate': False} else: raise DsdlCompilerException('Unknown type category: %s' % t.category) -def generate_one_type(template_expander, t): + +def generate_one_type(template_expander, t): # noqa: C901 (flake8 doesn't understand nested complexity..) t.name_space_type_name = get_name_space_prefix(t) t.cpp_full_type_name = '::' + t.full_name.replace('.', '::') t.include_guard = '__' + t.full_name.replace('.', '_').upper() @@ -381,6 +405,7 @@ def inject_constant_info(constants): text = text.replace('{\n\n ', '{\n ') return text + def make_template_expander(filename): ''' Templating is based on pyratemp (http://www.simple-is-better.org/template/pyratemp.html). @@ -432,6 +457,7 @@ def make_template_expander(filename): def expand(**args): # This function adds one indentation level (4 spaces); it will be used from the template args['indent'] = lambda text, idnt = ' ': idnt + text.replace('\n', '\n' + idnt) + # This function works like enumerate(), telling you whether the current item is the last one def enum_last_value(iterable, start=0): it = iter(iterable) @@ -442,6 +468,7 @@ def enum_last_value(iterable, start=0): last = val count += 1 yield count, True, last + args['enum_last_value'] = enum_last_value return template(**args) diff --git a/dsdl_compiler/libcanard_dsdl_compiler/pyratemp.py b/dsdl_compiler/libcanard_dsdl_compiler/pyratemp.py index eb4c1286..2b93d1e2 100644 --- a/dsdl_compiler/libcanard_dsdl_compiler/pyratemp.py +++ b/dsdl_compiler/libcanard_dsdl_compiler/pyratemp.py @@ -1,5 +1,6 @@ #!/usr/bin/env python # -*- coding: utf-8 -*- +# flake8: noqa """ Small, simple and powerful template-engine for Python. diff --git a/dsdl_compiler/libcanard_dsdlc b/dsdl_compiler/libcanard_dsdlc index dacb6d91..46c2d444 100755 --- a/dsdl_compiler/libcanard_dsdlc +++ b/dsdl_compiler/libcanard_dsdlc @@ -11,7 +11,10 @@ # from __future__ import division, absolute_import, print_function, unicode_literals -import os, sys, logging, argparse +import os +import sys +import logging +import argparse # This trickery allows to use the compiler even if pyuavcan is not installed in the system. # This is extremely important, as it makes the compiler (and therefore libcanard in general) @@ -23,15 +26,18 @@ if RUNNING_FROM_SRC_DIR: sys.path.insert(0, SCRIPT_DIR) sys.path.insert(0, LOCAL_PYUAVCAN_DIR) + def configure_logging(verbosity): fmt = '%(message)s' - level = { 0: logging.WARNING, 1: logging.INFO, 2: logging.DEBUG }.get(verbosity or 0, logging.DEBUG) + level = {0: logging.WARNING, 1: logging.INFO, 2: logging.DEBUG}.get(verbosity or 0, logging.DEBUG) logging.basicConfig(stream=sys.stderr, level=level, format=fmt) + def die(text): print(text, file=sys.stderr) exit(1) + DEFAULT_OUTDIR = 'dsdlc_generated' DESCRIPTION = '''UAVCAN DSDL compiler for the libcanard. @@ -41,14 +47,15 @@ This script can be used directly from the source directory, no installation requ Supported Python versions: 3.2+, 2.7. ''' +INCDIR_DESC = ('nested type namespaces, one path per argument. Can be also specified through the environment variable' + 'UAVCAN_DSDL_INCLUDE_PATH, where the path entries are separated by colons ":"') + argparser = argparse.ArgumentParser(description=DESCRIPTION) argparser.add_argument('source_dir', nargs='+', help='source directory with DSDL definitions') argparser.add_argument('--header_only', '-ho', action='store_true', help='Generate as header only library') argparser.add_argument('--verbose', '-v', action='count', help='verbosity level (-v, -vv)') argparser.add_argument('--outdir', '-O', default=DEFAULT_OUTDIR, help='output directory, default %s' % DEFAULT_OUTDIR) -argparser.add_argument('--incdir', '-I', default=[], action='append', help= -'''nested type namespaces, one path per argument. Can be also specified through the environment variable -UAVCAN_DSDL_INCLUDE_PATH, where the path entries are separated by colons ":"''') +argparser.add_argument('--incdir', '-I', default=[], action='append', help=INCDIR_DESC) args = argparser.parse_args() configure_logging(args.verbose) @@ -60,7 +67,7 @@ try: except KeyError: pass -from libcanard_dsdl_compiler import run as dsdlc_run +from libcanard_dsdl_compiler import run as dsdlc_run # noqa: E402 try: dsdlc_run(args.source_dir, args.incdir, args.outdir, args.header_only) diff --git a/show_data_type_info.py b/show_data_type_info.py index ef11aada..4b6c4324 100755 --- a/show_data_type_info.py +++ b/show_data_type_info.py @@ -12,8 +12,8 @@ ''''exec echo "Python not found" >&2 # ''' # We can't import from __future__ here because of the wickedness above. -import sys -import getopt +import sys # noqa: E402 +import getopt # noqa: E402 try: import uavcan @@ -21,34 +21,36 @@ sys.stderr.write('PyUAVCAN is not installed. Please install from PIP: sudo pip3 install uavcan\n') exit(1) + def printUsage(): print("""show_data_type_info: [-h, --help]: show this help [-c, --custom] [path/to/custom/types]: path to your custom types '00.mymsgtype.uavcan' """) - + + if __name__ == "__main__": # decode options given to the script try: - opts, args = getopt.getopt(sys.argv[1:],'hc:',['help','custom=']) + opts, args = getopt.getopt(sys.argv[1:], 'hc:', ['help', 'custom=']) except getopt.GetoptError: printUsage() sys.exit() - + # include/execute options given to the script for opt, arg in opts: - if opt in ('-h','--help'): + if opt in ('-h', '--help'): printUsage() sys.exit() - elif opt in ('-c','--custom'): + elif opt in ('-c', '--custom'): uavcan.load_dsdl(arg) - + longest_name = max(map(len, uavcan.TYPENAMES.keys())) - + header = 'Full Data Type Name'.ljust(longest_name) + ' | DDTID | Type Signature | Max Bit Len ' print(header) print('-' * len(header)) - + for typename, typedef in sorted(uavcan.TYPENAMES.items()): ddtid = typedef.default_dtid if typedef.default_dtid is not None else 'N/A' s = '%-*s % 5s 0x%016x' % (longest_name, typename, ddtid, typedef.get_data_type_signature()) @@ -56,4 +58,4 @@ def printUsage(): s += ' % 5d' % typedef.get_max_bitlen() except Exception: s += ' % 5d / %-5d' % (typedef.get_max_bitlen_request(), typedef.get_max_bitlen_response()) - print(s) \ No newline at end of file + print(s) From d14098c8cd359f452534c9a88fc6b4b568116571 Mon Sep 17 00:00:00 2001 From: mike7c2 Date: Mon, 18 Mar 2019 17:29:28 +0000 Subject: [PATCH 72/81] Add some documentation, and a flake8 config --- README.md | 12 ++++++++++++ setup.cfg | 3 +++ 2 files changed, 15 insertions(+) create mode 100644 setup.cfg diff --git a/README.md b/README.md index 277387c0..2be1086a 100644 --- a/README.md +++ b/README.md @@ -89,3 +89,15 @@ tar czvf libcanard.tgz cov-int ``` Then upload the resulting archive to Coverity. + +### Running flake8 for python code + +Flake8 is a tool for checking correctness and style of python code, [Flake 8 docs](http://flake8.pycqa.org/en/latest/). + +The setup for Flake8 is defined in `setup.cfg`. + +Flake8 should be run from the top level directory, ideally code should be reviewed to make sure there are no +flake errors before it is merged. +``` +libcanard$ flake8 +``` diff --git a/setup.cfg b/setup.cfg new file mode 100644 index 00000000..f6d9df05 --- /dev/null +++ b/setup.cfg @@ -0,0 +1,3 @@ +[flake8] +exclude = .git +max-line-length = 120 From f35bfad769a4c9f8431f57102dc777f8f0ce7751 Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Sun, 24 Mar 2019 20:26:12 +0200 Subject: [PATCH 73/81] README update as requested in #94 --- README.md | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/README.md b/README.md index 2be1086a..ffde5b84 100644 --- a/README.md +++ b/README.md @@ -90,14 +90,15 @@ tar czvf libcanard.tgz cov-int Then upload the resulting archive to Coverity. -### Running flake8 for python code +### Running flake8 for Python code -Flake8 is a tool for checking correctness and style of python code, [Flake 8 docs](http://flake8.pycqa.org/en/latest/). +[Flake8](http://flake8.pycqa.org/en/latest/) is a tool for checking correctness and style of Python code. The setup for Flake8 is defined in `setup.cfg`. Flake8 should be run from the top level directory, ideally code should be reviewed to make sure there are no flake errors before it is merged. -``` -libcanard$ flake8 +```bash +cd libcanard +flake8 ``` From 4770e55e60d10c776edc806374f25a806b466bd1 Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Tue, 26 Mar 2019 16:43:07 +0200 Subject: [PATCH 74/81] Fixed the argument order in isPriorityHigher(); thanks to yezhaq@hotmail.com for pointing this out --- canard.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/canard.c b/canard.c index 0f4e0954..f15db876 100644 --- a/canard.c +++ b/canard.c @@ -1021,9 +1021,9 @@ CANARD_INTERNAL CanardTxQueueItem* createTxItem(CanardPoolAllocator* allocator) } /** - * Returns true if priority of rhs is higher than id + * Returns true if priority of id is higher than rhs. */ -CANARD_INTERNAL bool isPriorityHigher(uint32_t rhs, uint32_t id) +CANARD_INTERNAL bool isPriorityHigher(uint32_t id, uint32_t rhs) { const uint32_t clean_id = id & CANARD_CAN_EXT_ID_MASK; const uint32_t rhs_clean_id = rhs & CANARD_CAN_EXT_ID_MASK; From d15f6c9459d07db85480209bb3a4844e9f836c50 Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Tue, 26 Mar 2019 20:36:31 +0200 Subject: [PATCH 75/81] Better argument names for isPriorityHigher() --- canard.c | 16 ++++++++-------- canard_internals.h | 4 ++-- 2 files changed, 10 insertions(+), 10 deletions(-) diff --git a/canard.c b/canard.c index f15db876..9751985a 100644 --- a/canard.c +++ b/canard.c @@ -1021,18 +1021,18 @@ CANARD_INTERNAL CanardTxQueueItem* createTxItem(CanardPoolAllocator* allocator) } /** - * Returns true if priority of id is higher than rhs. + * Returns true if priority of self is higher than other. */ -CANARD_INTERNAL bool isPriorityHigher(uint32_t id, uint32_t rhs) +CANARD_INTERNAL bool isPriorityHigher(uint32_t self, uint32_t other) { - const uint32_t clean_id = id & CANARD_CAN_EXT_ID_MASK; - const uint32_t rhs_clean_id = rhs & CANARD_CAN_EXT_ID_MASK; + const uint32_t clean_id = self & CANARD_CAN_EXT_ID_MASK; + const uint32_t rhs_clean_id = other & CANARD_CAN_EXT_ID_MASK; /* * STD vs EXT - if 11 most significant bits are the same, EXT loses. */ - const bool ext = (id & CANARD_CAN_FRAME_EFF) != 0; - const bool rhs_ext = (rhs & CANARD_CAN_FRAME_EFF) != 0; + const bool ext = (self & CANARD_CAN_FRAME_EFF) != 0; + const bool rhs_ext = (other & CANARD_CAN_FRAME_EFF) != 0; if (ext != rhs_ext) { uint32_t arb11 = ext ? (clean_id >> 18U) : clean_id; @@ -1050,8 +1050,8 @@ CANARD_INTERNAL bool isPriorityHigher(uint32_t id, uint32_t rhs) /* * RTR vs Data frame - if frame identifiers and frame types are the same, RTR loses. */ - const bool rtr = (id & CANARD_CAN_FRAME_RTR) != 0; - const bool rhs_rtr = (rhs & CANARD_CAN_FRAME_RTR) != 0; + const bool rtr = (self & CANARD_CAN_FRAME_RTR) != 0; + const bool rhs_rtr = (other & CANARD_CAN_FRAME_RTR) != 0; if (clean_id == rhs_clean_id && rtr != rhs_rtr) { return rhs_rtr; diff --git a/canard_internals.h b/canard_internals.h index baf4b06e..b4cb6ac2 100644 --- a/canard_internals.h +++ b/canard_internals.h @@ -70,8 +70,8 @@ CANARD_INTERNAL uint16_t extractDataType(uint32_t id); CANARD_INTERNAL void pushTxQueue(CanardInstance* ins, CanardTxQueueItem* item); -CANARD_INTERNAL bool isPriorityHigher(uint32_t id, - uint32_t rhs); +CANARD_INTERNAL bool isPriorityHigher(uint32_t self, + uint32_t other); CANARD_INTERNAL CanardTxQueueItem* createTxItem(CanardPoolAllocator* allocator); From 21f8827c3b5072d8b21906624652403ba420c150 Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Tue, 26 Mar 2019 21:00:48 +0200 Subject: [PATCH 76/81] Consistenly named locals in isPriorityHigher --- canard.c | 30 +++++++++++++++--------------- 1 file changed, 15 insertions(+), 15 deletions(-) diff --git a/canard.c b/canard.c index 9751985a..a475c199 100644 --- a/canard.c +++ b/canard.c @@ -1025,42 +1025,42 @@ CANARD_INTERNAL CanardTxQueueItem* createTxItem(CanardPoolAllocator* allocator) */ CANARD_INTERNAL bool isPriorityHigher(uint32_t self, uint32_t other) { - const uint32_t clean_id = self & CANARD_CAN_EXT_ID_MASK; - const uint32_t rhs_clean_id = other & CANARD_CAN_EXT_ID_MASK; + const uint32_t self_clean_id = self & CANARD_CAN_EXT_ID_MASK; + const uint32_t other_clean_id = other & CANARD_CAN_EXT_ID_MASK; /* * STD vs EXT - if 11 most significant bits are the same, EXT loses. */ - const bool ext = (self & CANARD_CAN_FRAME_EFF) != 0; - const bool rhs_ext = (other & CANARD_CAN_FRAME_EFF) != 0; - if (ext != rhs_ext) + const bool self_ext = (self & CANARD_CAN_FRAME_EFF) != 0; + const bool other_ext = (other & CANARD_CAN_FRAME_EFF) != 0; + if (self_ext != other_ext) { - uint32_t arb11 = ext ? (clean_id >> 18U) : clean_id; - uint32_t rhs_arb11 = rhs_ext ? (rhs_clean_id >> 18U) : rhs_clean_id; - if (arb11 != rhs_arb11) + const uint32_t self_arb11 = self_ext ? (self_clean_id >> 18U) : self_clean_id; + const uint32_t other_arb11 = other_ext ? (other_clean_id >> 18U) : other_clean_id; + if (self_arb11 != other_arb11) { - return arb11 < rhs_arb11; + return self_arb11 < other_arb11; } else { - return rhs_ext; + return other_ext; } } /* * RTR vs Data frame - if frame identifiers and frame types are the same, RTR loses. */ - const bool rtr = (self & CANARD_CAN_FRAME_RTR) != 0; - const bool rhs_rtr = (other & CANARD_CAN_FRAME_RTR) != 0; - if (clean_id == rhs_clean_id && rtr != rhs_rtr) + const bool self_rtr = (self & CANARD_CAN_FRAME_RTR) != 0; + const bool other_rtr = (other & CANARD_CAN_FRAME_RTR) != 0; + if (self_clean_id == other_clean_id && self_rtr != other_rtr) { - return rhs_rtr; + return other_rtr; } /* * Plain ID arbitration - greater value loses. */ - return clean_id < rhs_clean_id; + return self_clean_id < other_clean_id; } /** From f31d94254e4aaeb750f1aed83e6b1a518e5569ab Mon Sep 17 00:00:00 2001 From: Windel Bouwman Date: Mon, 8 Apr 2019 11:07:33 +0200 Subject: [PATCH 77/81] Fix bug regarding TAO (tail array optimization) when using nested compound types. --- dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl b/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl index ca8c09fb..841a76c4 100644 --- a/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl +++ b/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl @@ -121,7 +121,11 @@ uint32_t ${type_name}_encode_internal(${type_name}* source, %elif f.type_category == t.CATEGORY_COMPOUND: // Compound + %if f.last_item + offset = ${f.cpp_type}_encode_internal(&source->${f.name}, msg_buf, offset, root_item); + %else offset = ${f.cpp_type}_encode_internal(&source->${f.name}, msg_buf, offset, 0); + %endif %elif f.type_category == t.CATEGORY_PRIMITIVE and f.cpp_type == "float" and f.bitlen == 16: // float16 special handling From dd35340f56279349ec88ab8c67174d12ca74d537 Mon Sep 17 00:00:00 2001 From: David Lenfesty Date: Mon, 6 May 2019 18:13:34 -0600 Subject: [PATCH 78/81] Fixed issue with decoding dynamic arrays --- dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl b/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl index 841a76c4..25d7eada 100644 --- a/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl +++ b/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl @@ -279,7 +279,7 @@ int32_t ${type_name}_decode_internal( for (c = 0; c < dest->${'%s' % ((f.name + '.len'))}; c++) { %if f.cpp_type_category == t.CATEGORY_COMPOUND: - offset += ${f.cpp_type}_decode_internal(transfer, + offset = ${f.cpp_type}_decode_internal(transfer, 0, (void*)&dest->${'%s' % ((f.name + '.data'))}[c], dyn_arr_buf, From 00f0426f810f89be9943673dc21365021cdeb196 Mon Sep 17 00:00:00 2001 From: David Lenfesty Date: Mon, 6 May 2019 18:14:21 -0600 Subject: [PATCH 79/81] Changed comment in template to maybe match functionality better. --- dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl b/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl index 25d7eada..4c82ed1b 100644 --- a/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl +++ b/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl @@ -180,7 +180,7 @@ uint32_t ${type_name}_encode(${type_name}* source, void* msg_buf) * ${type_name} dyn memory will point to dyn_arr_buf memory. * NULL will ignore dynamic arrays decoding. * @param offset: Call with 0, bit offset to msg storage - * @retval offset or ERROR value if < 0 + * @retval new offset or ERROR value if < 0 */ int32_t ${type_name}_decode_internal( const CanardRxTransfer* transfer, From 152d5fb3c07aec6e6f1560e8a4ad4d18c255357c Mon Sep 17 00:00:00 2001 From: David Lenfesty Date: Mon, 6 May 2019 18:18:14 -0600 Subject: [PATCH 80/81] Fixed theoretical encoding issue --- dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl b/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl index 4c82ed1b..cc39256d 100644 --- a/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl +++ b/dsdl_compiler/libcanard_dsdl_compiler/code_type_template.tmpl @@ -34,7 +34,7 @@ * @param msg_buf: pointer to msg storage * @param offset: bit offset to msg storage * @param root_item: for detecting if TAO should be used - * @retval returns offset + * @retval returns new offset */ uint32_t ${type_name}_encode_internal(${type_name}* source, void* msg_buf, @@ -96,7 +96,7 @@ uint32_t ${type_name}_encode_internal(${type_name}* source, for (c = 0; c < source->${'%s' % ((f.name + '.len'))}; c++) { %if f.cpp_type_category == t.CATEGORY_COMPOUND: - offset += ${f.cpp_type}_encode_internal((void*)&source->${'%s' % ((f.name + '.data'))}[c], msg_buf, offset, 0); + offset = ${f.cpp_type}_encode_internal((void*)&source->${'%s' % ((f.name + '.data'))}[c], msg_buf, offset, 0); %else canardEncodeScalar(msg_buf, offset, From f444b7efc4e9c46ff4b6e818c14bd3334356af70 Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Wed, 8 May 2019 23:30:52 +0300 Subject: [PATCH 81/81] dsdlc stability warning --- dsdl_compiler/README.md | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/dsdl_compiler/README.md b/dsdl_compiler/README.md index 6a265dfa..22aa6435 100644 --- a/dsdl_compiler/README.md +++ b/dsdl_compiler/README.md @@ -1,5 +1,9 @@ # DSDL compiler for libcanard +**WARNING: this code generation tool is not production-ready; +do not use it unless you are feeling adventurous and willing to contribute.** +In a production setting consider writing the serialization code manually instead. + ## Overview Libcanard_dsdlc is a tool for converting UAVCAN DSDL definitions into libcanard-compatible C source files or headers.