39#include <moveit_msgs/msg/robot_trajectory.hpp>
69 double acceleration_scaling_factor,
double path_tolerance = 0.1,
70 double resample_dt = 0.1,
double min_angle_change = 0.001);
81 double acceleration_scaling_factor,
bool mitigate_overshoot =
false,
82 double overshoot_threshold = 0.01);
87[[nodiscard]] trajectory_msgs::msg::JointTrajectory
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.