Skip to content

Commit

Permalink
Renovate load controller tests (#569)
Browse files Browse the repository at this point in the history
  • Loading branch information
bmagyar authored Apr 29, 2023
1 parent 1e3129d commit 4037719
Show file tree
Hide file tree
Showing 13 changed files with 56 additions and 31 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -30,8 +30,9 @@ TEST(TestLoadDiffDriveController, load_controller)
std::make_unique<hardware_interface::ResourceManager>(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();
}
Original file line number Diff line number Diff line change
Expand Up @@ -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();
}
Original file line number Diff line number Diff line change
Expand Up @@ -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();
}
Original file line number Diff line number Diff line change
Expand Up @@ -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();
}
Original file line number Diff line number Diff line change
Expand Up @@ -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);
}
Original file line number Diff line number Diff line change
Expand Up @@ -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();
}
Original file line number Diff line number Diff line change
Expand Up @@ -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();
}
Original file line number Diff line number Diff line change
Expand Up @@ -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();
}
Original file line number Diff line number Diff line change
Expand Up @@ -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();
}
Original file line number Diff line number Diff line change
Expand Up @@ -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();
}
7 changes: 4 additions & 3 deletions tricycle_controller/test/test_load_tricycle_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@
* Author: Tony Najjar
*/

#include <gtest/gtest.h>
#include <gmock/gmock.h>
#include <memory>

#include "controller_manager/controller_manager.hpp"
Expand All @@ -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();
}
Original file line number Diff line number Diff line change
Expand Up @@ -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();
}

0 comments on commit 4037719

Please sign in to comment.