From 38fa72882b78448c0515279bd26ae646bb0d6eb3 Mon Sep 17 00:00:00 2001 From: Sebastian Castro Date: Fri, 20 Sep 2024 09:04:27 -0400 Subject: [PATCH] Reduce joint velocity and delay in tests --- moveit_ros/moveit_servo/tests/test_ros_integration.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/moveit_ros/moveit_servo/tests/test_ros_integration.cpp b/moveit_ros/moveit_servo/tests/test_ros_integration.cpp index 8ed44ba1df..4485200b7e 100644 --- a/moveit_ros/moveit_servo/tests/test_ros_integration.cpp +++ b/moveit_ros/moveit_servo/tests/test_ros_integration.cpp @@ -90,7 +90,7 @@ TEST_F(ServoRosFixture, testJointJog) std::fill(jog_cmd.velocities.begin(), jog_cmd.velocities.end(), 0.0); - jog_cmd.velocities[6] = 1.0; + jog_cmd.velocities[6] = 0.5; size_t count = 0; while (rclcpp::ok() && count < NUM_COMMANDS) @@ -98,7 +98,7 @@ TEST_F(ServoRosFixture, testJointJog) jog_cmd.header.stamp = servo_test_node_->now(); joint_jog_publisher->publish(jog_cmd); count++; - rclcpp::sleep_for(std::chrono::milliseconds(200)); + rclcpp::sleep_for(std::chrono::milliseconds(100)); } ASSERT_GE(traj_count_, NUM_COMMANDS); @@ -137,7 +137,7 @@ TEST_F(ServoRosFixture, testTwist) twist_cmd.header.stamp = servo_test_node_->now(); twist_publisher->publish(twist_cmd); count++; - rclcpp::sleep_for(std::chrono::milliseconds(200)); + rclcpp::sleep_for(std::chrono::milliseconds(100)); } ASSERT_GE(traj_count_, NUM_COMMANDS); @@ -178,7 +178,7 @@ TEST_F(ServoRosFixture, testPose) pose_cmd.header.stamp = servo_test_node_->now(); pose_publisher->publish(pose_cmd); count++; - rclcpp::sleep_for(std::chrono::milliseconds(200)); + rclcpp::sleep_for(std::chrono::milliseconds(100)); } ASSERT_GE(traj_count_, NUM_COMMANDS);