Skip to content

Commit

Permalink
Reduce joint velocity and delay in tests
Browse files Browse the repository at this point in the history
  • Loading branch information
sea-bass committed Sep 20, 2024
1 parent 3b2a7be commit 38fa728
Showing 1 changed file with 4 additions and 4 deletions.
8 changes: 4 additions & 4 deletions moveit_ros/moveit_servo/tests/test_ros_integration.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -90,15 +90,15 @@ 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)
{
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);
Expand Down Expand Up @@ -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);
Expand Down Expand Up @@ -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);
Expand Down

0 comments on commit 38fa728

Please sign in to comment.