moveit2
The MoveIt Motion Planning Framework for ROS 2.
test_time_parameterization.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2017, Ken Anderson
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
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Ken Anderson */
36 
37 #include <gtest/gtest.h>
38 #include <fstream>
45 #include <rclcpp/rclcpp.hpp>
46 
47 // Logger
48 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit_trajectory_processing.test.test_time_parameterization");
49 
50 // Static variables used in all tests
51 moveit::core::RobotModelConstPtr RMODEL = moveit::core::loadTestingRobotModel("pr2");
53 
54 // Initialize one-joint, 3 points exactly the same.
56 {
57  const int num = 3;
58  unsigned i;
59 
60  const moveit::core::JointModelGroup* group = trajectory.getGroup();
61  if (!group)
62  {
63  RCLCPP_ERROR(LOGGER, "Need to set the group");
64  return -1;
65  }
66  // leave initial velocity/acceleration unset
67  const std::vector<int>& idx = group->getVariableIndexList();
68  moveit::core::RobotState state(trajectory.getRobotModel());
69 
70  trajectory.clear();
71  for (i = 0; i < num; ++i)
72  {
73  state.setVariablePosition(idx[0], 1.0);
74  trajectory.addSuffixWayPoint(state, 0.0);
75  }
76 
77  return 0;
78 }
79 
80 // Initialize one-joint, straight-line trajectory
82 {
83  const int num = 10;
84  const double max = 2.0;
85  unsigned i;
86 
87  const moveit::core::JointModelGroup* group = trajectory.getGroup();
88  if (!group)
89  {
90  RCLCPP_ERROR(LOGGER, "Need to set the group");
91  return -1;
92  }
93  // leave initial velocity/acceleration unset
94  const std::vector<int>& idx = group->getVariableIndexList();
95  moveit::core::RobotState state(trajectory.getRobotModel());
96 
97  trajectory.clear();
98  for (i = 0; i < num; ++i)
99  {
100  state.setVariablePosition(idx[0], i * max / num);
101  trajectory.addSuffixWayPoint(state, 0.0);
102  }
103 
104  // leave final velocity/acceleration unset
105  state.setVariablePosition(idx[0], max);
106  trajectory.addSuffixWayPoint(state, 0.0);
107 
108  return 0;
109 }
110 
112 {
113  const moveit::core::JointModelGroup* group = trajectory.getGroup();
114  const std::vector<int>& idx = group->getVariableIndexList();
115  trajectory.print(std::cout, { idx[0] });
116 }
117 
118 TEST(TestTimeParameterization, TestIterativeParabolic)
119 {
121  EXPECT_EQ(initStraightTrajectory(TRAJECTORY), 0);
122 
123  auto wt = std::chrono::system_clock::now();
124  EXPECT_TRUE(time_parameterization.computeTimeStamps(TRAJECTORY));
125 
126  std::cout << "IterativeParabolicTimeParameterization took " << (std::chrono::system_clock::now() - wt).count()
127  << '\n';
130 }
131 
132 TEST(TestTimeParameterization, TestIterativeSpline)
133 {
134  trajectory_processing::IterativeSplineParameterization time_parameterization(false);
135  EXPECT_EQ(initStraightTrajectory(TRAJECTORY), 0);
136 
137  auto wt = std::chrono::system_clock::now();
138  EXPECT_TRUE(time_parameterization.computeTimeStamps(TRAJECTORY));
139  std::cout << "IterativeSplineParameterization took " << (std::chrono::system_clock::now() - wt).count() << '\n';
142 }
143 
144 TEST(TestTimeParameterization, TestIterativeSplineAddPoints)
145 {
146  trajectory_processing::IterativeSplineParameterization time_parameterization(true);
147  EXPECT_EQ(initStraightTrajectory(TRAJECTORY), 0);
148 
149  auto wt = std::chrono::system_clock::now();
150  EXPECT_TRUE(time_parameterization.computeTimeStamps(TRAJECTORY));
151  std::cout << "IterativeSplineParameterization with added points took "
152  << (std::chrono::system_clock::now() - wt).count() << '\n';
155 }
156 
157 TEST(TestTimeParameterization, TestRepeatedPoint)
158 {
159  trajectory_processing::IterativeSplineParameterization time_parameterization(true);
161 
162  EXPECT_TRUE(time_parameterization.computeTimeStamps(TRAJECTORY));
165 }
166 
167 int main(int argc, char** argv)
168 {
169  testing::InitGoogleTest(&argc, argv);
170  return RUN_ALL_TESTS();
171 }
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
Maintain a sequence of waypoints and the time durations between these waypoints.
const moveit::core::RobotModelConstPtr & getRobotModel() const
double getWayPointDurationFromStart(std::size_t index) const
Returns the duration after start that a waypoint will be reached.
void print(std::ostream &out, std::vector< int > variable_indexes=std::vector< int >()) const
Print information about the trajectory.
const moveit::core::JointModelGroup * getGroup() const
RobotTrajectory & addSuffixWayPoint(const moveit::core::RobotState &state, double dt)
Add a point to the trajectory.
bool computeTimeStamps(robot_trajectory::RobotTrajectory &trajectory, const double max_velocity_scaling_factor=1.0, const double max_acceleration_scaling_factor=1.0) const override
This class sets the timestamps of a trajectory to enforce velocity, acceleration constraints....
bool computeTimeStamps(robot_trajectory::RobotTrajectory &trajectory, const double max_velocity_scaling_factor=1.0, const double max_acceleration_scaling_factor=1.0) const override
moveit::core::RobotModelPtr loadTestingRobotModel(const std::string &robot_name)
Loads a robot from moveit_resources.
moveit::core::RobotModelConstPtr RMODEL
int main(int argc, char **argv)
int initStraightTrajectory(robot_trajectory::RobotTrajectory &trajectory)
void printTrajectory(robot_trajectory::RobotTrajectory &trajectory)
TEST(TestTimeParameterization, TestIterativeParabolic)
robot_trajectory::RobotTrajectory TRAJECTORY(RMODEL, "right_arm")
int initRepeatedPointTrajectory(robot_trajectory::RobotTrajectory &trajectory)