Skip to content

Commit

Permalink
Added remaining tests
Browse files Browse the repository at this point in the history
Signed-off-by: Yadunund <yadunund@openrobotics.org>
  • Loading branch information
Yadunund committed Nov 17, 2021
1 parent 7207547 commit 0be7812
Show file tree
Hide file tree
Showing 8 changed files with 602 additions and 7 deletions.
7 changes: 3 additions & 4 deletions rmf_task_sequence/test/unit/events/test_Call.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -76,16 +76,15 @@ SCENARIO("Test Call")
const auto travel_estimator = rmf_task::TravelEstimator(*parameters);

rmf_task::State expected_finish_state = initial_state;
REQUIRE(initial_state.time().has_value());
REQUIRE(expected_finish_state.time().has_value());
expected_finish_state.time(initial_state.time().value() + duration);

CHECK_MODEL(
*model,
initial_state,
*constraints,
travel_estimator,
expected_finish_state,
duration);
expected_finish_state);
}

WHEN("Testing header")
Expand All @@ -96,6 +95,6 @@ SCENARIO("Test Call")

CHECK(!header.category().empty());
CHECK(!header.detail().empty());
CHECK(header.original_duration_estimate() - duration < 100ms);
CHECK(header.original_duration_estimate() == duration);
}
}
99 changes: 99 additions & 0 deletions rmf_task_sequence/test/unit/events/test_GoToPlace.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,99 @@
/*
* Copyright (C) 2021 Open Source Robotics Foundation
*
* 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.
*
*/

#include <rmf_utils/catch.hpp>

#include <rmf_task_sequence/events/GoToPlace.hpp>

#include "../utils.hpp"

using namespace std::chrono_literals;

SCENARIO("Test GoToPlace")
{
using GoToPlace = rmf_task_sequence::events::GoToPlace;
using Goal = GoToPlace::Goal;

const auto goal = Goal{1};
auto description = GoToPlace::Description::make(goal);

const auto parameters = make_test_parameters();
const auto constraints = make_test_constraints();
const auto now = std::chrono::steady_clock::now();
rmf_task::State initial_state;
initial_state.waypoint(0)
.orientation(0.0)
.time(now)
.dedicated_charging_waypoint(0)
.battery_soc(1.0);

WHEN("Testing getters")
{
CHECK(description->destination().waypoint() == goal.waypoint());
CHECK_FALSE(description->destination().orientation());
CHECK(description->destination_name(*parameters) == "#1");
}

WHEN("Testing setters")
{
description->destination(Goal{2, 1.57});
CHECK(description->destination().waypoint() == 2);
REQUIRE(description->destination().orientation());
CHECK(abs(
*description->destination().orientation() - 1.57) < 1e-3);
CHECK(description->destination_name(*parameters) == "#2");
}

WHEN("Testing model and header")
{
// TODO(YV): Test model for cases where state is missing some parameters
const auto model = description->make_model(
initial_state,
*parameters);
const auto travel_estimator = rmf_task::TravelEstimator(*parameters);

rmf_task::State expected_finish_state = initial_state;
REQUIRE(expected_finish_state.time().has_value());
const auto duration_opt = estimate_travel_duration(
parameters->planner(),
initial_state,
goal);
REQUIRE(duration_opt.has_value());
expected_finish_state.waypoint(goal.waypoint())
.time(initial_state.time().value() + duration_opt.value());

if (goal.orientation())
expected_finish_state.orientation(*goal.orientation());
else
expected_finish_state.erase<rmf_task::State::CurrentOrientation>();

CHECK_MODEL(
*model,
initial_state,
*constraints,
travel_estimator,
expected_finish_state);

const auto header = description->generate_header(
initial_state,
*parameters);

CHECK(!header.category().empty());
CHECK(!header.detail().empty());
CHECK(header.original_duration_estimate() == duration_opt.value());
}
}
101 changes: 101 additions & 0 deletions rmf_task_sequence/test/unit/events/test_PerformAction.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,101 @@
/*
* Copyright (C) 2021 Open Source Robotics Foundation
*
* 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.
*
*/

#include <rmf_utils/catch.hpp>

#include <rmf_task_sequence/events/PerformAction.hpp>

#include "../utils.hpp"

using namespace std::chrono_literals;

SCENARIO("Test PerformAction")
{
using PerformAction = rmf_task_sequence::events::PerformAction;
const auto duration = 10s;
const std::string action_name = "test_action";
const rmf_traffic::agv::Planner::Goal finish_location{1};

auto description = PerformAction::Description::make(
action_name,
duration,
false,
finish_location);

const auto parameters = make_test_parameters();
const auto constraints = make_test_constraints();
const auto now = std::chrono::steady_clock::now();
rmf_task::State initial_state;
initial_state.waypoint(0)
.orientation(0.0)
.time(now)
.dedicated_charging_waypoint(0)
.battery_soc(1.0);

WHEN("Testing getters")
{
CHECK(description->action_name() == action_name);
CHECK(description->action_duration_estimate() == duration);
CHECK(description->use_tool_sink() == false);
REQUIRE(description->expected_finish_location().has_value());
CHECK(description->expected_finish_location().value().waypoint() == 1);
}

WHEN("Testing setters")
{
description->action_name("new_name");
CHECK(description->action_name() == "new_name");
description->action_duration_estimate(20s);
CHECK(description->action_duration_estimate() == 20s);
description->use_tool_sink(true);
CHECK(description->use_tool_sink() == true);
description->expected_finish_location(std::nullopt);
CHECK_FALSE(description->expected_finish_location().has_value());
}

WHEN("Testing model")
{
// TODO(YV): Test model for cases where state is missing some parameters
const auto model = description->make_model(
initial_state,
*parameters);
const auto travel_estimator = rmf_task::TravelEstimator(*parameters);

rmf_task::State expected_finish_state = initial_state;
REQUIRE(initial_state.time().has_value());
expected_finish_state.time(initial_state.time().value() + duration)
.waypoint(1);

CHECK_MODEL(
*model,
initial_state,
*constraints,
travel_estimator,
expected_finish_state);
}

WHEN("Testing header")
{
const auto header = description->generate_header(
initial_state,
*parameters);

CHECK(!header.category().empty());
CHECK(!header.detail().empty());
CHECK(header.original_duration_estimate() == duration);
}
}
94 changes: 94 additions & 0 deletions rmf_task_sequence/test/unit/events/test_Repeat.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,94 @@
/*
* Copyright (C) 2021 Open Source Robotics Foundation
*
* 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.
*
*/

#include <rmf_utils/catch.hpp>

#include <rmf_task_sequence/events/Repeat.hpp>
#include <rmf_task_sequence/events/WaitFor.hpp>

#include "../utils.hpp"

using namespace std::chrono_literals;

SCENARIO("Test Repeat")
{
using WaitFor = rmf_task_sequence::events::WaitFor;
using Repeat = rmf_task_sequence::events::Repeat;

const auto duration = 60s;
const auto event = WaitFor::Description::make(duration);
const std::size_t repetitions = 5;

auto description = Repeat::Description::make(event, repetitions);

const auto parameters = make_test_parameters();
const auto constraints = make_test_constraints();
const auto now = std::chrono::steady_clock::now();
rmf_task::State initial_state;
initial_state.waypoint(0)
.orientation(0.0)
.time(now)
.dedicated_charging_waypoint(0)
.battery_soc(1.0);

WHEN("Testing getters")
{
CHECK(description->event() == event);
CHECK(description->repetitions() == repetitions);
}

WHEN("Testing setters")
{
const auto new_event = WaitFor::Description::make(30s);
description->event(new_event);
// TODO(YV): More meaningful equality checks
CHECK(description->event() != event);

description->repetitions(10);
CHECK(description->repetitions() == 10);
}

WHEN("Testing model and header")
{
// TODO(YV): Test model for cases where state is missing some parameters
const auto model = description->make_model(
initial_state,
*parameters);
const auto travel_estimator = rmf_task::TravelEstimator(*parameters);

rmf_task::State expected_finish_state = initial_state;
REQUIRE(expected_finish_state.time().has_value());
const auto total_duration = repetitions * duration;
expected_finish_state
.time(initial_state.time().value() + total_duration);

CHECK_MODEL(
*model,
initial_state,
*constraints,
travel_estimator,
expected_finish_state);

const auto header = description->generate_header(
initial_state,
*parameters);

CHECK(!header.category().empty());
CHECK(!header.detail().empty());
CHECK(header.original_duration_estimate() == total_duration);
}
}
Loading

0 comments on commit 0be7812

Please sign in to comment.