moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
robot_trajectory_benchmark.cpp
Go to the documentation of this file.
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2023, 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
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 the 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: Mario Prats */
36
37// To run this benchmark, 'cd' to the build/moveit_core/trajectory_processing directory and directly run the binary.
38
39#include <benchmark/benchmark.h>
45
46// Robot and planning group to use in the benchmarks.
47constexpr char TEST_ROBOT[] = "panda";
48constexpr char TEST_GROUP[] = "panda_arm";
49
50// Benchmark manual creation of a trajectory with a given number of waypoints.
51// This includes creating and updating the individual RobotState's.
52static void robotTrajectoryCreate(benchmark::State& st)
53{
54 int n_states = st.range(0);
55 const moveit::core::RobotModelPtr& robot_model = moveit::core::loadTestingRobotModel(TEST_ROBOT);
56
57 // Make sure the group exists, otherwise exit early with an error.
58 if (!robot_model->hasJointModelGroup(TEST_GROUP))
59 {
60 st.SkipWithError("The planning group doesn't exist.");
61 return;
62 }
63 auto* group = robot_model->getJointModelGroup(TEST_GROUP);
64
65 // Robot state.
66 moveit::core::RobotState robot_state(robot_model);
67 robot_state.setToDefaultValues();
68
69 for (auto _ : st)
70 {
71 auto trajectory = std::make_shared<robot_trajectory::RobotTrajectory>(robot_model, group);
72 for (int i = 0; i < n_states; ++i)
73 {
74 // Create a sinusoidal test trajectory for all the joints.
75 const double joint_value = std::sin(0.001 * i);
76 const double duration_from_previous = 0.1;
77
78 moveit::core::RobotState robot_state_waypoint(robot_state);
79 Eigen::VectorXd joint_values = Eigen::VectorXd::Constant(group->getActiveVariableCount(), joint_value);
80 robot_state_waypoint.setJointGroupActivePositions(group, joint_values);
81 trajectory->addSuffixWayPoint(robot_state_waypoint, duration_from_previous);
82 }
83 }
84}
85
86// Benchmark timing of a trajectory with a given number of waypoints, via TOTG.
87static void robotTrajectoryTiming(benchmark::State& st)
88{
89 int n_states = st.range(0);
90 const moveit::core::RobotModelPtr& robot_model = moveit::core::loadTestingRobotModel(TEST_ROBOT);
91
92 // Make sure the group exists, otherwise exit early with an error.
93 if (!robot_model->hasJointModelGroup(TEST_GROUP))
94 {
95 st.SkipWithError("The planning group doesn't exist.");
96 return;
97 }
98 auto* group = robot_model->getJointModelGroup(TEST_GROUP);
99
100 // Robot state.
101 moveit::core::RobotState robot_state(robot_model);
102 robot_state.setToDefaultValues();
103
104 // Trajectory.
105 auto trajectory = std::make_shared<robot_trajectory::RobotTrajectory>(robot_model, group);
106 Eigen::VectorXd joint_values = Eigen::VectorXd::Zero(group->getActiveVariableCount());
107 for (int i = 0; i < n_states; ++i)
108 {
109 // Create a sinusoidal test trajectory for all the joints.
110 const double joint_value = std::sin(0.001 * i);
111 const double duration_from_previous = 0.0;
112
113 moveit::core::RobotState robot_state_waypoint(robot_state);
114 joint_values = Eigen::VectorXd::Constant(group->getActiveVariableCount(), joint_value);
115 robot_state_waypoint.setJointGroupActivePositions(group, joint_values);
116 trajectory->addSuffixWayPoint(robot_state_waypoint, duration_from_previous);
117 }
118
119 // Add some velocity / acceleration limits, which are needed for TOTG.
120 std::unordered_map<std::string, double> velocity_limits, acceleration_limits;
121 for (const auto& joint_name : group->getActiveJointModelNames())
122 {
123 velocity_limits[joint_name] = 1.0;
124 acceleration_limits[joint_name] = 2.0;
125 }
126
127 for (auto _ : st)
128 {
130 totg.computeTimeStamps(*trajectory, velocity_limits, acceleration_limits);
131 }
132}
133
134BENCHMARK(robotTrajectoryCreate)->RangeMultiplier(10)->Range(10, 100000)->Unit(benchmark::kMillisecond);
135BENCHMARK(robotTrajectoryTiming)->RangeMultiplier(10)->Range(10, 20000)->Unit(benchmark::kMillisecond);
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition robot_state.h:90
void setJointGroupActivePositions(const JointModelGroup *group, const std::vector< double > &gstate)
Given positions for the variables of active joints that make up a group, in the order found in the gr...
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.
BENCHMARK(robotTrajectoryCreate) -> RangeMultiplier(10) ->Range(10, 100000) ->Unit(benchmark::kMillisecond)
constexpr char TEST_GROUP[]
constexpr char TEST_ROBOT[]