moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
Namespaces | Functions
trajectory_tools.h File Reference
#include <moveit_msgs/msg/robot_trajectory.hpp>
#include <moveit/robot_trajectory/robot_trajectory.h>
#include <moveit/trajectory_processing/time_optimal_trajectory_generation.h>
Include dependency graph for trajectory_tools.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Namespaces

namespace  trajectory_processing
 

Functions

bool trajectory_processing::isTrajectoryEmpty (const moveit_msgs::msg::RobotTrajectory &trajectory)
 Checks if a robot trajectory is empty.
 
std::size_t trajectory_processing::trajectoryWaypointCount (const moveit_msgs::msg::RobotTrajectory &trajectory)
 Returns the number of waypoints in a robot trajectory.
 
bool trajectory_processing::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 (TOTG) algorithm.
 
bool trajectory_processing::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 trajectory_processing::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 rate.