1212// See the License for the specific language governing permissions and
1313// limitations under the License.
1414
15- #define TEST_BUG1
16- #define TEST_BUG2
17- #define TEST_BUG3
18-
1915#include < gtest/gtest.h>
2016#include < memory>
2117#include < string>
@@ -786,15 +782,10 @@ TEST_P(
786782 ASSERT_EQ (
787783 lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, diff_drive_controller->get_state ().id ());
788784
789- // !---- <BUG1> ----
790- #ifdef TEST_BUG1
791785 // Check if the controllers are not in chained mode
792- ASSERT_FALSE (pid_left_wheel_controller
793- ->is_in_chained_mode ()); // !BUG: should be not in chained mode but is in
786+ ASSERT_FALSE (pid_left_wheel_controller->is_in_chained_mode ());
794787 ASSERT_FALSE (pid_right_wheel_controller->is_in_chained_mode ());
795788 ASSERT_FALSE (diff_drive_controller->is_in_chained_mode ());
796- #endif
797- // !---- </BUG1> ----
798789}
799790
800791TEST_P (
@@ -832,8 +823,6 @@ TEST_P(
832823 EXPECT_FALSE (pid_right_wheel_controller->is_in_chained_mode ());
833824 ASSERT_FALSE (diff_drive_controller->is_in_chained_mode ());
834825
835- // !---- <BUG2> ----
836- #ifdef TEST_BUG2
837826 // Test Case: Trying to activate a preceding controller and one of the following controller
838827 // --> return error; preceding controller are not activated,
839828 // BUT following controller IS activated
@@ -866,12 +855,9 @@ TEST_P(
866855 position_tracking_controller->get_state ().id ());
867856
868857 // Check if the controllers are not in chained mode
869- ASSERT_FALSE (pid_left_wheel_controller
870- ->is_in_chained_mode ()); // !BUG: should be not in chained mode but is in
858+ ASSERT_FALSE (pid_left_wheel_controller->is_in_chained_mode ());
871859 ASSERT_FALSE (pid_right_wheel_controller->is_in_chained_mode ());
872860 ASSERT_FALSE (diff_drive_controller->is_in_chained_mode ());
873- #endif
874- // !---- </BUG2> ----
875861}
876862
877863TEST_P (
@@ -1075,8 +1061,6 @@ TEST_P(
10751061 ASSERT_EQ (
10761062 lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, diff_drive_controller->get_state ().id ());
10771063
1078- // !---- <BUG3> ----
1079- #ifdef TEST_BUG3
10801064 // Test Case: middle preceding/following controller deactivation but the most preceding and the
10811065 // lowest following controllers are active
10821066 // --> return error; controllers stay in the same state as they were
@@ -1100,10 +1084,7 @@ TEST_P(
11001084 // Attempt to deactivate the middle preceding/following controller
11011085 switch_test_controllers (
11021086 {}, {DIFF_DRIVE_CONTROLLER}, test_param.strictness , std::future_status::ready,
1103- expected.at (test_param.strictness )
1104- .return_type ); // !BUG: If BEST_EFFORT, all controllers should stay the same state as they
1105- // were, but a deadlock may occur during the switch_controller process,
1106- // causing the test to timeout.
1087+ expected.at (test_param.strictness ).return_type );
11071088
11081089 // All controllers should still be active
11091090 ASSERT_EQ (
@@ -1115,8 +1096,6 @@ TEST_P(
11151096 ASSERT_EQ (
11161097 lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE,
11171098 position_tracking_controller->get_state ().id ());
1118- #endif
1119- // !---- </BUG3> ----
11201099}
11211100
11221101TEST_P (TestControllerChainingWithControllerManager, test_chained_controllers_adding_in_random_order)
0 commit comments