Skip to content

Commit

Permalink
Fix Servo singularity scaling unit tests (#2414)
Browse files Browse the repository at this point in the history
* Fix Servo singularity scaling unit tests

* Fix Servo singularity scaling unit tests

* Simplify tests

* updateLinkTransforms is not needed after all
  • Loading branch information
sea-bass authored Oct 9, 2023
1 parent 739afb6 commit e2b8ac2
Showing 1 changed file with 4 additions and 11 deletions.
15 changes: 4 additions & 11 deletions moveit_ros/moveit_servo/tests/test_utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -152,8 +152,8 @@ TEST(ServoUtilsUnitTests, ApproachingSingularityScaling)
servo_params.move_group_name = "panda_arm";
const moveit::core::JointModelGroup* joint_model_group =
robot_state->getJointModelGroup(servo_params.move_group_name);
robot_state->setToDefaultValues();

rclcpp::sleep_for(std::chrono::milliseconds(500));
Eigen::Vector<double, 6> cartesian_delta{ 0.005, 0.0, 0.0, 0.0, 0.0, 0.0 };
// Home state
Eigen::Vector<double, 7> state_ready{ 0.0, -0.785, 0.0, -2.356, 0.0, 1.571, 0.785 };
Expand All @@ -178,8 +178,8 @@ TEST(ServoUtilsUnitTests, HaltForSingularityScaling)
servo_params.move_group_name = "panda_arm";
const moveit::core::JointModelGroup* joint_model_group =
robot_state->getJointModelGroup(servo_params.move_group_name);
robot_state->setToDefaultValues();

rclcpp::sleep_for(std::chrono::milliseconds(500));
Eigen::Vector<double, 6> cartesian_delta{ 0.005, 0.0, 0.0, 0.0, 0.0, 0.0 };

// Home state
Expand All @@ -205,24 +205,17 @@ TEST(ServoUtilsUnitTests, LeavingSingularityScaling)
servo_params.move_group_name = "panda_arm";
const moveit::core::JointModelGroup* joint_model_group =
robot_state->getJointModelGroup(servo_params.move_group_name);
robot_state->setToDefaultValues();

rclcpp::sleep_for(std::chrono::milliseconds(500));
Eigen::Vector<double, 6> cartesian_delta{ 0.005, 0.0, 0.0, 0.0, 0.0, 0.0 };
Eigen::Vector<double, 6> cartesian_delta{ -0.005, 0.0, 0.0, 0.0, 0.0, 0.0 };

// Home state
Eigen::Vector<double, 7> state_ready{ 0.0, -0.785, 0.0, -2.356, 0.0, 1.571, 0.785 };
robot_state->setJointGroupActivePositions(joint_model_group, state_ready);
auto scaling_result = moveit_servo::velocityScalingFactorForSingularity(robot_state, cartesian_delta, servo_params);
ASSERT_EQ(scaling_result.second, moveit_servo::StatusCode::NO_WARNING);

// Approach singularity
Eigen::Vector<double, 7> state_approaching_singularity{ 0.0, 0.334, 0.0, -1.177, 0.0, 1.510, 0.785 };
robot_state->setJointGroupActivePositions(joint_model_group, state_approaching_singularity);
scaling_result = moveit_servo::velocityScalingFactorForSingularity(robot_state, cartesian_delta, servo_params);
ASSERT_EQ(scaling_result.second, moveit_servo::StatusCode::DECELERATE_FOR_APPROACHING_SINGULARITY);

// Move away from singularity
cartesian_delta(0) *= -1;
Eigen::Vector<double, 7> state_leaving_singularity{ 0.0, 0.3458, 0.0, -1.1424, 0.0, 1.4865, 0.785 };
robot_state->setJointGroupActivePositions(joint_model_group, state_leaving_singularity);
scaling_result = moveit_servo::velocityScalingFactorForSingularity(robot_state, cartesian_delta, servo_params);
Expand Down

0 comments on commit e2b8ac2

Please sign in to comment.