diff --git a/libuavcan/CMakeLists.txt b/libuavcan/CMakeLists.txt index f36514b0dc..a7cfc68123 100644 --- a/libuavcan/CMakeLists.txt +++ b/libuavcan/CMakeLists.txt @@ -119,10 +119,14 @@ if (DEBUG_BUILD) message(STATUS "Debug build (note: requires gtest)") if (COMPILER_IS_GCC_COMPATIBLE) + # No such thing as too many warnings set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -Wextra -Werror -pedantic -Wfloat-equal -Wconversion") set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wsign-conversion -Wcast-align -Wmissing-declarations -Wlogical-op") set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wdouble-promotion -Wswitch-enum -Wtype-limits -Wno-error=array-bounds") - set(cpp03_flags "-std=c++03 -Wno-variadic-macros -Wno-long-long") + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wzero-as-null-pointer-constant -Wnon-virtual-dtor") + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Woverloaded-virtual -Wsign-promo -Wold-style-cast") + #set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Weffc++ -Wno-error=effc++") # Produces heaps of useless warnings + set(cpp03_flags "-std=c++03 -Wno-variadic-macros -Wno-long-long -Wno-zero-as-null-pointer-constant") set(optim_flags "-O3 -DNDEBUG -g0") else () message(STATUS "Compiler ID: ${CMAKE_CXX_COMPILER_ID}") diff --git a/libuavcan/dsdl_compiler/libuavcan_dsdl_compiler/data_type_template.tmpl b/libuavcan/dsdl_compiler/libuavcan_dsdl_compiler/data_type_template.tmpl index 8fd54b5db0..2b0acbf8e9 100644 --- a/libuavcan/dsdl_compiler/libuavcan_dsdl_compiler/data_type_template.tmpl +++ b/libuavcan/dsdl_compiler/libuavcan_dsdl_compiler/data_type_template.tmpl @@ -365,7 +365,7 @@ template <> inline const typename ${scope_prefix}<0>::TagToType< ${scope_prefix}<0>::Tag::${a.name} >::StorageType* ${scope_prefix}<0>::as< ${scope_prefix}<0>::Tag::${a.name} >() const { - return is(${scope_prefix}<0>::Tag::${a.name}) ? &${a.name} : NULL; + return is(${scope_prefix}<0>::Tag::${a.name}) ? &${a.name} : UAVCAN_NULLPTR; } template <> diff --git a/libuavcan/include/uavcan/build_config.hpp b/libuavcan/include/uavcan/build_config.hpp index c1ee6dc1e0..e9cb32072a 100644 --- a/libuavcan/include/uavcan/build_config.hpp +++ b/libuavcan/include/uavcan/build_config.hpp @@ -38,6 +38,18 @@ # endif #endif +/** + * The library uses UAVCAN_NULLPTR instead of UAVCAN_NULLPTR and nullptr in order to allow the use of + * -Wzero-as-null-pointer-constant. + */ +#ifndef UAVCAN_NULLPTR +# if UAVCAN_CPP_VERSION >= UAVCAN_CPP11 +# define UAVCAN_NULLPTR nullptr +# else +# define UAVCAN_NULLPTR NULL +# endif +#endif + /** * By default, libuavcan enables all features if it detects that it is being built for a general-purpose * target like Linux. Value of this macro influences other configuration options located below in this file. diff --git a/libuavcan/include/uavcan/driver/can.hpp b/libuavcan/include/uavcan/driver/can.hpp index d6f89c4f1b..d20feca154 100644 --- a/libuavcan/include/uavcan/driver/can.hpp +++ b/libuavcan/include/uavcan/driver/can.hpp @@ -46,7 +46,7 @@ struct UAVCAN_EXPORT CanFrame id(can_id), dlc((data_len > MaxDataLen) ? MaxDataLen : data_len) { - UAVCAN_ASSERT(can_data != NULL); + UAVCAN_ASSERT(can_data != UAVCAN_NULLPTR); UAVCAN_ASSERT(data_len == dlc); (void)copy(can_data, can_data + dlc, this->data); } @@ -232,7 +232,7 @@ public: * The pending TX argument contains an array of pointers to CAN frames that the library wants to transmit * next, per interface. This is intended to allow the driver to properly prioritize transmissions; many * drivers will not need to use it. If a write flag for the given interface is set to one in the select mask - * structure, then the corresponding pointer is guaranteed to be valid (not NULL). + * structure, then the corresponding pointer is guaranteed to be valid (not UAVCAN_NULLPTR). * * @param [in,out] inout_masks Masks indicating which interfaces are needed/available for IO. * @param [in] pending_tx Array of frames, per interface, that are likely to be transmitted next. diff --git a/libuavcan/include/uavcan/dynamic_memory.hpp b/libuavcan/include/uavcan/dynamic_memory.hpp index 51e0fb912f..7ead5bf584 100644 --- a/libuavcan/include/uavcan/dynamic_memory.hpp +++ b/libuavcan/include/uavcan/dynamic_memory.hpp @@ -153,15 +153,15 @@ PoolAllocator::PoolAllocator() : // coverity[dead_error_line : FALSE] free_list_[i].next = free_list_ + i + 1; } - free_list_[NumBlocks - 1].next = NULL; + free_list_[NumBlocks - 1].next = UAVCAN_NULLPTR; } template void* PoolAllocator::allocate(std::size_t size) { - if (free_list_ == NULL || size > BlockSize) + if (free_list_ == UAVCAN_NULLPTR || size > BlockSize) { - return NULL; + return UAVCAN_NULLPTR; } RaiiSynchronizer lock; @@ -184,7 +184,7 @@ void* PoolAllocator::allocate(std::size_t template void PoolAllocator::deallocate(const void* ptr) { - if (ptr == NULL) + if (ptr == UAVCAN_NULLPTR) { return; } diff --git a/libuavcan/include/uavcan/helpers/heap_based_pool_allocator.hpp b/libuavcan/include/uavcan/helpers/heap_based_pool_allocator.hpp index f2e9e9e0d6..7a0851cd56 100644 --- a/libuavcan/include/uavcan/helpers/heap_based_pool_allocator.hpp +++ b/libuavcan/include/uavcan/helpers/heap_based_pool_allocator.hpp @@ -75,7 +75,7 @@ public: static_cast(NumericTraits::max())))), num_reserved_blocks_(0), num_allocated_blocks_(0), - reserve_(NULL) + reserve_(UAVCAN_NULLPTR) { } /** @@ -101,7 +101,7 @@ public: { if (size > BlockSize) { - return NULL; + return UAVCAN_NULLPTR; } { @@ -110,7 +110,7 @@ public: Node* const p = reserve_; - if (UAVCAN_LIKELY(p != NULL)) + if (UAVCAN_LIKELY(p != UAVCAN_NULLPTR)) { reserve_ = reserve_->next; num_allocated_blocks_++; @@ -119,13 +119,13 @@ public: if (num_reserved_blocks_ >= capacity_hard_limit_) // Hard limit reached, no further allocations { - return NULL; + return UAVCAN_NULLPTR; } } // Unlikely branch void* const m = std::malloc(sizeof(Node)); - if (m != NULL) + if (m != UAVCAN_NULLPTR) { RaiiSynchronizer lock; (void)lock; @@ -142,7 +142,7 @@ public: */ virtual void deallocate(const void* ptr) { - if (ptr != NULL) + if (ptr != UAVCAN_NULLPTR) { RaiiSynchronizer lock; (void)lock; @@ -171,7 +171,7 @@ public: */ void shrink() { - Node* p = NULL; + Node* p = UAVCAN_NULLPTR; for (;;) { { @@ -179,7 +179,7 @@ public: (void)lock; // Removing from reserve and updating the counter. p = reserve_; - if (p != NULL) + if (p != UAVCAN_NULLPTR) { reserve_ = reserve_->next; num_reserved_blocks_--; diff --git a/libuavcan/include/uavcan/marshal/array.hpp b/libuavcan/include/uavcan/marshal/array.hpp index 41384d8a5a..1e2508238c 100644 --- a/libuavcan/include/uavcan/marshal/array.hpp +++ b/libuavcan/include/uavcan/marshal/array.hpp @@ -761,7 +761,8 @@ public: * Members must be comparable via operator ==. */ template - typename EnableIfsize()) && sizeof((*((const R*)(0U)))[0]), bool>::Type + typename EnableIf(0))->size()) && + sizeof((*(reinterpret_cast(0)))[0]), bool>::Type operator==(const R& rhs) const { if (size() != rhs.size()) @@ -786,7 +787,8 @@ public: * Any container with size() and [] is acceptable. */ template - typename EnableIfsize()) && sizeof((*((const R*)(0U)))[0]), bool>::Type + typename EnableIf(0))->size()) && + sizeof((*(reinterpret_cast(0)))[0]), bool>::Type isClose(const R& rhs) const { if (size() != rhs.size()) @@ -809,7 +811,7 @@ public: */ bool operator==(const char* ch) const { - if (ch == NULL) + if (ch == UAVCAN_NULLPTR) { return false; } @@ -830,7 +832,7 @@ public: StaticAssert::check(); StaticAssert::check(); Base::clear(); - if (ch == NULL) + if (ch == UAVCAN_NULLPTR) { handleFatalError("Array::operator=(const char*)"); } @@ -849,7 +851,7 @@ public: { StaticAssert::check(); StaticAssert::check(); - if (ch == NULL) + if (ch == UAVCAN_NULLPTR) { handleFatalError("Array::operator+=(const char*)"); } @@ -1001,7 +1003,8 @@ public: * Note that matrix packing code uses @ref areClose() for comparison. */ template - typename EnableIfbegin()) && sizeof(((const R*)(0U))->size())>::Type + typename EnableIf(0))->begin()) && + sizeof((reinterpret_cast(0))->size())>::Type packSquareMatrix(const R& src_row_major) { if (src_row_major.size() == MaxSize) @@ -1057,7 +1060,8 @@ public: * Please refer to the specification to learn more about matrix packing. */ template - typename EnableIfbegin()) && sizeof(((const R*)(0U))->size())>::Type + typename EnableIf(0))->begin()) && + sizeof((reinterpret_cast(0))->size())>::Type unpackSquareMatrix(R& dst_row_major) const { if (dst_row_major.size() == MaxSize) diff --git a/libuavcan/include/uavcan/node/generic_publisher.hpp b/libuavcan/include/uavcan/node/generic_publisher.hpp index 60623ecbe3..a8197b6cf9 100644 --- a/libuavcan/include/uavcan/node/generic_publisher.hpp +++ b/libuavcan/include/uavcan/node/generic_publisher.hpp @@ -86,7 +86,7 @@ class UAVCAN_EXPORT GenericPublisher : public GenericPublisherBase { struct ZeroTransferBuffer : public StaticTransferBufferImpl { - ZeroTransferBuffer() : StaticTransferBufferImpl(NULL, 0) { } + ZeroTransferBuffer() : StaticTransferBufferImpl(UAVCAN_NULLPTR, 0) { } }; typedef typename Select& msg); * void second(const Foo& msg); * In the latter case, an implicit cast will happen before the callback is invoked. + * + * This class is not copyable because it holds a reference to a stack-allocated transfer descriptor object. + * You can slice cast it to the underlying data type though, which would be copyable: + * DataType dt = rds; // where rds is of type ReceivedDataStructure + * // dt is now copyable */ template -class UAVCAN_EXPORT ReceivedDataStructure : public DataType_ +class UAVCAN_EXPORT ReceivedDataStructure : public DataType_, Noncopyable { const IncomingTransfer* const _transfer_; ///< Such weird name is necessary to avoid clashing with DataType fields template Ret safeget() const { - if (_transfer_ == NULL) + if (_transfer_ == UAVCAN_NULLPTR) { return Ret(); } @@ -47,13 +52,13 @@ class UAVCAN_EXPORT ReceivedDataStructure : public DataType_ protected: ReceivedDataStructure() - : _transfer_(NULL) + : _transfer_(UAVCAN_NULLPTR) { } ReceivedDataStructure(const IncomingTransfer* arg_transfer) : _transfer_(arg_transfer) { - UAVCAN_ASSERT(arg_transfer != NULL); + UAVCAN_ASSERT(arg_transfer != UAVCAN_NULLPTR); } public: @@ -230,7 +235,7 @@ int GenericSubscriber::checkInit() GlobalDataTypeRegistry::instance().freeze(); const DataTypeDescriptor* const descr = GlobalDataTypeRegistry::instance().find(DataTypeKind(DataSpec::DataTypeKind), DataSpec::getDataTypeFullName()); - if (descr == NULL) + if (descr == UAVCAN_NULLPTR) { UAVCAN_TRACE("GenericSubscriber", "Type [%s] is not registered", DataSpec::getDataTypeFullName()); return -ErrUnknownDataType; diff --git a/libuavcan/include/uavcan/node/global_data_type_registry.hpp b/libuavcan/include/uavcan/node/global_data_type_registry.hpp index fb8d43c39b..0148ce0f50 100644 --- a/libuavcan/include/uavcan/node/global_data_type_registry.hpp +++ b/libuavcan/include/uavcan/node/global_data_type_registry.hpp @@ -49,13 +49,13 @@ class UAVCAN_EXPORT GlobalDataTypeRegistry : Noncopyable { const DataTypeID id; explicit EntryInsertionComparator(const Entry* dtd) - : id((dtd == NULL) ? DataTypeID() : dtd->descriptor.getID()) + : id((dtd == UAVCAN_NULLPTR) ? DataTypeID() : dtd->descriptor.getID()) { - UAVCAN_ASSERT(dtd != NULL); + UAVCAN_ASSERT(dtd != UAVCAN_NULLPTR); } bool operator()(const Entry* entry) const { - UAVCAN_ASSERT(entry != NULL); + UAVCAN_ASSERT(entry != UAVCAN_NULLPTR); return entry->descriptor.getID() > id; } }; @@ -211,7 +211,9 @@ GlobalDataTypeRegistry::RegistrationResult GlobalDataTypeRegistry::registerDataT { return RegistrationResultFrozen; } + static Entry entry; + { const RegistrationResult remove_res = remove(&entry); if (remove_res != RegistrationResultOk) @@ -219,7 +221,11 @@ GlobalDataTypeRegistry::RegistrationResult GlobalDataTypeRegistry::registerDataT return remove_res; } } - entry = Entry(DataTypeKind(Type::DataTypeKind), id, Type::getDataTypeSignature(), Type::getDataTypeFullName()); + + // We can't just overwrite the entry itself because it's noncopyable + entry.descriptor = DataTypeDescriptor(DataTypeKind(Type::DataTypeKind), id, + Type::getDataTypeSignature(), Type::getDataTypeFullName()); + { const RegistrationResult remove_res = remove(&entry); if (remove_res != RegistrationResultOk) diff --git a/libuavcan/include/uavcan/node/scheduler.hpp b/libuavcan/include/uavcan/node/scheduler.hpp index 8f008054a8..7973337983 100644 --- a/libuavcan/include/uavcan/node/scheduler.hpp +++ b/libuavcan/include/uavcan/node/scheduler.hpp @@ -14,7 +14,7 @@ namespace uavcan class UAVCAN_EXPORT Scheduler; -class UAVCAN_EXPORT DeadlineHandler : public LinkedListNode, Noncopyable +class UAVCAN_EXPORT DeadlineHandler : public LinkedListNode { MonotonicTime deadline_; diff --git a/libuavcan/include/uavcan/node/service_client.hpp b/libuavcan/include/uavcan/node/service_client.hpp index d195dcc721..0e74bc7640 100644 --- a/libuavcan/include/uavcan/node/service_client.hpp +++ b/libuavcan/include/uavcan/node/service_client.hpp @@ -169,7 +169,7 @@ protected: ServiceClientBase(INode& node) : DeadlineHandler(node.getScheduler()) - , data_type_descriptor_(NULL) + , data_type_descriptor_(UAVCAN_NULLPTR) , request_timeout_(getDefaultRequestTimeout()) { } @@ -420,8 +420,8 @@ bool ServiceClient::shouldAcceptFrame(const RxFrame& frame { UAVCAN_ASSERT(frame.getTransferType() == TransferTypeServiceResponse); // Other types filtered out by dispatcher - return NULL != call_registry_.find(CallStateMatchingPredicate(ServiceCallID(frame.getSrcNodeID(), - frame.getTransferID()))); + return UAVCAN_NULLPTR != call_registry_.find(CallStateMatchingPredicate(ServiceCallID(frame.getSrcNodeID(), + frame.getTransferID()))); } @@ -474,8 +474,8 @@ int ServiceClient::addCallState(ServiceCallID call_id) } } - if (NULL == call_registry_.template emplace(SubscriberType::getNode(), - *this, call_id)) + if (UAVCAN_NULLPTR == call_registry_.template emplace(SubscriberType::getNode(), *this, call_id)) { SubscriberType::stop(); return -ErrMemory; @@ -527,7 +527,7 @@ int ServiceClient::call(NodeID server_node_id, const Reque * TODO move to init(), but this requires to somewhat refactor GenericSubscriber<> (remove TransferForwarder) */ TransferListenerWithFilter* const tl = SubscriberType::getTransferListener(); - if (tl == NULL) + if (tl == UAVCAN_NULLPTR) { UAVCAN_ASSERT(0); // Must have been created cancelCall(out_call_id); @@ -570,14 +570,14 @@ void ServiceClient::cancelAllCalls() template bool ServiceClient::hasPendingCallToServer(NodeID server_node_id) const { - return NULL != call_registry_.find(ServerSearchPredicate(server_node_id)); + return UAVCAN_NULLPTR != call_registry_.find(ServerSearchPredicate(server_node_id)); } template ServiceCallID ServiceClient::getCallIDByIndex(unsigned index) const { const CallState* const id = call_registry_.getByIndex(index); - return (id == NULL) ? ServiceCallID() : id->getCallID(); + return (id == UAVCAN_NULLPTR) ? ServiceCallID() : id->getCallID(); } } diff --git a/libuavcan/include/uavcan/protocol/data_type_info_provider.hpp b/libuavcan/include/uavcan/protocol/data_type_info_provider.hpp index 8a3104aa91..3da0ca790b 100644 --- a/libuavcan/include/uavcan/protocol/data_type_info_provider.hpp +++ b/libuavcan/include/uavcan/protocol/data_type_info_provider.hpp @@ -39,7 +39,7 @@ class UAVCAN_EXPORT DataTypeInfoProvider : Noncopyable /* * Asking the Global Data Type Registry for the matching type descriptor, either by name or by ID */ - const DataTypeDescriptor* desc = NULL; + const DataTypeDescriptor* desc = UAVCAN_NULLPTR; if (request.name.empty()) { @@ -62,7 +62,7 @@ class UAVCAN_EXPORT DataTypeInfoProvider : Noncopyable desc = GlobalDataTypeRegistry::instance().find(request.name.c_str()); } - if (desc == NULL) + if (desc == UAVCAN_NULLPTR) { UAVCAN_TRACE("DataTypeInfoProvider", "Cannot process GetDataTypeInfo for nonexistent type: dtid=%i dtk=%i name='%s'", diff --git a/libuavcan/include/uavcan/protocol/dynamic_node_id_server/centralized/server.hpp b/libuavcan/include/uavcan/protocol/dynamic_node_id_server/centralized/server.hpp index abbddcd8c3..207afa4bca 100644 --- a/libuavcan/include/uavcan/protocol/dynamic_node_id_server/centralized/server.hpp +++ b/libuavcan/include/uavcan/protocol/dynamic_node_id_server/centralized/server.hpp @@ -108,7 +108,7 @@ class Server : public AbstractServer return; } - const int res = storage_.add(node_id, (unique_id_or_null == NULL) ? UniqueID() : *unique_id_or_null); + const int res = storage_.add(node_id, (unique_id_or_null == UAVCAN_NULLPTR) ? UniqueID() : *unique_id_or_null); if (res < 0) { tracer_.onEvent(TraceError, res); diff --git a/libuavcan/include/uavcan/protocol/dynamic_node_id_server/distributed/cluster_manager.hpp b/libuavcan/include/uavcan/protocol/dynamic_node_id_server/distributed/cluster_manager.hpp index a56cd417aa..b4e573b29d 100644 --- a/libuavcan/include/uavcan/protocol/dynamic_node_id_server/distributed/cluster_manager.hpp +++ b/libuavcan/include/uavcan/protocol/dynamic_node_id_server/distributed/cluster_manager.hpp @@ -84,7 +84,7 @@ private: return &servers_[i]; } } - return NULL; + return UAVCAN_NULLPTR; } virtual void handleTimerEvent(const TimerEvent&) @@ -338,7 +338,7 @@ public: Log::Index getServerNextIndex(NodeID server_node_id) const { const Server* const s = findServer(server_node_id); - if (s != NULL) + if (s != UAVCAN_NULLPTR) { return s->next_index; } @@ -349,7 +349,7 @@ public: void incrementServerNextIndexBy(NodeID server_node_id, Log::Index increment) { Server* const s = findServer(server_node_id); - if (s != NULL) + if (s != UAVCAN_NULLPTR) { s->next_index = Log::Index(s->next_index + increment); } @@ -362,7 +362,7 @@ public: void decrementServerNextIndex(NodeID server_node_id) { Server* const s = findServer(server_node_id); - if (s != NULL) + if (s != UAVCAN_NULLPTR) { s->next_index--; } @@ -378,7 +378,7 @@ public: Log::Index getServerMatchIndex(NodeID server_node_id) const { const Server* const s = findServer(server_node_id); - if (s != NULL) + if (s != UAVCAN_NULLPTR) { return s->match_index; } @@ -389,7 +389,7 @@ public: void setServerMatchIndex(NodeID server_node_id, Log::Index match_index) { Server* const s = findServer(server_node_id); - if (s != NULL) + if (s != UAVCAN_NULLPTR) { s->match_index = match_index; } diff --git a/libuavcan/include/uavcan/protocol/dynamic_node_id_server/distributed/log.hpp b/libuavcan/include/uavcan/protocol/dynamic_node_id_server/distributed/log.hpp index 20f957b3e7..3ef89b31ee 100644 --- a/libuavcan/include/uavcan/protocol/dynamic_node_id_server/distributed/log.hpp +++ b/libuavcan/include/uavcan/protocol/dynamic_node_id_server/distributed/log.hpp @@ -285,7 +285,7 @@ public: const Entry* getEntryAtIndex(Index index) const { UAVCAN_ASSERT(last_index_ < Capacity); - return (index <= last_index_) ? &entries_[index] : NULL; + return (index <= last_index_) ? &entries_[index] : UAVCAN_NULLPTR; } Index getLastIndex() const { return last_index_; } diff --git a/libuavcan/include/uavcan/protocol/dynamic_node_id_server/distributed/persistent_state.hpp b/libuavcan/include/uavcan/protocol/dynamic_node_id_server/distributed/persistent_state.hpp index 0152b1851e..a1ca44ea79 100644 --- a/libuavcan/include/uavcan/protocol/dynamic_node_id_server/distributed/persistent_state.hpp +++ b/libuavcan/include/uavcan/protocol/dynamic_node_id_server/distributed/persistent_state.hpp @@ -63,7 +63,7 @@ public: } const Entry* const last_entry = log_.getEntryAtIndex(log_.getLastIndex()); - if (last_entry == NULL) + if (last_entry == UAVCAN_NULLPTR) { UAVCAN_ASSERT(0); return -ErrLogic; diff --git a/libuavcan/include/uavcan/protocol/dynamic_node_id_server/distributed/raft_core.hpp b/libuavcan/include/uavcan/protocol/dynamic_node_id_server/distributed/raft_core.hpp index 4080d8bbae..b446e3ee45 100644 --- a/libuavcan/include/uavcan/protocol/dynamic_node_id_server/distributed/raft_core.hpp +++ b/libuavcan/include/uavcan/protocol/dynamic_node_id_server/distributed/raft_core.hpp @@ -143,9 +143,10 @@ private: UAVCAN_ASSERT(commit_index_ <= persistent_state_.getLog().getLastIndex()); // Term - UAVCAN_ASSERT(persistent_state_.getLog().getEntryAtIndex(persistent_state_.getLog().getLastIndex()) != NULL); - UAVCAN_ASSERT(persistent_state_.getLog().getEntryAtIndex(persistent_state_.getLog().getLastIndex())->term - <= persistent_state_.getCurrentTerm()); + UAVCAN_ASSERT(persistent_state_.getLog().getEntryAtIndex(persistent_state_.getLog().getLastIndex()) != + UAVCAN_NULLPTR); + UAVCAN_ASSERT(persistent_state_.getLog().getEntryAtIndex(persistent_state_.getLog().getLastIndex())->term <= + persistent_state_.getCurrentTerm()); // Elections UAVCAN_ASSERT(server_state_ != ServerStateCandidate || !request_vote_client_.hasPendingCalls() || @@ -281,7 +282,7 @@ private: req.prev_log_index = Log::Index(cluster_.getServerNextIndex(node_id) - 1U); const Entry* const entry = persistent_state_.getLog().getEntryAtIndex(req.prev_log_index); - if (entry == NULL) + if (entry == UAVCAN_NULLPTR) { UAVCAN_ASSERT(0); handlePersistentStateUpdateError(-ErrLogic); @@ -470,7 +471,7 @@ private: * Reject the request if the assumed log index does not exist on the local node. */ const Entry* const prev_entry = persistent_state_.getLog().getEntryAtIndex(request.prev_log_index); - if (prev_entry == NULL) + if (prev_entry == UAVCAN_NULLPTR) { response.setResponseEnabled(true); return; @@ -880,7 +881,7 @@ public: for (int index = static_cast(persistent_state_.getLog().getLastIndex()); index >= 0; index--) { const Entry* const entry = persistent_state_.getLog().getEntryAtIndex(Log::Index(index)); - UAVCAN_ASSERT(entry != NULL); + UAVCAN_ASSERT(entry != UAVCAN_NULLPTR); const LogEntryInfo info(*entry, Log::Index(index) <= commit_index_); if (predicate(info)) { diff --git a/libuavcan/include/uavcan/protocol/dynamic_node_id_server/distributed/server.hpp b/libuavcan/include/uavcan/protocol/dynamic_node_id_server/distributed/server.hpp index cd72825e7d..52f712553a 100644 --- a/libuavcan/include/uavcan/protocol/dynamic_node_id_server/distributed/server.hpp +++ b/libuavcan/include/uavcan/protocol/dynamic_node_id_server/distributed/server.hpp @@ -154,7 +154,7 @@ class UAVCAN_EXPORT Server : public AbstractServer return; } - const UniqueID uid = (unique_id_or_null == NULL) ? UniqueID() : *unique_id_or_null; + const UniqueID uid = (unique_id_or_null == UAVCAN_NULLPTR) ? UniqueID() : *unique_id_or_null; if (raft_core_.isLeader()) { @@ -327,8 +327,8 @@ struct StateReport , num_unknown_nodes (s.getNodeDiscoverer().getNumUnknownNodes()) { const Entry* const e = s.getRaftCore().getPersistentState().getLog().getEntryAtIndex(last_log_index); - UAVCAN_ASSERT(e != NULL); - if (e != NULL) + UAVCAN_ASSERT(e != UAVCAN_NULLPTR); + if (e != UAVCAN_NULLPTR) { last_log_term = e->term; } diff --git a/libuavcan/include/uavcan/protocol/dynamic_node_id_server/node_discoverer.hpp b/libuavcan/include/uavcan/protocol/dynamic_node_id_server/node_discoverer.hpp index 4f856e7090..2eb96f36fa 100644 --- a/libuavcan/include/uavcan/protocol/dynamic_node_id_server/node_discoverer.hpp +++ b/libuavcan/include/uavcan/protocol/dynamic_node_id_server/node_discoverer.hpp @@ -54,7 +54,7 @@ public: * This method will be called when a new node responds to GetNodeInfo request. * If this method fails to register the node, the node will be queried again later and this method will be * invoked again. - * Unique ID will be NULL if the node is assumed to not implement the GetNodeInfo service. + * Unique ID will be UAVCAN_NULLPTR if the node is assumed to not implement the GetNodeInfo service. */ virtual void handleNewNodeDiscovery(const UniqueID* unique_id_or_null, NodeID node_id) = 0; @@ -123,7 +123,7 @@ class NodeDiscoverer : TimerBase { // This essentially means that we pick first available node. Remember that the map is unordered. const NodeMap::KVPair* const pair = node_map_.getByIndex(0); - return (pair == NULL) ? NodeID() : pair->key; + return (pair == UAVCAN_NULLPTR) ? NodeID() : pair->key; } bool needToQuery(NodeID node_id) @@ -190,7 +190,7 @@ class NodeDiscoverer : TimerBase void finalizeNodeDiscovery(const UniqueID* unique_id_or_null, NodeID node_id) { - trace(TraceDiscoveryNodeFinalized, node_id.get() | ((unique_id_or_null == NULL) ? 0U : 0x100U)); + trace(TraceDiscoveryNodeFinalized, node_id.get() | ((unique_id_or_null == UAVCAN_NULLPTR) ? 0U : 0x100U)); removeNode(node_id); /* * It is paramount to check if the server is still interested to receive this data. @@ -216,7 +216,7 @@ class NodeDiscoverer : TimerBase trace(TraceDiscoveryGetNodeInfoFailure, result.getCallID().server_node_id.get()); NodeData* const data = node_map_.access(result.getCallID().server_node_id); - if (data == NULL) + if (data == UAVCAN_NULLPTR) { return; // Probably it is a known node now } @@ -227,7 +227,7 @@ class NodeDiscoverer : TimerBase data->num_get_node_info_attempts++; if (data->num_get_node_info_attempts >= MaxAttemptsToGetNodeInfo) { - finalizeNodeDiscovery(NULL, result.getCallID().server_node_id); + finalizeNodeDiscovery(UAVCAN_NULLPTR, result.getCallID().server_node_id); // Warning: data pointer is invalidated now } } @@ -272,18 +272,18 @@ class NodeDiscoverer : TimerBase } NodeData* data = node_map_.access(msg.getSrcNodeID()); - if (data == NULL) + if (data == UAVCAN_NULLPTR) { trace(TraceDiscoveryNewNodeFound, msg.getSrcNodeID().get()); data = node_map_.insert(msg.getSrcNodeID(), NodeData()); - if (data == NULL) + if (data == UAVCAN_NULLPTR) { getNode().registerInternalFailure("NodeDiscoverer OOM"); return; } } - UAVCAN_ASSERT(data != NULL); + UAVCAN_ASSERT(data != UAVCAN_NULLPTR); if (msg.uptime_sec < data->last_seen_uptime) { diff --git a/libuavcan/include/uavcan/protocol/dynamic_node_id_server/node_id_selector.hpp b/libuavcan/include/uavcan/protocol/dynamic_node_id_server/node_id_selector.hpp index bd0b55c0f9..42e85926e8 100644 --- a/libuavcan/include/uavcan/protocol/dynamic_node_id_server/node_id_selector.hpp +++ b/libuavcan/include/uavcan/protocol/dynamic_node_id_server/node_id_selector.hpp @@ -28,8 +28,8 @@ public: : owner_(owner) , is_node_id_taken_(is_node_id_taken) { - UAVCAN_ASSERT(owner_ != NULL); - UAVCAN_ASSERT(is_node_id_taken_ != NULL); + UAVCAN_ASSERT(owner_ != UAVCAN_NULLPTR); + UAVCAN_ASSERT(is_node_id_taken_ != UAVCAN_NULLPTR); } /** diff --git a/libuavcan/include/uavcan/protocol/dynamic_node_id_server/storage_marshaller.hpp b/libuavcan/include/uavcan/protocol/dynamic_node_id_server/storage_marshaller.hpp index 296ff1e066..cbf32f8940 100644 --- a/libuavcan/include/uavcan/protocol/dynamic_node_id_server/storage_marshaller.hpp +++ b/libuavcan/include/uavcan/protocol/dynamic_node_id_server/storage_marshaller.hpp @@ -123,11 +123,11 @@ public: #endif #if UAVCAN_CPP_VERSION >= UAVCAN_CPP11 - const unsigned long long x = std::strtoull(val.c_str(), NULL, 10); + const unsigned long long x = std::strtoull(val.c_str(), UAVCAN_NULLPTR, 10); #else // There was no strtoull() before C++11, so we need to resort to strtoul() StaticAssert<(sizeof(unsigned long) >= sizeof(uint32_t))>::check(); - const unsigned long x = std::strtoul(val.c_str(), NULL, 10); + const unsigned long x = std::strtoul(val.c_str(), UAVCAN_NULLPTR, 10); #endif #if UAVCAN_CPP_VERSION >= UAVCAN_CPP11 diff --git a/libuavcan/include/uavcan/protocol/firmware_update_trigger.hpp b/libuavcan/include/uavcan/protocol/firmware_update_trigger.hpp index 820a00b94c..5b0d019481 100644 --- a/libuavcan/include/uavcan/protocol/firmware_update_trigger.hpp +++ b/libuavcan/include/uavcan/protocol/firmware_update_trigger.hpp @@ -226,7 +226,7 @@ class FirmwareUpdateTrigger : public INodeInfoListener, void trySetPendingNode(const NodeID node_id, const FirmwareFilePath& path) { - if (NULL != pending_nodes_.insert(node_id, path)) + if (UAVCAN_NULLPTR != pending_nodes_.insert(node_id, path)) { if (!TimerBase::isRunning()) { @@ -285,7 +285,7 @@ class FirmwareUpdateTrigger : public INodeInfoListener, } FirmwareFilePath* const old_path = pending_nodes_.access(result.getCallID().server_node_id); - if (old_path == NULL) + if (old_path == UAVCAN_NULLPTR) { // The entry has been removed, assuming that it's not needed anymore return; @@ -304,7 +304,7 @@ class FirmwareUpdateTrigger : public INodeInfoListener, } else { - UAVCAN_ASSERT(old_path != NULL); + UAVCAN_ASSERT(old_path != UAVCAN_NULLPTR); UAVCAN_ASSERT(TimerBase::isRunning()); // We won't have to call trySetPendingNode(), because we'll directly update the old path via the pointer @@ -336,7 +336,7 @@ class FirmwareUpdateTrigger : public INodeInfoListener, } FirmwareFilePath* const path = pending_nodes_.access(node_id); - if (path == NULL) + if (path == UAVCAN_NULLPTR) { UAVCAN_ASSERT(0); // pickNextNodeID() returned a node ID that is not present in the map return; @@ -367,7 +367,7 @@ public: : TimerBase(node) , begin_fw_update_client_(node) , checker_(checker) - , node_info_retriever_(NULL) + , node_info_retriever_(UAVCAN_NULLPTR) , pending_nodes_(node.getAllocator()) , request_interval_(MonotonicDuration::fromMSec(DefaultRequestIntervalMs)) , last_queried_node_id_(0) @@ -375,7 +375,7 @@ public: ~FirmwareUpdateTrigger() { - if (node_info_retriever_ != NULL) + if (node_info_retriever_ != UAVCAN_NULLPTR) { node_info_retriever_->removeListener(this); } diff --git a/libuavcan/include/uavcan/protocol/global_time_sync_master.hpp b/libuavcan/include/uavcan/protocol/global_time_sync_master.hpp index 69261af068..e64fb47833 100644 --- a/libuavcan/include/uavcan/protocol/global_time_sync_master.hpp +++ b/libuavcan/include/uavcan/protocol/global_time_sync_master.hpp @@ -129,7 +129,7 @@ class UAVCAN_EXPORT GlobalTimeSyncMaster : protected LoopbackFrameListenerBase const MonotonicTime otr_deadline = node_.getMonotonicTime() + max_transfer_interval; TransferID* const tid_ptr = node_.getDispatcher().getOutgoingTransferRegistry().accessOrCreate(otr_key, otr_deadline); - if (tid_ptr == NULL) + if (tid_ptr == UAVCAN_NULLPTR) { return -ErrMemory; } @@ -161,7 +161,7 @@ public: // Data type ID const DataTypeDescriptor* const desc = GlobalDataTypeRegistry::instance().find(DataTypeKindMessage, protocol::GlobalTimeSync::getDataTypeFullName()); - if (desc == NULL) + if (desc == UAVCAN_NULLPTR) { return -ErrUnknownDataType; } diff --git a/libuavcan/include/uavcan/protocol/logger.hpp b/libuavcan/include/uavcan/protocol/logger.hpp index 017de4dc18..07a6ba6a56 100644 --- a/libuavcan/include/uavcan/protocol/logger.hpp +++ b/libuavcan/include/uavcan/protocol/logger.hpp @@ -76,13 +76,13 @@ private: LogLevel getExternalSinkLevel() const { - return (external_sink_ == NULL) ? getLogLevelAboveAll() : external_sink_->getLogLevel(); + return (external_sink_ == UAVCAN_NULLPTR) ? getLogLevelAboveAll() : external_sink_->getLogLevel(); } public: explicit Logger(INode& node) : logmsg_pub_(node) - , external_sink_(NULL) + , external_sink_(UAVCAN_NULLPTR) { level_ = protocol::debug::LogLevel::ERROR; setTxTimeout(MonotonicDuration::fromMSec(DefaultTxTimeoutMs)); diff --git a/libuavcan/include/uavcan/protocol/node_info_retriever.hpp b/libuavcan/include/uavcan/protocol/node_info_retriever.hpp index 9ff2bcc79b..721ec37d68 100644 --- a/libuavcan/include/uavcan/protocol/node_info_retriever.hpp +++ b/libuavcan/include/uavcan/protocol/node_info_retriever.hpp @@ -131,7 +131,7 @@ private: bool operator()(INodeInfoListener* key) { - UAVCAN_ASSERT(key != NULL); + UAVCAN_ASSERT(key != UAVCAN_NULLPTR); key->handleNodeInfoRetrieved(node_id, node_info); return false; } @@ -150,7 +150,7 @@ private: bool operator()(INodeInfoListener* key) { - UAVCAN_ASSERT(key != NULL); + UAVCAN_ASSERT(key != UAVCAN_NULLPTR); (key->*method)(event); return false; } @@ -385,10 +385,10 @@ public: */ int addListener(INodeInfoListener* listener) { - if (listener != NULL) + if (listener != UAVCAN_NULLPTR) { removeListener(listener); - return (NULL == listeners_.emplace(listener)) ? -ErrMemory : 0; + return (UAVCAN_NULLPTR == listeners_.emplace(listener)) ? -ErrMemory : 0; } else { @@ -402,7 +402,7 @@ public: */ void removeListener(INodeInfoListener* listener) { - if (listener != NULL) + if (listener != UAVCAN_NULLPTR) { listeners_.removeAll(listener); } diff --git a/libuavcan/include/uavcan/protocol/param_server.hpp b/libuavcan/include/uavcan/protocol/param_server.hpp index 3d1395cff4..d3a6651ffb 100644 --- a/libuavcan/include/uavcan/protocol/param_server.hpp +++ b/libuavcan/include/uavcan/protocol/param_server.hpp @@ -90,7 +90,7 @@ class UAVCAN_EXPORT ParamServer void handleGetSet(const protocol::param::GetSet::Request& in, protocol::param::GetSet::Response& out) { - UAVCAN_ASSERT(manager_ != NULL); + UAVCAN_ASSERT(manager_ != UAVCAN_NULLPTR); // Recover the name from index if (in.name.empty()) @@ -131,7 +131,7 @@ class UAVCAN_EXPORT ParamServer void handleExecuteOpcode(const protocol::param::ExecuteOpcode::Request& in, protocol::param::ExecuteOpcode::Response& out) { - UAVCAN_ASSERT(manager_ != NULL); + UAVCAN_ASSERT(manager_ != UAVCAN_NULLPTR); if (in.opcode == protocol::param::ExecuteOpcode::Request::OPCODE_SAVE) { @@ -152,7 +152,7 @@ public: explicit ParamServer(INode& node) : get_set_srv_(node) , save_erase_srv_(node) - , manager_(NULL) + , manager_(UAVCAN_NULLPTR) { } /** @@ -161,7 +161,7 @@ public: */ int start(IParamManager* manager) { - if (manager == NULL) + if (manager == UAVCAN_NULLPTR) { return -ErrInvalidParam; } diff --git a/libuavcan/include/uavcan/protocol/restart_request_server.hpp b/libuavcan/include/uavcan/protocol/restart_request_server.hpp index d3cd23b5dc..62031fe983 100644 --- a/libuavcan/include/uavcan/protocol/restart_request_server.hpp +++ b/libuavcan/include/uavcan/protocol/restart_request_server.hpp @@ -67,7 +67,7 @@ class UAVCAN_EXPORT RestartRequestServer : Noncopyable public: explicit RestartRequestServer(INode& node) : srv_(node) - , handler_(NULL) + , handler_(UAVCAN_NULLPTR) { } /** diff --git a/libuavcan/include/uavcan/transport/dispatcher.hpp b/libuavcan/include/uavcan/transport/dispatcher.hpp index c4f40e00a3..53bc2e203f 100644 --- a/libuavcan/include/uavcan/transport/dispatcher.hpp +++ b/libuavcan/include/uavcan/transport/dispatcher.hpp @@ -24,7 +24,7 @@ class UAVCAN_EXPORT Dispatcher; /** * Inherit this class to receive notifications about all TX CAN frames that were transmitted with the loopback flag. */ -class UAVCAN_EXPORT LoopbackFrameListenerBase : public LinkedListNode, Noncopyable +class UAVCAN_EXPORT LoopbackFrameListenerBase : public LinkedListNode { Dispatcher& dispatcher_; @@ -138,7 +138,7 @@ public: , sysclock_(sysclock) , outgoing_transfer_reg_(allocator) #if !UAVCAN_TINY - , rx_listener_(NULL) + , rx_listener_(UAVCAN_NULLPTR) #endif , self_node_id_(NodeID::Broadcast) // Default , self_node_id_is_set_(false) @@ -207,10 +207,10 @@ public: LoopbackFrameListenerRegistry& getLoopbackFrameListenerRegistry() { return loopback_listeners_; } IRxFrameListener* getRxFrameListener() const { return rx_listener_; } - void removeRxFrameListener() { rx_listener_ = NULL; } + void removeRxFrameListener() { rx_listener_ = UAVCAN_NULLPTR; } void installRxFrameListener(IRxFrameListener* listener) { - UAVCAN_ASSERT(listener != NULL); + UAVCAN_ASSERT(listener != UAVCAN_NULLPTR); rx_listener_ = listener; } #endif diff --git a/libuavcan/include/uavcan/transport/transfer_listener.hpp b/libuavcan/include/uavcan/transport/transfer_listener.hpp index acf7c5999f..d384e6ea7d 100644 --- a/libuavcan/include/uavcan/transport/transfer_listener.hpp +++ b/libuavcan/include/uavcan/transport/transfer_listener.hpp @@ -96,7 +96,7 @@ public: /** * Internal, refer to the transport dispatcher class. */ -class UAVCAN_EXPORT TransferListener : public LinkedListNode, Noncopyable +class UAVCAN_EXPORT TransferListener : public LinkedListNode { const DataTypeDescriptor& data_type_; TransferBufferManager bufmgr_; @@ -180,7 +180,7 @@ public: TransferListenerWithFilter(TransferPerfCounter& perf, const DataTypeDescriptor& data_type, uint16_t max_buffer_size, IPoolAllocator& allocator) : TransferListener(perf, data_type, max_buffer_size, allocator) - , filter_(NULL) + , filter_(UAVCAN_NULLPTR) { } void installAcceptanceFilter(const ITransferAcceptanceFilter* acceptance_filter) diff --git a/libuavcan/include/uavcan/util/comparison.hpp b/libuavcan/include/uavcan/util/comparison.hpp index 8c8f007371..587d8625aa 100644 --- a/libuavcan/include/uavcan/util/comparison.hpp +++ b/libuavcan/include/uavcan/util/comparison.hpp @@ -77,7 +77,7 @@ struct HasIsCloseMethod template static NotApplicable test(...); - enum { Result = sizeof(test(NULL)) }; + enum { Result = sizeof(test(UAVCAN_NULLPTR)) }; }; /// First stage: bool L::isClose(R) diff --git a/libuavcan/include/uavcan/util/lazy_constructor.hpp b/libuavcan/include/uavcan/util/lazy_constructor.hpp index c7ae975663..c2076701de 100644 --- a/libuavcan/include/uavcan/util/lazy_constructor.hpp +++ b/libuavcan/include/uavcan/util/lazy_constructor.hpp @@ -60,13 +60,13 @@ class UAVCAN_EXPORT LazyConstructor public: LazyConstructor() - : ptr_(NULL) + : ptr_(UAVCAN_NULLPTR) { fill(data_.pool, data_.pool + sizeof(T), uint8_t(0)); } LazyConstructor(const LazyConstructor& rhs) // Implicit - : ptr_(NULL) + : ptr_(UAVCAN_NULLPTR) { fill(data_.pool, data_.pool + sizeof(T), uint8_t(0)); if (rhs) @@ -87,7 +87,7 @@ public: return *this; } - bool isConstructed() const { return ptr_ != NULL; } + bool isConstructed() const { return ptr_ != UAVCAN_NULLPTR; } operator T*() const { return ptr_; } @@ -103,7 +103,7 @@ public: { ptr_->~T(); } - ptr_ = NULL; + ptr_ = UAVCAN_NULLPTR; fill(data_.pool, data_.pool + sizeof(T), uint8_t(0)); } diff --git a/libuavcan/include/uavcan/util/linked_list.hpp b/libuavcan/include/uavcan/util/linked_list.hpp index 9ca898e1fd..915eb9c7e9 100644 --- a/libuavcan/include/uavcan/util/linked_list.hpp +++ b/libuavcan/include/uavcan/util/linked_list.hpp @@ -9,6 +9,7 @@ #include #include #include +#include namespace uavcan { @@ -16,13 +17,13 @@ namespace uavcan * Classes that are supposed to be linked-listed should derive this. */ template -class UAVCAN_EXPORT LinkedListNode +class UAVCAN_EXPORT LinkedListNode : Noncopyable { T* next_; protected: LinkedListNode() - : next_(NULL) + : next_(UAVCAN_NULLPTR) { } ~LinkedListNode() { } @@ -40,17 +41,17 @@ public: * Linked list root. */ template -class UAVCAN_EXPORT LinkedListRoot +class UAVCAN_EXPORT LinkedListRoot : Noncopyable { T* root_; public: LinkedListRoot() - : root_(NULL) + : root_(UAVCAN_NULLPTR) { } T* get() const { return root_; } - bool isEmpty() const { return get() == NULL; } + bool isEmpty() const { return get() == UAVCAN_NULLPTR; } /** * Complexity: O(N) @@ -100,7 +101,7 @@ unsigned LinkedListRoot::getLength() const template void LinkedListRoot::insert(T* node) { - if (node == NULL) + if (node == UAVCAN_NULLPTR) { UAVCAN_ASSERT(0); return; @@ -114,7 +115,7 @@ template template void LinkedListRoot::insertBefore(T* node, Predicate predicate) { - if (node == NULL) + if (node == UAVCAN_NULLPTR) { UAVCAN_ASSERT(0); return; @@ -122,7 +123,7 @@ void LinkedListRoot::insertBefore(T* node, Predicate predicate) remove(node); - if (root_ == NULL || predicate(root_)) + if (root_ == UAVCAN_NULLPTR || predicate(root_)) { node->setNextListNode(root_); root_ = node; @@ -146,7 +147,7 @@ void LinkedListRoot::insertBefore(T* node, Predicate predicate) template void LinkedListRoot::remove(const T* node) { - if (root_ == NULL || node == NULL) + if (root_ == UAVCAN_NULLPTR || node == UAVCAN_NULLPTR) { return; } diff --git a/libuavcan/include/uavcan/util/map.hpp b/libuavcan/include/uavcan/util/map.hpp index d7c2b29625..59ce72da74 100644 --- a/libuavcan/include/uavcan/util/map.hpp +++ b/libuavcan/include/uavcan/util/map.hpp @@ -66,20 +66,20 @@ private: static KVGroup* instantiate(IPoolAllocator& allocator) { void* const praw = allocator.allocate(sizeof(KVGroup)); - if (praw == NULL) + if (praw == UAVCAN_NULLPTR) { - return NULL; + return UAVCAN_NULLPTR; } return new (praw) KVGroup(); } static void destroy(KVGroup*& obj, IPoolAllocator& allocator) { - if (obj != NULL) + if (obj != UAVCAN_NULLPTR) { obj->~KVGroup(); allocator.deallocate(obj); - obj = NULL; + obj = UAVCAN_NULLPTR; } } @@ -92,7 +92,7 @@ private: return kvs + i; } } - return NULL; + return UAVCAN_NULLPTR; } }; @@ -167,7 +167,7 @@ public: /** * Complexity is O(1). */ - bool isEmpty() const { return find(YesPredicate()) == NULL; } + bool isEmpty() const { return find(YesPredicate()) == UAVCAN_NULLPTR; } /** * Complexity is O(N). @@ -193,7 +193,7 @@ typename Map::KVPair* Map::findKey(const Key& key) } p = p->getNextListNode(); } - return NULL; + return UAVCAN_NULLPTR; } template @@ -226,7 +226,7 @@ Value* Map::access(const Key& key) { UAVCAN_ASSERT(!(key == Key())); KVPair* const kv = findKey(key); - return kv ? &kv->value : NULL; + return kv ? &kv->value : UAVCAN_NULLPTR; } template @@ -243,9 +243,9 @@ Value* Map::insert(const Key& key, const Value& value) } KVGroup* const kvg = KVGroup::instantiate(allocator_); - if (kvg == NULL) + if (kvg == UAVCAN_NULLPTR) { - return NULL; + return UAVCAN_NULLPTR; } list_.insert(kvg); kvg->kvs[0] = KVPair(key, value); @@ -271,7 +271,7 @@ void Map::removeAllWhere(Predicate predicate) unsigned num_removed = 0; KVGroup* p = list_.get(); - while (p != NULL) + while (p != UAVCAN_NULLPTR) { KVGroup* const next_group = p->getNextListNode(); @@ -302,7 +302,7 @@ template const Key* Map::find(Predicate predicate) const { KVGroup* p = list_.get(); - while (p != NULL) + while (p != UAVCAN_NULLPTR) { KVGroup* const next_group = p->getNextListNode(); @@ -320,7 +320,7 @@ const Key* Map::find(Predicate predicate) const p = next_group; } - return NULL; + return UAVCAN_NULLPTR; } template @@ -334,7 +334,7 @@ typename Map::KVPair* Map::getByIndex(unsigned index) { // Slowly crawling through the dynamic storage KVGroup* p = list_.get(); - while (p != NULL) + while (p != UAVCAN_NULLPTR) { KVGroup* const next_group = p->getNextListNode(); @@ -354,7 +354,7 @@ typename Map::KVPair* Map::getByIndex(unsigned index) p = next_group; } - return NULL; + return UAVCAN_NULLPTR; } template diff --git a/libuavcan/include/uavcan/util/multiset.hpp b/libuavcan/include/uavcan/util/multiset.hpp index ae04dfd4e0..5813466c62 100644 --- a/libuavcan/include/uavcan/util/multiset.hpp +++ b/libuavcan/include/uavcan/util/multiset.hpp @@ -49,28 +49,28 @@ class UAVCAN_EXPORT Multiset : Noncopyable #endif Item() - : ptr(NULL) + : ptr(UAVCAN_NULLPTR) { fill_n(pool, sizeof(pool), static_cast(0)); } ~Item() { destroy(); } - bool isConstructed() const { return ptr != NULL; } + bool isConstructed() const { return ptr != UAVCAN_NULLPTR; } void destroy() { - if (ptr != NULL) + if (ptr != UAVCAN_NULLPTR) { ptr->~T(); - ptr = NULL; + ptr = UAVCAN_NULLPTR; fill_n(pool, sizeof(pool), static_cast(0)); } } }; private: - struct Chunk : LinkedListNode, ::uavcan::Noncopyable + struct Chunk : LinkedListNode { enum { NumItems = (MemPoolBlockSize - sizeof(LinkedListNode)) / sizeof(Item) }; Item items[NumItems]; @@ -85,20 +85,20 @@ private: static Chunk* instantiate(IPoolAllocator& allocator) { void* const praw = allocator.allocate(sizeof(Chunk)); - if (praw == NULL) + if (praw == UAVCAN_NULLPTR) { - return NULL; + return UAVCAN_NULLPTR; } return new (praw) Chunk(); } static void destroy(Chunk*& obj, IPoolAllocator& allocator) { - if (obj != NULL) + if (obj != UAVCAN_NULLPTR) { obj->~Chunk(); allocator.deallocate(obj); - obj = NULL; + obj = UAVCAN_NULLPTR; } } @@ -111,7 +111,7 @@ private: return items + i; } } - return NULL; + return UAVCAN_NULLPTR; } }; @@ -199,17 +199,17 @@ public: /** * Creates one item in-place and returns a pointer to it. - * If creation fails due to lack of memory, NULL will be returned. + * If creation fails due to lack of memory, UAVCAN_NULLPTR will be returned. * Complexity is O(N). */ T* emplace() { Item* const item = findOrCreateFreeSlot(); - if (item == NULL) + if (item == UAVCAN_NULLPTR) { - return NULL; + return UAVCAN_NULLPTR; } - UAVCAN_ASSERT(item->ptr == NULL); + UAVCAN_ASSERT(item->ptr == UAVCAN_NULLPTR); item->ptr = new (item->pool) T(); return item->ptr; } @@ -218,11 +218,11 @@ public: T* emplace(P1 p1) { Item* const item = findOrCreateFreeSlot(); - if (item == NULL) + if (item == UAVCAN_NULLPTR) { - return NULL; + return UAVCAN_NULLPTR; } - UAVCAN_ASSERT(item->ptr == NULL); + UAVCAN_ASSERT(item->ptr == UAVCAN_NULLPTR); item->ptr = new (item->pool) T(p1); return item->ptr; } @@ -231,11 +231,11 @@ public: T* emplace(P1 p1, P2 p2) { Item* const item = findOrCreateFreeSlot(); - if (item == NULL) + if (item == UAVCAN_NULLPTR) { - return NULL; + return UAVCAN_NULLPTR; } - UAVCAN_ASSERT(item->ptr == NULL); + UAVCAN_ASSERT(item->ptr == UAVCAN_NULLPTR); item->ptr = new (item->pool) T(p1, p2); return item->ptr; } @@ -244,11 +244,11 @@ public: T* emplace(P1 p1, P2 p2, P3 p3) { Item* const item = findOrCreateFreeSlot(); - if (item == NULL) + if (item == UAVCAN_NULLPTR) { - return NULL; + return UAVCAN_NULLPTR; } - UAVCAN_ASSERT(item->ptr == NULL); + UAVCAN_ASSERT(item->ptr == UAVCAN_NULLPTR); item->ptr = new (item->pool) T(p1, p2, p3); return item->ptr; } @@ -324,7 +324,7 @@ public: /** * Complexity is O(1). */ - bool isEmpty() const { return find(YesPredicate()) == NULL; } + bool isEmpty() const { return find(YesPredicate()) == UAVCAN_NULLPTR; } /** * Counts number of items stored. @@ -347,7 +347,7 @@ typename Multiset::Item* Multiset::findOrCreateFreeSlot() while (p) { Item* const dyn = p->findFreeSlot(); - if (dyn != NULL) + if (dyn != UAVCAN_NULLPTR) { return dyn; } @@ -357,9 +357,9 @@ typename Multiset::Item* Multiset::findOrCreateFreeSlot() // Create new chunk Chunk* const chunk = Chunk::instantiate(allocator_); - if (chunk == NULL) + if (chunk == UAVCAN_NULLPTR) { - return NULL; + return UAVCAN_NULLPTR; } list_.insert(chunk); return &chunk->items[0]; @@ -397,7 +397,7 @@ void Multiset::removeWhere(Predicate predicate, const RemoveStrategy strategy unsigned num_removed = 0; Chunk* p = list_.get(); - while (p != NULL) + while (p != UAVCAN_NULLPTR) { Chunk* const next_chunk = p->getNextListNode(); // For the case if the current entry gets modified @@ -437,7 +437,7 @@ template T* Multiset::find(Predicate predicate) { Chunk* p = list_.get(); - while (p != NULL) + while (p != UAVCAN_NULLPTR) { Chunk* const next_chunk = p->getNextListNode(); // For the case if the current entry gets modified @@ -454,7 +454,7 @@ T* Multiset::find(Predicate predicate) p = next_chunk; } - return NULL; + return UAVCAN_NULLPTR; } template diff --git a/libuavcan/src/marshal/uc_bit_array_copy.cpp b/libuavcan/src/marshal/uc_bit_array_copy.cpp index 3512ffaafa..5657655a45 100644 --- a/libuavcan/src/marshal/uc_bit_array_copy.cpp +++ b/libuavcan/src/marshal/uc_bit_array_copy.cpp @@ -28,7 +28,7 @@ void bitarrayCopy(const unsigned char* src, std::size_t src_offset, std::size_t // The number of bits to copy const uint8_t max_offset = uavcan::max(src_bit_offset, dst_bit_offset); - const std::size_t copy_bits = uavcan::min(last_bit - src_offset, (std::size_t)(8U - max_offset)); + const std::size_t copy_bits = uavcan::min(last_bit - src_offset, std::size_t(8U - max_offset)); /* * The mask indicating which bits of dest to update: diff --git a/libuavcan/src/node/uc_generic_publisher.cpp b/libuavcan/src/node/uc_generic_publisher.cpp index 28e9b36acd..2c42cfb0ff 100644 --- a/libuavcan/src/node/uc_generic_publisher.cpp +++ b/libuavcan/src/node/uc_generic_publisher.cpp @@ -22,7 +22,7 @@ int GenericPublisherBase::doInit(DataTypeKind dtkind, const char* dtname, CanTxQ GlobalDataTypeRegistry::instance().freeze(); const DataTypeDescriptor* const descr = GlobalDataTypeRegistry::instance().find(dtkind, dtname); - if (descr == NULL) + if (descr == UAVCAN_NULLPTR) { UAVCAN_TRACE("GenericPublisher", "Type [%s] is not registered", dtname); return -ErrUnknownDataType; diff --git a/libuavcan/src/node/uc_generic_subscriber.cpp b/libuavcan/src/node/uc_generic_subscriber.cpp index f77cda77b9..6f5adb66ab 100644 --- a/libuavcan/src/node/uc_generic_subscriber.cpp +++ b/libuavcan/src/node/uc_generic_subscriber.cpp @@ -10,7 +10,7 @@ namespace uavcan int GenericSubscriberBase::genericStart(TransferListener* listener, bool (Dispatcher::*registration_method)(TransferListener*)) { - if (listener == NULL) + if (listener == UAVCAN_NULLPTR) { UAVCAN_ASSERT(0); return -ErrLogic; @@ -26,7 +26,7 @@ int GenericSubscriberBase::genericStart(TransferListener* listener, void GenericSubscriberBase::stop(TransferListener* listener) { - if (listener != NULL) + if (listener != UAVCAN_NULLPTR) { node_.getDispatcher().unregisterMessageListener(listener); node_.getDispatcher().unregisterServiceRequestListener(listener); diff --git a/libuavcan/src/node/uc_global_data_type_registry.cpp b/libuavcan/src/node/uc_global_data_type_registry.cpp index 0a09d44d2f..7586201e2b 100644 --- a/libuavcan/src/node/uc_global_data_type_registry.cpp +++ b/libuavcan/src/node/uc_global_data_type_registry.cpp @@ -23,7 +23,7 @@ GlobalDataTypeRegistry::List* GlobalDataTypeRegistry::selectList(DataTypeKind ki else { UAVCAN_ASSERT(0); - return NULL; + return UAVCAN_NULLPTR; } } @@ -144,7 +144,7 @@ void GlobalDataTypeRegistry::freeze() const DataTypeDescriptor* GlobalDataTypeRegistry::find(const char* name) const { const DataTypeDescriptor* desc = find(DataTypeKindMessage, name); - if (desc == NULL) + if (desc == UAVCAN_NULLPTR) { desc = find(DataTypeKindService, name); } @@ -156,13 +156,13 @@ const DataTypeDescriptor* GlobalDataTypeRegistry::find(DataTypeKind kind, const if (!name) { UAVCAN_ASSERT(0); - return NULL; + return UAVCAN_NULLPTR; } const List* list = selectList(kind); if (!list) { UAVCAN_ASSERT(0); - return NULL; + return UAVCAN_NULLPTR; } Entry* p = list->get(); while (p) @@ -173,7 +173,7 @@ const DataTypeDescriptor* GlobalDataTypeRegistry::find(DataTypeKind kind, const } p = p->getNextListNode(); } - return NULL; + return UAVCAN_NULLPTR; } const DataTypeDescriptor* GlobalDataTypeRegistry::find(DataTypeKind kind, DataTypeID dtid) const @@ -182,7 +182,7 @@ const DataTypeDescriptor* GlobalDataTypeRegistry::find(DataTypeKind kind, DataTy if (!list) { UAVCAN_ASSERT(0); - return NULL; + return UAVCAN_NULLPTR; } Entry* p = list->get(); while (p) @@ -193,7 +193,7 @@ const DataTypeDescriptor* GlobalDataTypeRegistry::find(DataTypeKind kind, DataTy } p = p->getNextListNode(); } - return NULL; + return UAVCAN_NULLPTR; } } diff --git a/libuavcan/src/node/uc_service_client.cpp b/libuavcan/src/node/uc_service_client.cpp index 49c8179a3a..cfe14555b0 100644 --- a/libuavcan/src/node/uc_service_client.cpp +++ b/libuavcan/src/node/uc_service_client.cpp @@ -13,7 +13,7 @@ void ServiceClientBase::CallState::handleDeadline(MonotonicTime) { UAVCAN_TRACE("ServiceClient::CallState", "Timeout from nid=%d, tid=%d, dtname=%s", int(id_.server_node_id.get()), int(id_.transfer_id.get()), - (owner_.data_type_descriptor_ == NULL) ? "???" : owner_.data_type_descriptor_->getFullName()); + (owner_.data_type_descriptor_ == UAVCAN_NULLPTR) ? "???" : owner_.data_type_descriptor_->getFullName()); /* * What we're doing here is relaying execution from this call stack to a different one. * We need it because call registry cannot release memory from this callback, because this will destroy the @@ -46,18 +46,18 @@ int ServiceClientBase::prepareToCall(INode& node, /* * Determining the Data Type ID */ - if (data_type_descriptor_ == NULL) + if (data_type_descriptor_ == UAVCAN_NULLPTR) { GlobalDataTypeRegistry::instance().freeze(); data_type_descriptor_ = GlobalDataTypeRegistry::instance().find(DataTypeKindService, dtname); - if (data_type_descriptor_ == NULL) + if (data_type_descriptor_ == UAVCAN_NULLPTR) { UAVCAN_TRACE("ServiceClient", "Type [%s] is not registered", dtname); return -ErrUnknownDataType; } UAVCAN_TRACE("ServiceClient", "Data type descriptor inited: %s", data_type_descriptor_->toString().c_str()); } - UAVCAN_ASSERT(data_type_descriptor_ != NULL); + UAVCAN_ASSERT(data_type_descriptor_ != UAVCAN_NULLPTR); /* * Determining the Transfer ID diff --git a/libuavcan/src/transport/uc_can_acceptance_filter_configurator.cpp b/libuavcan/src/transport/uc_can_acceptance_filter_configurator.cpp index a7d5a9f29f..e468b3ca85 100644 --- a/libuavcan/src/transport/uc_can_acceptance_filter_configurator.cpp +++ b/libuavcan/src/transport/uc_can_acceptance_filter_configurator.cpp @@ -23,7 +23,7 @@ int16_t CanAcceptanceFilterConfigurator::loadInputConfiguration(AnonymousMessage CanFilterConfig anon_frame_cfg; anon_frame_cfg.id = DefaultAnonMsgID | CanFrame::FlagEFF; anon_frame_cfg.mask = DefaultAnonMsgMask | CanFrame::FlagEFF | CanFrame::FlagRTR | CanFrame::FlagERR; - if (multiset_configs_.emplace(anon_frame_cfg) == NULL) + if (multiset_configs_.emplace(anon_frame_cfg) == UAVCAN_NULLPTR) { return -ErrMemory; } @@ -33,18 +33,18 @@ int16_t CanAcceptanceFilterConfigurator::loadInputConfiguration(AnonymousMessage service_cfg.id = DefaultFilterServiceID; service_cfg.id |= (static_cast(node_.getNodeID().get()) << 8) | CanFrame::FlagEFF; service_cfg.mask = DefaultFilterServiceMask | CanFrame::FlagEFF | CanFrame::FlagRTR | CanFrame::FlagERR; - if (multiset_configs_.emplace(service_cfg) == NULL) + if (multiset_configs_.emplace(service_cfg) == UAVCAN_NULLPTR) { return -ErrMemory; } const TransferListener* p = node_.getDispatcher().getListOfMessageListeners().get(); - while (p != NULL) + while (p != UAVCAN_NULLPTR) { CanFilterConfig cfg; cfg.id = (static_cast(p->getDataTypeDescriptor().getID().get()) << 8) | CanFrame::FlagEFF; cfg.mask = DefaultFilterMsgMask | CanFrame::FlagEFF | CanFrame::FlagRTR | CanFrame::FlagERR; - if (multiset_configs_.emplace(cfg) == NULL) + if (multiset_configs_.emplace(cfg) == UAVCAN_NULLPTR) { return -ErrMemory; } @@ -149,7 +149,7 @@ int CanAcceptanceFilterConfigurator::applyConfiguration(void) for (uint8_t i = 0; i < node_.getDispatcher().getCanIOManager().getNumIfaces(); i++) { ICanIface* iface = can_driver.getIface(i); - if (iface == NULL) + if (iface == UAVCAN_NULLPTR) { UAVCAN_TRACE("CanAcceptanceFilter", "Failed to apply HW filter configuration"); return -ErrDriver; @@ -202,7 +202,7 @@ uint16_t CanAcceptanceFilterConfigurator::getNumFilters() const for (uint8_t i = 0; i < node_.getDispatcher().getCanIOManager().getNumIfaces(); i++) { const ICanIface* iface = can_driver.getIface(i); - if (iface == NULL) + if (iface == UAVCAN_NULLPTR) { UAVCAN_ASSERT(0); out = 0; @@ -226,7 +226,7 @@ uint16_t CanAcceptanceFilterConfigurator::getNumFilters() const int CanAcceptanceFilterConfigurator::addFilterConfig(const CanFilterConfig& config) { - if (multiset_configs_.emplace(config) == NULL) + if (multiset_configs_.emplace(config) == UAVCAN_NULLPTR) { return -ErrMemory; } diff --git a/libuavcan/src/transport/uc_can_io.cpp b/libuavcan/src/transport/uc_can_io.cpp index aa53d0c914..bcca883477 100644 --- a/libuavcan/src/transport/uc_can_io.cpp +++ b/libuavcan/src/transport/uc_can_io.cpp @@ -30,11 +30,11 @@ std::string CanRxFrame::toString(StringRepresentation mode) const */ void CanTxQueue::Entry::destroy(Entry*& obj, IPoolAllocator& allocator) { - if (obj != NULL) + if (obj != UAVCAN_NULLPTR) { obj->~Entry(); allocator.deallocate(obj); - obj = NULL; + obj = UAVCAN_NULLPTR; } } @@ -117,7 +117,7 @@ void CanTxQueue::push(const CanFrame& frame, MonotonicTime tx_deadline, Qos qos, } void* praw = allocator_.allocate(sizeof(Entry)); - if (praw == NULL) + if (praw == UAVCAN_NULLPTR) { UAVCAN_TRACE("CanTxQueue", "Push OOM #1, cleanup"); // No memory left in the pool, so we try to remove expired frames @@ -136,14 +136,14 @@ void CanTxQueue::push(const CanFrame& frame, MonotonicTime tx_deadline, Qos qos, praw = allocator_.allocate(sizeof(Entry)); // Try again } - if (praw == NULL) + if (praw == UAVCAN_NULLPTR) { UAVCAN_TRACE("CanTxQueue", "Push OOM #2, QoS arbitration"); registerRejectedFrame(); // Find a frame with lowest QoS Entry* p = queue_.get(); - if (p == NULL) + if (p == UAVCAN_NULLPTR) { UAVCAN_TRACE("CanTxQueue", "Push rejected: Nothing to replace"); return; @@ -168,7 +168,7 @@ void CanTxQueue::push(const CanFrame& frame, MonotonicTime tx_deadline, Qos qos, praw = allocator_.allocate(sizeof(Entry)); // Try again } - if (praw == NULL) + if (praw == UAVCAN_NULLPTR) { return; // Seems that there is no memory at all. } @@ -196,12 +196,12 @@ CanTxQueue::Entry* CanTxQueue::peek() return p; } } - return NULL; + return UAVCAN_NULLPTR; } void CanTxQueue::remove(Entry*& entry) { - if (entry == NULL) + if (entry == UAVCAN_NULLPTR) { UAVCAN_ASSERT(0); return; @@ -212,13 +212,13 @@ void CanTxQueue::remove(Entry*& entry) const CanFrame* CanTxQueue::getTopPriorityPendingFrame() const { - return (queue_.get() == NULL) ? NULL : &queue_.get()->frame; + return (queue_.get() == UAVCAN_NULLPTR) ? UAVCAN_NULLPTR : &queue_.get()->frame; } bool CanTxQueue::topPriorityHigherOrEqual(const CanFrame& rhs_frame) const { const Entry* entry = queue_.get(); - if (entry == NULL) + if (entry == UAVCAN_NULLPTR) { return false; } @@ -232,7 +232,7 @@ int CanIOManager::sendToIface(uint8_t iface_index, const CanFrame& frame, Monoto { UAVCAN_ASSERT(iface_index < MaxCanIfaces); ICanIface* const iface = driver_.getIface(iface_index); - if (iface == NULL) + if (iface == UAVCAN_NULLPTR) { UAVCAN_ASSERT(0); // Nonexistent interface return -ErrLogic; @@ -254,7 +254,7 @@ int CanIOManager::sendFromTxQueue(uint8_t iface_index) { UAVCAN_ASSERT(iface_index < MaxCanIfaces); CanTxQueue::Entry* entry = tx_queues_[iface_index]->peek(); - if (entry == NULL) + if (entry == UAVCAN_NULLPTR) { return 0; } @@ -323,7 +323,7 @@ uint8_t CanIOManager::makePendingTxMask() const CanIfacePerfCounters CanIOManager::getIfacePerfCounters(uint8_t iface_index) const { ICanIface* const iface = driver_.getIface(iface_index); - if (iface == NULL || iface_index >= MaxCanIfaces) + if (iface == UAVCAN_NULLPTR || iface_index >= MaxCanIfaces) { UAVCAN_ASSERT(0); return CanIfacePerfCounters(); @@ -475,7 +475,7 @@ int CanIOManager::receive(CanRxFrame& out_frame, MonotonicTime blocking_deadline if (masks.read & (1 << i)) { ICanIface* const iface = driver_.getIface(i); - if (iface == NULL) + if (iface == UAVCAN_NULLPTR) { UAVCAN_ASSERT(0); // Nonexistent interface continue; diff --git a/libuavcan/src/transport/uc_dispatcher.cpp b/libuavcan/src/transport/uc_dispatcher.cpp index 0349862ca9..f304689bc4 100644 --- a/libuavcan/src/transport/uc_dispatcher.cpp +++ b/libuavcan/src/transport/uc_dispatcher.cpp @@ -211,7 +211,7 @@ void Dispatcher::handleLoopbackFrame(const CanRxFrame& can_frame) void Dispatcher::notifyRxFrameListener(const CanRxFrame& can_frame, CanIOFlags flags) { - if (rx_listener_ != NULL) + if (rx_listener_ != UAVCAN_NULLPTR) { rx_listener_->handleRxFrame(can_frame, flags); } diff --git a/libuavcan/src/transport/uc_frame.cpp b/libuavcan/src/transport/uc_frame.cpp index 26cbb55c42..d97c34f091 100644 --- a/libuavcan/src/transport/uc_frame.cpp +++ b/libuavcan/src/transport/uc_frame.cpp @@ -157,7 +157,7 @@ bool Frame::compile(CanFrame& out_can_frame) const tail |= (1U << 5); } - UAVCAN_ASSERT(payload_len_ < sizeof(static_cast(NULL)->data)); + UAVCAN_ASSERT(payload_len_ < sizeof(static_cast(UAVCAN_NULLPTR)->data)); out_can_frame.dlc = static_cast(payload_len_); (void)copy(payload_, payload_ + payload_len_, out_can_frame.data); diff --git a/libuavcan/src/transport/uc_outgoing_transfer_registry.cpp b/libuavcan/src/transport/uc_outgoing_transfer_registry.cpp index 852e850ccb..fc49f65aa3 100644 --- a/libuavcan/src/transport/uc_outgoing_transfer_registry.cpp +++ b/libuavcan/src/transport/uc_outgoing_transfer_registry.cpp @@ -29,12 +29,12 @@ TransferID* OutgoingTransferRegistry::accessOrCreate(const OutgoingTransferRegis { UAVCAN_ASSERT(!new_deadline.isZero()); Value* p = map_.access(key); - if (p == NULL) + if (p == UAVCAN_NULLPTR) { p = map_.insert(key, Value()); - if (p == NULL) + if (p == UAVCAN_NULLPTR) { - return NULL; + return UAVCAN_NULLPTR; } UAVCAN_TRACE("OutgoingTransferRegistry", "Created %s", key.toString().c_str()); } @@ -44,7 +44,7 @@ TransferID* OutgoingTransferRegistry::accessOrCreate(const OutgoingTransferRegis bool OutgoingTransferRegistry::exists(DataTypeID dtid, TransferType tt) const { - return NULL != map_.find(ExistenceCheckingPredicate(dtid, tt)); + return UAVCAN_NULLPTR != map_.find(ExistenceCheckingPredicate(dtid, tt)); } void OutgoingTransferRegistry::cleanup(MonotonicTime ts) diff --git a/libuavcan/src/transport/uc_transfer_buffer.cpp b/libuavcan/src/transport/uc_transfer_buffer.cpp index f30c9da675..5e670cf0eb 100644 --- a/libuavcan/src/transport/uc_transfer_buffer.cpp +++ b/libuavcan/src/transport/uc_transfer_buffer.cpp @@ -79,20 +79,20 @@ TransferBufferManagerEntry::Block* TransferBufferManagerEntry::Block::instantiate(IPoolAllocator& allocator) { void* const praw = allocator.allocate(sizeof(Block)); - if (praw == NULL) + if (praw == UAVCAN_NULLPTR) { - return NULL; + return UAVCAN_NULLPTR; } return new (praw) Block; } void TransferBufferManagerEntry::Block::destroy(Block*& obj, IPoolAllocator& allocator) { - if (obj != NULL) + if (obj != UAVCAN_NULLPTR) { obj->~Block(); allocator.deallocate(obj); - obj = NULL; + obj = UAVCAN_NULLPTR; } } @@ -131,20 +131,20 @@ TransferBufferManagerEntry* TransferBufferManagerEntry::instantiate(IPoolAllocat uint16_t max_size) { void* const praw = allocator.allocate(sizeof(TransferBufferManagerEntry)); - if (praw == NULL) + if (praw == UAVCAN_NULLPTR) { - return NULL; + return UAVCAN_NULLPTR; } return new (praw) TransferBufferManagerEntry(allocator, max_size); } void TransferBufferManagerEntry::destroy(TransferBufferManagerEntry*& obj, IPoolAllocator& allocator) { - if (obj != NULL) + if (obj != UAVCAN_NULLPTR) { obj->~TransferBufferManagerEntry(); allocator.deallocate(obj); - obj = NULL; + obj = UAVCAN_NULLPTR; } } @@ -206,7 +206,7 @@ int TransferBufferManagerEntry::write(unsigned offset, const uint8_t* data, unsi unsigned left_to_write = len; const uint8_t* inptr = data; Block* p = blocks_.get(); - Block* last_written_block = NULL; + Block* last_written_block = UAVCAN_NULLPTR; // First we need to write the part that is already allocated while (p) @@ -224,20 +224,20 @@ int TransferBufferManagerEntry::write(unsigned offset, const uint8_t* data, unsi while (left_to_write > 0) { // cppcheck-suppress nullPointer - UAVCAN_ASSERT(p == NULL); + UAVCAN_ASSERT(p == UAVCAN_NULLPTR); // Allocating the chunk Block* new_block = Block::instantiate(allocator_); - if (new_block == NULL) + if (new_block == UAVCAN_NULLPTR) { break; // We're in deep shit. } // Appending the chain with the new block - if (last_written_block != NULL) + if (last_written_block != UAVCAN_NULLPTR) { - UAVCAN_ASSERT(last_written_block->getNextListNode() == NULL); // Because it is last in the chain + UAVCAN_ASSERT(last_written_block->getNextListNode() == UAVCAN_NULLPTR); // Because it is last in the chain last_written_block->setNextListNode(new_block); - new_block->setNextListNode(NULL); + new_block->setNextListNode(UAVCAN_NULLPTR); } else { @@ -284,7 +284,7 @@ TransferBufferManagerEntry* TransferBufferManager::findFirst(const TransferBuffe } dyn = dyn->getNextListNode(); } - return NULL; + return UAVCAN_NULLPTR; } TransferBufferManager::~TransferBufferManager() @@ -304,7 +304,7 @@ ITransferBuffer* TransferBufferManager::access(const TransferBufferManagerKey& k if (key.isEmpty()) { UAVCAN_ASSERT(0); - return NULL; + return UAVCAN_NULLPTR; } return findFirst(key); } @@ -314,21 +314,21 @@ ITransferBuffer* TransferBufferManager::create(const TransferBufferManagerKey& k if (key.isEmpty()) { UAVCAN_ASSERT(0); - return NULL; + return UAVCAN_NULLPTR; } remove(key); TransferBufferManagerEntry* tbme = TransferBufferManagerEntry::instantiate(allocator_, max_buf_size_); - if (tbme == NULL) + if (tbme == UAVCAN_NULLPTR) { - return NULL; // Epic fail. + return UAVCAN_NULLPTR; // Epic fail. } buffers_.insert(tbme); UAVCAN_TRACE("TransferBufferManager", "Buffer created [num=%u], %s", getNumBuffers(), key.toString().c_str()); - if (tbme != NULL) + if (tbme != UAVCAN_NULLPTR) { UAVCAN_ASSERT(tbme->isEmpty()); tbme->reset(key); @@ -341,7 +341,7 @@ void TransferBufferManager::remove(const TransferBufferManagerKey& key) UAVCAN_ASSERT(!key.isEmpty()); TransferBufferManagerEntry* dyn = findFirst(key); - if (dyn != NULL) + if (dyn != UAVCAN_NULLPTR) { UAVCAN_TRACE("TransferBufferManager", "Buffer deleted, %s", key.toString().c_str()); buffers_.remove(dyn); diff --git a/libuavcan/src/transport/uc_transfer_listener.cpp b/libuavcan/src/transport/uc_transfer_listener.cpp index d5a7ea6280..304e67126a 100644 --- a/libuavcan/src/transport/uc_transfer_listener.cpp +++ b/libuavcan/src/transport/uc_transfer_listener.cpp @@ -32,7 +32,7 @@ SingleFrameIncomingTransfer::SingleFrameIncomingTransfer(const RxFrame& frm) int SingleFrameIncomingTransfer::read(unsigned offset, uint8_t* data, unsigned len) const { - if (data == NULL) + if (data == UAVCAN_NULLPTR) { UAVCAN_ASSERT(0); return -ErrInvalidParam; @@ -71,7 +71,7 @@ MultiFrameIncomingTransfer::MultiFrameIncomingTransfer(MonotonicTime ts_mono, Ut int MultiFrameIncomingTransfer::read(unsigned offset, uint8_t* data, unsigned len) const { const ITransferBuffer* const tbb = const_cast(buf_acc_).access(); - if (tbb == NULL) + if (tbb == UAVCAN_NULLPTR) { UAVCAN_TRACE("MultiFrameIncomingTransfer", "Read failed: no such buffer"); return -ErrLogic; @@ -153,7 +153,7 @@ void TransferListener::handleReception(TransferReceiver& receiver, const RxFrame { perf_.addRxTransfer(); const ITransferBuffer* tbb = tba.access(); - if (tbb == NULL) + if (tbb == UAVCAN_NULLPTR) { UAVCAN_TRACE("TransferListener", "Buffer access failure, last frame: %s", frame.toString().c_str()); break; @@ -206,7 +206,7 @@ void TransferListener::handleFrame(const RxFrame& frame) const TransferBufferManagerKey key(frame.getSrcNodeID(), frame.getTransferType()); TransferReceiver* recv = receivers_.access(key); - if (recv == NULL) + if (recv == UAVCAN_NULLPTR) { if (!frame.isStartOfTransfer()) { @@ -215,7 +215,7 @@ void TransferListener::handleFrame(const RxFrame& frame) TransferReceiver new_recv; recv = receivers_.insert(key, new_recv); - if (recv == NULL) + if (recv == UAVCAN_NULLPTR) { UAVCAN_TRACE("TransferListener", "Receiver registration failed; frame %s", frame.toString().c_str()); return; @@ -242,7 +242,7 @@ void TransferListener::handleFrame(const RxFrame& frame) */ void TransferListenerWithFilter::handleFrame(const RxFrame& frame) { - if (filter_ != NULL) + if (filter_ != UAVCAN_NULLPTR) { if (filter_->shouldAcceptFrame(frame)) { diff --git a/libuavcan/src/transport/uc_transfer_receiver.cpp b/libuavcan/src/transport/uc_transfer_receiver.cpp index 435ccd7f39..d60e92861d 100644 --- a/libuavcan/src/transport/uc_transfer_receiver.cpp +++ b/libuavcan/src/transport/uc_transfer_receiver.cpp @@ -148,11 +148,11 @@ TransferReceiver::ResultCode TransferReceiver::receive(const RxFrame& frame, Tra // Payload write ITransferBuffer* buf = tba.access(); - if (buf == NULL) + if (buf == UAVCAN_NULLPTR) { buf = tba.create(); } - if (buf == NULL) + if (buf == UAVCAN_NULLPTR) { UAVCAN_TRACE("TransferReceiver", "Failed to access the buffer, %s", frame.toString().c_str()); prepareForNextTransfer(); diff --git a/libuavcan/src/transport/uc_transfer_sender.cpp b/libuavcan/src/transport/uc_transfer_sender.cpp index 0a9dc4a700..f5d69d9b9e 100644 --- a/libuavcan/src/transport/uc_transfer_sender.cpp +++ b/libuavcan/src/transport/uc_transfer_sender.cpp @@ -156,7 +156,7 @@ int TransferSender::send(const uint8_t* payload, unsigned payload_len, Monotonic OutgoingTransferRegistry::MinEntryLifetime); TransferID* const tid = dispatcher_.getOutgoingTransferRegistry().accessOrCreate(otr_key, otr_deadline); - if (tid == NULL) + if (tid == UAVCAN_NULLPTR) { UAVCAN_TRACE("TransferSender", "OTR access failure, dtid=%d tt=%i", int(data_type_id_.get()), int(transfer_type)); diff --git a/libuavcan/src/uc_data_type.cpp b/libuavcan/src/uc_data_type.cpp index ec9e648183..5f605d60ff 100644 --- a/libuavcan/src/uc_data_type.cpp +++ b/libuavcan/src/uc_data_type.cpp @@ -100,7 +100,7 @@ const unsigned DataTypeDescriptor::MaxFullNameLen; bool DataTypeDescriptor::isValid() const { return id_.isValidForDataTypeKind(kind_) && - (full_name_ != NULL) && + (full_name_ != UAVCAN_NULLPTR) && (*full_name_ != '\0'); } diff --git a/libuavcan/src/uc_dynamic_memory.cpp b/libuavcan/src/uc_dynamic_memory.cpp index 1b682f6b1b..e806d5de9e 100644 --- a/libuavcan/src/uc_dynamic_memory.cpp +++ b/libuavcan/src/uc_dynamic_memory.cpp @@ -18,7 +18,7 @@ void* LimitedPoolAllocator::allocate(std::size_t size) } else { - return NULL; + return UAVCAN_NULLPTR; } } diff --git a/libuavcan/test/clock.hpp b/libuavcan/test/clock.hpp index 0ef3f0565b..623321bae7 100644 --- a/libuavcan/test/clock.hpp +++ b/libuavcan/test/clock.hpp @@ -79,7 +79,7 @@ public: virtual uavcan::UtcTime getUtc() const { struct timeval tv; - const int ret = gettimeofday(&tv, NULL); + const int ret = gettimeofday(&tv, UAVCAN_NULLPTR); if (ret != 0) { assert(0); diff --git a/libuavcan/test/dsdl_test/dsdl_test.cpp b/libuavcan/test/dsdl_test/dsdl_test.cpp index 103adf2dbd..fdaaac4859 100644 --- a/libuavcan/test/dsdl_test/dsdl_test.cpp +++ b/libuavcan/test/dsdl_test/dsdl_test.cpp @@ -107,7 +107,7 @@ TEST(Dsdl, CloseComparison) // /* // * Descriptors // */ -// const uavcan::DataTypeDescriptor* desc = NULL; +// const uavcan::DataTypeDescriptor* desc = UAVCAN_NULLPTR; // // desc = GlobalDataTypeRegistry::instance().find(uavcan::DataTypeKindMessage, "root_ns_a.EmptyMessage"); // ASSERT_TRUE(desc); diff --git a/libuavcan/test/dynamic_memory.cpp b/libuavcan/test/dynamic_memory.cpp index cbe3650614..2a4b17b9dc 100644 --- a/libuavcan/test/dynamic_memory.cpp +++ b/libuavcan/test/dynamic_memory.cpp @@ -38,7 +38,7 @@ TEST(DynamicMemory, OutOfMemory) EXPECT_EQ(2, pool32.getNumUsedBlocks()); EXPECT_EQ(2, pool32.getPeakNumUsedBlocks()); - ASSERT_FALSE(pool32.allocate(32)); // No free blocks left --> NULL + ASSERT_FALSE(pool32.allocate(32)); // No free blocks left --> UAVCAN_NULLPTR EXPECT_EQ(2, pool32.getNumUsedBlocks()); EXPECT_EQ(0, pool32.getNumFreeBlocks()); EXPECT_EQ(2, pool32.getPeakNumUsedBlocks()); diff --git a/libuavcan/test/marshal/scalar_codec.cpp b/libuavcan/test/marshal/scalar_codec.cpp index ee816fdea4..e9012f71b5 100644 --- a/libuavcan/test/marshal/scalar_codec.cpp +++ b/libuavcan/test/marshal/scalar_codec.cpp @@ -22,18 +22,18 @@ TEST(ScalarCodec, Basic) /* * Encoding some variables */ - ASSERT_EQ(1, sc_wr.encode<12>((uint16_t)0xbeda)); // --> 0xeda - ASSERT_EQ(1, sc_wr.encode<1>((uint8_t)1)); - ASSERT_EQ(1, sc_wr.encode<1>((uint16_t)0)); - ASSERT_EQ(1, sc_wr.encode<4>((uint8_t)8)); - ASSERT_EQ(1, sc_wr.encode<32>((uint32_t)0xdeadbeef)); - ASSERT_EQ(1, sc_wr.encode<3>((int8_t)-1)); - ASSERT_EQ(1, sc_wr.encode<4>((int8_t)-6)); - ASSERT_EQ(1, sc_wr.encode<20>((int32_t)-123456)); + ASSERT_EQ(1, sc_wr.encode<12>(uint16_t(0xbeda))); // --> 0xeda + ASSERT_EQ(1, sc_wr.encode<1>(uint8_t(1))); + ASSERT_EQ(1, sc_wr.encode<1>(uint16_t(0))); + ASSERT_EQ(1, sc_wr.encode<4>(uint8_t(8))); + ASSERT_EQ(1, sc_wr.encode<32>(uint32_t(0xdeadbeef))); + ASSERT_EQ(1, sc_wr.encode<3>(int8_t(-1))); + ASSERT_EQ(1, sc_wr.encode<4>(int8_t(-6))); + ASSERT_EQ(1, sc_wr.encode<20>(int32_t(-123456))); ASSERT_EQ(1, sc_wr.encode<64>(std::numeric_limits::min())); ASSERT_EQ(1, sc_wr.encode<64>(std::numeric_limits::max())); - ASSERT_EQ(1, sc_wr.encode<15>((int16_t)-1)); - ASSERT_EQ(1, sc_wr.encode<2>((int16_t)-1)); + ASSERT_EQ(1, sc_wr.encode<15>(int16_t(-1))); + ASSERT_EQ(1, sc_wr.encode<2>(int16_t(-1))); ASSERT_EQ(1, sc_wr.encode<16>(std::numeric_limits::min())); ASSERT_EQ(1, sc_wr.encode<64>(std::numeric_limits::max())); // Total 302 bit (38 bytes) @@ -86,11 +86,11 @@ TEST(ScalarCodec, RepresentationCorrectness) uavcan::BitStream bs_wr(buf); uavcan::ScalarCodec sc_wr(bs_wr); - ASSERT_EQ(1, sc_wr.encode<12>((uint16_t)0xbeda)); // --> 0xeda - ASSERT_EQ(1, sc_wr.encode<3>((int8_t)-1)); - ASSERT_EQ(1, sc_wr.encode<4>((int8_t)-5)); - ASSERT_EQ(1, sc_wr.encode<2>((int16_t)-1)); - ASSERT_EQ(1, sc_wr.encode<4>((uint8_t)0x88)); // --> 8 + ASSERT_EQ(1, sc_wr.encode<12>(uint16_t(0xbeda))); // --> 0xeda + ASSERT_EQ(1, sc_wr.encode<3>(int8_t(-1))); + ASSERT_EQ(1, sc_wr.encode<4>(int8_t(-5))); + ASSERT_EQ(1, sc_wr.encode<2>(int16_t(-1))); + ASSERT_EQ(1, sc_wr.encode<4>(uint8_t(0x88))); // --> 8 // This representation was carefully crafted and triple checked: static const std::string REFERENCE = "11011010 11101111 01111100 00000000"; diff --git a/libuavcan/test/node/global_data_type_registry.cpp b/libuavcan/test/node/global_data_type_registry.cpp index 488320bcd9..f81b290285 100644 --- a/libuavcan/test/node/global_data_type_registry.cpp +++ b/libuavcan/test/node/global_data_type_registry.cpp @@ -125,7 +125,7 @@ TEST(GlobalDataTypeRegistry, Basic) /* * Searching */ - const uavcan::DataTypeDescriptor* pdtd = NULL; + const uavcan::DataTypeDescriptor* pdtd = UAVCAN_NULLPTR; ASSERT_FALSE(GlobalDataTypeRegistry::instance().find(uavcan::DataTypeKindMessage, "Nonexistent")); ASSERT_FALSE(GlobalDataTypeRegistry::instance().find("Nonexistent")); ASSERT_FALSE(GlobalDataTypeRegistry::instance().find(uavcan::DataTypeKindMessage, 987)); diff --git a/libuavcan/test/node/service_client.cpp b/libuavcan/test/node/service_client.cpp index 4c08c0f8a9..9d8d169e91 100644 --- a/libuavcan/test/node/service_client.cpp +++ b/libuavcan/test/node/service_client.cpp @@ -43,7 +43,7 @@ struct ServiceCallResultHandler } else { - std::cout << "MISMATCH: status=" << last_status << ", last_server_node_id=" + std::cout << "MISMATCH: status=" << int(last_status) << ", last_server_node_id=" << int(last_server_node_id.get()) << ", last response:\n" << last_response << std::endl; return false; } diff --git a/libuavcan/test/node/subscriber.cpp b/libuavcan/test/node/subscriber.cpp index e24336fc23..40be485af9 100644 --- a/libuavcan/test/node/subscriber.cpp +++ b/libuavcan/test/node/subscriber.cpp @@ -82,7 +82,7 @@ TEST(Subscriber, Basic) sizeof(uavcan::Subscriber) << std::endl; // Null binder - will fail - ASSERT_EQ(-uavcan::ErrInvalidParam, sub_extended.start(Listener::ExtendedBinder(NULL, NULL))); + ASSERT_EQ(-uavcan::ErrInvalidParam, sub_extended.start(Listener::ExtendedBinder(UAVCAN_NULLPTR, UAVCAN_NULLPTR))); Listener listener; diff --git a/libuavcan/test/node/test_node.hpp b/libuavcan/test/node/test_node.hpp index 8032d06419..889b9d928b 100644 --- a/libuavcan/test/node/test_node.hpp +++ b/libuavcan/test/node/test_node.hpp @@ -7,6 +7,7 @@ #if __GNUC__ // We need auto_ptr for compatibility reasons # pragma GCC diagnostic ignored "-Wdeprecated-declarations" +# pragma GCC diagnostic ignored "-Wzero-as-null-pointer-constant" #endif #include @@ -72,11 +73,11 @@ struct PairableCanDriver : public uavcan::ICanDriver, public uavcan::ICanIface virtual uavcan::ICanIface* getIface(uavcan::uint8_t iface_index) { - if (iface_index == 0) - { - return this; - } - return NULL; + return (iface_index == 0) ? this : UAVCAN_NULLPTR; + } + virtual const uavcan::ICanIface* getIface(uavcan::uint8_t iface_index) const + { + return (iface_index == 0) ? this : UAVCAN_NULLPTR; } virtual uavcan::uint8_t getNumIfaces() const { return 1; } diff --git a/libuavcan/test/protocol/dynamic_node_id_server/distributed/server.cpp b/libuavcan/test/protocol/dynamic_node_id_server/distributed/server.cpp index 7d7d9a3913..488b905514 100644 --- a/libuavcan/test/protocol/dynamic_node_id_server/distributed/server.cpp +++ b/libuavcan/test/protocol/dynamic_node_id_server/distributed/server.cpp @@ -5,6 +5,7 @@ #if __GNUC__ // We need auto_ptr for compatibility reasons # pragma GCC diagnostic ignored "-Wdeprecated-declarations" +# pragma GCC diagnostic ignored "-Wzero-as-null-pointer-constant" #endif #include diff --git a/libuavcan/test/protocol/dynamic_node_id_server/event_tracer.hpp b/libuavcan/test/protocol/dynamic_node_id_server/event_tracer.hpp index 790165fbcb..b2c30ce6ab 100644 --- a/libuavcan/test/protocol/dynamic_node_id_server/event_tracer.hpp +++ b/libuavcan/test/protocol/dynamic_node_id_server/event_tracer.hpp @@ -43,7 +43,7 @@ public: { const uavcan::MonotonicDuration ts = SystemClockDriver().getMonotonic() - startup_ts_; std::cout << "EVENT [" << id_ << "]\t" << ts.toString() << "\t" - << code << "\t" << getEventName(code) << "\t" << argument << std::endl; + << int(code) << "\t" << getEventName(code) << "\t" << argument << std::endl; event_log_.push_back(EventLogEntry(code, argument)); } @@ -67,7 +67,7 @@ public: } } - std::cout << "No such event in the event log, code " << code << ", log length " << event_log_.size() + std::cout << "No such event in the event log, code " << int(code) << ", log length " << event_log_.size() << std::endl; throw std::runtime_error("EventTracer::getLastEventArgumentOrFail()"); diff --git a/libuavcan/test/protocol/dynamic_node_id_server/node_discoverer.cpp b/libuavcan/test/protocol/dynamic_node_id_server/node_discoverer.cpp index eb3fe234b4..63481e94a7 100644 --- a/libuavcan/test/protocol/dynamic_node_id_server/node_discoverer.cpp +++ b/libuavcan/test/protocol/dynamic_node_id_server/node_discoverer.cpp @@ -5,6 +5,7 @@ #if __GNUC__ // We need auto_ptr for compatibility reasons # pragma GCC diagnostic ignored "-Wdeprecated-declarations" +# pragma GCC diagnostic ignored "-Wzero-as-null-pointer-constant" #endif #include @@ -43,7 +44,7 @@ public: virtual NodeAwareness checkNodeAwareness(uavcan::NodeID node_id) const { const NodeInfo* const ni = const_cast(this)->findNode(node_id); - if (ni == NULL) + if (ni == UAVCAN_NULLPTR) { return NodeAwarenessUnknown; } @@ -53,7 +54,7 @@ public: virtual void handleNewNodeDiscovery(const UniqueID* unique_id_or_null, uavcan::NodeID node_id) { NodeInfo info; - if (unique_id_or_null != NULL) + if (unique_id_or_null != UAVCAN_NULLPTR) { info.unique_id = *unique_id_or_null; } @@ -70,7 +71,7 @@ public: return &nodes.at(i); } } - return NULL; + return UAVCAN_NULLPTR; } NodeInfo* findNode(const uavcan::NodeID& node_id) @@ -82,7 +83,7 @@ public: return &nodes.at(i); } } - return NULL; + return UAVCAN_NULLPTR; } }; diff --git a/libuavcan/test/protocol/helpers.hpp b/libuavcan/test/protocol/helpers.hpp index dc57f21c63..b1d2f97157 100644 --- a/libuavcan/test/protocol/helpers.hpp +++ b/libuavcan/test/protocol/helpers.hpp @@ -14,18 +14,16 @@ template class SubscriptionCollector : uavcan::Noncopyable { - typedef uavcan::ReceivedDataStructure ReceivedDataStructType; - - void handler(const ReceivedDataStructType& msg) + void handler(const DataType& msg) { - this->msg.reset(new ReceivedDataStructType(msg)); + this->msg.reset(new DataType(msg)); } public: - std::auto_ptr msg; + std::auto_ptr msg; typedef uavcan::MethodBinder Binder; + void (SubscriptionCollector::*)(const DataType&)> Binder; Binder bind() { return Binder(this, &SubscriptionCollector::handler); } }; diff --git a/libuavcan/test/protocol/node_info_retriever.cpp b/libuavcan/test/protocol/node_info_retriever.cpp index d16e58eae8..032895e366 100644 --- a/libuavcan/test/protocol/node_info_retriever.cpp +++ b/libuavcan/test/protocol/node_info_retriever.cpp @@ -5,6 +5,7 @@ #if __GNUC__ // We need auto_ptr for compatibility reasons # pragma GCC diagnostic ignored "-Wdeprecated-declarations" +# pragma GCC diagnostic ignored "-Wzero-as-null-pointer-constant" #endif #include diff --git a/libuavcan/test/transport/can/can.hpp b/libuavcan/test/transport/can/can.hpp index 512c2f790e..41563a1ac8 100644 --- a/libuavcan/test/transport/can/can.hpp +++ b/libuavcan/test/transport/can/can.hpp @@ -217,7 +217,7 @@ public: for (unsigned i = 0; i < ifaces.size(); i++) { - ifaces.at(i).pending_tx = (pending_tx[i] == NULL) ? uavcan::CanFrame() : *pending_tx[i]; + ifaces.at(i).pending_tx = (pending_tx[i] == UAVCAN_NULLPTR) ? uavcan::CanFrame() : *pending_tx[i]; } if (select_failure) @@ -270,6 +270,7 @@ public: } virtual uavcan::ICanIface* getIface(uavcan::uint8_t iface_index) { return &ifaces.at(iface_index); } + virtual const uavcan::ICanIface* getIface(uavcan::uint8_t iface_index) const { return &ifaces.at(iface_index); } virtual uavcan::uint8_t getNumIfaces() const { return uavcan::uint8_t(ifaces.size()); } }; diff --git a/libuavcan/test/transport/frame.cpp b/libuavcan/test/transport/frame.cpp index 2cc8c5fe5b..522ad42f9d 100644 --- a/libuavcan/test/transport/frame.cpp +++ b/libuavcan/test/transport/frame.cpp @@ -37,7 +37,7 @@ TEST(Frame, MessageParseCompile) * Parse */ // Invalid CAN frames - ASSERT_FALSE(frame.parse(CanFrame(can_id | CanFrame::FlagRTR, (const uint8_t*)"", 0))); + ASSERT_FALSE(frame.parse(CanFrame(can_id | CanFrame::FlagRTR, reinterpret_cast(""), 0))); ASSERT_FALSE(frame.parse(makeCanFrame(can_id, payload_string, STD))); // Valid @@ -119,7 +119,7 @@ TEST(Frame, ServiceParseCompile) * Parse */ // Invalid CAN frames - ASSERT_FALSE(frame.parse(CanFrame(can_id | CanFrame::FlagRTR, (const uint8_t*)"", 0))); + ASSERT_FALSE(frame.parse(CanFrame(can_id | CanFrame::FlagRTR, reinterpret_cast(""), 0))); ASSERT_FALSE(frame.parse(makeCanFrame(can_id, payload_string, STD))); // Valid diff --git a/libuavcan/test/transport/transfer_buffer.cpp b/libuavcan/test/transport/transfer_buffer.cpp index e3baf42f64..9ed74bc7ba 100644 --- a/libuavcan/test/transport/transfer_buffer.cpp +++ b/libuavcan/test/transport/transfer_buffer.cpp @@ -2,6 +2,12 @@ * Copyright (C) 2014 Pavel Kirienko */ +#if __GNUC__ +// We need auto_ptr for compatibility reasons +# pragma GCC diagnostic ignored "-Wdeprecated-declarations" +# pragma GCC diagnostic ignored "-Wzero-as-null-pointer-constant" +#endif + #include #include #include @@ -238,7 +244,7 @@ TEST(TransferBufferManager, Basic) ASSERT_FALSE(mgr->access(TransferBufferManagerKey(0, uavcan::TransferTypeMessageBroadcast))); ASSERT_FALSE(mgr->access(TransferBufferManagerKey(127, uavcan::TransferTypeServiceRequest))); - ITransferBuffer* tbb = NULL; + ITransferBuffer* tbb = UAVCAN_NULLPTR; const TransferBufferManagerKey keys[5] = { diff --git a/libuavcan/test/transport/transfer_test_helpers.hpp b/libuavcan/test/transport/transfer_test_helpers.hpp index 55dda5a35f..14d6ccc8b1 100644 --- a/libuavcan/test/transport/transfer_test_helpers.hpp +++ b/libuavcan/test/transport/transfer_test_helpers.hpp @@ -102,7 +102,7 @@ struct Transfer os << "ts_m=" << ts_monotonic << " ts_utc=" << ts_utc << " prio=" << int(priority.get()) - << " tt=" << transfer_type + << " tt=" << int(transfer_type) << " tid=" << int(transfer_id.get()) << " snid=" << int(src_node_id.get()) << " dnid=" << int(dst_node_id.get()) @@ -135,7 +135,7 @@ public: transfers_.push(rx); std::cout << "Received transfer: " << rx.toString() << std::endl; - const bool single_frame = dynamic_cast(&transfer) != NULL; + const bool single_frame = dynamic_cast(&transfer) != UAVCAN_NULLPTR; const bool anonymous = single_frame && transfer.getSrcNodeID().isBroadcast() && @@ -314,7 +314,7 @@ public: class NullAllocator : public uavcan::IPoolAllocator { public: - virtual void* allocate(std::size_t) { return NULL; } + virtual void* allocate(std::size_t) { return UAVCAN_NULLPTR; } virtual void deallocate(const void*) { } virtual uint16_t getBlockCapacity() const { return 0; } }; diff --git a/libuavcan/test/util/linked_list.cpp b/libuavcan/test/util/linked_list.cpp index 96c8be0e6d..8910bb8684 100644 --- a/libuavcan/test/util/linked_list.cpp +++ b/libuavcan/test/util/linked_list.cpp @@ -102,7 +102,11 @@ TEST(LinkedList, Basic) TEST(LinkedList, Sorting) { uavcan::LinkedListRoot root; - ListItem items[] = {0, 1, 2, 3, 4, 5}; + ListItem items[6]; + for (int i = 0; i < 6; i++) + { + items[i].value = i; + } EXPECT_EQ(0, root.getLength()); diff --git a/libuavcan/test/util/map.cpp b/libuavcan/test/util/map.cpp index 0fa31f03f1..6d6d21859e 100644 --- a/libuavcan/test/util/map.cpp +++ b/libuavcan/test/util/map.cpp @@ -5,6 +5,7 @@ #if __GNUC__ // We need auto_ptr for compatibility reasons # pragma GCC diagnostic ignored "-Wdeprecated-declarations" +# pragma GCC diagnostic ignored "-Wzero-as-null-pointer-constant" #endif #include @@ -139,7 +140,7 @@ TEST(Map, Basic) const std::string key = toString(i); const std::string value = toString(i); std::string* res = map->insert(key, value); // Will override some from the above - if (res == NULL) + if (res == UAVCAN_NULLPTR) { ASSERT_LT(2, i); break; diff --git a/libuavcan/test/util/multiset.cpp b/libuavcan/test/util/multiset.cpp index 715d99922d..15d117b927 100644 --- a/libuavcan/test/util/multiset.cpp +++ b/libuavcan/test/util/multiset.cpp @@ -2,6 +2,12 @@ * Copyright (C) 2014 Pavel Kirienko */ +#if __GNUC__ +// We need auto_ptr for compatibility reasons +# pragma GCC diagnostic ignored "-Wdeprecated-declarations" +# pragma GCC diagnostic ignored "-Wzero-as-null-pointer-constant" +#endif + #include #include #include @@ -136,7 +142,7 @@ TEST(Multiset, Basic) { const std::string value = toString(i); std::string* res = mset->emplace(value); // Will NOT override above - if (res == NULL) + if (res == UAVCAN_NULLPTR) { ASSERT_LT(2, i); break; diff --git a/libuavcan_drivers/posix/include/uavcan_posix/basic_file_server_backend.hpp b/libuavcan_drivers/posix/include/uavcan_posix/basic_file_server_backend.hpp index 2acf7d659d..eec15f99d3 100644 --- a/libuavcan_drivers/posix/include/uavcan_posix/basic_file_server_backend.hpp +++ b/libuavcan_drivers/posix/include/uavcan_posix/basic_file_server_backend.hpp @@ -85,15 +85,15 @@ protected: enum { InvalidFD = -1 }; FDCacheItem() : - next_(NULL), + next_(UAVCAN_NULLPTR), last_access_(0), fd_(InvalidFD), oflags_(0), - path_(NULL) + path_(UAVCAN_NULLPTR) { } FDCacheItem(int fd, const char* path, int oflags) : - next_(NULL), + next_(UAVCAN_NULLPTR), last_access_(0), fd_(fd), oflags_(oflags), @@ -111,7 +111,7 @@ protected: bool valid() const { - return path_ != NULL; + return path_ != UAVCAN_NULLPTR; } int getFD() const @@ -127,7 +127,7 @@ protected: std::time_t acessed() { using namespace std; - last_access_ = time(NULL); + last_access_ = time(UAVCAN_NULLPTR); return getAccess(); } @@ -139,7 +139,7 @@ protected: bool expired() const { using namespace std; - return 0 == last_access_ || (time(NULL) - last_access_) > MaxAgeSeconds; + return 0 == last_access_ || (time(UAVCAN_NULLPTR) - last_access_) > MaxAgeSeconds; } bool equals(const char* path, int oflags) const @@ -165,7 +165,7 @@ protected: return pi; } } - return NULL; + return UAVCAN_NULLPTR; } FDCacheItem* find(int fd) @@ -177,7 +177,7 @@ protected: return pi; } } - return NULL; + return UAVCAN_NULLPTR; } FDCacheItem* add(FDCacheItem* pi) @@ -239,7 +239,7 @@ protected: public: FDCache(uavcan::INode& node) : TimerBase(node), - head_(NULL) + head_(UAVCAN_NULLPTR) { } virtual ~FDCache() @@ -259,7 +259,7 @@ protected: FDCacheItem* pi = find(path, oflags); - if (pi != NULL) + if (pi != UAVCAN_NULLPTR) { pi->acessed(); } @@ -281,10 +281,10 @@ protected: { /* Allocation worked but clone or path failed */ delete pi; - pi = NULL; + pi = UAVCAN_NULLPTR; } - if (pi == NULL) + if (pi == UAVCAN_NULLPTR) { /* * If allocation fails no harm just can not cache it @@ -301,7 +301,7 @@ protected: virtual int close(int fd, bool done) { FDCacheItem* pi = find(fd); - if (pi == NULL) + if (pi == UAVCAN_NULLPTR) { /* * If not found just close it @@ -318,11 +318,11 @@ protected: FDCacheBase& getFDCache() { - if (fdcache_ == NULL) + if (fdcache_ == UAVCAN_NULLPTR) { fdcache_ = new FDCache(node_); - if (fdcache_ == NULL) + if (fdcache_ == UAVCAN_NULLPTR) { fdcache_ = &fallback_; } @@ -435,7 +435,7 @@ protected: public: BasicFileServerBackend(uavcan::INode& node) : - fdcache_(NULL), + fdcache_(UAVCAN_NULLPTR), node_(node) { } @@ -444,7 +444,7 @@ public: if (fdcache_ != &fallback_) { delete fdcache_; - fdcache_ = NULL; + fdcache_ = UAVCAN_NULLPTR; } } }; diff --git a/libuavcan_drivers/posix/include/uavcan_posix/firmware_version_checker.hpp b/libuavcan_drivers/posix/include/uavcan_posix/firmware_version_checker.hpp index 8a43af35b7..a7f87b1035 100644 --- a/libuavcan_drivers/posix/include/uavcan_posix/firmware_version_checker.hpp +++ b/libuavcan_drivers/posix/include/uavcan_posix/firmware_version_checker.hpp @@ -184,9 +184,9 @@ class FirmwareVersionChecker : public uavcan::IFirmwareVersionChecker if (fd >= 0) { - AppDescriptor* pdescriptor = NULL; + AppDescriptor* pdescriptor = UAVCAN_NULLPTR; - while (pdescriptor == NULL) + while (pdescriptor == UAVCAN_NULLPTR) { int len = read(fd, chunk, sizeof(chunk)); @@ -274,15 +274,15 @@ protected: fname_root[n++] = getPathSeparator(); fname_root[n++] = '\0'; - if (fwdir != NULL) + if (fwdir != UAVCAN_NULLPTR) { - struct dirent* pfile = NULL; - while ((pfile = readdir(fwdir)) != NULL) + struct dirent* pfile = UAVCAN_NULLPTR; + while ((pfile = readdir(fwdir)) != UAVCAN_NULLPTR) { if (DIRENT_ISFILE(pfile->d_type)) { // Open any bin file in there. - if (strstr(pfile->d_name, ".bin") != NULL) + if (strstr(pfile->d_name, ".bin") != UAVCAN_NULLPTR) { PathString full_src_path = fname_root; full_src_path += pfile->d_name; diff --git a/libuavcan_drivers/stm32/driver/include/uavcan_stm32/thread.hpp b/libuavcan_drivers/stm32/driver/include/uavcan_stm32/thread.hpp index ee18eea0ae..fe74e50357 100644 --- a/libuavcan_drivers/stm32/driver/include/uavcan_stm32/thread.hpp +++ b/libuavcan_drivers/stm32/driver/include/uavcan_stm32/thread.hpp @@ -107,7 +107,7 @@ public: int init() { - return pthread_mutex_init(&mutex_, NULL); + return pthread_mutex_init(&mutex_, UAVCAN_NULLPTR); } int deinit() diff --git a/libuavcan_drivers/stm32/driver/src/uc_stm32_can.cpp b/libuavcan_drivers/stm32/driver/src/uc_stm32_can.cpp index 8d50b27d94..45eafaf65d 100644 --- a/libuavcan_drivers/stm32/driver/src/uc_stm32_can.cpp +++ b/libuavcan_drivers/stm32/driver/src/uc_stm32_can.cpp @@ -77,9 +77,9 @@ namespace CanIface* ifaces[UAVCAN_STM32_NUM_IFACES] = { - NULL + UAVCAN_NULLPTR #if UAVCAN_STM32_NUM_IFACES > 1 - , NULL + , UAVCAN_NULLPTR #endif }; @@ -91,7 +91,7 @@ inline void handleTxInterrupt(uavcan::uint8_t iface_index) { utc_usec--; } - if (ifaces[iface_index] != NULL) + if (ifaces[iface_index] != UAVCAN_NULLPTR) { ifaces[iface_index]->handleTxInterrupt(utc_usec); } @@ -109,7 +109,7 @@ inline void handleRxInterrupt(uavcan::uint8_t iface_index, uavcan::uint8_t fifo_ { utc_usec--; } - if (ifaces[iface_index] != NULL) + if (ifaces[iface_index] != UAVCAN_NULLPTR) { ifaces[iface_index]->handleRxInterrupt(fifo_index, utc_usec); } @@ -809,7 +809,7 @@ uavcan::CanSelectMasks CanDriver::makeSelectMasks(const uavcan::CanFrame* (& pen // Iface 0 msk.read = if0_.isRxBufferEmpty() ? 0 : 1; - if (pending_tx[0] != NULL) + if (pending_tx[0] != UAVCAN_NULLPTR) { msk.write = if0_.canAcceptNewTxFrame(*pending_tx[0]) ? 1 : 0; } @@ -821,7 +821,7 @@ uavcan::CanSelectMasks CanDriver::makeSelectMasks(const uavcan::CanFrame* (& pen msk.read |= 1 << 1; } - if (pending_tx[1] != NULL) + if (pending_tx[1] != UAVCAN_NULLPTR) { if (if1_.canAcceptNewTxFrame(*pending_tx[1])) { @@ -982,7 +982,7 @@ int CanDriver::init(const uavcan::uint32_t bitrate, const CanIface::OperatingMod if (res < 0) // a typical race condition. { UAVCAN_STM32_LOG("Iface 0 init failed %i", res); - ifaces[0] = NULL; + ifaces[0] = UAVCAN_NULLPTR; goto fail; } @@ -996,7 +996,7 @@ int CanDriver::init(const uavcan::uint32_t bitrate, const CanIface::OperatingMod if (res < 0) { UAVCAN_STM32_LOG("Iface 1 init failed %i", res); - ifaces[1] = NULL; + ifaces[1] = UAVCAN_NULLPTR; goto fail; } #endif @@ -1017,7 +1017,7 @@ CanIface* CanDriver::getIface(uavcan::uint8_t iface_index) { return ifaces[iface_index]; } - return NULL; + return UAVCAN_NULLPTR; } bool CanDriver::hadActivity() diff --git a/libuavcan_drivers/stm32/driver/src/uc_stm32_thread.cpp b/libuavcan_drivers/stm32/driver/src/uc_stm32_thread.cpp index 9b9a0d2d79..61d73d4fad 100644 --- a/libuavcan_drivers/stm32/driver/src/uc_stm32_thread.cpp +++ b/libuavcan_drivers/stm32/driver/src/uc_stm32_thread.cpp @@ -200,7 +200,7 @@ int BusEvent::addPollWaiter(::pollfd* fds) { for (unsigned i = 0; i < MaxPollWaiters; i++) { - if (pollset_[i] == NULL) + if (pollset_[i] == UAVCAN_NULLPTR) { pollset_[i] = fds; return 0; @@ -215,7 +215,7 @@ int BusEvent::removePollWaiter(::pollfd* fds) { if (fds == pollset_[i]) { - pollset_[i] = NULL; + pollset_[i] = UAVCAN_NULLPTR; return 0; } } @@ -268,7 +268,7 @@ void BusEvent::signalFromInterrupt() for (unsigned i = 0; i < MaxPollWaiters; i++) { ::pollfd* const fd = pollset_[i]; - if (fd != NULL) + if (fd != UAVCAN_NULLPTR) { fd->revents |= fd->events & POLLIN; if ((fd->revents != 0) && (fd->sem->semcount <= 0)) diff --git a/libuavcan_drivers/stm32/test_stm32f107/src/board/board.cpp b/libuavcan_drivers/stm32/test_stm32f107/src/board/board.cpp index 3f9bdd86ba..2bcf3ee70c 100644 --- a/libuavcan_drivers/stm32/test_stm32f107/src/board/board.cpp +++ b/libuavcan_drivers/stm32/test_stm32f107/src/board/board.cpp @@ -31,7 +31,7 @@ void init() chibios_rt::System::init(); - sdStart(&STDOUT_SD, NULL); + sdStart(&STDOUT_SD, nullptr); } __attribute__((noreturn))