Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

improved checking for joint-space jumps of Cartesian path #843

Merged
merged 16 commits into from
Apr 16, 2018

Conversation

rhaschke
Copy link
Contributor

This is a rework of #821, with cleaner implementation, particularly more readable unittests.
I also dropped the recently added flags test_for_relative_jump and test_for_absolute_jump in the JumpThreshold struct. @mlautman, @v4hn, @davetcoleman please review to finally merge this.
I also already included Michael's PR #831.

From my point of view, this PR can be squash-merged if finally accepted.

robot_state->copyJointGroupPositions(joint_model_group, joint_positions);
joint_positions[0] -= 1.01;
robot_state->setJointGroupPositions(joint_model_group, joint_positions);
traj.push_back(robot_state);
Copy link
Contributor

@mlautman mlautman Apr 16, 2018

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

On further reflection, I think we should have the cutoff further than 1 index from the end of the list. Returning 3/4 is susceptible to off by one errors

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I don't get this point. Can you please elaborate?

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Off by one errors are one of the most common types of bugs. The probability that some future bug slips past the test because of an off by one error that returns the length of the input trajectory minus one rather than actually finding the jump is non-trivial. While developing #821 I found a bug in my own code that did exactly this. It would be really easy to add another point to the trajectory so that the test would expect 3 out of 5 rather than 3 out of 4.

This was the thinking behind the changes that got reverted in 20dc432.


// direct call of absolute version: factor slightly smaller than 3 (1.01 > 2.99 * 1.01 / 3)
generateTestTraj(traj, robot_model, joint_model_group);
double fraction = robot_state::RobotState::testRelativeJointSpaceJump(joint_model_group, traj, 2.99);
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think this is a regression from the tests in #821. More test coverage is generally better. Why did you revert these?


std::size_t generateTestTraj(std::vector<std::shared_ptr<robot_state::RobotState>>& traj,
                             const moveit::core::RobotModelConstPtr& robot_model,
                             const robot_model::JointModelGroup* joint_model_group)
{
  traj.clear();

  std::size_t n_joints = joint_model_group->getJointModelNames().size();
  for (std::size_t traj_ix = 0; traj_ix < 3; ++traj_ix)
  {
    std::shared_ptr<robot_state::RobotState> robot_state1(new robot_state::RobotState(robot_model));
    robot_state1->setToDefaultValues();
    traj.push_back(robot_state1);
  }

  // This is a jump
  std::shared_ptr<robot_state::RobotState> robot_state2(new robot_state::RobotState(robot_model));
  robot_state2->setToDefaultValues();
  std::vector<double> joint_positions;
  robot_state2->copyJointGroupPositions(joint_model_group, joint_positions);
  joint_positions[0] -= 1.01;
  robot_state2->setJointGroupPositions(joint_model_group, joint_positions);
  traj.push_back(robot_state2);

  return traj.size();
}

TEST_F(LoadPR2, testJointSpaceJumpAbsolute)
{
  const robot_model::JointModelGroup* joint_model_group = robot_model->getJointModelGroup("right_arm");
  std::vector<std::shared_ptr<robot_state::RobotState>> traj;
  std::size_t traj_len = generateTestTraj(traj, robot_model, joint_model_group);

  robot_state::JumpThreshold jt_abs(1.0, 1.0);
  double fraction = robot_state::RobotState::testJointSpaceJump(joint_model_group, traj, jt_abs);

  EXPECT_NEAR(traj.size(), 3, 0.01);
  EXPECT_NEAR(fraction, 3. / (double)traj_len, 0.01);
}

TEST_F(LoadPR2, testJointSpaceJumpRelative)
{
  const robot_model::JointModelGroup* joint_model_group = robot_model->getJointModelGroup("right_arm");
  std::vector<std::shared_ptr<robot_state::RobotState>> traj;
  std::size_t traj_len = generateTestTraj(traj, robot_model, joint_model_group);

  robot_state::JumpThreshold jt_rel(1.0);
  double fraction = robot_state::RobotState::testJointSpaceJump(joint_model_group, traj, jt_rel);

  EXPECT_NEAR(traj.size(), 3, 0.01);
  EXPECT_NEAR(fraction, 3. / (double)traj_len, 0.01);
}

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

As discussed here, your test extensions were overly complex and didn't added any functionality. In 20dc432 you already reverted most of those changes.
I simply cleaned them up even more to facilitate readability.
I agree that more test coverage is better. However, I'm puzzled why you complain, as I have even more tests, namely testing for both direct (testAbsoluteJointSpaceJump / testRelativeJointSpaceJump) and indirect calls (testJointSpaceJump).

Copy link
Contributor

@mlautman mlautman left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I would like my minor changes to be included but in general, I approve this PR

robot_state->copyJointGroupPositions(joint_model_group, joint_positions);
joint_positions[0] -= 1.01;
robot_state->setJointGroupPositions(joint_model_group, joint_positions);
traj.push_back(robot_state);
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Off by one errors are one of the most common types of bugs. The probability that some future bug slips past the test because of an off by one error that returns the length of the input trajectory minus one rather than actually finding the jump is non-trivial. While developing #821 I found a bug in my own code that did exactly this. It would be really easy to add another point to the trajectory so that the test would expect 3 out of 5 rather than 3 out of 4.

This was the thinking behind the changes that got reverted in 20dc432.

@davetcoleman davetcoleman merged commit ea1104d into moveit:kinetic-devel Apr 16, 2018
@davetcoleman
Copy link
Member

I synced this and other changes to melodic just now.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

None yet

4 participants