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 {
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 
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 
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  const double ideal_duration = 0.317;
112 
114  robot_state.setToDefaultValues();
115  robot_state.zeroVelocities();
116  robot_state.zeroAccelerations();
117  // Special attention to Joint 0. It is the only joint to move in this test.
118  // Zero velocities and accelerations at the endpoints
119  robot_state.setVariablePosition("panda_joint1", 0.0);
120  trajectory_->addPrefixWayPoint(robot_state, 0.0);
121 
122  robot_state.setToDefaultValues();
123  robot_state.setVariablePosition("panda_joint1", 0.1);
124  trajectory_->addSuffixWayPoint(robot_state, DEFAULT_TIMESTEP);
125 
126  EXPECT_TRUE(
127  smoother_.applySmoothing(*trajectory_, 1.0 /* max vel scaling factor */, 1.0 /* max accel scaling factor */));
128 
129  // No waypoint durations of zero except the first
130  for (size_t waypoint_idx = 1; waypoint_idx < trajectory_->getWayPointCount() - 1; ++waypoint_idx)
131  {
132  EXPECT_NE(trajectory_->getWayPointDurationFromPrevious(waypoint_idx), 0);
133  }
134 
135  // The trajectory duration should be within 10% of the analytical solution since the implementation here extends
136  // the duration by 10% increments
137  EXPECT_GT(trajectory_->getWayPointDurationFromStart(trajectory_->getWayPointCount() - 1), 0.9999 * ideal_duration);
138  EXPECT_LT(trajectory_->getWayPointDurationFromStart(trajectory_->getWayPointCount() - 1), 1.11 * ideal_duration);
139 }
140 
141 TEST_F(RuckigTests, single_waypoint)
142 {
143  // With only one waypoint, Ruckig cannot smooth the trajectory.
144  // It should simply pass the trajectory through unmodified and return true.
145 
147  robot_state.setToDefaultValues();
148  robot_state.zeroVelocities();
149  robot_state.zeroAccelerations();
150  // First waypoint is default joint positions
151  trajectory_->addSuffixWayPoint(robot_state, DEFAULT_TIMESTEP);
152 
153  // Trajectory should not change
154  auto first_waypoint_input = robot_state;
155 
156  // Only one waypoint is acceptable. True is returned.
157  EXPECT_TRUE(
158  smoother_.applySmoothing(*trajectory_, 1.0 /* max vel scaling factor */, 1.0 /* max accel scaling factor */));
159  // And the waypoint did not change
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)
163  {
164  EXPECT_EQ(first_waypoint_input.getVariablePosition(variable_name),
165  new_first_waypoint->getVariablePosition(variable_name));
166  }
167 }
168 
169 int main(int argc, char** argv)
170 {
171  testing::InitGoogleTest(&argc, argv);
172  return RUN_ALL_TESTS();
173 }
moveit::core
Core components of MoveIt.
Definition: kinematics_base.h:83
moveit::core::RobotState
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:155
trajectory_processing::RuckigSmoothing
Definition: ruckig_traj_smoothing.h:77
EXPECT_TRUE
#define EXPECT_TRUE(args)
main
int main(int argc, char **argv)
Definition: test_ruckig_traj_smoothing.cpp:169
TEST_F
TEST_F(RuckigTests, basic_trajectory)
Definition: test_ruckig_traj_smoothing.cpp:62
robot_model_test_utils.h
ruckig_traj_smoothing.h
robot_state.h
EXPECT_EQ
#define EXPECT_EQ(a, b)
moveit::core::loadTestingRobotModel
moveit::core::RobotModelPtr loadTestingRobotModel(const std::string &robot_name)
Loads a robot from moveit_resources.
Definition: robot_model_test_utils.cpp:117


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Sat Apr 27 2024 02:25:25