Skip to content

Commit 1f93eb1

Browse files
christophfroehlichbmagyar
authored andcommitted
Increase test coverage of interface configuration getters (backport #856)
1 parent 854810c commit 1f93eb1

File tree

10 files changed

+228
-7
lines changed

10 files changed

+228
-7
lines changed

force_torque_sensor_broadcaster/test/test_force_torque_sensor_broadcaster.cpp

Lines changed: 24 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -32,6 +32,8 @@
3232
#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"
3333

3434
using hardware_interface::LoanedStateInterface;
35+
using testing::IsEmpty;
36+
using testing::SizeIs;
3537

3638
namespace
3739
{
@@ -157,6 +159,12 @@ TEST_F(ForceTorqueSensorBroadcasterTest, SensorName_Configure_Success)
157159

158160
// configure passed
159161
ASSERT_EQ(fts_broadcaster_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS);
162+
163+
// check interface configuration
164+
auto cmd_if_conf = fts_broadcaster_->command_interface_configuration();
165+
ASSERT_THAT(cmd_if_conf.names, IsEmpty());
166+
auto state_if_conf = fts_broadcaster_->state_interface_configuration();
167+
ASSERT_THAT(state_if_conf.names, SizeIs(6lu));
160168
}
161169

162170
TEST_F(ForceTorqueSensorBroadcasterTest, InterfaceNames_Configure_Success)
@@ -175,7 +183,7 @@ TEST_F(ForceTorqueSensorBroadcasterTest, InterfaceNames_Configure_Success)
175183
ASSERT_EQ(fts_broadcaster_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS);
176184
}
177185

178-
TEST_F(ForceTorqueSensorBroadcasterTest, SensorName_Activate_Success)
186+
TEST_F(ForceTorqueSensorBroadcasterTest, SensorName_ActivateDeactivate_Success)
179187
{
180188
SetUpFTSBroadcaster();
181189

@@ -186,6 +194,21 @@ TEST_F(ForceTorqueSensorBroadcasterTest, SensorName_Activate_Success)
186194
// configure and activate success
187195
ASSERT_EQ(fts_broadcaster_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS);
188196
ASSERT_EQ(fts_broadcaster_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS);
197+
198+
// check interface configuration
199+
auto cmd_if_conf = fts_broadcaster_->command_interface_configuration();
200+
ASSERT_THAT(cmd_if_conf.names, IsEmpty());
201+
auto state_if_conf = fts_broadcaster_->state_interface_configuration();
202+
ASSERT_THAT(state_if_conf.names, SizeIs(6lu));
203+
204+
// deactivate passed
205+
ASSERT_EQ(fts_broadcaster_->on_deactivate(rclcpp_lifecycle::State()), NODE_SUCCESS);
206+
207+
// check interface configuration
208+
cmd_if_conf = fts_broadcaster_->command_interface_configuration();
209+
ASSERT_THAT(cmd_if_conf.names, IsEmpty());
210+
state_if_conf = fts_broadcaster_->state_interface_configuration();
211+
ASSERT_THAT(state_if_conf.names, SizeIs(6lu)); // did not change
189212
}
190213

191214
TEST_F(ForceTorqueSensorBroadcasterTest, SensorName_Update_Success)

force_torque_sensor_broadcaster/test/test_force_torque_sensor_broadcaster.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -36,7 +36,7 @@ class FriendForceTorqueSensorBroadcaster
3636
FRIEND_TEST(ForceTorqueSensorBroadcasterTest, SensorNameParameterIsEmpty);
3737
FRIEND_TEST(ForceTorqueSensorBroadcasterTest, InterfaceNameParameterIsEmpty);
3838

39-
FRIEND_TEST(ForceTorqueSensorBroadcasterTest, ActivateSuccess);
39+
FRIEND_TEST(ForceTorqueSensorBroadcasterTest, SensorName_ActivateDeactivate_Success);
4040
FRIEND_TEST(ForceTorqueSensorBroadcasterTest, UpdateTest);
4141
FRIEND_TEST(ForceTorqueSensorBroadcasterTest, SensorStatePublishTest);
4242
};

forward_command_controller/test/test_forward_command_controller.cpp

Lines changed: 42 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -34,6 +34,8 @@
3434
#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"
3535

3636
using hardware_interface::LoanedCommandInterface;
37+
using testing::IsEmpty;
38+
using testing::SizeIs;
3739

3840
namespace
3941
{
@@ -128,6 +130,13 @@ TEST_F(ForwardCommandControllerTest, ConfigureParamsSuccess)
128130
ASSERT_EQ(
129131
controller_->on_configure(rclcpp_lifecycle::State()),
130132
controller_interface::CallbackReturn::SUCCESS);
133+
134+
// check interface configuration
135+
auto cmd_if_conf = controller_->command_interface_configuration();
136+
EXPECT_EQ(cmd_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);
137+
ASSERT_THAT(cmd_if_conf.names, SizeIs(2lu));
138+
auto state_if_conf = controller_->state_interface_configuration();
139+
ASSERT_THAT(state_if_conf.names, IsEmpty());
131140
}
132141

133142
TEST_F(ForwardCommandControllerTest, ActivateWithWrongJointsNamesFails)
@@ -173,9 +182,23 @@ TEST_F(ForwardCommandControllerTest, ActivateSuccess)
173182
ASSERT_EQ(
174183
controller_->on_configure(rclcpp_lifecycle::State()),
175184
controller_interface::CallbackReturn::SUCCESS);
185+
186+
// check interface configuration
187+
auto cmd_if_conf = controller_->command_interface_configuration();
188+
EXPECT_EQ(cmd_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);
189+
ASSERT_THAT(cmd_if_conf.names, SizeIs(joint_names_.size()));
190+
auto state_if_conf = controller_->state_interface_configuration();
191+
ASSERT_THAT(state_if_conf.names, IsEmpty());
192+
176193
ASSERT_EQ(
177194
controller_->on_activate(rclcpp_lifecycle::State()),
178195
controller_interface::CallbackReturn::SUCCESS);
196+
197+
// check interface configuration
198+
cmd_if_conf = controller_->command_interface_configuration();
199+
ASSERT_THAT(cmd_if_conf.names, SizeIs(joint_names_.size()));
200+
state_if_conf = controller_->state_interface_configuration();
201+
ASSERT_THAT(state_if_conf.names, IsEmpty());
179202
}
180203

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

349+
// check interface configuration
350+
auto cmd_if_conf = controller_->command_interface_configuration();
351+
ASSERT_THAT(cmd_if_conf.names, SizeIs(joint_names_.size()));
352+
EXPECT_EQ(cmd_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);
353+
auto state_if_conf = controller_->state_interface_configuration();
354+
ASSERT_THAT(state_if_conf.names, IsEmpty());
355+
326356
node_state = controller_->get_node()->activate();
327357
ASSERT_EQ(node_state.id(), lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE);
328358

359+
// check interface configuration
360+
cmd_if_conf = controller_->command_interface_configuration();
361+
ASSERT_THAT(cmd_if_conf.names, SizeIs(joint_names_.size()));
362+
state_if_conf = controller_->state_interface_configuration();
363+
ASSERT_THAT(state_if_conf.names, IsEmpty());
364+
329365
auto command_msg = std::make_shared<std_msgs::msg::Float64MultiArray>();
330366
command_msg->data = {10.0, 20.0, 30.0};
331367

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

383+
// check interface configuration
384+
cmd_if_conf = controller_->command_interface_configuration();
385+
ASSERT_THAT(cmd_if_conf.names, SizeIs(joint_names_.size())); // did not change
386+
state_if_conf = controller_->state_interface_configuration();
387+
ASSERT_THAT(state_if_conf.names, IsEmpty());
388+
347389
// command ptr should be reset (nullptr) after deactivation - same check as in `update`
348390
ASSERT_FALSE(
349391
controller_->rt_command_ptr_.readFromNonRT() &&

forward_command_controller/test/test_multi_interface_forward_command_controller.cpp

Lines changed: 23 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -36,6 +36,8 @@
3636
#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"
3737

3838
using hardware_interface::LoanedCommandInterface;
39+
using testing::IsEmpty;
40+
using testing::SizeIs;
3941

4042
namespace
4143
{
@@ -148,6 +150,13 @@ TEST_F(MultiInterfaceForwardCommandControllerTest, ConfigureParamsSuccess)
148150
ASSERT_EQ(
149151
controller_->on_configure(rclcpp_lifecycle::State()),
150152
controller_interface::CallbackReturn::SUCCESS);
153+
154+
// check interface configuration
155+
auto cmd_if_conf = controller_->command_interface_configuration();
156+
ASSERT_THAT(cmd_if_conf.names, SizeIs(3lu));
157+
EXPECT_EQ(cmd_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);
158+
auto state_if_conf = controller_->state_interface_configuration();
159+
ASSERT_THAT(state_if_conf.names, IsEmpty());
151160
}
152161

153162
TEST_F(MultiInterfaceForwardCommandControllerTest, ActivateWithWrongJointsNamesFails)
@@ -282,6 +291,13 @@ TEST_F(MultiInterfaceForwardCommandControllerTest, ActivateDeactivateCommandsRes
282291
{
283292
SetUpController(true);
284293

294+
// check interface configuration
295+
auto cmd_if_conf = controller_->command_interface_configuration();
296+
ASSERT_THAT(cmd_if_conf.names, SizeIs(3lu));
297+
EXPECT_EQ(cmd_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);
298+
auto state_if_conf = controller_->state_interface_configuration();
299+
ASSERT_THAT(state_if_conf.names, IsEmpty());
300+
285301
// send command
286302
auto command_ptr = std::make_shared<forward_command_controller::CmdType>();
287303
command_ptr->data = {10.0, 20.0, 30.0};
@@ -300,6 +316,13 @@ TEST_F(MultiInterfaceForwardCommandControllerTest, ActivateDeactivateCommandsRes
300316
auto node_state = controller_->get_node()->deactivate();
301317
ASSERT_EQ(node_state.id(), lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE);
302318

319+
// check interface configuration
320+
cmd_if_conf = controller_->command_interface_configuration();
321+
ASSERT_THAT(cmd_if_conf.names, SizeIs(3lu));
322+
EXPECT_EQ(cmd_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);
323+
state_if_conf = controller_->state_interface_configuration();
324+
ASSERT_THAT(state_if_conf.names, IsEmpty());
325+
303326
// command ptr should be reset (nullptr) after deactivation - same check as in `update`
304327
ASSERT_FALSE(
305328
controller_->rt_command_ptr_.readFromNonRT() &&

gripper_controllers/test/test_gripper_controllers.cpp

Lines changed: 12 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -31,6 +31,8 @@ using hardware_interface::LoanedCommandInterface;
3131
using hardware_interface::LoanedStateInterface;
3232
using GripperCommandAction = control_msgs::action::GripperCommand;
3333
using GoalHandle = rclcpp_action::ServerGoalHandle<GripperCommandAction>;
34+
using testing::SizeIs;
35+
using testing::UnorderedElementsAre;
3436

3537
template <typename T>
3638
void GripperControllerTest<T>::SetUpTestCase()
@@ -108,6 +110,16 @@ TYPED_TEST(GripperControllerTest, ConfigureParamsSuccess)
108110
ASSERT_EQ(
109111
this->controller_->on_configure(rclcpp_lifecycle::State()),
110112
controller_interface::CallbackReturn::SUCCESS);
113+
114+
// check interface configuration
115+
auto cmd_if_conf = this->controller_->command_interface_configuration();
116+
ASSERT_THAT(cmd_if_conf.names, SizeIs(1lu));
117+
ASSERT_THAT(cmd_if_conf.names, UnorderedElementsAre(std::string("joint_1/") + TypeParam::value));
118+
EXPECT_EQ(cmd_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);
119+
auto state_if_conf = this->controller_->state_interface_configuration();
120+
ASSERT_THAT(state_if_conf.names, SizeIs(2lu));
121+
ASSERT_THAT(state_if_conf.names, UnorderedElementsAre("joint_1/position", "joint_1/velocity"));
122+
EXPECT_EQ(state_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);
111123
}
112124

113125
TYPED_TEST(GripperControllerTest, ActivateWithWrongJointsNamesFails)

imu_sensor_broadcaster/test/test_imu_sensor_broadcaster.cpp

Lines changed: 23 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -32,6 +32,8 @@
3232
#include "sensor_msgs/msg/imu.hpp"
3333

3434
using hardware_interface::LoanedStateInterface;
35+
using testing::IsEmpty;
36+
using testing::SizeIs;
3537

3638
namespace
3739
{
@@ -114,6 +116,12 @@ TEST_F(IMUSensorBroadcasterTest, SensorName_Configure_Success)
114116

115117
// configure passed
116118
ASSERT_EQ(imu_broadcaster_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS);
119+
120+
// check interface configuration
121+
auto cmd_if_conf = imu_broadcaster_->command_interface_configuration();
122+
ASSERT_THAT(cmd_if_conf.names, IsEmpty());
123+
auto state_if_conf = imu_broadcaster_->state_interface_configuration();
124+
ASSERT_THAT(state_if_conf.names, SizeIs(10lu));
117125
}
118126

119127
TEST_F(IMUSensorBroadcasterTest, SensorName_Activate_Success)
@@ -127,6 +135,21 @@ TEST_F(IMUSensorBroadcasterTest, SensorName_Activate_Success)
127135
// configure and activate success
128136
ASSERT_EQ(imu_broadcaster_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS);
129137
ASSERT_EQ(imu_broadcaster_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS);
138+
139+
// check interface configuration
140+
auto cmd_if_conf = imu_broadcaster_->command_interface_configuration();
141+
ASSERT_THAT(cmd_if_conf.names, IsEmpty());
142+
auto state_if_conf = imu_broadcaster_->state_interface_configuration();
143+
ASSERT_THAT(state_if_conf.names, SizeIs(10lu));
144+
145+
// deactivate passed
146+
ASSERT_EQ(imu_broadcaster_->on_deactivate(rclcpp_lifecycle::State()), NODE_SUCCESS);
147+
148+
// check interface configuration
149+
cmd_if_conf = imu_broadcaster_->command_interface_configuration();
150+
ASSERT_THAT(cmd_if_conf.names, IsEmpty());
151+
state_if_conf = imu_broadcaster_->state_interface_configuration();
152+
ASSERT_THAT(state_if_conf.names, SizeIs(10lu)); // did not change
130153
}
131154

132155
TEST_F(IMUSensorBroadcasterTest, SensorName_Update_Success)

0 commit comments

Comments
 (0)