diff --git a/hardware_interface/test/test_resource_manager_prepare_perform_switch.cpp b/hardware_interface/test/test_resource_manager_prepare_perform_switch.cpp index 801eacb445..0e93e990e6 100644 --- a/hardware_interface/test/test_resource_manager_prepare_perform_switch.cpp +++ b/hardware_interface/test/test_resource_manager_prepare_perform_switch.cpp @@ -367,21 +367,21 @@ TEST_F( EXPECT_EQ(claimed_actuator_position_state_->get_value(), 0.0); // When TestActuatorHardware is INACTIVE expect OK - EXPECT_FALSE(rm_->prepare_command_mode_switch(legal_keys_actuator, legal_keys_actuator)); + EXPECT_TRUE(rm_->prepare_command_mode_switch(legal_keys_actuator, legal_keys_actuator)); EXPECT_EQ(claimed_system_acceleration_state_->get_value(), 0.0); EXPECT_EQ(claimed_actuator_position_state_->get_value(), 0.0); EXPECT_TRUE(rm_->perform_command_mode_switch(legal_keys_actuator, legal_keys_actuator)); EXPECT_EQ(claimed_system_acceleration_state_->get_value(), 0.0); EXPECT_EQ(claimed_actuator_position_state_->get_value(), 0.0); - EXPECT_FALSE(rm_->prepare_command_mode_switch(legal_keys_actuator, empty_keys)); + EXPECT_TRUE(rm_->prepare_command_mode_switch(legal_keys_actuator, empty_keys)); EXPECT_EQ(claimed_system_acceleration_state_->get_value(), 0.0); EXPECT_EQ(claimed_actuator_position_state_->get_value(), 0.0); EXPECT_TRUE(rm_->perform_command_mode_switch(legal_keys_actuator, empty_keys)); EXPECT_EQ(claimed_system_acceleration_state_->get_value(), 0.0); EXPECT_EQ(claimed_actuator_position_state_->get_value(), 0.0); - EXPECT_FALSE(rm_->prepare_command_mode_switch(empty_keys, legal_keys_actuator)); + EXPECT_TRUE(rm_->prepare_command_mode_switch(empty_keys, legal_keys_actuator)); EXPECT_EQ(claimed_system_acceleration_state_->get_value(), 0.0); EXPECT_EQ(claimed_actuator_position_state_->get_value(), 0.0); EXPECT_TRUE(rm_->perform_command_mode_switch(empty_keys, legal_keys_actuator));