Skip to content

Commit

Permalink
Use constant definitions for testing special values
Browse files Browse the repository at this point in the history
Inside the tests there exist special values to simulate an error in the hardware.
These magic numbers were used and defined at different places. This creates
one common place to define those. This should make maintenance more stable
and the tests easier to understand for new developers.
  • Loading branch information
fmauch committed Jul 13, 2023
1 parent d149da6 commit 432721b
Show file tree
Hide file tree
Showing 5 changed files with 53 additions and 18 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@
#include "controller_manager/controller_manager.hpp"
#include "controller_manager_test_common.hpp"
#include "hardware_interface/types/lifecycle_state_names.hpp"
#include "hardware_interface/types/test_hardware_interface_constants.hpp"
#include "lifecycle_msgs/msg/state.hpp"
#include "test_controller/test_controller.hpp"

Expand Down Expand Up @@ -162,10 +163,6 @@ class TestControllerManagerWithTestableCM
{}, strictness);
}

// values to set to hardware to simulate failure on read and write
static constexpr double READ_FAIL_VALUE = 28282828.0;
static constexpr double WRITE_FAIL_VALUE = 23232323.0;

static constexpr char TEST_CONTROLLER_ACTUATOR_NAME[] = "test_controller_actuator";
static constexpr char TEST_CONTROLLER_SYSTEM_NAME[] = "test_controller_system";
static constexpr char TEST_BROADCASTER_ALL_NAME[] = "test_broadcaster_all";
Expand Down Expand Up @@ -258,7 +255,8 @@ TEST_P(TestControllerManagerWithTestableCM, stop_controllers_on_hardware_read_er

// Simulate error in read() on TEST_ACTUATOR_HARDWARE_NAME by setting first command interface to
// READ_FAIL_VALUE
test_controller_actuator->set_first_command_interface_value_to = READ_FAIL_VALUE;
test_controller_actuator->set_first_command_interface_value_to =
hardware_interface::testing_constants::READ_FAIL_VALUE;
{
auto new_counter = test_controller_actuator->internal_counter + 1;
EXPECT_EQ(controller_interface::return_type::OK, cm_->update(TIME, PERIOD));
Expand Down Expand Up @@ -327,8 +325,10 @@ TEST_P(TestControllerManagerWithTestableCM, stop_controllers_on_hardware_read_er

// Simulate error in read() on TEST_ACTUATOR_HARDWARE_NAME and TEST_SYSTEM_HARDWARE_NAME
// by setting first command interface to READ_FAIL_VALUE
test_controller_actuator->set_first_command_interface_value_to = READ_FAIL_VALUE;
test_controller_system->set_first_command_interface_value_to = READ_FAIL_VALUE;
test_controller_actuator->set_first_command_interface_value_to =
hardware_interface::testing_constants::READ_FAIL_VALUE;
test_controller_system->set_first_command_interface_value_to =
hardware_interface::testing_constants::READ_FAIL_VALUE;
{
auto previous_counter_lower = test_controller_actuator->internal_counter + 1;
auto previous_counter_higher = test_controller_system->internal_counter + 1;
Expand Down Expand Up @@ -450,7 +450,8 @@ TEST_P(TestControllerManagerWithTestableCM, stop_controllers_on_hardware_write_e

// Simulate error in write() on TEST_ACTUATOR_HARDWARE_NAME by setting first command interface to
// WRITE_FAIL_VALUE
test_controller_actuator->set_first_command_interface_value_to = WRITE_FAIL_VALUE;
test_controller_actuator->set_first_command_interface_value_to =
hardware_interface::testing_constants::WRITE_FAIL_VALUE;
{
auto new_counter = test_controller_actuator->internal_counter + 1;
EXPECT_EQ(controller_interface::return_type::OK, cm_->update(TIME, PERIOD));
Expand Down Expand Up @@ -519,8 +520,10 @@ TEST_P(TestControllerManagerWithTestableCM, stop_controllers_on_hardware_write_e

// Simulate error in write() on TEST_ACTUATOR_HARDWARE_NAME and TEST_SYSTEM_HARDWARE_NAME
// by setting first command interface to WRITE_FAIL_VALUE
test_controller_actuator->set_first_command_interface_value_to = WRITE_FAIL_VALUE;
test_controller_system->set_first_command_interface_value_to = WRITE_FAIL_VALUE;
test_controller_actuator->set_first_command_interface_value_to =
hardware_interface::testing_constants::WRITE_FAIL_VALUE;
test_controller_system->set_first_command_interface_value_to =
hardware_interface::testing_constants::WRITE_FAIL_VALUE;
{
auto previous_counter_lower = test_controller_actuator->internal_counter + 1;
auto previous_counter_higher = test_controller_system->internal_counter + 1;
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,29 @@
// Copyright (c) 2023, FZI Forschungszentrum Informatik
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
//
/// \author: Felix Exner <[email protected]>

#ifndef HARDWARE_INTERFACE__TYPES__TEST_HARDWARE_INTERFACE_CONSTANTS_HPP_
#define HARDWARE_INTERFACE__TYPES__TEST_HARDWARE_INTERFACE_CONSTANTS_HPP_
namespace hardware_interface
{
namespace test_constants
{
/// Constants defining special values used inside tests to trigger things like deactivate or errors
/// on read/write.
constexpr double READ_FAIL_VALUE = 28282828.0;
constexpr double WRITE_FAIL_VALUE = 23232323.0;
} // namespace test_constants
} // namespace hardware_interface
#endif // HARDWARE_INTERFACE__TYPES__TEST_HARDWARE_INTERFACE_CONSTANTS_HPP_
5 changes: 3 additions & 2 deletions hardware_interface/test/test_components/test_actuator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@
#include <vector>

#include "hardware_interface/actuator_interface.hpp"
#include "hardware_interface/types/test_hardware_interface_constants.hpp"

using hardware_interface::ActuatorInterface;
using hardware_interface::CommandInterface;
Expand Down Expand Up @@ -76,7 +77,7 @@ class TestActuator : public ActuatorInterface
return_type read(const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/) override
{
// simulate error on read
if (velocity_command_ == 28282828.0)
if (velocity_command_ == hardware_interface::test_constants::READ_FAIL_VALUE)
{
// reset value to get out from error on the next call - simplifies CM tests
velocity_command_ = 0.0;
Expand All @@ -93,7 +94,7 @@ class TestActuator : public ActuatorInterface
return_type write(const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/) override
{
// simulate error on write
if (velocity_command_ == 23232323.0)
if (velocity_command_ == hardware_interface::test_constants::WRITE_FAIL_VALUE)
{
// reset value to get out from error on the next call - simplifies CM tests
velocity_command_ = 0.0;
Expand Down
5 changes: 3 additions & 2 deletions hardware_interface/test/test_components/test_system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@

#include "hardware_interface/system_interface.hpp"
#include "hardware_interface/types/hardware_interface_type_values.hpp"
#include "hardware_interface/types/test_hardware_interface_constants.hpp"

using hardware_interface::CommandInterface;
using hardware_interface::return_type;
Expand Down Expand Up @@ -81,7 +82,7 @@ class TestSystem : public SystemInterface
return_type read(const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/) override
{
// simulate error on read
if (velocity_command_[0] == 28282828)
if (velocity_command_[0] == hardware_interface::test_constants::READ_FAIL_VALUE)
{
// reset value to get out from error on the next call - simplifies CM tests
velocity_command_[0] = 0.0;
Expand All @@ -93,7 +94,7 @@ class TestSystem : public SystemInterface
return_type write(const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/) override
{
// simulate error on write
if (velocity_command_[0] == 23232323)
if (velocity_command_[0] == hardware_interface::test_constants::WRITE_FAIL_VALUE)
{
// reset value to get out from error on the next call - simplifies CM tests
velocity_command_[0] = 0.0;
Expand Down
9 changes: 5 additions & 4 deletions hardware_interface/test/test_resource_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,7 @@
#include "hardware_interface/actuator_interface.hpp"
#include "hardware_interface/resource_manager.hpp"
#include "hardware_interface/types/lifecycle_state_names.hpp"
#include "hardware_interface/types/test_hardware_interface_constants.hpp"
#include "lifecycle_msgs/msg/state.hpp"
#include "rclcpp_lifecycle/state.hpp"
#include "ros2_control_test_assets/descriptions.hpp"
Expand Down Expand Up @@ -1546,8 +1547,6 @@ class ResourceManagerTestReadWriteError : public ResourceManagerTest
const rclcpp::Duration duration = rclcpp::Duration::from_seconds(0.01);

// values to set to hardware to simulate failure on read and write
static constexpr double READ_FAIL_VALUE = 28282828.0;
static constexpr double WRITE_FAIL_VALUE = 23232323.0;
};

TEST_F(ResourceManagerTestReadWriteError, handle_error_on_hardware_read)
Expand All @@ -1558,7 +1557,8 @@ TEST_F(ResourceManagerTestReadWriteError, handle_error_on_hardware_read)
// check read methods failures
check_read_or_write_failure(
std::bind(&TestableResourceManager::read, rm, _1, _2),
std::bind(&TestableResourceManager::write, rm, _1, _2), READ_FAIL_VALUE);
std::bind(&TestableResourceManager::write, rm, _1, _2),
hardware_interface::test_constants::READ_FAIL_VALUE);
}

TEST_F(ResourceManagerTestReadWriteError, handle_error_on_hardware_write)
Expand All @@ -1569,7 +1569,8 @@ TEST_F(ResourceManagerTestReadWriteError, handle_error_on_hardware_write)
// check write methods failures
check_read_or_write_failure(
std::bind(&TestableResourceManager::write, rm, _1, _2),
std::bind(&TestableResourceManager::read, rm, _1, _2), WRITE_FAIL_VALUE);
std::bind(&TestableResourceManager::read, rm, _1, _2),
hardware_interface::test_constants::WRITE_FAIL_VALUE);
}

TEST_F(ResourceManagerTest, test_caching_of_controllers_to_hardware)
Expand Down

0 comments on commit 432721b

Please sign in to comment.