From 97919ccc9d7faaf82c4d11aa36be2b5a17c7849a Mon Sep 17 00:00:00 2001 From: Julian Kent Date: Thu, 8 Aug 2019 17:38:54 +0200 Subject: [PATCH] Add a more real-world test of the collision prevention --- src/lib/CollisionPrevention/CMakeLists.txt | 2 + .../CollisionPrevention.cpp | 14 +- .../CollisionPreventionTest.cpp | 135 ++++++++++++++++++ 3 files changed, 150 insertions(+), 1 deletion(-) create mode 100644 src/lib/CollisionPrevention/CollisionPreventionTest.cpp diff --git a/src/lib/CollisionPrevention/CMakeLists.txt b/src/lib/CollisionPrevention/CMakeLists.txt index ae36bf94b623..69c5bf98313c 100644 --- a/src/lib/CollisionPrevention/CMakeLists.txt +++ b/src/lib/CollisionPrevention/CMakeLists.txt @@ -33,3 +33,5 @@ px4_add_library(CollisionPrevention CollisionPrevention.cpp) target_compile_options(CollisionPrevention PRIVATE -Wno-cast-align) # TODO: fix and enable + +px4_add_functional_gtest(SRC CollisionPreventionTest.cpp LINKLIBS CollisionPrevention ) diff --git a/src/lib/CollisionPrevention/CollisionPrevention.cpp b/src/lib/CollisionPrevention/CollisionPrevention.cpp index c64be5bc3053..d01a6b6517d4 100644 --- a/src/lib/CollisionPrevention/CollisionPrevention.cpp +++ b/src/lib/CollisionPrevention/CollisionPrevention.cpp @@ -53,6 +53,18 @@ CollisionPrevention::~CollisionPrevention() if (_mavlink_log_pub != nullptr) { orb_unadvertise(_mavlink_log_pub); } + + if (_constraints_pub != nullptr) { + orb_unadvertise(_constraints_pub); + } + + if (_obstacle_distance_pub != nullptr) { + orb_unadvertise(_obstacle_distance_pub); + } + + if (_pub_vehicle_command != nullptr) { + orb_unadvertise(_pub_vehicle_command); + } } void CollisionPrevention::_publishConstrainedSetpoint(const Vector2f &original_setpoint, @@ -102,7 +114,7 @@ void CollisionPrevention::_updateOffboardObstacleDistance(obstacle_distance_s &o void CollisionPrevention::_updateDistanceSensor(obstacle_distance_s &obstacle) { for (unsigned i = 0; i < ORB_MULTI_MAX_INSTANCES; i++) { - distance_sensor_s distance_sensor; + distance_sensor_s distance_sensor {}; _sub_distance_sensor[i].copy(&distance_sensor); // consider only instaces with updated, valid data and orientations useful for collision prevention diff --git a/src/lib/CollisionPrevention/CollisionPreventionTest.cpp b/src/lib/CollisionPrevention/CollisionPreventionTest.cpp new file mode 100644 index 000000000000..a96c06f9a1a8 --- /dev/null +++ b/src/lib/CollisionPrevention/CollisionPreventionTest.cpp @@ -0,0 +1,135 @@ +/**************************************************************************** + * + * Copyright (C) 2019 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. + * + ****************************************************************************/ + +#include +#include + +// to run: make tests TESTFILTER=CollisionPrevention + +class CollisionPreventionTest : public ::testing::Test +{ +public: + void SetUp() override + { + uORB::Manager::initialize(); + param_init(); + } + + void TearDown() override + { + param_reset_all(); + uORB::Manager::terminate(); + } +}; + +TEST_F(CollisionPreventionTest, instantiation) { CollisionPrevention cp(nullptr); } + +TEST_F(CollisionPreventionTest, behaviorOff) +{ + // GIVEN: a simple setup condition + CollisionPrevention cp(nullptr); + matrix::Vector2f original_setpoint(10, 0); + float max_speed = 3.f; + matrix::Vector2f curr_pos(0, 0); + matrix::Vector2f curr_vel(2, 0); + + // WHEN: we check if the setpoint should be modified + matrix::Vector2f modified_setpoint = original_setpoint; + cp.modifySetpoint(modified_setpoint, max_speed, curr_pos, curr_vel); + + // THEN: it should be the same + EXPECT_EQ(original_setpoint, modified_setpoint); +} + +TEST_F(CollisionPreventionTest, withoutObstacleMessageNothing) +{ + // GIVEN: a simple setup condition + CollisionPrevention cp(nullptr); + matrix::Vector2f original_setpoint(10, 0); + float max_speed = 3.f; + matrix::Vector2f curr_pos(0, 0); + matrix::Vector2f curr_vel(2, 0); + + // AND: a parameter handle + param_t param = param_handle(px4::params::MPC_COL_PREV_D); + + + // WHEN: we set the parameter check then apply the setpoint modification + float value = 10; // try to keep 10m away from obstacles + param_set(param, &value); + + matrix::Vector2f modified_setpoint = original_setpoint; + cp.modifySetpoint(modified_setpoint, max_speed, curr_pos, curr_vel); + + // THEN: it shouldn't interfere with the setpoint, because there isn't an obstacle + EXPECT_EQ(original_setpoint, modified_setpoint); +} + +TEST_F(CollisionPreventionTest, testBehaviorOnWithAnObstacle) +{ + // GIVEN: a simple setup condition + CollisionPrevention cp(nullptr); + matrix::Vector2f original_setpoint(10, 0); + float max_speed = 3; + matrix::Vector2f curr_pos(0, 0); + matrix::Vector2f curr_vel(2, 0); + + // AND: a parameter handle + param_t param = param_handle(px4::params::MPC_COL_PREV_D); + float value = 10; // try to keep 10m distance + param_set(param, &value); + + // AND: an obstacle message + obstacle_distance_s message; + memset(&message, 0xDEAD, sizeof(message)); + message.min_distance = 100; + message.max_distance = 1000; + message.timestamp = hrt_absolute_time(); + int distances_array_size = sizeof(message.distances) / sizeof(message.distances[0]); + message.increment = 360 / distances_array_size; + + for (int i = 0; i < distances_array_size; i++) { + message.distances[i] = 101; + } + + orb_advert_t obstacle_distance_pub = orb_advertise(ORB_ID(obstacle_distance), &message); + + + // WHEN: we publish the message and set the parameter and then run the setpoint modification + matrix::Vector2f modified_setpoint = original_setpoint; + cp.modifySetpoint(modified_setpoint, max_speed, curr_pos, curr_vel); + orb_unadvertise(obstacle_distance_pub); + + // THEN: it should be cut down a lot + EXPECT_GT(original_setpoint.norm() * 0.5f, modified_setpoint.norm()); //FIXME: this should actually be constrained to 0 +}