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

Add waypoint duration to the trajectory deep copy unit test #2961

Merged
merged 3 commits into from
Nov 16, 2021
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
14 changes: 12 additions & 2 deletions moveit_core/robot_trajectory/test/test_robot_trajectory.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -115,6 +115,14 @@ class RobotTrajectoryTestFixture : public testing::Test
std::vector<double> trajectory_first_state_after_update;
trajectory_first_waypoint_after_update->copyJointGroupPositions(arm_jmg_name_, trajectory_first_state_after_update);
EXPECT_EQ(trajectory_first_state[0], trajectory_first_state_after_update[0]);

// Modify the first waypoint duration
double trajectory_first_duration_before_update = trajectory->getWayPointDurationFromPrevious(0);
double new_duration = trajectory_first_duration_before_update + 0.1;
trajectory->setWayPointDurationFromPrevious(0, new_duration);

// Check that the trajectory's first duration was updated
EXPECT_EQ(trajectory->getWayPointDurationFromPrevious(0), new_duration);
}

void modifyFirstWaypointAndCheckTrajectory(robot_trajectory::RobotTrajectoryPtr& trajectory)
Expand Down Expand Up @@ -212,7 +220,7 @@ TEST_F(RobotTrajectoryTestFixture, RobotTrajectoryShallowCopy)
trajectory_copy_first_waypoint_after_update.copyJointGroupPositions(arm_jmg_name_,
trajectory_copy_first_state_after_update);

// Check that we updated the value correctly in the trajectory
// Check that we updated the joint position correctly in the trajectory
EXPECT_EQ(trajectory_first_state_after_update[0], trajectory_copy_first_state_after_update[0]);
}

Expand All @@ -238,8 +246,10 @@ TEST_F(RobotTrajectoryTestFixture, RobotTrajectoryDeepCopy)
trajectory_copy_first_waypoint_after_update.copyJointGroupPositions(arm_jmg_name_,
trajectory_copy_first_state_after_update);

// Check that we updated the value correctly in the trajectory
// Check that joint positions changed in the original trajectory but not the deep copy
EXPECT_NE(trajectory_first_state_after_update[0], trajectory_copy_first_state_after_update[0]);
// Check that the first waypoint duration changed in the original trajectory but not the deep copy
EXPECT_NE(trajectory->getWayPointDurationFromPrevious(0), trajectory_copy->getWayPointDurationFromPrevious(0));
}

int main(int argc, char** argv)
Expand Down