moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
ruckig_traj_smoothing.h
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: Jack Center, Wyatt Rees, Andy Zelenak, Stephanie Eng */
35
36#pragma once
37
38#include <Eigen/Core>
39#include <list>
41#include <ruckig/ruckig.hpp>
42
44{
46{
47public:
58 const double max_velocity_scaling_factor = 1.0,
59 const double max_acceleration_scaling_factor = 1.0, const bool mitigate_overshoot = false,
60 const double overshoot_threshold = 0.01);
61
75 const std::unordered_map<std::string, double>& velocity_limits,
76 const std::unordered_map<std::string, double>& acceleration_limits,
77 const std::unordered_map<std::string, double>& jerk_limits,
78 const double max_velocity_scaling_factor = 1.0,
79 const double max_acceleration_scaling_factor = 1.0, const bool mitigate_overshoot = false,
80 const double overshoot_threshold = 0.01);
81
91 const std::vector<moveit_msgs::msg::JointLimits>& joint_limits,
92 const double max_velocity_scaling_factor = 1.0,
93 const double max_acceleration_scaling_factor = 1.0);
94
95private:
100 [[nodiscard]] static bool validateGroup(const robot_trajectory::RobotTrajectory& trajectory);
101
109 [[nodiscard]] static bool getRobotModelBounds(const double max_velocity_scaling_factor,
110 const double max_acceleration_scaling_factor,
111 const moveit::core::JointModelGroup* const group,
112 ruckig::InputParameter<ruckig::DynamicDOFs>& ruckig_input);
113
121 static void getNextRuckigInput(const moveit::core::RobotStateConstPtr& current_waypoint,
122 const moveit::core::RobotStateConstPtr& next_waypoint,
123 const moveit::core::JointModelGroup* joint_group,
124 ruckig::InputParameter<ruckig::DynamicDOFs>& ruckig_input);
125
132 static void initializeRuckigState(const moveit::core::RobotState& first_waypoint,
133 const moveit::core::JointModelGroup* joint_group,
134 ruckig::InputParameter<ruckig::DynamicDOFs>& ruckig_input);
135
143 [[nodiscard]] static bool runRuckig(robot_trajectory::RobotTrajectory& trajectory,
144 ruckig::InputParameter<ruckig::DynamicDOFs>& ruckig_input,
145 const bool mitigate_overshoot = false, const double overshoot_threshold = 0.01);
146
156 static void extendTrajectoryDuration(const double duration_extension_factor, size_t num_waypoints,
157 const size_t num_dof, const std::vector<int>& move_group_idx,
158 const robot_trajectory::RobotTrajectory& original_trajectory,
160
162 static bool checkOvershoot(ruckig::Trajectory<ruckig::DynamicDOFs, ruckig::StandardVector>& ruckig_trajectory,
163 const size_t num_dof, ruckig::InputParameter<ruckig::DynamicDOFs>& ruckig_input,
164 const double overshoot_threshold);
165};
166} // namespace trajectory_processing
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition robot_state.h:90
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.