Go to the documentation of this file.
40 #include <unordered_map>
42 #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);
72 const std::unordered_map<std::string, double>& velocity_limits,
73 const std::unordered_map<std::string, double>& acceleration_limits,
74 const std::unordered_map<std::string, double>& jerk_limits,
75 const bool mitigate_overshoot =
false,
const double overshoot_threshold = 0.01);
92 const double max_acceleration_scaling_factor,
94 ruckig::InputParameter<ruckig::DynamicDOFs>& ruckig_input);
103 static void getNextRuckigInput(
const moveit::core::RobotStateConstPtr& current_waypoint,
104 const moveit::core::RobotStateConstPtr& next_waypoint,
106 ruckig::InputParameter<ruckig::DynamicDOFs>& ruckig_input);
117 ruckig::InputParameter<ruckig::DynamicDOFs>& ruckig_input);
131 static std::optional<robot_trajectory::RobotTrajectory>
133 ruckig::InputParameter<ruckig::DynamicDOFs>& ruckig_input,
size_t batch_size = 100);
143 ruckig::InputParameter<ruckig::DynamicDOFs>& ruckig_input,
144 const bool mitigate_overshoot =
false,
const double overshoot_threshold = 0.01);
156 const size_t num_dof,
const std::vector<int>& move_group_idx,
161 static bool checkOvershoot(ruckig::Trajectory<ruckig::DynamicDOFs, ruckig::StandardVector>& ruckig_trajectory,
162 const size_t num_dof, ruckig::InputParameter<ruckig::DynamicDOFs>& ruckig_input,
163 const double overshoot_threshold);
Representation of a robot's state. This includes position, velocity, acceleration and effort.
static void extendTrajectoryDuration(const double duration_extension_factor, size_t num_waypoints, const size_t num_dof, const std::vector< int > &move_group_idx, const robot_trajectory::RobotTrajectory &original_trajectory, robot_trajectory::RobotTrajectory &trajectory)
Extend the duration of every trajectory segment.
Maintain a sequence of waypoints and the time durations between these waypoints.
static std::optional< robot_trajectory::RobotTrajectory > runRuckigInBatches(const robot_trajectory::RobotTrajectory &trajectory, ruckig::InputParameter< ruckig::DynamicDOFs > &ruckig_input, size_t batch_size=100)
Break the trajectory parameter into batches of reasonable size (~100), run Ruckig on each of them,...
static void initializeRuckigState(const moveit::core::RobotState &first_waypoint, const moveit::core::JointModelGroup *joint_group, ruckig::InputParameter< ruckig::DynamicDOFs > &ruckig_input)
Initialize Ruckig position/vel/accel. This initializes ruckig_input and ruckig_output to the same val...
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 jerk-limited smoothing to a trajectory.
static void getNextRuckigInput(const moveit::core::RobotStateConstPtr ¤t_waypoint, const moveit::core::RobotStateConstPtr &next_waypoint, const moveit::core::JointModelGroup *joint_group, ruckig::InputParameter< ruckig::DynamicDOFs > &ruckig_input)
Feed previous output back as input for next iteration. Get next target state from the next waypoint.
static bool validateGroup(const robot_trajectory::RobotTrajectory &trajectory)
A utility function to check if the group is defined.
static bool getRobotModelBounds(const double max_velocity_scaling_factor, const double max_acceleration_scaling_factor, moveit::core::JointModelGroup const *const group, ruckig::InputParameter< ruckig::DynamicDOFs > &ruckig_input)
A utility function to get bounds from a JointModelGroup and save them for Ruckig.
static bool runRuckig(robot_trajectory::RobotTrajectory &trajectory, ruckig::InputParameter< ruckig::DynamicDOFs > &ruckig_input, const bool mitigate_overshoot=false, const double overshoot_threshold=0.01)
A utility function to instantiate and run Ruckig for a series of waypoints.
static bool checkOvershoot(ruckig::Trajectory< ruckig::DynamicDOFs, ruckig::StandardVector > &ruckig_trajectory, const size_t num_dof, ruckig::InputParameter< ruckig::DynamicDOFs > &ruckig_input, const double overshoot_threshold)
Check if a trajectory out of Ruckig overshoots the target state.
moveit_core
Author(s): Ioan Sucan
, Sachin Chitta , Acorn Pooley
autogenerated on Sun Nov 3 2024 03:26:15