#include <TrajectoryPlanner.h>
Public Member Functions | |
| void | absJointConfigurationDifference (const std::vector< double > &p1, const std::vector< double > &p2, std::vector< double > &diff) |
| double | absJointConfigurationDist (const std::vector< double > &p1, const std::vector< double > &p2) |
| void | computeDijkstraPath (const std::vector< std::vector< std::vector< double > > > &ik_solutions, const std::vector< bool > &valid_poses, std::vector< std::vector< double > > &path, std::string measure) |
| void | computeGreedyPath (const std::vector< std::vector< std::vector< double > > > &ik_solutions, const std::vector< bool > &valid_poses, std::vector< std::vector< double > > &path) |
| void | getMaxJointVelocities (const std::vector< double > v1, const std::vector< double > v2, std::vector< double > &velocities, double &min_time) |
| void | getMaxJointVelocities (const std::vector< double > v1, const std::vector< double > v2, Eigen::VectorXf &velocities, double &min_time) |
| void | jointConfigurationDifference (const std::vector< double > &p1, const std::vector< double > &p2, std::vector< double > &diff) |
| double | jointConfigurationMinTravelTime (const std::vector< double > v1, const std::vector< double > v2) |
| double | jointDist (double angle1, double angle2, unsigned int joint) |
| void | planTrajectoryVelocity (const std::vector< std::vector< double > > &joint_traj, std::vector< std::vector< double > > &vel, std::vector< double > &time, const double scale_t=1, const double scale_v=1) |
| void | planTrajectoryVelocity (const std::vector< std::vector< double > > &joint_traj, const std::vector< tf::Pose > &pose_traj, std::vector< std::vector< double > > &vel, std::vector< double > &time, const double scale_t=1, const double scale_v=1) |
| TrajectoryPlanner () | |
Public Attributes | |
| std::vector< double > | left_limits_ |
| std::vector< double > | max_velocities_ |
| std::vector< double > | right_limits_ |
Definition at line 14 of file TrajectoryPlanner.h.
Definition at line 21 of file TrajectoryPlanner.cpp.
| void TrajectoryPlanner::absJointConfigurationDifference | ( | const std::vector< double > & | p1, |
| const std::vector< double > & | p2, | ||
| std::vector< double > & | diff | ||
| ) |
Definition at line 103 of file TrajectoryPlanner.cpp.
| double TrajectoryPlanner::absJointConfigurationDist | ( | const std::vector< double > & | p1, |
| const std::vector< double > & | p2 | ||
| ) |
Definition at line 75 of file TrajectoryPlanner.cpp.
| void TrajectoryPlanner::computeDijkstraPath | ( | const std::vector< std::vector< std::vector< double > > > & | ik_solutions, |
| const std::vector< bool > & | valid_poses, | ||
| std::vector< std::vector< double > > & | path, | ||
| std::string | measure | ||
| ) |
Definition at line 341 of file TrajectoryPlanner.cpp.
| void TrajectoryPlanner::computeGreedyPath | ( | const std::vector< std::vector< std::vector< double > > > & | ik_solutions, |
| const std::vector< bool > & | valid_poses, | ||
| std::vector< std::vector< double > > & | path | ||
| ) |
Definition at line 312 of file TrajectoryPlanner.cpp.
| void TrajectoryPlanner::getMaxJointVelocities | ( | const std::vector< double > | v1, |
| const std::vector< double > | v2, | ||
| std::vector< double > & | velocities, | ||
| double & | min_time | ||
| ) |
Definition at line 152 of file TrajectoryPlanner.cpp.
| void TrajectoryPlanner::getMaxJointVelocities | ( | const std::vector< double > | v1, |
| const std::vector< double > | v2, | ||
| Eigen::VectorXf & | velocities, | ||
| double & | min_time | ||
| ) |
Definition at line 132 of file TrajectoryPlanner.cpp.
| void TrajectoryPlanner::jointConfigurationDifference | ( | const std::vector< double > & | p1, |
| const std::vector< double > & | p2, | ||
| std::vector< double > & | diff | ||
| ) |
Definition at line 85 of file TrajectoryPlanner.cpp.
| double TrajectoryPlanner::jointConfigurationMinTravelTime | ( | const std::vector< double > | v1, |
| const std::vector< double > | v2 | ||
| ) |
Definition at line 115 of file TrajectoryPlanner.cpp.
| double TrajectoryPlanner::jointDist | ( | double | angle1, |
| double | angle2, | ||
| unsigned int | joint | ||
| ) |
Definition at line 62 of file TrajectoryPlanner.cpp.
| void TrajectoryPlanner::planTrajectoryVelocity | ( | const std::vector< std::vector< double > > & | joint_traj, |
| std::vector< std::vector< double > > & | vel, | ||
| std::vector< double > & | time, | ||
| const double | scale_t = 1, |
||
| const double | scale_v = 1 |
||
| ) |
Definition at line 177 of file TrajectoryPlanner.cpp.
| void TrajectoryPlanner::planTrajectoryVelocity | ( | const std::vector< std::vector< double > > & | joint_traj, |
| const std::vector< tf::Pose > & | pose_traj, | ||
| std::vector< std::vector< double > > & | vel, | ||
| std::vector< double > & | time, | ||
| const double | scale_t = 1, |
||
| const double | scale_v = 1 |
||
| ) |
Definition at line 209 of file TrajectoryPlanner.cpp.
Definition at line 38 of file TrajectoryPlanner.h.
Definition at line 37 of file TrajectoryPlanner.h.
Definition at line 39 of file TrajectoryPlanner.h.