Skip to content

Commit

Permalink
Re-enable test_servo_pose_tracking integration test (#423)
Browse files Browse the repository at this point in the history
Co-authored-by: AndyZe <zelenak@picknik.ai>
  • Loading branch information
Vatan Aksoy Tezer and AndyZe committed Apr 19, 2021
1 parent fc6e6fe commit 2bd2261
Show file tree
Hide file tree
Showing 6 changed files with 12 additions and 12 deletions.
12 changes: 6 additions & 6 deletions moveit_ros/moveit_servo/CMakeLists.txt
Original file line number Diff line number Diff line change
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
2 changes: 1 addition & 1 deletion moveit_ros/moveit_servo/test/pose_tracking_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -209,8 +209,8 @@ TEST_F(PoseTrackingFixture, OutgoingMsgTest)

int main(int argc, char** argv)
{
::testing::InitGoogleTest(&argc, argv);
rclcpp::init(argc, argv);
::testing::InitGoogleTest(&argc, argv);

int result = RUN_ALL_TESTS();
rclcpp::shutdown();
Expand Down
2 changes: 1 addition & 1 deletion moveit_ros/moveit_servo/test/test_servo_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -222,8 +222,8 @@ TEST_F(ServoFixture, DynamicParameterTest)

int main(int argc, char** argv)
{
::testing::InitGoogleTest(&argc, argv);
rclcpp::init(argc, argv);
::testing::InitGoogleTest(&argc, argv);

int ret = RUN_ALL_TESTS();
rclcpp::shutdown();
Expand Down
2 changes: 1 addition & 1 deletion moveit_ros/moveit_servo/test/test_servo_singularity.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -100,8 +100,8 @@ TEST_F(ServoFixture, ReachSingular)

int main(int argc, char** argv)
{
::testing::InitGoogleTest(&argc, argv);
rclcpp::init(argc, argv);
::testing::InitGoogleTest(&argc, argv);

int ret = RUN_ALL_TESTS();
rclcpp::shutdown();
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 @@ -363,7 +363,7 @@ TEST_F(ServoCalcsTestFixture, TestEnforceVelLimits)
EXPECT_LE(desired_velocity[i], vel_limits[i] * servo_calcs_->parameters_->publish_period);
}

// Let's check the negative velocities too
// Let's check negative velocity limits too
desired_velocity *= -1;
servo_calcs_->prev_joint_velocity_ = desired_velocity;
servo_calcs_->enforceVelLimits(desired_velocity);
Expand Down Expand Up @@ -505,8 +505,8 @@ TEST_F(ServoCalcsTestFixture, TestComposeOutputMsg)

int main(int argc, char** argv)
{
::testing::InitGoogleTest(&argc, argv);
rclcpp::init(argc, argv);
::testing::InitGoogleTest(&argc, argv);

// Set up the shared node
TEST_NODE = std::make_shared<rclcpp::Node>("servo_calcs_test");
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -174,8 +174,8 @@ TEST_F(ConstrainedPlanningTestFixture, PositionConstraint)

int main(int argc, char** argv)
{
::testing::InitGoogleTest(&argc, argv);
rclcpp::init(argc, argv);
::testing::InitGoogleTest(&argc, argv);

int ret = RUN_ALL_TESTS();
rclcpp::shutdown();
Expand Down

0 comments on commit 2bd2261

Please sign in to comment.