Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Re-re-enable servo tests. #423

Merged
merged 7 commits into from
Apr 19, 2021
Merged
Show file tree
Hide file tree
Changes from 4 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
26 changes: 13 additions & 13 deletions moveit_ros/moveit_servo/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -191,13 +191,13 @@ if(BUILD_TESTING)

# This test is flaky, disabling until it is fixed
# Unit test for ServoCalcs
# ament_add_gtest_executable(
# unit_test_servo_calcs
# test/unit_test_servo_calcs.cpp
# )
# target_link_libraries(unit_test_servo_calcs ${SERVO_LIB_NAME})
# ament_target_dependencies(unit_test_servo_calcs ${THIS_PACKAGE_INCLUDE_DEPENDS} Boost)
# add_ros_test(test/launch/unit_test_servo_calcs.test.py ARGS "test_binary_dir:=${CMAKE_CURRENT_BINARY_DIR}")
ament_add_gtest_executable(
unit_test_servo_calcs
test/unit_test_servo_calcs.cpp
)
target_link_libraries(unit_test_servo_calcs ${SERVO_LIB_NAME})
ament_target_dependencies(unit_test_servo_calcs ${THIS_PACKAGE_INCLUDE_DEPENDS} Boost)
add_ros_test(test/launch/unit_test_servo_calcs.test.py ARGS "test_binary_dir:=${CMAKE_CURRENT_BINARY_DIR}")
# end Unit test for ServoCalcs

# Servo integration launch test
Expand Down Expand Up @@ -243,12 +243,12 @@ if(BUILD_TESTING)

# Flaky, disabling until it is fixed
# pose_tracking
# ament_add_gtest_executable(test_servo_pose_tracking
# test/pose_tracking_test.cpp
# )
# ament_target_dependencies(test_servo_pose_tracking ${THIS_PACKAGE_INCLUDE_DEPENDS})
# target_link_libraries(test_servo_pose_tracking ${POSE_TRACKING})
# add_ros_test(test/launch/test_servo_pose_tracking.test.py ARGS "test_binary_dir:=${CMAKE_CURRENT_BINARY_DIR}")
ament_add_gtest_executable(test_servo_pose_tracking
test/pose_tracking_test.cpp
)
ament_target_dependencies(test_servo_pose_tracking ${THIS_PACKAGE_INCLUDE_DEPENDS})
target_link_libraries(test_servo_pose_tracking ${POSE_TRACKING})
add_ros_test(test/launch/test_servo_pose_tracking.test.py ARGS "test_binary_dir:=${CMAKE_CURRENT_BINARY_DIR}")

# # low_latency
# add_rostest_gtest(servo_low_latency_test
Expand Down
4 changes: 2 additions & 2 deletions moveit_ros/moveit_servo/test/unit_test_servo_calcs.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -360,7 +360,7 @@ TEST_F(ServoCalcsTestFixture, TestEnforceVelLimits)
for (size_t i = 0; i < 7; ++i)
{
// We need to check vs radians-per-loop allowable rate (not rad/s)
EXPECT_LE(desired_velocity[i], vel_limits[i] * servo_calcs_->parameters_->publish_period);
EXPECT_GE(desired_velocity[i], vel_limits[i] * servo_calcs_->parameters_->publish_period);
JafarAbdi marked this conversation as resolved.
Show resolved Hide resolved
}

// Let's check the negative velocities too
Expand All @@ -370,7 +370,7 @@ TEST_F(ServoCalcsTestFixture, TestEnforceVelLimits)
for (size_t i = 0; i < 7; ++i)
{
// We need to check vs radians-per-loop allowable rate (not rad/s)
EXPECT_GE(desired_velocity[i], -1 * vel_limits[i] * servo_calcs_->parameters_->publish_period);
EXPECT_LE(desired_velocity[i], -1 * vel_limits[i] * servo_calcs_->parameters_->publish_period);
AndyZe marked this conversation as resolved.
Show resolved Hide resolved
}
}

Expand Down