36 #include <gtest/gtest.h>
43 constexpr
double DEFAULT_TIMESTEP = 0.1;
44 constexpr
char JOINT_GROUP[] =
"panda_arm";
46 class RuckigTests :
public testing::Test
52 trajectory_ = std::make_shared<robot_trajectory::RobotTrajectory>(robot_model_, JOINT_GROUP);
55 moveit::core::RobotModelPtr robot_model_;
56 robot_trajectory::RobotTrajectoryPtr trajectory_;
62 TEST_F(RuckigTests, basic_trajectory)
69 trajectory_->addSuffixWayPoint(
robot_state, DEFAULT_TIMESTEP);
72 std::vector<double> joint_positions;
73 robot_state.copyJointGroupPositions(JOINT_GROUP, joint_positions);
74 joint_positions.at(0) += 0.05;
75 robot_state.setJointGroupPositions(JOINT_GROUP, joint_positions);
76 trajectory_->addSuffixWayPoint(
robot_state, DEFAULT_TIMESTEP);
79 smoother_.applySmoothing(*trajectory_, 1.0 , 1.0 ));
82 TEST_F(RuckigTests, basic_trajectory_with_custom_limits)
91 trajectory_->addSuffixWayPoint(
robot_state, DEFAULT_TIMESTEP);
94 std::vector<double> joint_positions;
95 robot_state.copyJointGroupPositions(JOINT_GROUP, joint_positions);
96 joint_positions.at(0) += 0.05;
97 robot_state.setJointGroupPositions(JOINT_GROUP, joint_positions);
98 trajectory_->addSuffixWayPoint(
robot_state, DEFAULT_TIMESTEP);
101 std::unordered_map<std::string, double> vel_limits{ {
"panda_joint1", 1.3 } };
102 std::unordered_map<std::string, double> accel_limits{ {
"panda_joint2", 2.3 }, {
"panda_joint3", 3.3 } };
103 std::unordered_map<std::string, double> jerk_limits{ {
"panda_joint5", 100.0 } };
105 EXPECT_TRUE(smoother_.applySmoothing(*trajectory_, vel_limits, accel_limits, jerk_limits));
111 const double ideal_duration = 0.317;
119 robot_state.setVariablePosition(
"panda_joint1", 0.0);
123 robot_state.setVariablePosition(
"panda_joint1", 0.1);
124 trajectory_->addSuffixWayPoint(
robot_state, DEFAULT_TIMESTEP);
127 smoother_.applySmoothing(*trajectory_, 1.0 , 1.0 ));
130 for (
size_t waypoint_idx = 1; waypoint_idx < trajectory_->getWayPointCount() - 1; ++waypoint_idx)
132 EXPECT_NE(trajectory_->getWayPointDurationFromPrevious(waypoint_idx), 0);
137 EXPECT_GT(trajectory_->getWayPointDurationFromStart(trajectory_->getWayPointCount() - 1), 0.9999 * ideal_duration);
138 EXPECT_LT(trajectory_->getWayPointDurationFromStart(trajectory_->getWayPointCount() - 1), 1.11 * ideal_duration);
151 trajectory_->addSuffixWayPoint(
robot_state, DEFAULT_TIMESTEP);
158 smoother_.applySmoothing(*trajectory_, 1.0 , 1.0 ));
160 auto const new_first_waypoint = trajectory_->getFirstWayPointPtr();
161 auto const& variable_names = new_first_waypoint->getVariableNames();
162 for (std::string
const& variable_name : variable_names)
164 EXPECT_EQ(first_waypoint_input.getVariablePosition(variable_name),
165 new_first_waypoint->getVariablePosition(variable_name));
169 int main(
int argc,
char** argv)
171 testing::InitGoogleTest(&argc, argv);
172 return RUN_ALL_TESTS();