diff --git a/admittance_controller/test/test_load_admittance_controller.cpp b/admittance_controller/test/test_load_admittance_controller.cpp index 1f290aeff6..23be1f23f5 100644 --- a/admittance_controller/test/test_load_admittance_controller.cpp +++ b/admittance_controller/test/test_load_admittance_controller.cpp @@ -33,8 +33,9 @@ TEST(TestLoadAdmittanceController, load_controller) ros2_control_test_assets::minimal_robot_urdf), executor, "test_controller_manager"); - ASSERT_NO_THROW( - cm.load_controller("load_admittance_controller", "admittance_controller/AdmittanceController")); + ASSERT_EQ( + cm.load_controller("load_admittance_controller", "admittance_controller/AdmittanceController"), + nullptr); } int main(int argc, char ** argv) diff --git a/diff_drive_controller/test/test_load_diff_drive_controller.cpp b/diff_drive_controller/test/test_load_diff_drive_controller.cpp index 20caf46b6f..1eb8939031 100644 --- a/diff_drive_controller/test/test_load_diff_drive_controller.cpp +++ b/diff_drive_controller/test/test_load_diff_drive_controller.cpp @@ -30,8 +30,9 @@ TEST(TestLoadDiffDriveController, load_controller) std::make_unique(ros2_control_test_assets::diffbot_urdf), executor, "test_controller_manager"); - ASSERT_NO_THROW( - cm.load_controller("test_diff_drive_controller", "diff_drive_controller/DiffDriveController")); + ASSERT_NE( + cm.load_controller("test_diff_drive_controller", "diff_drive_controller/DiffDriveController"), + nullptr); rclcpp::shutdown(); } diff --git a/effort_controllers/test/test_load_joint_group_effort_controller.cpp b/effort_controllers/test/test_load_joint_group_effort_controller.cpp index a216d46db3..61bb1ddf9a 100644 --- a/effort_controllers/test/test_load_joint_group_effort_controller.cpp +++ b/effort_controllers/test/test_load_joint_group_effort_controller.cpp @@ -32,8 +32,10 @@ TEST(TestLoadJointGroupVelocityController, load_controller) ros2_control_test_assets::minimal_robot_urdf), executor, "test_controller_manager"); - ASSERT_NO_THROW(cm.load_controller( - "test_joint_group_effort_controller", "effort_controllers/JointGroupEffortController")); + ASSERT_NE( + cm.load_controller( + "test_joint_group_effort_controller", "effort_controllers/JointGroupEffortController"), + nullptr); rclcpp::shutdown(); } diff --git a/force_torque_sensor_broadcaster/test/test_load_force_torque_sensor_broadcaster.cpp b/force_torque_sensor_broadcaster/test/test_load_force_torque_sensor_broadcaster.cpp index 6e9b6b1167..a9ca5e88fc 100644 --- a/force_torque_sensor_broadcaster/test/test_load_force_torque_sensor_broadcaster.cpp +++ b/force_torque_sensor_broadcaster/test/test_load_force_torque_sensor_broadcaster.cpp @@ -38,9 +38,11 @@ TEST(TestLoadForceTorqueSensorBroadcaster, load_controller) ros2_control_test_assets::minimal_robot_urdf), executor, "test_controller_manager"); - ASSERT_NO_THROW(cm.load_controller( - "test_force_torque_sensor_broadcaster", - "force_torque_sensor_broadcaster/ForceTorqueSensorBroadcaster")); + ASSERT_NE( + cm.load_controller( + "test_force_torque_sensor_broadcaster", + "force_torque_sensor_broadcaster/ForceTorqueSensorBroadcaster"), + nullptr); rclcpp::shutdown(); } diff --git a/forward_command_controller/test/test_load_forward_command_controller.cpp b/forward_command_controller/test/test_load_forward_command_controller.cpp index 464b57b69d..b493e52b2a 100644 --- a/forward_command_controller/test/test_load_forward_command_controller.cpp +++ b/forward_command_controller/test/test_load_forward_command_controller.cpp @@ -34,8 +34,10 @@ TEST(TestLoadForwardCommandController, load_controller) ros2_control_test_assets::minimal_robot_urdf), executor, "test_controller_manager"); - ASSERT_NO_THROW(cm.load_controller( - "test_forward_command_controller", "forward_command_controller/ForwardCommandController")); + ASSERT_NE( + cm.load_controller( + "test_forward_command_controller", "forward_command_controller/ForwardCommandController"), + nullptr); rclcpp::shutdown(); } diff --git a/forward_command_controller/test/test_load_multi_interface_forward_command_controller.cpp b/forward_command_controller/test/test_load_multi_interface_forward_command_controller.cpp index 2f540bd0e5..41a9b74698 100644 --- a/forward_command_controller/test/test_load_multi_interface_forward_command_controller.cpp +++ b/forward_command_controller/test/test_load_multi_interface_forward_command_controller.cpp @@ -35,7 +35,9 @@ TEST(TestLoadMultiInterfaceForwardController, load_controller) ros2_control_test_assets::minimal_robot_urdf), executor, "test_controller_manager"); - ASSERT_NO_THROW(cm.load_controller( - "test_forward_command_controller", - "forward_command_controller/MultiInterfaceForwardCommandController")); + ASSERT_NE( + cm.load_controller( + "test_forward_command_controller", + "forward_command_controller/MultiInterfaceForwardCommandController"), + nullptr); } diff --git a/gripper_controllers/test/test_load_gripper_action_controllers.cpp b/gripper_controllers/test/test_load_gripper_action_controllers.cpp index b355cdf34a..130b12e0bb 100644 --- a/gripper_controllers/test/test_load_gripper_action_controllers.cpp +++ b/gripper_controllers/test/test_load_gripper_action_controllers.cpp @@ -32,10 +32,14 @@ TEST(TestLoadGripperActionControllers, load_controller) ros2_control_test_assets::minimal_robot_urdf), executor, "test_controller_manager"); - ASSERT_NO_THROW(cm.load_controller( - "test_gripper_action_position_controller", "position_controllers/GripperActionController")); - ASSERT_NO_THROW(cm.load_controller( - "test_gripper_action_effort_controller", "effort_controllers/GripperActionController")); + ASSERT_NE( + cm.load_controller( + "test_gripper_action_position_controller", "position_controllers/GripperActionController"), + nullptr); + ASSERT_NE( + cm.load_controller( + "test_gripper_action_effort_controller", "effort_controllers/GripperActionController"), + nullptr); rclcpp::shutdown(); } diff --git a/imu_sensor_broadcaster/test/test_load_imu_sensor_broadcaster.cpp b/imu_sensor_broadcaster/test/test_load_imu_sensor_broadcaster.cpp index e90c9915ed..e7cfd1bcf7 100644 --- a/imu_sensor_broadcaster/test/test_load_imu_sensor_broadcaster.cpp +++ b/imu_sensor_broadcaster/test/test_load_imu_sensor_broadcaster.cpp @@ -38,8 +38,10 @@ TEST(TestLoadIMUSensorBroadcaster, load_controller) ros2_control_test_assets::minimal_robot_urdf), executor, "test_controller_manager"); - ASSERT_NO_THROW(cm.load_controller( - "test_imu_sensor_broadcaster", "imu_sensor_broadcaster/IMUSensorBroadcaster")); + ASSERT_NE( + cm.load_controller( + "test_imu_sensor_broadcaster", "imu_sensor_broadcaster/IMUSensorBroadcaster"), + nullptr); rclcpp::shutdown(); } diff --git a/joint_state_broadcaster/test/test_load_joint_state_broadcaster.cpp b/joint_state_broadcaster/test/test_load_joint_state_broadcaster.cpp index d7a2934f57..5efb587805 100644 --- a/joint_state_broadcaster/test/test_load_joint_state_broadcaster.cpp +++ b/joint_state_broadcaster/test/test_load_joint_state_broadcaster.cpp @@ -34,8 +34,10 @@ TEST(TestLoadJointStateBroadcaster, load_controller) ros2_control_test_assets::minimal_robot_urdf), executor, "test_controller_manager"); - ASSERT_NO_THROW(cm.load_controller( - "test_joint_state_broadcaster", "joint_state_broadcaster/JointStateBroadcaster")); + ASSERT_NE( + cm.load_controller( + "test_joint_state_broadcaster", "joint_state_broadcaster/JointStateBroadcaster"), + nullptr); rclcpp::shutdown(); } diff --git a/joint_trajectory_controller/test/test_load_joint_trajectory_controller.cpp b/joint_trajectory_controller/test/test_load_joint_trajectory_controller.cpp index 0f94d0b16c..eb1a3691e6 100644 --- a/joint_trajectory_controller/test/test_load_joint_trajectory_controller.cpp +++ b/joint_trajectory_controller/test/test_load_joint_trajectory_controller.cpp @@ -35,8 +35,10 @@ TEST(TestLoadJointStateController, load_controller) ros2_control_test_assets::minimal_robot_urdf), executor, "test_controller_manager"); - ASSERT_NO_THROW(cm.load_controller( - "test_joint_trajectory_controller", "joint_trajectory_controller/JointTrajectoryController")); + ASSERT_NE( + cm.load_controller( + "test_joint_trajectory_controller", "joint_trajectory_controller/JointTrajectoryController"), + nullptr); rclcpp::shutdown(); } diff --git a/position_controllers/test/test_load_joint_group_position_controller.cpp b/position_controllers/test/test_load_joint_group_position_controller.cpp index cc376bd2d4..fe61039fdb 100644 --- a/position_controllers/test/test_load_joint_group_position_controller.cpp +++ b/position_controllers/test/test_load_joint_group_position_controller.cpp @@ -32,8 +32,10 @@ TEST(TestLoadJointGroupPositionController, load_controller) ros2_control_test_assets::minimal_robot_urdf), executor, "test_controller_manager"); - ASSERT_NO_THROW(cm.load_controller( - "test_joint_group_position_controller", "position_controllers/JointGroupPositionController")); + ASSERT_NE( + cm.load_controller( + "test_joint_group_position_controller", "position_controllers/JointGroupPositionController"), + nullptr); rclcpp::shutdown(); } diff --git a/tricycle_controller/test/test_load_tricycle_controller.cpp b/tricycle_controller/test/test_load_tricycle_controller.cpp index d04b83ae27..9298fae574 100644 --- a/tricycle_controller/test/test_load_tricycle_controller.cpp +++ b/tricycle_controller/test/test_load_tricycle_controller.cpp @@ -16,7 +16,7 @@ * Author: Tony Najjar */ -#include +#include #include #include "controller_manager/controller_manager.hpp" @@ -36,8 +36,9 @@ TEST(TestLoadTricycleController, load_controller) ros2_control_test_assets::minimal_robot_urdf), executor, "test_controller_manager"); - ASSERT_NO_THROW( - cm.load_controller("test_tricycle_controller", "tricycle_controller/TricycleController")); + ASSERT_NE( + cm.load_controller("test_tricycle_controller", "tricycle_controller/TricycleController"), + nullptr); rclcpp::shutdown(); } diff --git a/velocity_controllers/test/test_load_joint_group_velocity_controller.cpp b/velocity_controllers/test/test_load_joint_group_velocity_controller.cpp index 36d5a8368d..1872b5f746 100644 --- a/velocity_controllers/test/test_load_joint_group_velocity_controller.cpp +++ b/velocity_controllers/test/test_load_joint_group_velocity_controller.cpp @@ -32,8 +32,10 @@ TEST(TestLoadJointGroupVelocityController, load_controller) ros2_control_test_assets::minimal_robot_urdf), executor, "test_controller_manager"); - ASSERT_NO_THROW(cm.load_controller( - "test_joint_group_velocity_controller", "velocity_controllers/JointGroupVelocityController")); + ASSERT_NE( + cm.load_controller( + "test_joint_group_velocity_controller", "velocity_controllers/JointGroupVelocityController"), + nullptr); rclcpp::shutdown(); }