moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
trajectory_tools.cpp
Go to the documentation of this file.
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2012, Willow Garage, Inc.
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: Ioan Sucan */
36
40
41#include <rclcpp/logger.hpp>
42#include <rclcpp/logging.hpp>
44{
45
46namespace
47{
48rclcpp::Logger getLogger()
49{
50 return moveit::getLogger("moveit.trajectory_processing.trajectory_tools");
51}
52} // namespace
53
54bool isTrajectoryEmpty(const moveit_msgs::msg::RobotTrajectory& trajectory)
55{
56 return trajectory.joint_trajectory.points.empty() && trajectory.multi_dof_joint_trajectory.points.empty();
57}
58
59std::size_t trajectoryWaypointCount(const moveit_msgs::msg::RobotTrajectory& trajectory)
60{
61 return std::max(trajectory.joint_trajectory.points.size(), trajectory.multi_dof_joint_trajectory.points.size());
62}
63bool applyTOTGTimeParameterization(robot_trajectory::RobotTrajectory& trajectory, double velocity_scaling_factor,
64 double acceleration_scaling_factor, double path_tolerance, double resample_dt,
65 double min_angle_change)
66{
67 TimeOptimalTrajectoryGeneration totg(path_tolerance, resample_dt, min_angle_change);
68 return totg.computeTimeStamps(trajectory, velocity_scaling_factor, acceleration_scaling_factor);
69}
70bool applyRuckigSmoothing(robot_trajectory::RobotTrajectory& trajectory, double velocity_scaling_factor,
71 double acceleration_scaling_factor, bool mitigate_overshoot, double overshoot_threshold)
72{
73 RuckigSmoothing time_param;
74 return time_param.applySmoothing(trajectory, velocity_scaling_factor, acceleration_scaling_factor, mitigate_overshoot,
75 overshoot_threshold);
76}
77
78trajectory_msgs::msg::JointTrajectory createTrajectoryMessage(const std::vector<std::string>& joint_names,
79 const trajectory_processing::Trajectory& trajectory,
80 const int sampling_rate)
81{
82 trajectory_msgs::msg::JointTrajectory trajectory_msg;
83 if (sampling_rate <= 0)
84 {
85 RCLCPP_ERROR(getLogger(), "Cannot sample trajectory with sampling rate <= 0. Returning empty trajectory.");
86 return trajectory_msg;
87 }
88 trajectory_msg.joint_names = joint_names;
89 const double time_step = 1.0 / static_cast<double>(sampling_rate);
90 const int n_samples = static_cast<int>(std::ceil(trajectory.getDuration() / time_step)) + 1;
91 trajectory_msg.points.reserve(n_samples);
92 for (int sample = 0; sample < n_samples; ++sample)
93 {
94 const double t = sample * time_step;
95 trajectory_msgs::msg::JointTrajectoryPoint point;
96 auto position = trajectory.getPosition(t);
97 auto velocity = trajectory.getVelocity(t);
98 auto acceleration = trajectory.getAcceleration(t);
99 for (std::size_t i = 0; i < joint_names.size(); i++)
100 {
101 point.positions.push_back(position[i]);
102 point.velocities.push_back(velocity[i]);
103 point.accelerations.push_back(acceleration[i]);
104 }
105 point.time_from_start = rclcpp::Duration(std::chrono::duration<double>(t));
106 trajectory_msg.points.push_back(std::move(point));
107 }
108 return trajectory_msg;
109}
110} // namespace trajectory_processing
Maintain a sequence of waypoints and the time durations between these waypoints.
static bool applySmoothing(robot_trajectory::RobotTrajectory &trajectory, const double max_velocity_scaling_factor=1.0, const double max_acceleration_scaling_factor=1.0, const bool mitigate_overshoot=false, const double overshoot_threshold=0.01)
Apply smoothing to a time-parameterized trajectory so that jerk limits are not violated.
bool computeTimeStamps(robot_trajectory::RobotTrajectory &trajectory, const double max_velocity_scaling_factor=1.0, const double max_acceleration_scaling_factor=1.0) const override
Compute a trajectory with waypoints spaced equally in time (according to resample_dt_)....
Eigen::VectorXd getAcceleration(double time) const
Return the acceleration vector for a given point in time.
Eigen::VectorXd getPosition(double time) const
Return the position/configuration vector for a given point in time.
double getDuration() const
Returns the optimal duration of the trajectory.
Eigen::VectorXd getVelocity(double time) const
Return the velocity vector for a given point in time.
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
Definition logger.cpp:79
bool applyTOTGTimeParameterization(robot_trajectory::RobotTrajectory &trajectory, double velocity_scaling_factor, double acceleration_scaling_factor, double path_tolerance=0.1, double resample_dt=0.1, double min_angle_change=0.001)
Applies time parameterization to a robot trajectory using the Time-Optimal Trajectory Generation (TOT...
bool applyRuckigSmoothing(robot_trajectory::RobotTrajectory &trajectory, double velocity_scaling_factor, double acceleration_scaling_factor, bool mitigate_overshoot=false, double overshoot_threshold=0.01)
Applies Ruckig smoothing to a robot trajectory.
trajectory_msgs::msg::JointTrajectory createTrajectoryMessage(const std::vector< std::string > &joint_names, const trajectory_processing::Trajectory &trajectory, const int sampling_rate)
Converts a trajectory_processing::Trajectory into a JointTrajectory message with a given sampling rat...
bool isTrajectoryEmpty(const moveit_msgs::msg::RobotTrajectory &trajectory)
Checks if a robot trajectory is empty.
std::size_t trajectoryWaypointCount(const moveit_msgs::msg::RobotTrajectory &trajectory)
Returns the number of waypoints in a robot trajectory.