Skip to content

Commit

Permalink
Add further test conditions
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich committed Nov 24, 2023
1 parent 0cf768c commit 618e41f
Show file tree
Hide file tree
Showing 4 changed files with 92 additions and 0 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,8 @@
#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"

using hardware_interface::LoanedCommandInterface;
using testing::IsEmpty;
using testing::SizeIs;

namespace
{
Expand Down Expand Up @@ -128,6 +130,13 @@ TEST_F(ForwardCommandControllerTest, ConfigureParamsSuccess)
ASSERT_EQ(
controller_->on_configure(rclcpp_lifecycle::State()),
controller_interface::CallbackReturn::SUCCESS);

// check interface configuration
auto cmd_if_conf = controller_->command_interface_configuration();
EXPECT_EQ(cmd_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);
ASSERT_THAT(cmd_if_conf.names, SizeIs(2lu));
auto state_if_conf = controller_->state_interface_configuration();
ASSERT_THAT(state_if_conf.names, IsEmpty());
}

TEST_F(ForwardCommandControllerTest, ActivateWithWrongJointsNamesFails)
Expand Down Expand Up @@ -173,9 +182,23 @@ TEST_F(ForwardCommandControllerTest, ActivateSuccess)
ASSERT_EQ(
controller_->on_configure(rclcpp_lifecycle::State()),
controller_interface::CallbackReturn::SUCCESS);

// check interface configuration
auto cmd_if_conf = controller_->command_interface_configuration();
EXPECT_EQ(cmd_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);
ASSERT_THAT(cmd_if_conf.names, SizeIs(3lu));
auto state_if_conf = controller_->state_interface_configuration();
ASSERT_THAT(state_if_conf.names, IsEmpty());

ASSERT_EQ(
controller_->on_activate(rclcpp_lifecycle::State()),
controller_interface::CallbackReturn::SUCCESS);

// check interface configuration
cmd_if_conf = controller_->command_interface_configuration();
ASSERT_THAT(cmd_if_conf.names, SizeIs(3lu));
state_if_conf = controller_->state_interface_configuration();
ASSERT_THAT(state_if_conf.names, IsEmpty());
}

TEST_F(ForwardCommandControllerTest, CommandSuccessTest)
Expand Down Expand Up @@ -323,9 +346,22 @@ TEST_F(ForwardCommandControllerTest, ActivateDeactivateCommandsResetSuccess)
auto node_state = controller_->configure();
ASSERT_EQ(node_state.id(), lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE);

// check interface configuration
auto cmd_if_conf = controller_->command_interface_configuration();
ASSERT_THAT(cmd_if_conf.names, SizeIs(3lu));
EXPECT_EQ(cmd_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);
auto state_if_conf = controller_->state_interface_configuration();
ASSERT_THAT(state_if_conf.names, IsEmpty());

node_state = controller_->get_node()->activate();
ASSERT_EQ(node_state.id(), lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE);

// check interface configuration
cmd_if_conf = controller_->command_interface_configuration();
ASSERT_THAT(cmd_if_conf.names, SizeIs(3lu));
state_if_conf = controller_->state_interface_configuration();
ASSERT_THAT(state_if_conf.names, IsEmpty());

auto command_msg = std::make_shared<std_msgs::msg::Float64MultiArray>();
command_msg->data = {10.0, 20.0, 30.0};

Expand All @@ -344,6 +380,12 @@ TEST_F(ForwardCommandControllerTest, ActivateDeactivateCommandsResetSuccess)
node_state = controller_->get_node()->deactivate();
ASSERT_EQ(node_state.id(), lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE);

// check interface configuration
cmd_if_conf = controller_->command_interface_configuration();
ASSERT_THAT(cmd_if_conf.names, SizeIs(3lu)); // did not change
state_if_conf = controller_->state_interface_configuration();
ASSERT_THAT(state_if_conf.names, IsEmpty());

// command ptr should be reset (nullptr) after deactivation - same check as in `update`
ASSERT_FALSE(
controller_->rt_command_ptr_.readFromNonRT() &&
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,8 @@
#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"

using hardware_interface::LoanedCommandInterface;
using testing::IsEmpty;
using testing::SizeIs;

namespace
{
Expand Down Expand Up @@ -148,6 +150,13 @@ TEST_F(MultiInterfaceForwardCommandControllerTest, ConfigureParamsSuccess)
ASSERT_EQ(
controller_->on_configure(rclcpp_lifecycle::State()),
controller_interface::CallbackReturn::SUCCESS);

// check interface configuration
auto cmd_if_conf = controller_->command_interface_configuration();
ASSERT_THAT(cmd_if_conf.names, SizeIs(3lu));
EXPECT_EQ(cmd_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);
auto state_if_conf = controller_->state_interface_configuration();
ASSERT_THAT(state_if_conf.names, IsEmpty());
}

TEST_F(MultiInterfaceForwardCommandControllerTest, ActivateWithWrongJointsNamesFails)
Expand Down Expand Up @@ -282,6 +291,13 @@ TEST_F(MultiInterfaceForwardCommandControllerTest, ActivateDeactivateCommandsRes
{
SetUpController(true);

// check interface configuration
auto cmd_if_conf = controller_->command_interface_configuration();
ASSERT_THAT(cmd_if_conf.names, SizeIs(3lu));
EXPECT_EQ(cmd_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);
auto state_if_conf = controller_->state_interface_configuration();
ASSERT_THAT(state_if_conf.names, IsEmpty());

// send command
auto command_ptr = std::make_shared<forward_command_controller::CmdType>();
command_ptr->data = {10.0, 20.0, 30.0};
Expand All @@ -300,6 +316,13 @@ TEST_F(MultiInterfaceForwardCommandControllerTest, ActivateDeactivateCommandsRes
auto node_state = controller_->get_node()->deactivate();
ASSERT_EQ(node_state.id(), lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE);

// check interface configuration
cmd_if_conf = controller_->command_interface_configuration();
ASSERT_THAT(cmd_if_conf.names, SizeIs(3lu));
EXPECT_EQ(cmd_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);
state_if_conf = controller_->state_interface_configuration();
ASSERT_THAT(state_if_conf.names, IsEmpty());

// command ptr should be reset (nullptr) after deactivation - same check as in `update`
ASSERT_FALSE(
controller_->rt_command_ptr_.readFromNonRT() &&
Expand Down
12 changes: 12 additions & 0 deletions gripper_controllers/test/test_gripper_controllers.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,8 @@ using hardware_interface::LoanedCommandInterface;
using hardware_interface::LoanedStateInterface;
using GripperCommandAction = control_msgs::action::GripperCommand;
using GoalHandle = rclcpp_action::ServerGoalHandle<GripperCommandAction>;
using testing::SizeIs;
using testing::UnorderedElementsAre;

template <typename T>
void GripperControllerTest<T>::SetUpTestCase()
Expand Down Expand Up @@ -108,6 +110,16 @@ TYPED_TEST(GripperControllerTest, ConfigureParamsSuccess)
ASSERT_EQ(
this->controller_->on_configure(rclcpp_lifecycle::State()),
controller_interface::CallbackReturn::SUCCESS);

// check interface configuration
auto cmd_if_conf = this->controller_->command_interface_configuration();
ASSERT_THAT(cmd_if_conf.names, SizeIs(1lu));
ASSERT_THAT(cmd_if_conf.names, UnorderedElementsAre(std::string("joint_1/") + TypeParam::value));
EXPECT_EQ(cmd_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);
auto state_if_conf = this->controller_->state_interface_configuration();
ASSERT_THAT(state_if_conf.names, SizeIs(2lu));
ASSERT_THAT(state_if_conf.names, UnorderedElementsAre("joint_1/position", "joint_1/velocity"));
EXPECT_EQ(state_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);
}

TYPED_TEST(GripperControllerTest, ActivateWithWrongJointsNamesFails)
Expand Down
15 changes: 15 additions & 0 deletions tricycle_controller/test/test_tricycle_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,7 @@ using hardware_interface::LoanedCommandInterface;
using hardware_interface::LoanedStateInterface;
using lifecycle_msgs::msg::State;
using testing::SizeIs;
using testing::UnorderedElementsAre;

class TestableTricycleController : public tricycle_controller::TricycleController
{
Expand Down Expand Up @@ -209,6 +210,20 @@ TEST_F(TestTricycleController, configure_succeeds_when_joints_are_specified)
rclcpp::Parameter("steering_joint_name", rclcpp::ParameterValue(steering_joint_name)));

ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), CallbackReturn::SUCCESS);

// check interface configuration
auto cmd_if_conf = controller_->command_interface_configuration();
ASSERT_THAT(cmd_if_conf.names, SizeIs(2lu));
ASSERT_THAT(
cmd_if_conf.names,
UnorderedElementsAre(traction_joint_name + "/velocity", steering_joint_name + "/position"));
EXPECT_EQ(cmd_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);
auto state_if_conf = controller_->state_interface_configuration();
ASSERT_THAT(state_if_conf.names, SizeIs(2lu));
ASSERT_THAT(
state_if_conf.names,
UnorderedElementsAre(traction_joint_name + "/velocity", steering_joint_name + "/position"));
EXPECT_EQ(state_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);
}

TEST_F(TestTricycleController, activate_fails_without_resources_assigned)
Expand Down

0 comments on commit 618e41f

Please sign in to comment.