moveit2
The MoveIt Motion Planning Framework for ROS 2.
test_ruckig_traj_smoothing.cpp
Go to the documentation of this file.
1 /*******************************************************************************
2  * BSD 3-Clause License
3  *
4  * Copyright (c) 2021, PickNik Robotics
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions are met:
9  *
10  * * Redistributions of source code must retain the above copyright notice, this
11  * list of conditions and the following disclaimer.
12  *
13  * * Redistributions in binary form must reproduce the above copyright notice,
14  * this list of conditions and the following disclaimer in the documentation
15  * and/or other materials provided with the distribution.
16  *
17  * * Neither the name of the copyright holder nor the names of its
18  * contributors may be used to endorse or promote products derived from
19  * this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
22  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
23  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
24  * ARE
25  * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
26  * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
27  * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
28  * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
30  * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
31  * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
32  *******************************************************************************/
33 
34 /* Author: Andy Zelenak */
35 
36 #include <gtest/gtest.h>
40 
41 namespace
42 {
43 constexpr double DEFAULT_TIMESTEP = 0.1; // sec
44 constexpr char JOINT_GROUP[] = "panda_arm";
45 
46 class RuckigTests : public testing::Test
47 {
48 protected:
49  void SetUp() override
50  {
51  robot_model_ = moveit::core::loadTestingRobotModel("panda");
52  trajectory_ = std::make_shared<robot_trajectory::RobotTrajectory>(robot_model_, JOINT_GROUP);
53  }
54 
55  moveit::core::RobotModelPtr robot_model_;
56  robot_trajectory::RobotTrajectoryPtr trajectory_;
58 };
59 
60 } // namespace
61 
62 TEST_F(RuckigTests, basic_trajectory)
63 {
64  moveit::core::RobotState robot_state(robot_model_);
65  robot_state.setToDefaultValues();
66  robot_state.zeroVelocities();
67  robot_state.zeroAccelerations();
68  // First waypoint is default joint positions
69  trajectory_->addSuffixWayPoint(robot_state, DEFAULT_TIMESTEP);
70 
71  // Second waypoint has slightly-different joint positions
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);
77 
78  EXPECT_TRUE(
79  smoother_.applySmoothing(*trajectory_, 1.0 /* max vel scaling factor */, 1.0 /* max accel scaling factor */));
80 }
81 
82 TEST_F(RuckigTests, basic_trajectory_with_custom_limits)
83 {
84  // Check the version of computeTimeStamps that takes custom velocity/acceleration limits
85 
86  moveit::core::RobotState robot_state(robot_model_);
87  robot_state.setToDefaultValues();
88  robot_state.zeroVelocities();
89  robot_state.zeroAccelerations();
90  // First waypoint is default joint positions
91  trajectory_->addSuffixWayPoint(robot_state, DEFAULT_TIMESTEP);
92 
93  // Second waypoint has slightly-different joint positions
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);
99 
100  // Custom velocity & acceleration limits for some joints
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 } };
104 
105  EXPECT_TRUE(smoother_.applySmoothing(*trajectory_, vel_limits, accel_limits, jerk_limits));
106 }
107 
108 TEST_F(RuckigTests, trajectory_duration)
109 {
110  // Compare against the OJET online trajectory generator: https://www.trajectorygenerator.com/ojet-online/
111  // Limits can be verified like this. Note that Ruckig applies defaults if the RobotModel has none.
112  // robot_model_->printModelInfo(std::cerr);
113  const double ideal_duration = 0.210;
114 
115  moveit::core::RobotState robot_state(robot_model_);
116  robot_state.setToDefaultValues();
117  robot_state.zeroVelocities();
118  robot_state.zeroAccelerations();
119  // Special attention to Joint 0. It is the only joint to move in this test.
120  // Zero velocities and accelerations at the endpoints
121  robot_state.setVariablePosition("panda_joint1", 0.0);
122  trajectory_->addSuffixWayPoint(robot_state, 0.0);
123 
124  robot_state.setVariablePosition("panda_joint1", 0.1);
125  trajectory_->addSuffixWayPoint(robot_state, DEFAULT_TIMESTEP);
126 
127  EXPECT_TRUE(
128  smoother_.applySmoothing(*trajectory_, 1.0 /* max vel scaling factor */, 1.0 /* max accel scaling factor */));
129 
130  // No waypoint durations of zero except the first
131  for (size_t waypoint_idx = 1; waypoint_idx < trajectory_->getWayPointCount() - 1; ++waypoint_idx)
132  {
133  EXPECT_NE(trajectory_->getWayPointDurationFromPrevious(waypoint_idx), 0);
134  }
135 
136  // The trajectory duration should be within 10% of the analytical solution since the implementation here extends
137  // the duration by 10% at every iteration.
138  EXPECT_GT(trajectory_->getWayPointDurationFromStart(trajectory_->getWayPointCount() - 1), 0.9999 * ideal_duration);
139  EXPECT_LT(trajectory_->getWayPointDurationFromStart(trajectory_->getWayPointCount() - 1), 1.11 * ideal_duration);
140 }
141 
142 TEST_F(RuckigTests, single_waypoint)
143 {
144  // With only one waypoint, Ruckig cannot smooth the trajectory.
145  // It should simply pass the trajectory through unmodified and return true.
146 
147  moveit::core::RobotState robot_state(robot_model_);
148  robot_state.setToDefaultValues();
149  robot_state.zeroVelocities();
150  robot_state.zeroAccelerations();
151  // First waypoint is default joint positions
152  trajectory_->addSuffixWayPoint(robot_state, DEFAULT_TIMESTEP);
153 
154  // Trajectory should not change
155  auto first_waypoint_input = robot_state;
156 
157  // Only one waypoint is acceptable. True is returned.
158  EXPECT_TRUE(
159  smoother_.applySmoothing(*trajectory_, 1.0 /* max vel scaling factor */, 1.0 /* max accel scaling factor */));
160  // And the waypoint did not change
161  const auto new_first_waypoint = trajectory_->getFirstWayPointPtr();
162  const auto& variable_names = new_first_waypoint->getVariableNames();
163  for (const std::string& variable_name : variable_names)
164  {
165  EXPECT_EQ(first_waypoint_input.getVariablePosition(variable_name),
166  new_first_waypoint->getVariablePosition(variable_name));
167  }
168 }
169 
170 int main(int argc, char** argv)
171 {
172  testing::InitGoogleTest(&argc, argv);
173  return RUN_ALL_TESTS();
174 }
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.hpp:90
void zeroVelocities()
Set all velocities to 0.0.
void setVariablePosition(const std::string &variable, double value)
Set the position of a single variable. An exception is thrown if the variable name is not known.
void setJointGroupPositions(const std::string &joint_group_name, const double *gstate)
Given positions for the variables that make up a group, in the order found in the group (including va...
void copyJointGroupPositions(const std::string &joint_group_name, std::vector< double > &gstate) const
For a given group, copy the position values of the variables that make up the group into another loca...
void zeroAccelerations()
Set all accelerations to 0.0.
void setToDefaultValues()
Set all joints to their default positions. The default position is 0, or if that is not within bounds...
moveit::core::RobotModelPtr loadTestingRobotModel(const std::string &package_name, const std::string &urdf_relative_path, const std::string &srdf_relative_path)
Loads a robot model given a URDF and SRDF file in a package.
TEST_F(RuckigTests, basic_trajectory)
int main(int argc, char **argv)