Skip to content

Commit

Permalink
feat: add tests
Browse files Browse the repository at this point in the history
  • Loading branch information
domire8 committed Dec 3, 2024
1 parent dcf91ee commit 79aea72
Show file tree
Hide file tree
Showing 6 changed files with 96 additions and 0 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -52,6 +52,32 @@ class MinimalCartesianInput : public ComponentT {
std::promise<void> received_;
};

template<class ComponentT>
class ExceptionCartesianInput : public ComponentT {
public:
ExceptionCartesianInput(const rclcpp::NodeOptions& node_options, const std::string& topic)
: ComponentT(node_options, "exception_cartesian_input"), thrown_(false) {
this->received_future = this->received_.get_future();
this->template add_input<modulo_core::EncodedState>(
"cartesian_state",
[this](const std::shared_ptr<modulo_core::EncodedState>) {
if (!this->thrown_) {
this->thrown_ = true;
throw std::runtime_error("Error");
} else {
this->received_.set_value();
}
},
topic);
}

std::shared_future<void> received_future;

private:
bool thrown_;
std::promise<void> received_;
};

template<class ComponentT>
class MinimalTwistOutput : public ComponentT {
public:
Expand Down
11 changes: 11 additions & 0 deletions source/modulo_components/test/cpp/test_component_communication.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,17 @@ TEST_F(ComponentCommunicationTest, InputOutput) {
EXPECT_THROW(output_node->publish(), modulo_core::exceptions::CoreException);
}

TEST_F(ComponentCommunicationTest, ExceptionInputOutput) {
auto cartesian_state = state_representation::CartesianState::Random("test");
auto input_node = std::make_shared<ExceptionCartesianInput<Component>>(rclcpp::NodeOptions(), "/topic");
auto output_node =
std::make_shared<MinimalCartesianOutput<Component>>(rclcpp::NodeOptions(), "/topic", cartesian_state, true);
this->exec_->add_node(input_node);
this->exec_->add_node(output_node);
auto return_code = this->exec_->spin_until_future_complete(input_node->received_future, 500ms);
ASSERT_EQ(return_code, rclcpp::FutureReturnCode::SUCCESS);
}

TEST_F(ComponentCommunicationTest, InputOutputManual) {
auto cartesian_state = state_representation::CartesianState::Random("test");
auto input_node = std::make_shared<MinimalCartesianInput<Component>>(rclcpp::NodeOptions(), "/topic");
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,17 @@ TEST_F(LifecycleComponentCommunicationTest, InputOutput) {
EXPECT_THROW(output_node->publish(), modulo_core::exceptions::CoreException);
}

TEST_F(LifecycleComponentCommunicationTest, ExceptionInputOutput) {
auto cartesian_state = state_representation::CartesianState::Random("test");
auto input_node = std::make_shared<ExceptionCartesianInput<LifecycleComponent>>(rclcpp::NodeOptions(), "/topic");
auto output_node = std::make_shared<MinimalCartesianOutput<LifecycleComponent>>(
rclcpp::NodeOptions(), "/topic", cartesian_state, true);
add_configure_activate(this->exec_, input_node);
add_configure_activate(this->exec_, output_node);
auto return_code = this->exec_->spin_until_future_complete(input_node->received_future, 500ms);
ASSERT_EQ(return_code, rclcpp::FutureReturnCode::SUCCESS);
}

TEST_F(LifecycleComponentCommunicationTest, InputOutputManual) {
auto cartesian_state = state_representation::CartesianState::Random("test");
auto input_node = std::make_shared<MinimalCartesianInput<LifecycleComponent>>(rclcpp::NodeOptions(), "/topic");
Expand Down
21 changes: 21 additions & 0 deletions source/modulo_components/test/python/conftest.py
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
import clproto
import pytest
import state_representation as sr
from types import MethodType
from modulo_components.component import Component
from modulo_core import EncodedState
from rclpy.task import Future
Expand Down Expand Up @@ -122,6 +123,26 @@ def _make_minimal_cartesian_input(component_type, topic):
yield _make_minimal_cartesian_input(request.param[0], request.param[1])


@pytest.fixture
def exception_cartesian_input(request):
def _make_exception_cartesian_input(component_type, topic):
def callback(self):
if not self.thrown:
self.thrown = True
raise RuntimeError()
else:
self.received_future.set_result(True)

component = component_type("exception_cartesian_input")
component.received_future = Future()
component.thrown = False
component.callback = MethodType(callback, component)
component.add_input("cartesian_pose", lambda msg: component.callback(), EncodedState, topic)
return component

yield _make_exception_cartesian_input(request.param[0], request.param[1])


@pytest.fixture
def minimal_sensor_input(request):
def _make_minimal_sensor_input(component_type, topic):
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,15 @@ def test_input_output(ros_exec, random_pose, minimal_cartesian_output, minimal_c
minimal_cartesian_output.publish()


@pytest.mark.parametrize("exception_cartesian_input", [[Component, "/topic"]], indirect=True)
@pytest.mark.parametrize("minimal_cartesian_output", [[Component, "/topic", True]], indirect=True)
def test_exception_input_output(ros_exec, minimal_cartesian_output, exception_cartesian_input):
ros_exec.add_node(exception_cartesian_input)
ros_exec.add_node(minimal_cartesian_output)
ros_exec.spin_until_future_complete(exception_cartesian_input.received_future, timeout_sec=0.5)
assert exception_cartesian_input.received_future.done() and exception_cartesian_input.received_future.result()


@pytest.mark.parametrize("minimal_cartesian_input", [[Component, "/topic"]], indirect=True)
@pytest.mark.parametrize("minimal_cartesian_output", [[Component, "/topic", False]], indirect=True)
def test_input_output_manual(ros_exec, random_pose, minimal_cartesian_output, minimal_cartesian_input):
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,24 @@ def test_input_output(ros_exec, make_lifecycle_change_client, random_pose, minim
minimal_cartesian_output.publish()


@pytest.mark.parametrize("exception_cartesian_input", [[LifecycleComponent, "/topic"]], indirect=True)
@pytest.mark.parametrize("minimal_cartesian_output", [[LifecycleComponent, "/topic", True]], indirect=True)
def test_exception_input_output(
ros_exec, make_lifecycle_change_client, minimal_cartesian_output, exception_cartesian_input):
input_change_client = make_lifecycle_change_client("exception_cartesian_input")
output_change_client = make_lifecycle_change_client("minimal_cartesian_output")
ros_exec.add_node(input_change_client)
ros_exec.add_node(output_change_client)
ros_exec.add_node(exception_cartesian_input)
ros_exec.add_node(minimal_cartesian_output)
input_change_client.configure(ros_exec)
output_change_client.configure(ros_exec)
input_change_client.activate(ros_exec)
output_change_client.activate(ros_exec)
ros_exec.spin_until_future_complete(exception_cartesian_input.received_future, timeout_sec=0.5)
assert exception_cartesian_input.received_future.done() and exception_cartesian_input.received_future.result()


@pytest.mark.parametrize("minimal_cartesian_input", [[LifecycleComponent, "/topic"]], indirect=True)
@pytest.mark.parametrize("minimal_cartesian_output", [[LifecycleComponent, "/topic", False]], indirect=True)
def test_input_output_manual(ros_exec, make_lifecycle_change_client, random_pose, minimal_cartesian_output,
Expand Down

0 comments on commit 79aea72

Please sign in to comment.