18 #ifndef COB_CARTESIAN_CONTROLLER_TRAJECTORY_PROFILE_GENERATOR_TRAJECTORY_PROFILE_GENERATOR_BASE_H 19 #define COB_CARTESIAN_CONTROLLER_TRAJECTORY_PROFILE_GENERATOR_TRAJECTORY_PROFILE_GENERATOR_BASE_H 27 #define MIN_VELOCITY_THRESHOLD 0.001 40 const double Se_lin,
const double Se_rot)
43 std::vector<double> linear_path, angular_path;
54 for (
unsigned int i = 0; i < pm.
pm_.size(); i++)
72 std::vector<double> array;
96 #endif // COB_CARTESIAN_CONTROLLER_TRAJECTORY_PROFILE_GENERATOR_TRAJECTORY_PROFILE_GENERATOR_BASE_H TrajectoryProfileBase(const cob_cartesian_controller::CartesianActionStruct ¶ms)
const cob_cartesian_controller::CartesianActionStruct & params_
virtual ~TrajectoryProfileBase()
virtual bool calculateProfile(std::vector< double > *path_matrix, const double Se_lin, const double Se_rot)
virtual bool getProfileTimings(double Se, double te, bool calcMaxTe, cob_cartesian_controller::ProfileTimings &pt)=0
virtual std::vector< double > getTrajectory(double se, cob_cartesian_controller::ProfileTimings pt)=0
cob_cartesian_controller::ProfileTimings pt_max_
void adjustArrayLength(std::vector< cob_cartesian_controller::PathArray > &m)
std::vector< double > array_
std::vector< PathArray > pm_
void copyMatrix(std::vector< double > *path_array, std::vector< cob_cartesian_controller::PathArray > &m)
virtual bool generatePath(cob_cartesian_controller::PathArray &pa)