diff --git a/libuavcan/CMakeLists.txt b/libuavcan/CMakeLists.txt index 3550251523..95293dd1c9 100644 --- a/libuavcan/CMakeLists.txt +++ b/libuavcan/CMakeLists.txt @@ -101,7 +101,8 @@ if (DEBUG_BUILD) message(STATUS "Debug build (note: requires gtest)") if (COMPILER_IS_GCC_COMPATIBLE) - set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -Wextra -Werror -pedantic") + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -Wextra -Werror -pedantic -Wfloat-equal -Wconversion") + set(exec_common_flags "-Wno-conversion -Wno-float-equal") set(cpp03_flags "-std=c++03 -Wno-variadic-macros -Wno-long-long") set(optim_flags "-O3 -DNDEBUG -g0") else () @@ -120,9 +121,9 @@ if (DEBUG_BUILD) # GTest executables find_package(GTest REQUIRED) - add_libuavcan_test(libuavcan_test uavcan "") # Default - add_libuavcan_test(libuavcan_test_cpp03 uavcan_cpp03 ${cpp03_flags}) # C++03 - add_libuavcan_test(libuavcan_test_optim uavcan_optim ${optim_flags}) # Max optimization + add_libuavcan_test(libuavcan_test uavcan "${exec_common_flags}") # Default + add_libuavcan_test(libuavcan_test_cpp03 uavcan_cpp03 "${exec_common_flags} ${cpp03_flags}") # C++03 + add_libuavcan_test(libuavcan_test_optim uavcan_optim "${exec_common_flags} ${optim_flags}") # Max optimization else () message(STATUS "Release build type: " ${CMAKE_BUILD_TYPE}) endif () diff --git a/libuavcan/include/uavcan/driver/can.hpp b/libuavcan/include/uavcan/driver/can.hpp index 248af5ac98..d55859d0a0 100644 --- a/libuavcan/include/uavcan/driver/can.hpp +++ b/libuavcan/include/uavcan/driver/can.hpp @@ -34,7 +34,7 @@ struct UAVCAN_EXPORT CanFrame : id(0) , dlc(0) { - fill(data, data + MaxDataLen, 0); + fill(data, data + MaxDataLen, uint8_t(0)); } CanFrame(uint32_t can_id, const uint8_t* can_data, uint8_t data_len) diff --git a/libuavcan/include/uavcan/marshal/array.hpp b/libuavcan/include/uavcan/marshal/array.hpp index ca94e79044..22c9aa8ad5 100644 --- a/libuavcan/include/uavcan/marshal/array.hpp +++ b/libuavcan/include/uavcan/marshal/array.hpp @@ -530,7 +530,7 @@ public: void push_back(const ValueType& value) { Base::grow(); - Base::at(size() - 1) = value; + Base::at(SizeType(size() - 1)) = value; } /** diff --git a/libuavcan/include/uavcan/marshal/float_spec.hpp b/libuavcan/include/uavcan/marshal/float_spec.hpp index f43d5a39da..ec06e53f60 100644 --- a/libuavcan/include/uavcan/marshal/float_spec.hpp +++ b/libuavcan/include/uavcan/marshal/float_spec.hpp @@ -90,21 +90,25 @@ IEEE754Converter::toNative<16>(typename IntegerSpec<16, SignednessUnsigned, Cast return halfToNativeNonIeee(value); } + template struct IEEE754Limits; template <> struct IEEE754Limits<16> { - static typename NativeFloatSelector<16>::Type max() { return 65504.0; } - static typename NativeFloatSelector<16>::Type epsilon() { return 9.77e-04; } + typedef typename NativeFloatSelector<16>::Type NativeType; + static NativeType max() { return static_cast(65504.0); } + static NativeType epsilon() { return static_cast(9.77e-04); } }; template <> struct IEEE754Limits<32> { - static typename NativeFloatSelector<32>::Type max() { return 3.40282346638528859812e+38; } - static typename NativeFloatSelector<32>::Type epsilon() { return 1.19209289550781250000e-7; } + typedef typename NativeFloatSelector<32>::Type NativeType; + static NativeType max() { return static_cast(3.40282346638528859812e+38); } + static NativeType epsilon() { return static_cast(1.19209289550781250000e-7); } }; template <> struct IEEE754Limits<64> { - static typename NativeFloatSelector<64>::Type max() { return 1.79769313486231570815e+308L; } - static typename NativeFloatSelector<64>::Type epsilon() { return 2.22044604925031308085e-16L; } + typedef typename NativeFloatSelector<64>::Type NativeType; + static NativeType max() { return static_cast(1.79769313486231570815e+308L); } + static NativeType epsilon() { return static_cast(2.22044604925031308085e-16L); } }; diff --git a/libuavcan/include/uavcan/transport/frame.hpp b/libuavcan/include/uavcan/transport/frame.hpp index 5dc07a4e23..ce8d82cff7 100644 --- a/libuavcan/include/uavcan/transport/frame.hpp +++ b/libuavcan/include/uavcan/transport/frame.hpp @@ -71,7 +71,7 @@ public: bool isLast() const { return last_frame_; } void makeLast() { last_frame_ = true; } - void setIndex(uint_fast8_t index) { frame_index_ = index; } + void setIndex(int index) { frame_index_ = uint_fast8_t(index); } bool isFirst() const { return frame_index_ == 0; } diff --git a/libuavcan/include/uavcan/util/bitset.hpp b/libuavcan/include/uavcan/util/bitset.hpp index 1fe2abc300..0a9c5ea43e 100644 --- a/libuavcan/include/uavcan/util/bitset.hpp +++ b/libuavcan/include/uavcan/util/bitset.hpp @@ -94,11 +94,11 @@ public: validatePos(pos); if (val) { - data_[getByteNum(pos)] |= (1 << getBitNum(pos)); + data_[getByteNum(pos)] = char(data_[getByteNum(pos)] | (1 << getBitNum(pos))); } else { - data_[getByteNum(pos)] &= ~(1 << getBitNum(pos)); + data_[getByteNum(pos)] = char(data_[getByteNum(pos)] & ~(1 << getBitNum(pos))); } return *this; } diff --git a/libuavcan/include/uavcan/util/comparison.hpp b/libuavcan/include/uavcan/util/comparison.hpp index 095a1e3593..008aca0210 100644 --- a/libuavcan/include/uavcan/util/comparison.hpp +++ b/libuavcan/include/uavcan/util/comparison.hpp @@ -9,6 +9,16 @@ namespace uavcan { +/** + * Exact comparison of two floats that suppresses the compiler warnings. + */ +template +UAVCAN_EXPORT +inline bool areFloatsExactlyEqual(const T& left, const T& right) +{ + return (left <= right) && (left >= right); +} + /** * This function performs fuzzy comparison of two floating point numbers. * Type of T can be either float, double or long double. @@ -27,7 +37,7 @@ inline bool areFloatsClose(T a, T b, const T absolute_epsilon, const T relative_ // Infinity if (isInfinity(a) || isInfinity(b)) { - return a == b; + return areFloatsExactlyEqual(a, b); } // Close numbers near zero diff --git a/libuavcan/include/uavcan/util/lazy_constructor.hpp b/libuavcan/include/uavcan/util/lazy_constructor.hpp index 3ad8ed2aa7..1d82bacdc7 100644 --- a/libuavcan/include/uavcan/util/lazy_constructor.hpp +++ b/libuavcan/include/uavcan/util/lazy_constructor.hpp @@ -60,7 +60,7 @@ public: LazyConstructor() : ptr_(NULL) { - fill(data_.pool, data_.pool + sizeof(T), 0); + fill(data_.pool, data_.pool + sizeof(T), uint8_t(0)); } LazyConstructor(const LazyConstructor& rhs) // Implicit @@ -102,7 +102,7 @@ public: ptr_->~T(); } ptr_ = NULL; - fill(data_.pool, data_.pool + sizeof(T), 0); + fill(data_.pool, data_.pool + sizeof(T), uint8_t(0)); } void construct() diff --git a/libuavcan/include/uavcan/util/templates.hpp b/libuavcan/include/uavcan/util/templates.hpp index 2a3d101468..6388e2ca66 100644 --- a/libuavcan/include/uavcan/util/templates.hpp +++ b/libuavcan/include/uavcan/util/templates.hpp @@ -429,7 +429,8 @@ struct UAVCAN_EXPORT NumericTraits #endif /** - * Replacement for std::isnan() + * Replacement for std::isnan(). + * Note that direct float comparison (==, !=) is intentionally avoided. */ template inline bool isNaN(T arg) @@ -439,12 +440,13 @@ inline bool isNaN(T arg) #else // coverity[same_on_both_sides : FALSE] // cppcheck-suppress duplicateExpression - return arg != arg; + return !(arg <= arg); #endif } /** - * Replacement for std::isinf() + * Replacement for std::isinf(). + * Note that direct float comparison (==, !=) is intentionally avoided. */ template inline bool isInfinity(T arg) @@ -452,12 +454,13 @@ inline bool isInfinity(T arg) #if UAVCAN_CPP_VERSION >= UAVCAN_CPP11 return std::isinf(arg); #else - return arg == NumericTraits::infinity() || arg == -NumericTraits::infinity(); + return (arg >= NumericTraits::infinity()) || (arg <= -NumericTraits::infinity()); #endif } /** - * Replacement for std::signbit() + * Replacement for std::signbit(). + * Note that direct float comparison (==, !=) is intentionally avoided. */ template inline bool getSignBit(T arg) @@ -465,7 +468,7 @@ inline bool getSignBit(T arg) #if UAVCAN_CPP_VERSION >= UAVCAN_CPP11 return std::signbit(arg); #else - return arg < T(0) || (arg == T(0) && T(1) / arg < T(0)); + return arg < T(0) || (((arg <= T(0)) && (arg >= T(0))) && (T(1) / arg < T(0))); #endif } diff --git a/libuavcan/src/driver/uc_can.cpp b/libuavcan/src/driver/uc_can.cpp index 974de88359..8b06469cc2 100644 --- a/libuavcan/src/driver/uc_can.cpp +++ b/libuavcan/src/driver/uc_can.cpp @@ -68,7 +68,7 @@ std::string CanFrame::toString(StringRepresentation mode) const char buf[50]; char* wpos = buf; char* const epos = buf + sizeof(buf); - fill(buf, buf + sizeof(buf), 0); + fill(buf, buf + sizeof(buf), uint8_t(0)); if (id & FlagEFF) { diff --git a/libuavcan/src/marshal/uc_bit_array_copy.cpp b/libuavcan/src/marshal/uc_bit_array_copy.cpp index 54ab2e48d7..6eef841b1d 100644 --- a/libuavcan/src/marshal/uc_bit_array_copy.cpp +++ b/libuavcan/src/marshal/uc_bit_array_copy.cpp @@ -81,8 +81,8 @@ void bitarrayCopy(const unsigned char* src_org, int src_offset, int src_len, uns bit_diff_ls = src_offset_modulo - dst_offset_modulo; bit_diff_rs = CHAR_BIT - bit_diff_ls; - c = *src++ << bit_diff_ls; - c |= *src >> bit_diff_rs; + c = static_cast(*src++ << bit_diff_ls); + c = static_cast(c | (*src >> bit_diff_rs)); c &= reverse_mask_xor[dst_offset_modulo]; } else @@ -90,7 +90,7 @@ void bitarrayCopy(const unsigned char* src_org, int src_offset, int src_len, uns bit_diff_rs = dst_offset_modulo - src_offset_modulo; bit_diff_ls = CHAR_BIT - bit_diff_rs; - c = *src >> bit_diff_rs & reverse_mask_xor[dst_offset_modulo]; + c = static_cast(*src >> bit_diff_rs & reverse_mask_xor[dst_offset_modulo]); } PREPARE_FIRST_COPY(); *dst++ |= c; @@ -102,8 +102,8 @@ void bitarrayCopy(const unsigned char* src_org, int src_offset, int src_len, uns while (--byte_len >= 0) { - c = *src++ << bit_diff_ls; - c |= *src >> bit_diff_rs; + c = static_cast(*src++ << bit_diff_ls); + c = static_cast(c | (*src >> bit_diff_rs)); *dst++ = c; } @@ -113,8 +113,8 @@ void bitarrayCopy(const unsigned char* src_org, int src_offset, int src_len, uns src_len_modulo = src_len % CHAR_BIT; if (src_len_modulo) { - c = *src++ << bit_diff_ls; - c |= *src >> bit_diff_rs; + c = static_cast(*src++ << bit_diff_ls); + c = static_cast(c | (*src >> bit_diff_rs)); c &= reverse_mask[src_len_modulo]; *dst &= reverse_mask_xor[src_len_modulo]; diff --git a/libuavcan/src/marshal/uc_bit_stream.cpp b/libuavcan/src/marshal/uc_bit_stream.cpp index 213bb3100c..d437771f79 100644 --- a/libuavcan/src/marshal/uc_bit_stream.cpp +++ b/libuavcan/src/marshal/uc_bit_stream.cpp @@ -22,7 +22,7 @@ int BitStream::write(const uint8_t* bytes, const int bitlen) UAVCAN_ASSERT(MaxBytesPerRW >= bytelen); tmp[0] = tmp[bytelen - 1] = 0; - fill(tmp, tmp + bytelen, 0); + fill(tmp, tmp + bytelen, uint8_t(0)); copyBitArray(bytes, 0, bitlen, tmp, bit_offset_ % 8); const int new_bit_offset = bit_offset_ + bitlen; @@ -31,7 +31,7 @@ int BitStream::write(const uint8_t* bytes, const int bitlen) tmp[0] |= byte_cache_; // (new_bit_offset % 8 == 0) means that this write was perfectly aligned. - byte_cache_ = (new_bit_offset % 8) ? tmp[bytelen - 1] : 0; + byte_cache_ = uint8_t((new_bit_offset % 8) ? tmp[bytelen - 1] : 0); /* * Dump the data into the destination buffer. @@ -69,7 +69,7 @@ int BitStream::read(uint8_t* bytes, const int bitlen) return ResultOutOfBuffer; } - fill(bytes, bytes + bitlenToBytelen(bitlen), 0); + fill(bytes, bytes + bitlenToBytelen(bitlen), uint8_t(0)); copyBitArray(tmp, bit_offset_ % 8, bitlen, bytes, 0); bit_offset_ += bitlen; return ResultOk; diff --git a/libuavcan/src/marshal/uc_float_spec.cpp b/libuavcan/src/marshal/uc_float_spec.cpp index 07c0d980c1..cddf6bb696 100644 --- a/libuavcan/src/marshal/uc_float_spec.cpp +++ b/libuavcan/src/marshal/uc_float_spec.cpp @@ -22,8 +22,8 @@ namespace uavcan */ uint16_t IEEE754Converter::nativeNonIeeeToHalf(float value) { - uint16_t hbits = static_cast(getSignBit(value)) << 15; - if (value == 0.0f) + uint16_t hbits = uint16_t(getSignBit(value) ? 0x8000U : 0); + if (areFloatsExactlyEqual(value, 0.0F)) { return hbits; } @@ -48,12 +48,12 @@ uint16_t IEEE754Converter::nativeNonIeeeToHalf(float value) else { value = std::ldexp(value, 11 - exp); - hbits |= ((exp + 14) << 10); + hbits |= uint16_t((exp + 14) << 10); } const int32_t ival = static_cast(value); - hbits |= static_cast(((ival < 0) ? (-ival) : ival) & 0x3FFU); + hbits = uint16_t(hbits | (((ival < 0) ? (-ival) : ival) & 0x3FFU)); float diff = std::fabs(value - static_cast(ival)); - hbits += diff >= 0.5F; + hbits = uint16_t(hbits + (diff >= 0.5F)); return hbits; } diff --git a/libuavcan/src/marshal/uc_scalar_codec.cpp b/libuavcan/src/marshal/uc_scalar_codec.cpp index b0807a8bcd..6fa62e20b3 100644 --- a/libuavcan/src/marshal/uc_scalar_codec.cpp +++ b/libuavcan/src/marshal/uc_scalar_codec.cpp @@ -24,7 +24,7 @@ int ScalarCodec::encodeBytesImpl(uint8_t* const bytes, const unsigned bitlen) // Underlying stream class assumes that more significant bits have lower index, so we need to shift some. if (bitlen % 8) { - bytes[bitlen / 8] <<= (8 - (bitlen % 8)) & 7; + bytes[bitlen / 8] = uint8_t(bytes[bitlen / 8] << ((8 - (bitlen % 8)) & 7)); } return stream_.write(bytes, bitlen); } @@ -37,7 +37,7 @@ int ScalarCodec::decodeBytesImpl(uint8_t* const bytes, const unsigned bitlen) { if (bitlen % 8) { - bytes[bitlen / 8] >>= (8 - (bitlen % 8)) & 7; // As in encode(), vice versa + bytes[bitlen / 8] = uint8_t(bytes[bitlen / 8] >> ((8 - (bitlen % 8)) & 7)); // As in encode(), vice versa } } return read_res; diff --git a/libuavcan/src/protocol/uc_global_time_sync_master.cpp b/libuavcan/src/protocol/uc_global_time_sync_master.cpp index 96ed06b1a8..8f45c43c1a 100644 --- a/libuavcan/src/protocol/uc_global_time_sync_master.cpp +++ b/libuavcan/src/protocol/uc_global_time_sync_master.cpp @@ -22,7 +22,7 @@ int GlobalTimeSyncMaster::IfaceMaster::init() { TransferSender* const ts = pub_.getTransferSender(); UAVCAN_ASSERT(ts != NULL); - ts->setIfaceMask(1 << iface_index_); + ts->setIfaceMask(uint8_t(1 << iface_index_)); ts->setCanIOFlags(CanIOFlagLoopback); } return res; diff --git a/libuavcan/src/protocol/uc_network_compat_checker.cpp b/libuavcan/src/protocol/uc_network_compat_checker.cpp index 4c215b29c8..6738f723cb 100644 --- a/libuavcan/src/protocol/uc_network_compat_checker.cpp +++ b/libuavcan/src/protocol/uc_network_compat_checker.cpp @@ -25,7 +25,7 @@ MonotonicDuration NetworkCompatibilityChecker::getNetworkDiscoveryDelay() const NodeID NetworkCompatibilityChecker::findNextUncheckedNode() { - for (int i = 1; i <= NodeID::Max; i++) + for (uint8_t i = 1; i <= NodeID::Max; i++) { if (nid_mask_present_.test(i) && !nid_mask_checked_.test(i)) { @@ -141,7 +141,10 @@ int NetworkCompatibilityChecker::checkNodes() { UAVCAN_TRACE("NodeInitializer", "Checking nid=%i", int(nid.get())); const int res = checkOneNode(nid); - result_.num_failed_nodes += (res < 0) ? 1U : 0U; + if (res < 0) + { + result_.num_failed_nodes++; + } UAVCAN_TRACE("NodeInitializer", "Checked nid=%i result=%i", int(nid.get()), res); } else { break; } diff --git a/libuavcan/src/protocol/uc_node_status_monitor.cpp b/libuavcan/src/protocol/uc_node_status_monitor.cpp index 6bb5a6e81f..1e3cd9f128 100644 --- a/libuavcan/src/protocol/uc_node_status_monitor.cpp +++ b/libuavcan/src/protocol/uc_node_status_monitor.cpp @@ -58,7 +58,7 @@ void NodeStatusMonitor::handleTimerEvent(const TimerEvent&) { const int OfflineTimeoutMs100 = protocol::NodeStatus::OFFLINE_TIMEOUT_MS / 100; - for (int i = 1; i <= NodeID::Max; i++) + for (uint8_t i = 1; i <= NodeID::Max; i++) { const NodeID nid(i); UAVCAN_ASSERT(nid.isUnicast()); @@ -66,7 +66,7 @@ void NodeStatusMonitor::handleTimerEvent(const TimerEvent&) if (entry.time_since_last_update_ms100 >= 0 && entry.status_code != protocol::NodeStatus::STATUS_OFFLINE) { - entry.time_since_last_update_ms100 += TimerPeriodMs100; + entry.time_since_last_update_ms100 = int8_t(entry.time_since_last_update_ms100 + TimerPeriodMs100); if (entry.time_since_last_update_ms100 >= OfflineTimeoutMs100) { Entry new_entry_value; @@ -123,7 +123,7 @@ NodeID NodeStatusMonitor::findNodeWithWorstStatus() const NodeID nid_with_worst_status; NodeStatusCode worst_status_code = protocol::NodeStatus::STATUS_OK; - for (int i = 1; i <= NodeID::Max; i++) + for (uint8_t i = 1; i <= NodeID::Max; i++) { const NodeID nid(i); UAVCAN_ASSERT(nid.isUnicast()); diff --git a/libuavcan/src/protocol/uc_node_status_provider.cpp b/libuavcan/src/protocol/uc_node_status_provider.cpp index 32a5bacb7f..7a6425684e 100644 --- a/libuavcan/src/protocol/uc_node_status_provider.cpp +++ b/libuavcan/src/protocol/uc_node_status_provider.cpp @@ -19,7 +19,7 @@ int NodeStatusProvider::publish() { const MonotonicDuration uptime = getNode().getMonotonicTime() - creation_timestamp_; UAVCAN_ASSERT(uptime.isPositive()); - node_info_.status.uptime_sec = uptime.toMSec() / 1000; + node_info_.status.uptime_sec = uint32_t(uptime.toMSec() / 1000); UAVCAN_ASSERT(node_info_.status.status_code <= protocol::NodeStatus::FieldTypes::status_code::max()); diff --git a/libuavcan/src/protocol/uc_transport_stats_provider.cpp b/libuavcan/src/protocol/uc_transport_stats_provider.cpp index 7a76bc431e..63c31c4ba7 100644 --- a/libuavcan/src/protocol/uc_transport_stats_provider.cpp +++ b/libuavcan/src/protocol/uc_transport_stats_provider.cpp @@ -19,7 +19,7 @@ void TransportStatsProvider::handleGetTransportStats(const protocol::GetTranspor resp.transfers_rx = perf.getRxTransferCount(); const CanIOManager& canio = srv_.getNode().getDispatcher().getCanIOManager(); - for (int i = 0; i < canio.getNumIfaces(); i++) + for (uint8_t i = 0; i < canio.getNumIfaces(); i++) { const CanIfacePerfCounters can_perf = canio.getIfacePerfCounters(i); protocol::CANIfaceStats stats; diff --git a/libuavcan/src/transport/uc_can_io.cpp b/libuavcan/src/transport/uc_can_io.cpp index 00113ecf50..dd9d19ba0f 100644 --- a/libuavcan/src/transport/uc_can_io.cpp +++ b/libuavcan/src/transport/uc_can_io.cpp @@ -20,7 +20,7 @@ std::string CanRxFrame::toString(StringRepresentation mode) const out += " ts_m=" + ts_mono.toString(); out += " ts_utc=" + ts_utc.toString(); out += " iface="; - out += '0' + iface_index; + out += char('0' + iface_index); return out; } #endif @@ -268,7 +268,7 @@ uint8_t CanIOManager::makePendingTxMask() const { if (!tx_queues_[i]->isEmpty()) { - write_mask |= 1 << i; + write_mask |= uint8_t(1 << i); } } return write_mask; @@ -331,7 +331,7 @@ int CanIOManager::send(const CanFrame& frame, MonotonicTime tx_deadline, Monoton uint8_t iface_mask, CanTxQueue::Qos qos, CanIOFlags flags) { const uint8_t num_ifaces = getNumIfaces(); - const uint8_t all_ifaces_mask = (1U << num_ifaces) - 1; + const uint8_t all_ifaces_mask = uint8_t((1U << num_ifaces) - 1); iface_mask &= all_ifaces_mask; if (blocking_deadline > tx_deadline) @@ -375,7 +375,7 @@ int CanIOManager::send(const CanFrame& frame, MonotonicTime tx_deadline, Monoton res = sendToIface(i, frame, tx_deadline, flags); if (res > 0) { - iface_mask &= ~(1 << i); // Mark transmitted + iface_mask &= uint8_t(~(1 << i)); // Mark transmitted } } } @@ -420,7 +420,7 @@ int CanIOManager::receive(CanRxFrame& out_frame, MonotonicTime blocking_deadline { CanSelectMasks masks; masks.write = makePendingTxMask(); - masks.read = (1 << num_ifaces) - 1; + masks.read = uint8_t((1 << num_ifaces) - 1); { const int select_res = callSelect(masks, blocking_deadline); if (select_res < 0) diff --git a/libuavcan/src/transport/uc_frame.cpp b/libuavcan/src/transport/uc_frame.cpp index 58ad6ff945..f7b2fb17ec 100644 --- a/libuavcan/src/transport/uc_frame.cpp +++ b/libuavcan/src/transport/uc_frame.cpp @@ -42,7 +42,7 @@ int Frame::setPayload(const uint8_t* data, unsigned len) } len = min(unsigned(maxlen), len); (void)copy(data, data + len, payload_); - payload_len_ = len; + payload_len_ = uint_fast8_t(len); return len; } @@ -69,12 +69,12 @@ bool Frame::parse(const CanFrame& can_frame) * CAN ID parsing */ const uint32_t id = can_frame.id & CanFrame::MaskExtID; - transfer_id_ = bitunpack<0, 3>(id); - last_frame_ = bitunpack<3, 1>(id); - frame_index_ = bitunpack<4, 6>(id); - src_node_id_ = bitunpack<10, 7>(id); + transfer_id_ = uint8_t(bitunpack<0, 3>(id)); + last_frame_ = bitunpack<3, 1>(id) != 0; + frame_index_ = uint8_t(bitunpack<4, 6>(id)); + src_node_id_ = uint8_t(bitunpack<10, 7>(id)); transfer_type_ = TransferType(bitunpack<17, 2>(id)); - data_type_id_ = bitunpack<19, 10>(id); + data_type_id_ = uint16_t(bitunpack<19, 10>(id)); /* * CAN payload parsing @@ -101,7 +101,7 @@ bool Frame::parse(const CanFrame& can_frame) return false; } dst_node_id_ = can_frame.data[0] & 0x7F; - payload_len_ = can_frame.dlc - 1; + payload_len_ = uint8_t(can_frame.dlc - 1); (void)copy(can_frame.data + 1, can_frame.data + can_frame.dlc, payload_); break; } @@ -117,7 +117,7 @@ bool Frame::parse(const CanFrame& can_frame) template inline static uint32_t bitpack(uint32_t field) { - return (field & ((1UL << WIDTH) - 1)) << OFFSET; + return uint32_t((field & ((1UL << WIDTH) - 1)) << OFFSET); } bool Frame::compile(CanFrame& out_can_frame) const @@ -151,7 +151,7 @@ bool Frame::compile(CanFrame& out_can_frame) const { UAVCAN_ASSERT((payload_len_ + 1U) <= sizeof(out_can_frame.data)); out_can_frame.data[0] = dst_node_id_.get(); - out_can_frame.dlc = payload_len_ + 1; + out_can_frame.dlc = uint8_t(payload_len_ + 1); (void)copy(payload_, payload_ + payload_len_, out_can_frame.data + 1); break; } @@ -255,7 +255,7 @@ std::string RxFrame::toString() const out += " ts_m=" + ts_mono_.toString(); out += " ts_utc=" + ts_utc_.toString(); out += " iface="; - out += '0' + iface_index_; + out += char('0' + iface_index_); return out; } #endif diff --git a/libuavcan/src/transport/uc_transfer_buffer.cpp b/libuavcan/src/transport/uc_transfer_buffer.cpp index 192f43fdc2..dbdcbdc4b6 100644 --- a/libuavcan/src/transport/uc_transfer_buffer.cpp +++ b/libuavcan/src/transport/uc_transfer_buffer.cpp @@ -216,7 +216,7 @@ int DynamicTransferBufferManagerEntry::write(unsigned offset, const uint8_t* dat } const int actually_written = len - left_to_write; - max_write_pos_ = max(offset + actually_written, unsigned(max_write_pos_)); + max_write_pos_ = max(uint16_t(offset + actually_written), uint16_t(max_write_pos_)); return actually_written; } @@ -260,7 +260,7 @@ int StaticTransferBufferImpl::write(unsigned offset, const uint8_t* data, unsign } UAVCAN_ASSERT((offset + len) <= size_); (void)copy(data, data + len, data_ + offset); - max_write_pos_ = max(offset + len, unsigned(max_write_pos_)); + max_write_pos_ = max(uint16_t(offset + len), uint16_t(max_write_pos_)); return len; } @@ -268,7 +268,7 @@ void StaticTransferBufferImpl::reset() { max_write_pos_ = 0; #if UAVCAN_DEBUG - fill(data_, data_ + size_, 0); + fill(data_, data_ + size_, uint8_t(0)); #endif } @@ -306,7 +306,7 @@ bool StaticTransferBufferManagerEntryImpl::migrateFrom(const TransferBufferManag TransferBufferManagerEntry::reset(); return false; } - buf_.setMaxWritePos(res); + buf_.setMaxWritePos(uint16_t(res)); if (res < int(buf_.getSize())) { return true; @@ -329,7 +329,7 @@ StaticTransferBufferManagerEntryImpl* TransferBufferManagerImpl::findFirstStatic { for (unsigned i = 0; true; i++) { - StaticTransferBufferManagerEntryImpl* const sb = getStaticByIndex(i); + StaticTransferBufferManagerEntryImpl* const sb = getStaticByIndex(uint16_t(i)); if (sb == NULL) { break; @@ -492,7 +492,7 @@ unsigned TransferBufferManagerImpl::getNumStaticBuffers() const unsigned res = 0; for (unsigned i = 0; true; i++) { - StaticTransferBufferManagerEntryImpl* const sb = getStaticByIndex(i); + StaticTransferBufferManagerEntryImpl* const sb = getStaticByIndex(uint16_t(i)); if (sb == NULL) { break; diff --git a/libuavcan/src/transport/uc_transfer_listener.cpp b/libuavcan/src/transport/uc_transfer_listener.cpp index de6c72c910..ddd9a22698 100644 --- a/libuavcan/src/transport/uc_transfer_listener.cpp +++ b/libuavcan/src/transport/uc_transfer_listener.cpp @@ -25,7 +25,7 @@ SingleFrameIncomingTransfer::SingleFrameIncomingTransfer(const RxFrame& frm) : IncomingTransfer(frm.getMonotonicTimestamp(), frm.getUtcTimestamp(), frm.getTransferType(), frm.getTransferID(), frm.getSrcNodeID(), frm.getIfaceIndex()) , payload_(frm.getPayloadPtr()) - , payload_len_(frm.getPayloadLen()) + , payload_len_(uint8_t(frm.getPayloadLen())) { UAVCAN_ASSERT(frm.isValid()); } diff --git a/libuavcan/src/transport/uc_transfer_receiver.cpp b/libuavcan/src/transport/uc_transfer_receiver.cpp index 7fff829a0f..a68f11c137 100644 --- a/libuavcan/src/transport/uc_transfer_receiver.cpp +++ b/libuavcan/src/transport/uc_transfer_receiver.cpp @@ -20,7 +20,7 @@ void TransferReceiver::registerError() const { if (error_cnt_ < 0xFF) { - error_cnt_ += 1; + error_cnt_ = static_cast(error_cnt_ + 1); } else { @@ -102,33 +102,33 @@ bool TransferReceiver::validate(const RxFrame& frame) const bool TransferReceiver::writePayload(const RxFrame& frame, ITransferBuffer& buf) { const uint8_t* const payload = frame.getPayloadPtr(); - const int payload_len = frame.getPayloadLen(); + const unsigned payload_len = frame.getPayloadLen(); if (frame.isFirst()) // First frame contains CRC, we need to extract it now { if (frame.getPayloadLen() < TransferCRC::NumBytes) { return false; // Must have been validated earlier though. I think I'm paranoid. - } - this_transfer_crc_ = (payload[0] & 0xFF) | (uint16_t(payload[1] & 0xFF) << 8); // Little endian. + this_transfer_crc_ = static_cast(payload[0] & 0xFF); + this_transfer_crc_ |= static_cast(static_cast(payload[1] & 0xFF) << 8); // Little endian. - const int effective_payload_len = payload_len - TransferCRC::NumBytes; + const unsigned effective_payload_len = payload_len - TransferCRC::NumBytes; const int res = buf.write(buffer_write_pos_, payload + TransferCRC::NumBytes, effective_payload_len); - const bool success = res == effective_payload_len; + const bool success = res == static_cast(effective_payload_len); if (success) { - buffer_write_pos_ += effective_payload_len; + buffer_write_pos_ = static_cast(buffer_write_pos_ + effective_payload_len); } return success; } else { const int res = buf.write(buffer_write_pos_, payload, payload_len); - const bool success = res == payload_len; + const bool success = res == static_cast(payload_len); if (success) { - buffer_write_pos_ += payload_len; + buffer_write_pos_ = static_cast(buffer_write_pos_ + payload_len); } return success; } diff --git a/libuavcan/src/transport/uc_transfer_sender.cpp b/libuavcan/src/transport/uc_transfer_sender.cpp index f91e48b5e3..7ff5ce327f 100644 --- a/libuavcan/src/transport/uc_transfer_sender.cpp +++ b/libuavcan/src/transport/uc_transfer_sender.cpp @@ -52,8 +52,8 @@ int TransferSender::send(const uint8_t* payload, int payload_len, MonotonicTime static const int BUFLEN = sizeof(static_cast(0)->data); uint8_t buf[BUFLEN]; - buf[0] = crc.get() & 0xFF; // Transfer CRC, little endian - buf[1] = (crc.get() >> 8) & 0xFF; + buf[0] = uint8_t(crc.get() & 0xFFU); // Transfer CRC, little endian + buf[1] = uint8_t((crc.get() >> 8) & 0xFF); (void)copy(payload, payload + BUFLEN - 2, buf + 2); const int write_res = frame.setPayload(buf, BUFLEN); diff --git a/libuavcan/test/marshal/float_spec.cpp b/libuavcan/test/marshal/float_spec.cpp index 3fa9b47225..ce0f6b5143 100644 --- a/libuavcan/test/marshal/float_spec.cpp +++ b/libuavcan/test/marshal/float_spec.cpp @@ -8,6 +8,14 @@ #include +TEST(FloatSpec, Sizes) +{ + uavcan::StaticAssert::Type) == 4>::check(); + uavcan::StaticAssert::Type) == 4>::check(); + uavcan::StaticAssert::Type) == 8>::check(); + uavcan::StaticAssert::Type) >= 10>::check(); +} + TEST(FloatSpec, Limits) { using uavcan::FloatSpec;