41 #include <ruckig/ruckig.hpp>
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);
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);
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);
109 [[nodiscard]]
static bool getRobotModelBounds(
const double max_velocity_scaling_factor,
110 const double max_acceleration_scaling_factor,
112 ruckig::InputParameter<ruckig::DynamicDOFs>& ruckig_input);
121 static void getNextRuckigInput(
const moveit::core::RobotStateConstPtr& current_waypoint,
122 const moveit::core::RobotStateConstPtr& next_waypoint,
124 ruckig::InputParameter<ruckig::DynamicDOFs>& ruckig_input);
134 ruckig::InputParameter<ruckig::DynamicDOFs>& ruckig_input);
144 ruckig::InputParameter<ruckig::DynamicDOFs>& ruckig_input,
145 const bool mitigate_overshoot =
false,
const double overshoot_threshold = 0.01);
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,
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);
Representation of a robot's state. This includes position, velocity, acceleration and effort.
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.