Skip to content

Commit

Permalink
Optical Flow: add unit testes for only using downward distance sensor (
Browse files Browse the repository at this point in the history
…#23266)

* Test for Optical Flow checks correct camera position

* Formatting fixed

* Update src/modules/sensors/vehicle_optical_flow/test/CMakeLists.txt

Co-authored-by: Mathieu Bresciani <[email protected]>

* Update src/modules/sensors/vehicle_optical_flow/test/VehicleOpticalFlowTest.cpp

Co-authored-by: Mathieu Bresciani <[email protected]>

* Update src/modules/sensors/vehicle_optical_flow/test/VehicleOpticalFlowTest.cpp

Co-authored-by: Silvan Fuhrer <[email protected]>

* For test GIVEN/WHEN/THEN added

---------

Co-authored-by: Mathieu Bresciani <[email protected]>
Co-authored-by: Silvan Fuhrer <[email protected]>
  • Loading branch information
3 people authored Jan 22, 2025
1 parent caaae6e commit ee150a1
Show file tree
Hide file tree
Showing 4 changed files with 161 additions and 2 deletions.
4 changes: 4 additions & 0 deletions src/modules/sensors/vehicle_optical_flow/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -36,3 +36,7 @@ px4_add_library(vehicle_optical_flow
VehicleOpticalFlow.hpp
)
target_link_libraries(vehicle_optical_flow PRIVATE px4_work_queue)

if(BUILD_TESTING)
add_subdirectory(test)
endif()
Original file line number Diff line number Diff line change
Expand Up @@ -73,9 +73,12 @@ class VehicleOpticalFlow : public ModuleParams, public px4::ScheduledWorkItem

void PrintStatus();

protected:
void UpdateDistanceSensor();
int _distance_sensor_selected{-1}; // because we can have several distance sensor instances with different orientations

private:
void ClearAccumulatedData();
void UpdateDistanceSensor();
void UpdateSensorGyro();

void Run() override;
Expand Down Expand Up @@ -117,7 +120,6 @@ class VehicleOpticalFlow : public ModuleParams, public px4::ScheduledWorkItem
uint16_t _quality_sum{0};
uint8_t _accumulated_count{0};

int _distance_sensor_selected{-1}; // because we can have several distance sensor instances with different orientations
hrt_abstime _last_range_sensor_update{0};

bool _delta_angle_available{false};
Expand Down
35 changes: 35 additions & 0 deletions src/modules/sensors/vehicle_optical_flow/test/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,35 @@
############################################################################
#
# Copyright (c) 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 VehicleOpticalFlowTest.cpp LINKLIBS vehicle_optical_flow uORB sensor_calibration)
Original file line number Diff line number Diff line change
@@ -0,0 +1,118 @@
/****************************************************************************
*
* Copyright (c) 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 VehicleOpticalFlow
*/

#include <gtest/gtest.h>
#include "../VehicleOpticalFlow.hpp"
#include <uORB/uORBManager.hpp>
#include <uORB/topics/distance_sensor.h>


distance_sensor_s createDistanceSensorMessage(uint16_t orientation)
{
distance_sensor_s message;
message.timestamp = hrt_absolute_time();
message.min_distance = 1.f;
message.max_distance = 100.f;
message.current_distance = 1.1f;

message.variance = 0.1f;
message.signal_quality = 100;
message.type = distance_sensor_s::MAV_DISTANCE_SENSOR_LASER;
message.orientation = orientation;
message.h_fov = math::radians(50.f);
message.v_fov = math::radians(30.f);
return message;

}

class VehicleOpticalFlowTest : public ::testing::Test
{
public:

class VehicleOpticalFlowTestable : public sensors::VehicleOpticalFlow
{
public:
void UpdateDistanceSensorPublic()
{
VehicleOpticalFlow::UpdateDistanceSensor();
}
bool IsDistanceSensorSelected()
{
return _distance_sensor_selected >= 0;

}
};

void SetUp() override
{
uORB::Manager::initialize();

}
void TearDown() override
{
uORB::Manager::terminate();
}
};


TEST_F(VehicleOpticalFlowTest, CameraFacingDown)
{
// GIVEN: message with sensor camera facing down
distance_sensor_s message = createDistanceSensorMessage(distance_sensor_s::ROTATION_DOWNWARD_FACING);
orb_advertise(ORB_ID(distance_sensor), &message);

// WHEN: update distance sensor
VehicleOpticalFlowTest::VehicleOpticalFlowTestable testable;
testable.UpdateDistanceSensorPublic();

// THEN: sensor selected
EXPECT_TRUE(testable.IsDistanceSensorSelected());
}

TEST_F(VehicleOpticalFlowTest, CameraFacingForward)
{
// GIVEN: message with sensor camera facing forward
distance_sensor_s message = createDistanceSensorMessage(distance_sensor_s::ROTATION_FORWARD_FACING);
orb_advertise(ORB_ID(distance_sensor), &message);

// WHEN: update distance sensor
VehicleOpticalFlowTest::VehicleOpticalFlowTestable testable;
testable.UpdateDistanceSensorPublic();

// THEN: sensor is not selected
EXPECT_FALSE(testable.IsDistanceSensorSelected());
}

0 comments on commit ee150a1

Please sign in to comment.