trajectory_utils.h
Go to the documentation of this file.
1 //
2 // Created by yijiangh on 7/9/17.
3 //
4 
5 #ifndef CHOREO_PROCESS_PLANNING_TRAJECTORY_UTILS_H
6 #define CHOREO_PROCESS_PLANNING_TRAJECTORY_UTILS_H
7 
8 #include <Eigen/Geometry>
9 
11 {
12 // Cartesian Interpolation
13 typedef std::vector<Eigen::Affine3d, Eigen::aligned_allocator<Eigen::Affine3d> > PoseVector;
14 
15 PoseVector interpolateCartesian(const Eigen::Affine3d& start, const Eigen::Affine3d& stop,
16  double ds);
17 // Joint Interpolation
18 typedef std::vector<std::vector<double> > JointVector;
19 
20 JointVector interpolateJoint(const std::vector<double>& start, const std::vector<double>& stop,
21  double dtheta);
22 }
23 
24 #endif //CHOREO_PROCESS_PLANNING_TRAJECTORY_UTILS_H
JointVector interpolateJoint(const std::vector< double > &start, const std::vector< double > &stop, double dtheta)
std::vector< std::vector< double > > JointVector
PoseVector interpolateCartesian(const Eigen::Affine3d &start, const Eigen::Affine3d &stop, double ds)
std::vector< Eigen::Affine3d, Eigen::aligned_allocator< Eigen::Affine3d > > PoseVector


choreo_process_planning
Author(s): Yijiang Huang
autogenerated on Thu Jul 18 2019 03:59:02