#include <cubic_trajectory.h>
Public Member Functions | |
| CubicTrajectory () | |
| bool | parameterize (const trajectory_msgs::JointTrajectory &trajectory_in, const std::vector< motion_planning_msgs::JointLimits > &limits, spline_smoother::SplineTrajectory &spline) |
Private Member Functions | |
| double | calculateMinimumTime (const trajectory_msgs::JointTrajectoryPoint &start, const trajectory_msgs::JointTrajectoryPoint &end, const std::vector< motion_planning_msgs::JointLimits > &limits) |
| double | minSegmentTime (const double &q0, const double &q1, const double &v0, const double &v1, const motion_planning_msgs::JointLimits &limit) |
| bool | quadSolve (const double &a, const double &b, const double &c, std::vector< double > &solution) |
| bool | quadSolve (const double &a, const double &b, const double &c, double &solution) |
| bool | validSolution (const double &q0, const double &q1, const double &v0, const double &v1, const double &dT, const double &vmax, const double &amax) |
Private Attributes | |
| bool | apply_limits_ |
Static Private Attributes | |
| static const double | EPS_TRAJECTORY = 1.0e-8 |
Definition at line 47 of file cubic_trajectory.h.
| spline_smoother::CubicTrajectory::CubicTrajectory | ( | ) |
Definition at line 41 of file cubic_trajectory.cpp.
| double spline_smoother::CubicTrajectory::calculateMinimumTime | ( | const trajectory_msgs::JointTrajectoryPoint & | start, | |
| const trajectory_msgs::JointTrajectoryPoint & | end, | |||
| const std::vector< motion_planning_msgs::JointLimits > & | limits | |||
| ) | [private] |
Definition at line 46 of file cubic_trajectory.cpp.
| double spline_smoother::CubicTrajectory::minSegmentTime | ( | const double & | q0, | |
| const double & | q1, | |||
| const double & | v0, | |||
| const double & | v1, | |||
| const motion_planning_msgs::JointLimits & | limit | |||
| ) | [private] |
Definition at line 63 of file cubic_trajectory.cpp.
| bool spline_smoother::CubicTrajectory::parameterize | ( | const trajectory_msgs::JointTrajectory & | trajectory_in, | |
| const std::vector< motion_planning_msgs::JointLimits > & | limits, | |||
| spline_smoother::SplineTrajectory & | spline | |||
| ) |
Definition at line 205 of file cubic_trajectory.cpp.
| bool spline_smoother::CubicTrajectory::quadSolve | ( | const double & | a, | |
| const double & | b, | |||
| const double & | c, | |||
| std::vector< double > & | solution | |||
| ) | [private] |
Definition at line 283 of file cubic_trajectory.cpp.
| bool spline_smoother::CubicTrajectory::quadSolve | ( | const double & | a, | |
| const double & | b, | |||
| const double & | c, | |||
| double & | solution | |||
| ) | [private] |
Definition at line 249 of file cubic_trajectory.cpp.
| bool spline_smoother::CubicTrajectory::validSolution | ( | const double & | q0, | |
| const double & | q1, | |||
| const double & | v0, | |||
| const double & | v1, | |||
| const double & | dT, | |||
| const double & | vmax, | |||
| const double & | amax | |||
| ) | [private] |
Definition at line 159 of file cubic_trajectory.cpp.
bool spline_smoother::CubicTrajectory::apply_limits_ [private] |
Definition at line 85 of file cubic_trajectory.h.
const double spline_smoother::CubicTrajectory::EPS_TRAJECTORY = 1.0e-8 [static, private] |
Definition at line 65 of file cubic_trajectory.h.