MoveIt Pro API
Core Behaviors for MoveIt Pro
Loading...
Searching...
No Matches
cartesian_timing.hpp File Reference
#include <optional>
#include <string>
#include <Eigen/Core>
#include <tl_expected/expected.hpp>
#include "cartesian_planning/types.hpp"
Include dependency graph for cartesian_timing.hpp:
This graph shows which files directly or indirectly include this file:

Classes

struct  cartesian_planning::CartesianLimits
 Cartesian velocity and acceleration limits for the trapezoidal profile. More...
 
struct  cartesian_planning::TrapezoidalProfileError
 
struct  cartesian_planning::ResampledTrajectory
 Resampled trajectory data at uniform control rate. More...
 

Namespaces

namespace  cartesian_planning
 

Functions

tl::expected< ResampledTrajectory, TrapezoidalProfileErrorcartesian_planning::fitCartesianTrapezoidalVelocityProfile (const Path &cartesian_path, const JointSpacePath &joint_path, const CartesianLimits &cartesian_limits, const Eigen::VectorXd &max_joint_velocities, const Eigen::VectorXd &max_joint_accelerations, int control_rate)
 Assign timestamps to a dense joint-space path so the Cartesian-space trajectory follows a trapezoidal velocity profile.