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  // First waypoint is default joint positions
67  trajectory_->addSuffixWayPoint(robot_state, DEFAULT_TIMESTEP);
68 
69  // Second waypoint has slightly-different joint positions
70  std::vector<double> joint_positions;
71  robot_state.copyJointGroupPositions(JOINT_GROUP, joint_positions);
72  joint_positions.at(0) += 0.05;
73  robot_state.setJointGroupPositions(JOINT_GROUP, joint_positions);
74  robot_state.update();
75  trajectory_->addSuffixWayPoint(robot_state, DEFAULT_TIMESTEP);
76 
77  EXPECT_TRUE(
78  smoother_.applySmoothing(*trajectory_, 1.0 /* max vel scaling factor */, 1.0 /* max accel scaling factor */));
79 }
80 
81 TEST_F(RuckigTests, basic_trajectory_with_custom_limits)
82 {
83  // Check the version of computeTimeStamps that takes custom velocity/acceleration limits
84 
85  moveit::core::RobotState robot_state(robot_model_);
86  robot_state.setToDefaultValues();
87  // First waypoint is default joint positions
88  trajectory_->addSuffixWayPoint(robot_state, DEFAULT_TIMESTEP);
89 
90  // Second waypoint has slightly-different joint positions
91  std::vector<double> joint_positions;
92  robot_state.copyJointGroupPositions(JOINT_GROUP, joint_positions);
93  joint_positions.at(0) += 0.05;
94  robot_state.setJointGroupPositions(JOINT_GROUP, joint_positions);
95  robot_state.update();
96  trajectory_->addSuffixWayPoint(robot_state, DEFAULT_TIMESTEP);
97 
98  // Custom velocity & acceleration limits for some joints
99  std::unordered_map<std::string, double> vel_limits{ { "panda_joint1", 1.3 } };
100  std::unordered_map<std::string, double> accel_limits{ { "panda_joint2", 2.3 }, { "panda_joint3", 3.3 } };
101  std::unordered_map<std::string, double> jerk_limits{ { "panda_joint5", 100.0 } };
102 
103  EXPECT_TRUE(smoother_.applySmoothing(*trajectory_, vel_limits, accel_limits, jerk_limits));
104 }
105 
106 TEST_F(RuckigTests, trajectory_duration)
107 {
108  // Compare against the OJET online trajectory generator: https://www.trajectorygenerator.com/ojet-online/
109  const double ideal_duration = 0.21025;
110 
111  moveit::core::RobotState robot_state(robot_model_);
112  robot_state.setToDefaultValues();
113  // Special attention to Joint 0. It is the only joint to move in this test.
114  // Zero velocities and accelerations at the endpoints
115  robot_state.setVariablePosition("panda_joint1", 0.0);
116  robot_state.update();
117  trajectory_->addSuffixWayPoint(robot_state, 0.0);
118 
119  robot_state.setVariablePosition("panda_joint1", 0.1);
120  robot_state.update();
121  trajectory_->addSuffixWayPoint(robot_state, DEFAULT_TIMESTEP);
122 
123  EXPECT_TRUE(
124  smoother_.applySmoothing(*trajectory_, 1.0 /* max vel scaling factor */, 1.0 /* max accel scaling factor */));
125  EXPECT_GT(trajectory_->getWayPointDurationFromStart(trajectory_->getWayPointCount() - 1), 0.9999 * ideal_duration);
126  EXPECT_LT(trajectory_->getWayPointDurationFromStart(trajectory_->getWayPointCount() - 1), 1.5 * ideal_duration);
127 }
128 
129 TEST_F(RuckigTests, single_waypoint)
130 {
131  // With only one waypoint, Ruckig cannot smooth the trajectory.
132  // It should simply pass the trajectory through unmodified and return true.
133 
134  moveit::core::RobotState robot_state(robot_model_);
135  robot_state.setToDefaultValues();
136  // First waypoint is default joint positions
137  trajectory_->addSuffixWayPoint(robot_state, DEFAULT_TIMESTEP);
138 
139  robot_state.update();
140 
141  // Trajectory should not change
142  auto first_waypoint_input = robot_state;
143 
144  // Only one waypoint is acceptable. True is returned.
145  EXPECT_TRUE(
146  smoother_.applySmoothing(*trajectory_, 1.0 /* max vel scaling factor */, 1.0 /* max accel scaling factor */));
147  // And the waypoint did not change
148  auto const new_first_waypoint = trajectory_->getFirstWayPointPtr();
149  auto const& variable_names = new_first_waypoint->getVariableNames();
150  for (std::string const& variable_name : variable_names)
151  {
152  EXPECT_EQ(first_waypoint_input.getVariablePosition(variable_name),
153  new_first_waypoint->getVariablePosition(variable_name));
154  }
155 }
156 
157 int main(int argc, char** argv)
158 {
159  testing::InitGoogleTest(&argc, argv);
160  return RUN_ALL_TESTS();
161 }
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:90
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.
Definition: robot_state.h:188
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...
Definition: robot_state.h:605
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...
Definition: robot_state.h:691
void update(bool force=false)
Update all transforms.
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 &robot_name)
Loads a robot from moveit_resources.
TEST_F(RuckigTests, basic_trajectory)
int main(int argc, char **argv)