Skip to content

Commit

Permalink
Duplicate empty _node check removed from Subscription.hpp (#23316) (#…
Browse files Browse the repository at this point in the history
…23317)

* Duplicate empty `_node` check removed from Subscription.hpp (#23316)

* newline

* move uORB gtests to uORB/test

---------

Co-authored-by: Jacob Dahl <[email protected]>
Co-authored-by: Jacob Dahl <[email protected]>
  • Loading branch information
3 people authored Mar 7, 2025
1 parent c83fd11 commit 5be867d
Show file tree
Hide file tree
Showing 5 changed files with 164 additions and 20 deletions.
4 changes: 3 additions & 1 deletion platforms/common/uORB/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -112,4 +112,6 @@ if(PX4_TESTING)
add_subdirectory(uORB_tests)
endif()

px4_add_functional_gtest(SRC uORBMessageFieldsTest.cpp LINKLIBS uORB)
if(PX4_TESTING)
add_subdirectory(test)
endif()
28 changes: 10 additions & 18 deletions platforms/common/uORB/Subscription.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -118,16 +118,8 @@ class Subscription
bool valid() const { return _node != nullptr; }
bool advertised()
{
if (valid()) {
return Manager::is_advertised(_node);
}

// try to initialize
if (subscribe()) {
// check again if valid
if (valid()) {
return Manager::is_advertised(_node);
}
return Manager::is_advertised(_node);
}

return false;
Expand All @@ -138,11 +130,11 @@ class Subscription
*/
bool updated()
{
if (!valid()) {
subscribe();
if (subscribe()) {
return Manager::updates_available(_node, _last_generation);
}

return valid() ? Manager::updates_available(_node, _last_generation) : false;
return false;
}

/**
Expand All @@ -151,11 +143,11 @@ class Subscription
*/
bool update(void *dst)
{
if (!valid()) {
subscribe();
if (subscribe()) {
return Manager::orb_data_copy(_node, dst, _last_generation, true);
}

return valid() ? Manager::orb_data_copy(_node, dst, _last_generation, true) : false;
return false;
}

/**
Expand All @@ -164,11 +156,11 @@ class Subscription
*/
bool copy(void *dst)
{
if (!valid()) {
subscribe();
if (subscribe()) {
return Manager::orb_data_copy(_node, dst, _last_generation, false);
}

return valid() ? Manager::orb_data_copy(_node, dst, _last_generation, false) : false;
return false;
}

/**
Expand Down
36 changes: 36 additions & 0 deletions platforms/common/uORB/test/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,36 @@
############################################################################
#
# Copyright (c) 2019-2024 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT

# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################

px4_add_functional_gtest(SRC uORBMessageFieldsTest.cpp LINKLIBS uORB)
px4_add_functional_gtest(SRC uORBSubscriptionTest.cpp LINKLIBS uORB)
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@
*
****************************************************************************/

#include "uORBMessageFields.hpp"
#include <uORB/uORBMessageFields.hpp>

#include <gtest/gtest.h>
#include <containers/Bitset.hpp>
Expand Down
114 changes: 114 additions & 0 deletions platforms/common/uORB/test/uORBSubscriptionTest.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,114 @@
/****************************************************************************
*
* Copyright (c) 2019-2024 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/

/**
* Test for Subscription
*/

#include <gtest/gtest.h>
#include <uORB/Subscription.hpp>
#include <uORB/uORB.h>
#include <uORB/topics/orb_test.h>

namespace uORB
{
namespace test
{


class uORBSubscriptionTestable : public uORB::Subscription
{
public:
uORBSubscriptionTestable() : Subscription(ORB_ID(orb_test), 0)
{
}

void setNodeValue(void *node)
{
_node = node;

}
void *getNodeValue()
{
return _node;
}

};


class uORBSubscriptionTest : public ::testing::Test
{
protected:
uORBSubscriptionTestable testable;

static void SetUpTestSuite()
{
uORB::Manager::initialize();

orb_test_s message{};
orb_advertise(ORB_ID(orb_test), &message);

}
static void TearDownTestSuite()
{
uORB::Manager::terminate();
}

void TearDown() override
{
testable.setNodeValue(nullptr);
}


};

TEST_F(uORBSubscriptionTest, updateWhenSubscribedThenNotSubscribedTwice)
{
int anyValue = 1;
testable.setNodeValue(&anyValue);

testable.updated();

ASSERT_EQ(testable.getNodeValue(), &anyValue) << "Original node value don't have to be overrwiten";
}

TEST_F(uORBSubscriptionTest, updateWhenNotSubscribedThenSubscribed)
{
testable.setNodeValue(nullptr);

testable.updated();

ASSERT_NE(testable.getNodeValue(), nullptr) << "Node value after 'updated' have to be initialized";
}
}
}

0 comments on commit 5be867d

Please sign in to comment.