Skip to content

Commit

Permalink
fix(robot-model): kinematics tests (#207)
Browse files Browse the repository at this point in the history
  • Loading branch information
domire8 authored Dec 12, 2024
1 parent 4b821d0 commit 2e26bd7
Show file tree
Hide file tree
Showing 2 changed files with 4 additions and 3 deletions.
1 change: 1 addition & 0 deletions CHANGELOG.md
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@ Release Versions
## Upcoming changes

- fix(robot-model): improve ik performance (#205)
- fix(robot-model): kinematics tests (#207)

## 9.0.1

Expand Down
6 changes: 3 additions & 3 deletions source/robot_model/test/tests/test_kinematics.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -311,9 +311,9 @@ TEST_F(RobotModelKinematicsTest, TestInverseKinematics) {
InverseKinematicsParameters param = InverseKinematicsParameters();
param.tolerance = tol;

std::size_t num_samples = 10000;
std::size_t num_samples = 100;
for (const auto& urdf : std::vector<std::string>{"panda_arm.urdf", "ur5e.urdf", "xarm.urdf"}) {
auto robot = std::make_unique<Model>("robot", std::string(TEST_FIXTURES) + "panda_arm.urdf");
auto robot = std::make_unique<Model>("robot", std::string(TEST_FIXTURES) + urdf);
state_representation::JointPositions config("robot", robot->get_joint_frames());

int success = 0;
Expand All @@ -322,7 +322,7 @@ TEST_F(RobotModelKinematicsTest, TestInverseKinematics) {
double total_time = 0;
for (std::size_t i = 0; i < num_samples; ++i) {
config.set_positions(pinocchio::randomConfiguration(robot->get_pinocchio_model()));
auto reference = franka->forward_kinematics(config);
auto reference = robot->forward_kinematics(config);
try {
start_time = std::chrono::system_clock::now();
robot->inverse_kinematics(reference, param);
Expand Down

0 comments on commit 2e26bd7

Please sign in to comment.