Skip to content

Commit

Permalink
🧪 parameter tests (TAMS-Group#10)
Browse files Browse the repository at this point in the history
Signed-off-by: Tyler Weaver <tylerjw@gmail.com>
  • Loading branch information
tylerjw committed Jan 3, 2022
1 parent 7fdc9d1 commit 0aa8a72
Show file tree
Hide file tree
Showing 6 changed files with 169 additions and 26 deletions.
14 changes: 5 additions & 9 deletions .github/workflows/ci.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -17,14 +17,12 @@ jobs:
fail-fast: false
matrix:
env:
# TODO(tylerjw): re-enable testing on testing once moveit is fixed on buildfarm
# - NAME: "rolling-testing-ccov"
# ROS_REPO: testing
# TODO(tylerjw): enable coverage once there is a test
# TARGET_CMAKE_ARGS: -DENABLE_COVERAGE=ON
# CCOV: true
- NAME: "rolling-testing-ccov"
ROS_REPO: testing
TARGET_CMAKE_ARGS: -DENABLE_COVERAGE=ON
CCOV: true
- NAME: "rolling-main"
# ROS_REPO: main
ROS_REPO: main
- NAME: "address-leak-ub-sanitizers"
TARGET_CMAKE_ARGS: >
-DCMAKE_BUILD_TYPE=Debug
Expand All @@ -51,8 +49,6 @@ jobs:

env:
ROS_DISTRO: rolling
# TODO(tylerjw): re-enable testing on testing once moveit is fixed on buildfarm
ROS_REPO: main
UPSTREAM_WORKSPACE: upstream.repos
UPSTREAM_CMAKE_ARGS: >
-DCMAKE_BUILD_TYPE=Release
Expand Down
1 change: 1 addition & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -111,6 +111,7 @@ target_link_libraries(
project_warnings
PUBLIC
Eigen3::Eigen
fmt::fmt
moveit_core::moveit_collision_detection_fcl
moveit_core::moveit_kinematics_base
moveit_core::moveit_robot_model
Expand Down
11 changes: 11 additions & 0 deletions include/bio_ik/parameters.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,8 @@

#pragma once

#include <fmt/core.h>

#include <cfloat>
#include <limits>
#include <optional>
Expand Down Expand Up @@ -59,6 +61,15 @@ struct RosParameters {
size_t population_size = 8;
size_t elite_count = 4;
bool enable_linear_fitness = false;

inline operator std::string() const {
return fmt::format(
"[RosParameters: enable_profiler={}, mode={}, enable_counter={}, "
"random_seed={}, dpos={}, drot={}, dtwist={}, skip_wipeout={}, "
"population_size={}, elite_count={}, enable_linear_fitness={}]",
enable_profiler, mode, enable_counter, random_seed, dpos, drot, dtwist,
skip_wipeout, population_size, elite_count, enable_linear_fitness);
}
};

/**
Expand Down
33 changes: 16 additions & 17 deletions src/parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -136,41 +136,40 @@ std::set<std::string> valid_modes() {

std::optional<std::string> validate(const RosParameters& ros_params) {
if (valid_modes().count(ros_params.mode) == 0)
return fmt::format("Mode: {}\nValid Modes: {}\n", ros_params.mode,
return fmt::format("Mode: \"{}\" is not in set: {}\n", ros_params.mode,
valid_modes());
return std::nullopt;
}

std::optional<RosParameters> get_ros_parameters(
const rclcpp::Node::SharedPtr& node) {
using rclcpp::ParameterValue;
RosParameters ros_params;

auto ros_parameters = RosParameters{
const auto default_values = RosParameters{};
const auto ros_params = RosParameters{
.enable_profiler =
declare(node, "enable_profiler", ros_params.enable_profiler,
declare(node, "enable_profiler", default_values.enable_profiler,
DescriptorBuilder().additional_constraints(
fmt::format("One of {}", valid_modes()))),
.mode = declare(node, "mode", ros_params.mode),
.mode = declare(node, "mode", default_values.mode),
.enable_counter =
declare(node, "enable_counter", ros_params.enable_counter),
.random_seed = declare(node, "random_seed", ros_params.random_seed),
.dpos = declare(node, "dpos", ros_params.dpos),
.drot = declare(node, "drot", ros_params.drot),
.dtwist = declare(node, "dtwist", ros_params.dtwist),
.skip_wipeout = declare(node, "skip_wipeout", ros_params.skip_wipeout),
declare(node, "enable_counter", default_values.enable_counter),
.random_seed = declare(node, "random_seed", default_values.random_seed),
.dpos = declare(node, "dpos", default_values.dpos),
.drot = declare(node, "drot", default_values.drot),
.dtwist = declare(node, "dtwist", default_values.dtwist),
.skip_wipeout =
declare(node, "skip_wipeout", default_values.skip_wipeout),
.population_size = static_cast<size_t>(
declare(node, "population_size",
static_cast<int64_t>(ros_params.population_size),
static_cast<int64_t>(default_values.population_size),
DescriptorBuilder().integer_range(2))),
.elite_count = static_cast<size_t>(declare(
node, "elite_count", static_cast<int64_t>(ros_params.elite_count),
node, "elite_count", static_cast<int64_t>(default_values.elite_count),
DescriptorBuilder().integer_range(2))),
.enable_linear_fitness = declare(node, "enable_linear_fitness",
ros_params.enable_linear_fitness),
default_values.enable_linear_fitness),
};

if (auto error = validate(ros_params)) {
if (const auto error = validate(ros_params)) {
RCLCPP_ERROR_STREAM(rclcpp::get_logger("bio_ik"), *error);
return std::nullopt;
} else {
Expand Down
7 changes: 7 additions & 0 deletions test/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -9,4 +9,11 @@ if(BUILD_TESTING)
# project_warnings
# bio_ik
# )

ament_add_gtest(parameter_tests parameter_tests.cpp)
target_link_libraries(parameter_tests
project_options
project_warnings
bio_ik
)
endif()
129 changes: 129 additions & 0 deletions test/parameter_tests.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,129 @@
// Copyright 2021 PickNik Inc
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions are met:
//
// * Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// * 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.
//
// * Neither the name of the PickNik Inc 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 HOLDER 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 <iostream>
#include <memory>
#include <rclcpp/rclcpp.hpp>

#include "bio_ik/parameters.hpp"
#include "gtest/gtest.h"

TEST(ParameterTests, DefaultValidMode) // NOLINT
{
// GIVEN a default constructed bio_ik::RosParameters
const auto ros_params = bio_ik::RosParameters{};

// WHEN we call validate
const auto result = bio_ik::validate(ros_params);

// THEN we expect the result to not contain an error
EXPECT_FALSE(result.has_value())
<< "bio_ik::validate returned error: " << *result;
}

TEST(ParameterTests, NotValidMode) // NOLINT
{
// GIVEN a bio_ik::RosParameters with an invalid mode
const auto ros_params = bio_ik::RosParameters{.mode = "invalid"};

// WHEN we call validate
const auto result = bio_ik::validate(ros_params);

// THEN we expect the result to contain an error
EXPECT_TRUE(result.has_value()) << "bio_ik::validate did not return an error";
}

TEST(ParameterTests, GetIsValid) // NOLIINT
{
// WHEN we call get_ros_parameters with no overridden parameters
const auto ros_params =
bio_ik::get_ros_parameters(std::make_shared<rclcpp::Node>("_"));

// THEN we expect the result to be valid
EXPECT_TRUE(ros_params.has_value())
<< "get_ros_parameters did not return a result";
}

TEST(ParameterTests, DefaultSameAsRosDefault) // NOLINT
{
// GIVEN a default constructed bio_ik::RosParameters
const auto default_ros_parameters = bio_ik::RosParameters{};

// WHEN we create another one using the get_ros_parameters function without
// overriding any ros parameters
const auto ros_params =
bio_ik::get_ros_parameters(std::make_shared<rclcpp::Node>("_"));

// THEN we expect the result to have a value and that to be the same as the
// default constructed one except for the random seed
ASSERT_TRUE(ros_params.has_value())
<< "get_ros_parameters did not return a result";
EXPECT_TRUE([](const auto& lhs, const auto& rhs) {
return std::tie(lhs.enable_profiler, lhs.mode, lhs.enable_counter, lhs.dpos,
lhs.drot, lhs.dtwist, lhs.skip_wipeout, lhs.population_size,
lhs.elite_count, lhs.enable_linear_fitness) ==
std::tie(rhs.enable_profiler, rhs.mode, rhs.enable_counter, rhs.dpos,
rhs.drot, rhs.dtwist, rhs.skip_wipeout, rhs.population_size,
rhs.elite_count, rhs.enable_linear_fitness);
}(ros_params.value(), default_ros_parameters))
<< "\nget_ros_parameters: " + std::string(ros_params.value()) +
"\ndefault_ros_parameters: " + std::string(default_ros_parameters);
}

TEST(ParameterTests, StringOperator) // NOLINT
{
// GIVEN a default constructed bio_ik::RosParameters
// WHEN we convert it to std::string
// THEN we don't expect it to not throw
EXPECT_NO_THROW(auto _ = std::string(bio_ik::RosParameters{}));
}

TEST(ParameterTests, GetInvalidParameters) // NOLINT
{
// GIVEN a ros node with a parameter override
auto node = std::make_shared<rclcpp::Node>(
"_", rclcpp::NodeOptions().append_parameter_override(
"mode", rclcpp::ParameterValue("invalid")));

// WHEN we call get_ros_parameters
auto result = bio_ik::get_ros_parameters(node);

// THEN we expect the result to have failed
EXPECT_FALSE(result.has_value())
<< "get_ros_parameters should have returned no value, returned: " +
std::string(result.value());
}

int main(int argc, char** argv) {
rclcpp::init(argc, argv);
::testing::InitGoogleTest(&argc, argv);

int result = RUN_ALL_TESTS();
rclcpp::shutdown();
return result;
}

0 comments on commit 0aa8a72

Please sign in to comment.