moveit2
The MoveIt Motion Planning Framework for ROS 2.
trajectory_tools.h
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 
37 #pragma once
38 
39 #include <moveit_msgs/msg/robot_trajectory.hpp>
42 
43 namespace trajectory_processing
44 {
50 bool isTrajectoryEmpty(const moveit_msgs::msg::RobotTrajectory& trajectory);
56 std::size_t trajectoryWaypointCount(const moveit_msgs::msg::RobotTrajectory& trajectory);
68 bool applyTOTGTimeParameterization(robot_trajectory::RobotTrajectory& trajectory, double velocity_scaling_factor,
69  double acceleration_scaling_factor, double path_tolerance = 0.1,
70  double resample_dt = 0.1, double min_angle_change = 0.001);
80 bool applyRuckigSmoothing(robot_trajectory::RobotTrajectory& trajectory, double velocity_scaling_factor,
81  double acceleration_scaling_factor, bool mitigate_overshoot = false,
82  double overshoot_threshold = 0.01);
83 
87 [[nodiscard]] trajectory_msgs::msg::JointTrajectory
88 createTrajectoryMessage(const std::vector<std::string>& joint_names,
89  const trajectory_processing::Trajectory& trajectory, const int sampling_rate);
90 } // namespace trajectory_processing
Maintain a sequence of waypoints and the time durations between these waypoints.
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.