Skip to content

Commit 2ac7bb2

Browse files
authored
Add tests for interface_configuration_type consistently (#899) (#1011)
1 parent 100c754 commit 2ac7bb2

22 files changed

+804
-111
lines changed

ackermann_steering_controller/test/test_ackermann_steering_controller.cpp

Lines changed: 15 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -46,41 +46,43 @@ TEST_F(AckermannSteeringControllerTest, all_parameters_set_configure_success)
4646
ASSERT_EQ(controller_->ackermann_params_.rear_wheel_track, rear_wheel_track_);
4747
}
4848

49-
TEST_F(AckermannSteeringControllerTest, check_exported_intefaces)
49+
TEST_F(AckermannSteeringControllerTest, check_exported_interfaces)
5050
{
5151
SetUpController();
5252

5353
ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS);
5454

55-
auto command_intefaces = controller_->command_interface_configuration();
56-
ASSERT_EQ(command_intefaces.names.size(), joint_command_values_.size());
55+
auto cmd_if_conf = controller_->command_interface_configuration();
56+
ASSERT_EQ(cmd_if_conf.names.size(), joint_command_values_.size());
5757
EXPECT_EQ(
58-
command_intefaces.names[CMD_TRACTION_RIGHT_WHEEL],
58+
cmd_if_conf.names[CMD_TRACTION_RIGHT_WHEEL],
5959
rear_wheels_names_[0] + "/" + traction_interface_name_);
6060
EXPECT_EQ(
61-
command_intefaces.names[CMD_TRACTION_LEFT_WHEEL],
61+
cmd_if_conf.names[CMD_TRACTION_LEFT_WHEEL],
6262
rear_wheels_names_[1] + "/" + traction_interface_name_);
6363
EXPECT_EQ(
64-
command_intefaces.names[CMD_STEER_RIGHT_WHEEL],
64+
cmd_if_conf.names[CMD_STEER_RIGHT_WHEEL],
6565
front_wheels_names_[0] + "/" + steering_interface_name_);
6666
EXPECT_EQ(
67-
command_intefaces.names[CMD_STEER_LEFT_WHEEL],
67+
cmd_if_conf.names[CMD_STEER_LEFT_WHEEL],
6868
front_wheels_names_[1] + "/" + steering_interface_name_);
69+
EXPECT_EQ(cmd_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);
6970

70-
auto state_intefaces = controller_->state_interface_configuration();
71-
ASSERT_EQ(state_intefaces.names.size(), joint_state_values_.size());
71+
auto state_if_conf = controller_->state_interface_configuration();
72+
ASSERT_EQ(state_if_conf.names.size(), joint_state_values_.size());
7273
EXPECT_EQ(
73-
state_intefaces.names[STATE_TRACTION_RIGHT_WHEEL],
74+
state_if_conf.names[STATE_TRACTION_RIGHT_WHEEL],
7475
controller_->rear_wheels_state_names_[0] + "/" + traction_interface_name_);
7576
EXPECT_EQ(
76-
state_intefaces.names[STATE_TRACTION_LEFT_WHEEL],
77+
state_if_conf.names[STATE_TRACTION_LEFT_WHEEL],
7778
controller_->rear_wheels_state_names_[1] + "/" + traction_interface_name_);
7879
EXPECT_EQ(
79-
state_intefaces.names[STATE_STEER_RIGHT_WHEEL],
80+
state_if_conf.names[STATE_STEER_RIGHT_WHEEL],
8081
controller_->front_wheels_state_names_[0] + "/" + steering_interface_name_);
8182
EXPECT_EQ(
82-
state_intefaces.names[STATE_STEER_LEFT_WHEEL],
83+
state_if_conf.names[STATE_STEER_LEFT_WHEEL],
8384
controller_->front_wheels_state_names_[1] + "/" + steering_interface_name_);
85+
EXPECT_EQ(state_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);
8486

8587
// check ref itfsTIME
8688
auto reference_interfaces = controller_->export_reference_interfaces();

ackermann_steering_controller/test/test_ackermann_steering_controller.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -62,7 +62,7 @@ class TestableAckermannSteeringController
6262
: public ackermann_steering_controller::AckermannSteeringController
6363
{
6464
FRIEND_TEST(AckermannSteeringControllerTest, all_parameters_set_configure_success);
65-
FRIEND_TEST(AckermannSteeringControllerTest, check_exported_intefaces);
65+
FRIEND_TEST(AckermannSteeringControllerTest, check_exported_interfaces);
6666
FRIEND_TEST(AckermannSteeringControllerTest, activate_success);
6767
FRIEND_TEST(AckermannSteeringControllerTest, update_success);
6868
FRIEND_TEST(AckermannSteeringControllerTest, deactivate_success);

ackermann_steering_controller/test/test_ackermann_steering_controller_preceeding.cpp

Lines changed: 15 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -48,41 +48,43 @@ TEST_F(AckermannSteeringControllerTest, all_parameters_set_configure_success)
4848
ASSERT_EQ(controller_->ackermann_params_.rear_wheel_track, rear_wheel_track_);
4949
}
5050

51-
TEST_F(AckermannSteeringControllerTest, check_exported_intefaces)
51+
TEST_F(AckermannSteeringControllerTest, check_exported_interfaces)
5252
{
5353
SetUpController();
5454

5555
ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS);
5656

57-
auto command_intefaces = controller_->command_interface_configuration();
58-
ASSERT_EQ(command_intefaces.names.size(), joint_command_values_.size());
57+
auto cmd_if_conf = controller_->command_interface_configuration();
58+
ASSERT_EQ(cmd_if_conf.names.size(), joint_command_values_.size());
5959
EXPECT_EQ(
60-
command_intefaces.names[CMD_TRACTION_RIGHT_WHEEL],
60+
cmd_if_conf.names[CMD_TRACTION_RIGHT_WHEEL],
6161
preceeding_prefix_ + "/" + rear_wheels_names_[0] + "/" + traction_interface_name_);
6262
EXPECT_EQ(
63-
command_intefaces.names[CMD_TRACTION_LEFT_WHEEL],
63+
cmd_if_conf.names[CMD_TRACTION_LEFT_WHEEL],
6464
preceeding_prefix_ + "/" + rear_wheels_names_[1] + "/" + traction_interface_name_);
6565
EXPECT_EQ(
66-
command_intefaces.names[CMD_STEER_RIGHT_WHEEL],
66+
cmd_if_conf.names[CMD_STEER_RIGHT_WHEEL],
6767
preceeding_prefix_ + "/" + front_wheels_names_[0] + "/" + steering_interface_name_);
6868
EXPECT_EQ(
69-
command_intefaces.names[CMD_STEER_LEFT_WHEEL],
69+
cmd_if_conf.names[CMD_STEER_LEFT_WHEEL],
7070
preceeding_prefix_ + "/" + front_wheels_names_[1] + "/" + steering_interface_name_);
71+
EXPECT_EQ(cmd_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);
7172

72-
auto state_intefaces = controller_->state_interface_configuration();
73-
ASSERT_EQ(state_intefaces.names.size(), joint_state_values_.size());
73+
auto state_if_conf = controller_->state_interface_configuration();
74+
ASSERT_EQ(state_if_conf.names.size(), joint_state_values_.size());
7475
EXPECT_EQ(
75-
state_intefaces.names[STATE_TRACTION_RIGHT_WHEEL],
76+
state_if_conf.names[STATE_TRACTION_RIGHT_WHEEL],
7677
controller_->rear_wheels_state_names_[0] + "/" + traction_interface_name_);
7778
EXPECT_EQ(
78-
state_intefaces.names[STATE_TRACTION_LEFT_WHEEL],
79+
state_if_conf.names[STATE_TRACTION_LEFT_WHEEL],
7980
controller_->rear_wheels_state_names_[1] + "/" + traction_interface_name_);
8081
EXPECT_EQ(
81-
state_intefaces.names[STATE_STEER_RIGHT_WHEEL],
82+
state_if_conf.names[STATE_STEER_RIGHT_WHEEL],
8283
controller_->front_wheels_state_names_[0] + "/" + steering_interface_name_);
8384
EXPECT_EQ(
84-
state_intefaces.names[STATE_STEER_LEFT_WHEEL],
85+
state_if_conf.names[STATE_STEER_LEFT_WHEEL],
8586
controller_->front_wheels_state_names_[1] + "/" + steering_interface_name_);
87+
EXPECT_EQ(state_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);
8688

8789
// check ref itfs
8890
auto reference_interfaces = controller_->export_reference_interfaces();

admittance_controller/test/test_admittance_controller.cpp

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -159,12 +159,15 @@ TEST_F(AdmittanceControllerTest, check_interfaces)
159159

160160
auto command_interfaces = controller_->command_interface_configuration();
161161
ASSERT_EQ(command_interfaces.names.size(), joint_command_values_.size());
162+
EXPECT_EQ(
163+
command_interfaces.type, controller_interface::interface_configuration_type::INDIVIDUAL);
162164

163165
ASSERT_EQ(
164166
controller_->command_interfaces_.size(), command_interface_types_.size() * joint_names_.size());
165167

166168
auto state_interfaces = controller_->state_interface_configuration();
167169
ASSERT_EQ(state_interfaces.names.size(), joint_state_values_.size() + fts_state_values_.size());
170+
EXPECT_EQ(state_interfaces.type, controller_interface::interface_configuration_type::INDIVIDUAL);
168171

169172
ASSERT_EQ(
170173
controller_->state_interfaces_.size(),

bicycle_steering_controller/test/test_bicycle_steering_controller.cpp

Lines changed: 11 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -44,29 +44,29 @@ TEST_F(BicycleSteeringControllerTest, all_parameters_set_configure_success)
4444
ASSERT_EQ(controller_->bicycle_params_.rear_wheel_radius, rear_wheels_radius_);
4545
}
4646

47-
TEST_F(BicycleSteeringControllerTest, check_exported_intefaces)
47+
TEST_F(BicycleSteeringControllerTest, check_exported_interfaces)
4848
{
4949
SetUpController();
5050

5151
ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS);
5252

53-
auto command_intefaces = controller_->command_interface_configuration();
54-
ASSERT_EQ(command_intefaces.names.size(), joint_command_values_.size());
53+
auto cmd_if_conf = controller_->command_interface_configuration();
54+
ASSERT_EQ(cmd_if_conf.names.size(), joint_command_values_.size());
5555
EXPECT_EQ(
56-
command_intefaces.names[CMD_TRACTION_WHEEL],
57-
rear_wheels_names_[0] + "/" + traction_interface_name_);
56+
cmd_if_conf.names[CMD_TRACTION_WHEEL], rear_wheels_names_[0] + "/" + traction_interface_name_);
5857
EXPECT_EQ(
59-
command_intefaces.names[CMD_STEER_WHEEL],
60-
front_wheels_names_[0] + "/" + steering_interface_name_);
58+
cmd_if_conf.names[CMD_STEER_WHEEL], front_wheels_names_[0] + "/" + steering_interface_name_);
59+
EXPECT_EQ(cmd_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);
6160

62-
auto state_intefaces = controller_->state_interface_configuration();
63-
ASSERT_EQ(state_intefaces.names.size(), joint_state_values_.size());
61+
auto state_if_conf = controller_->state_interface_configuration();
62+
ASSERT_EQ(state_if_conf.names.size(), joint_state_values_.size());
6463
EXPECT_EQ(
65-
state_intefaces.names[STATE_TRACTION_WHEEL],
64+
state_if_conf.names[STATE_TRACTION_WHEEL],
6665
controller_->rear_wheels_state_names_[0] + "/" + traction_interface_name_);
6766
EXPECT_EQ(
68-
state_intefaces.names[STATE_STEER_AXIS],
67+
state_if_conf.names[STATE_STEER_AXIS],
6968
controller_->front_wheels_state_names_[0] + "/" + steering_interface_name_);
69+
EXPECT_EQ(state_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);
7070

7171
// check ref itfsTIME
7272
auto reference_interfaces = controller_->export_reference_interfaces();

bicycle_steering_controller/test/test_bicycle_steering_controller.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -60,7 +60,7 @@ class TestableBicycleSteeringController
6060
: public bicycle_steering_controller::BicycleSteeringController
6161
{
6262
FRIEND_TEST(BicycleSteeringControllerTest, all_parameters_set_configure_success);
63-
FRIEND_TEST(BicycleSteeringControllerTest, check_exported_intefaces);
63+
FRIEND_TEST(BicycleSteeringControllerTest, check_exported_interfaces);
6464
FRIEND_TEST(BicycleSteeringControllerTest, activate_success);
6565
FRIEND_TEST(BicycleSteeringControllerTest, update_success);
6666
FRIEND_TEST(BicycleSteeringControllerTest, deactivate_success);

bicycle_steering_controller/test/test_bicycle_steering_controller_preceeding.cpp

Lines changed: 11 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -46,31 +46,31 @@ TEST_F(BicycleSteeringControllerTest, all_parameters_set_configure_success)
4646
ASSERT_EQ(controller_->bicycle_params_.rear_wheel_radius, rear_wheels_radius_);
4747
}
4848

49-
TEST_F(BicycleSteeringControllerTest, check_exported_intefaces)
49+
TEST_F(BicycleSteeringControllerTest, check_exported_interfaces)
5050
{
5151
SetUpController();
5252

5353
ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS);
5454

55-
auto command_intefaces = controller_->command_interface_configuration();
56-
ASSERT_EQ(command_intefaces.names.size(), joint_command_values_.size());
55+
auto cmd_if_conf = controller_->command_interface_configuration();
56+
ASSERT_EQ(cmd_if_conf.names.size(), joint_command_values_.size());
5757
EXPECT_EQ(
58-
command_intefaces.names[CMD_TRACTION_WHEEL],
58+
cmd_if_conf.names[CMD_TRACTION_WHEEL],
5959
preceeding_prefix_ + "/" + rear_wheels_names_[0] + "/" + traction_interface_name_);
60-
6160
EXPECT_EQ(
62-
command_intefaces.names[CMD_STEER_WHEEL],
61+
cmd_if_conf.names[CMD_STEER_WHEEL],
6362
preceeding_prefix_ + "/" + front_wheels_names_[0] + "/" + steering_interface_name_);
63+
EXPECT_EQ(cmd_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);
6464

65-
auto state_intefaces = controller_->state_interface_configuration();
66-
ASSERT_EQ(state_intefaces.names.size(), joint_state_values_.size());
67-
65+
auto state_if_conf = controller_->state_interface_configuration();
66+
ASSERT_EQ(state_if_conf.names.size(), joint_state_values_.size());
6867
EXPECT_EQ(
69-
state_intefaces.names[STATE_TRACTION_WHEEL],
68+
state_if_conf.names[STATE_TRACTION_WHEEL],
7069
controller_->rear_wheels_state_names_[0] + "/" + traction_interface_name_);
7170
EXPECT_EQ(
72-
state_intefaces.names[STATE_STEER_AXIS],
71+
state_if_conf.names[STATE_STEER_AXIS],
7372
controller_->front_wheels_state_names_[0] + "/" + steering_interface_name_);
73+
EXPECT_EQ(state_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);
7474

7575
// check ref itfs
7676
auto reference_interfaces = controller_->export_reference_interfaces();

diff_drive_controller/test/test_diff_drive_controller.cpp

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -247,12 +247,12 @@ TEST_F(TestDiffDriveController, configure_succeeds_when_wheels_are_specified)
247247

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

250-
ASSERT_THAT(
251-
controller_->state_interface_configuration().names,
252-
SizeIs(left_wheel_names.size() + right_wheel_names.size()));
253-
ASSERT_THAT(
254-
controller_->command_interface_configuration().names,
255-
SizeIs(left_wheel_names.size() + right_wheel_names.size()));
250+
auto state_if_conf = controller_->state_interface_configuration();
251+
ASSERT_THAT(state_if_conf.names, SizeIs(left_wheel_names.size() + right_wheel_names.size()));
252+
EXPECT_EQ(state_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);
253+
auto cmd_if_conf = controller_->command_interface_configuration();
254+
ASSERT_THAT(cmd_if_conf.names, SizeIs(left_wheel_names.size() + right_wheel_names.size()));
255+
EXPECT_EQ(cmd_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);
256256
}
257257

258258
TEST_F(TestDiffDriveController, configure_succeeds_tf_test_prefix_false_no_namespace)

force_torque_sensor_broadcaster/test/test_force_torque_sensor_broadcaster.cpp

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -162,8 +162,10 @@ TEST_F(ForceTorqueSensorBroadcasterTest, SensorName_Configure_Success)
162162
// check interface configuration
163163
auto cmd_if_conf = fts_broadcaster_->command_interface_configuration();
164164
ASSERT_THAT(cmd_if_conf.names, IsEmpty());
165+
ASSERT_EQ(cmd_if_conf.type, controller_interface::interface_configuration_type::NONE);
165166
auto state_if_conf = fts_broadcaster_->state_interface_configuration();
166167
ASSERT_THAT(state_if_conf.names, SizeIs(6lu));
168+
ASSERT_EQ(state_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);
167169
}
168170

169171
TEST_F(ForceTorqueSensorBroadcasterTest, InterfaceNames_Configure_Success)
@@ -196,17 +198,21 @@ TEST_F(ForceTorqueSensorBroadcasterTest, SensorName_ActivateDeactivate_Success)
196198
// check interface configuration
197199
auto cmd_if_conf = fts_broadcaster_->command_interface_configuration();
198200
ASSERT_THAT(cmd_if_conf.names, IsEmpty());
201+
ASSERT_EQ(cmd_if_conf.type, controller_interface::interface_configuration_type::NONE);
199202
auto state_if_conf = fts_broadcaster_->state_interface_configuration();
200203
ASSERT_THAT(state_if_conf.names, SizeIs(6lu));
204+
ASSERT_EQ(state_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);
201205

202206
// deactivate passed
203207
ASSERT_EQ(fts_broadcaster_->on_deactivate(rclcpp_lifecycle::State()), NODE_SUCCESS);
204208

205209
// check interface configuration
206210
cmd_if_conf = fts_broadcaster_->command_interface_configuration();
207211
ASSERT_THAT(cmd_if_conf.names, IsEmpty());
212+
ASSERT_EQ(cmd_if_conf.type, controller_interface::interface_configuration_type::NONE);
208213
state_if_conf = fts_broadcaster_->state_interface_configuration();
209214
ASSERT_THAT(state_if_conf.names, SizeIs(6lu)); // did not change
215+
ASSERT_EQ(state_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);
210216
}
211217

212218
TEST_F(ForceTorqueSensorBroadcasterTest, SensorName_Update_Success)

forward_command_controller/test/test_forward_command_controller.cpp

Lines changed: 9 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -137,6 +137,7 @@ TEST_F(ForwardCommandControllerTest, ConfigureParamsSuccess)
137137
ASSERT_THAT(cmd_if_conf.names, SizeIs(2lu));
138138
auto state_if_conf = controller_->state_interface_configuration();
139139
ASSERT_THAT(state_if_conf.names, IsEmpty());
140+
ASSERT_EQ(state_if_conf.type, controller_interface::interface_configuration_type::NONE);
140141
}
141142

142143
TEST_F(ForwardCommandControllerTest, ActivateWithWrongJointsNamesFails)
@@ -189,6 +190,7 @@ TEST_F(ForwardCommandControllerTest, ActivateSuccess)
189190
ASSERT_THAT(cmd_if_conf.names, SizeIs(joint_names_.size()));
190191
auto state_if_conf = controller_->state_interface_configuration();
191192
ASSERT_THAT(state_if_conf.names, IsEmpty());
193+
ASSERT_EQ(state_if_conf.type, controller_interface::interface_configuration_type::NONE);
192194

193195
ASSERT_EQ(
194196
controller_->on_activate(rclcpp_lifecycle::State()),
@@ -197,8 +199,10 @@ TEST_F(ForwardCommandControllerTest, ActivateSuccess)
197199
// check interface configuration
198200
cmd_if_conf = controller_->command_interface_configuration();
199201
ASSERT_THAT(cmd_if_conf.names, SizeIs(joint_names_.size()));
202+
EXPECT_EQ(cmd_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);
200203
state_if_conf = controller_->state_interface_configuration();
201204
ASSERT_THAT(state_if_conf.names, IsEmpty());
205+
ASSERT_EQ(state_if_conf.type, controller_interface::interface_configuration_type::NONE);
202206
}
203207

204208
TEST_F(ForwardCommandControllerTest, CommandSuccessTest)
@@ -352,15 +356,18 @@ TEST_F(ForwardCommandControllerTest, ActivateDeactivateCommandsResetSuccess)
352356
EXPECT_EQ(cmd_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);
353357
auto state_if_conf = controller_->state_interface_configuration();
354358
ASSERT_THAT(state_if_conf.names, IsEmpty());
359+
EXPECT_EQ(state_if_conf.type, controller_interface::interface_configuration_type::NONE);
355360

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

359364
// check interface configuration
360365
cmd_if_conf = controller_->command_interface_configuration();
361366
ASSERT_THAT(cmd_if_conf.names, SizeIs(joint_names_.size()));
367+
EXPECT_EQ(cmd_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);
362368
state_if_conf = controller_->state_interface_configuration();
363369
ASSERT_THAT(state_if_conf.names, IsEmpty());
370+
EXPECT_EQ(state_if_conf.type, controller_interface::interface_configuration_type::NONE);
364371

365372
auto command_msg = std::make_shared<std_msgs::msg::Float64MultiArray>();
366373
command_msg->data = {10.0, 20.0, 30.0};
@@ -383,8 +390,10 @@ TEST_F(ForwardCommandControllerTest, ActivateDeactivateCommandsResetSuccess)
383390
// check interface configuration
384391
cmd_if_conf = controller_->command_interface_configuration();
385392
ASSERT_THAT(cmd_if_conf.names, SizeIs(joint_names_.size())); // did not change
393+
EXPECT_EQ(cmd_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);
386394
state_if_conf = controller_->state_interface_configuration();
387395
ASSERT_THAT(state_if_conf.names, IsEmpty());
396+
EXPECT_EQ(state_if_conf.type, controller_interface::interface_configuration_type::NONE);
388397

389398
// command ptr should be reset (nullptr) after deactivation - same check as in `update`
390399
ASSERT_FALSE(

0 commit comments

Comments
 (0)