Skip to content

Commit

Permalink
update tests corresponding to the refactor
Browse files Browse the repository at this point in the history
  • Loading branch information
saikishor committed Jul 21, 2024
1 parent 016249a commit 6851fa9
Show file tree
Hide file tree
Showing 2 changed files with 9 additions and 3 deletions.
4 changes: 4 additions & 0 deletions joint_trajectory_controller/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -59,10 +59,12 @@ if(BUILD_TESTING)

ament_add_gmock(test_trajectory test/test_trajectory.cpp)
target_link_libraries(test_trajectory joint_trajectory_controller)
ament_target_dependencies(test_trajectory ros2_control_test_assets)
target_compile_definitions(test_trajectory PRIVATE _USE_MATH_DEFINES)

ament_add_gmock(test_tolerances test/test_tolerances.cpp)
target_link_libraries(test_tolerances joint_trajectory_controller)
ament_target_dependencies(test_tolerances ros2_control_test_assets)
target_compile_definitions(test_tolerances PRIVATE _USE_MATH_DEFINES)

ament_add_gmock(test_trajectory_controller
Expand All @@ -71,6 +73,7 @@ if(BUILD_TESTING)
target_link_libraries(test_trajectory_controller
joint_trajectory_controller
)
ament_target_dependencies(test_trajectory_controller ros2_control_test_assets)
target_compile_definitions(joint_trajectory_controller PRIVATE _USE_MATH_DEFINES)

ament_add_gmock(test_load_joint_trajectory_controller
Expand All @@ -93,6 +96,7 @@ if(BUILD_TESTING)
target_link_libraries(test_trajectory_actions
joint_trajectory_controller
)
ament_target_dependencies(test_trajectory_actions ros2_control_test_assets)
endif()


Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,7 @@
#include "hardware_interface/types/hardware_interface_type_values.hpp"
#include "joint_trajectory_controller/joint_trajectory_controller.hpp"
#include "joint_trajectory_controller/tolerances.hpp"
#include "ros2_control_test_assets/descriptions.hpp"

namespace
{
Expand Down Expand Up @@ -249,7 +250,7 @@ class TrajectoryControllerTest : public ::testing::Test

void SetUpTrajectoryController(
rclcpp::Executor & executor, const std::vector<rclcpp::Parameter> & parameters = {},
const std::string & urdf = "")
const std::string & urdf = ros2_control_test_assets::minimal_robot_urdf)
{
auto ret = SetUpTrajectoryControllerLocal(parameters, urdf);
if (ret != controller_interface::return_type::OK)
Expand All @@ -260,7 +261,8 @@ class TrajectoryControllerTest : public ::testing::Test
}

controller_interface::return_type SetUpTrajectoryControllerLocal(
const std::vector<rclcpp::Parameter> & parameters = {}, const std::string & urdf = "")
const std::vector<rclcpp::Parameter> & parameters = {},
const std::string & urdf = ros2_control_test_assets::minimal_robot_urdf)
{
traj_controller_ = std::make_shared<TestableJointTrajectoryController>();

Expand Down Expand Up @@ -302,7 +304,7 @@ class TrajectoryControllerTest : public ::testing::Test
const std::vector<double> initial_vel_joints = INITIAL_VEL_JOINTS,
const std::vector<double> initial_acc_joints = INITIAL_ACC_JOINTS,
const std::vector<double> initial_eff_joints = INITIAL_EFF_JOINTS,
const std::string & urdf = "")
const std::string & urdf = ros2_control_test_assets::minimal_robot_urdf)
{
auto has_nonzero_vel_param =
std::find_if(
Expand Down

0 comments on commit 6851fa9

Please sign in to comment.