spline_smoother::CubicParameterizedTrajectory Class Reference

#include <cubic_parameterized_trajectory.h>

List of all members.

Public Member Functions

 CubicParameterizedTrajectory ()
bool parameterize (const trajectory_msgs::JointTrajectory &trajectory_in, const std::vector< motion_planning_msgs::JointLimits > &limits, spline_smoother::SplineTrajectory &spline)

Private Member Functions

double getAccelerationLimit (const trajectory_msgs::JointTrajectoryPoint &start, const trajectory_msgs::JointTrajectoryPoint &end, const std::vector< motion_planning_msgs::JointLimits > &limits)
double getDistance (const trajectory_msgs::JointTrajectoryPoint &start, const trajectory_msgs::JointTrajectoryPoint &end, const std::vector< motion_planning_msgs::JointLimits > &limits)
void getLimit (const trajectory_msgs::JointTrajectoryPoint &start, const trajectory_msgs::JointTrajectoryPoint &end, const std::vector< motion_planning_msgs::JointLimits > &limits, motion_planning_msgs::JointLimits &limit_out)
double getVelocityLimit (const trajectory_msgs::JointTrajectoryPoint &start, const trajectory_msgs::JointTrajectoryPoint &end, const std::vector< motion_planning_msgs::JointLimits > &limits)
bool hasAccelerationLimits (const std::vector< motion_planning_msgs::JointLimits > &limits)
double jointDiff (const double &start, const double &end, const motion_planning_msgs::JointLimits &limit)
void solveCubicSpline (const double &q0, const double &q1, const double &v0, const double &v1, const double &dt, std::vector< double > &coefficients)

Private Attributes

bool apply_limits_

Static Private Attributes

static const double EPS_TRAJECTORY = 1.0e-8

Detailed Description

Definition at line 48 of file cubic_parameterized_trajectory.h.


Constructor & Destructor Documentation

spline_smoother::CubicParameterizedTrajectory::CubicParameterizedTrajectory (  ) 

Definition at line 41 of file cubic_parameterized_trajectory.cpp.


Member Function Documentation

double spline_smoother::CubicParameterizedTrajectory::getAccelerationLimit ( const trajectory_msgs::JointTrajectoryPoint &  start,
const trajectory_msgs::JointTrajectoryPoint &  end,
const std::vector< motion_planning_msgs::JointLimits > &  limits 
) [private]

Definition at line 71 of file cubic_parameterized_trajectory.cpp.

double spline_smoother::CubicParameterizedTrajectory::getDistance ( 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_parameterized_trajectory.cpp.

void spline_smoother::CubicParameterizedTrajectory::getLimit ( const trajectory_msgs::JointTrajectoryPoint &  start,
const trajectory_msgs::JointTrajectoryPoint &  end,
const std::vector< motion_planning_msgs::JointLimits > &  limits,
motion_planning_msgs::JointLimits &  limit_out 
) [private]

Definition at line 93 of file cubic_parameterized_trajectory.cpp.

double spline_smoother::CubicParameterizedTrajectory::getVelocityLimit ( const trajectory_msgs::JointTrajectoryPoint &  start,
const trajectory_msgs::JointTrajectoryPoint &  end,
const std::vector< motion_planning_msgs::JointLimits > &  limits 
) [private]

Definition at line 57 of file cubic_parameterized_trajectory.cpp.

bool spline_smoother::CubicParameterizedTrajectory::hasAccelerationLimits ( const std::vector< motion_planning_msgs::JointLimits > &  limits  )  [private]

Definition at line 85 of file cubic_parameterized_trajectory.cpp.

double spline_smoother::CubicParameterizedTrajectory::jointDiff ( const double &  start,
const double &  end,
const motion_planning_msgs::JointLimits &  limit 
) [private]

Definition at line 113 of file cubic_parameterized_trajectory.cpp.

bool spline_smoother::CubicParameterizedTrajectory::parameterize ( const trajectory_msgs::JointTrajectory &  trajectory_in,
const std::vector< motion_planning_msgs::JointLimits > &  limits,
spline_smoother::SplineTrajectory spline 
)

Definition at line 138 of file cubic_parameterized_trajectory.cpp.

void spline_smoother::CubicParameterizedTrajectory::solveCubicSpline ( const double &  q0,
const double &  q1,
const double &  v0,
const double &  v1,
const double &  dt,
std::vector< double > &  coefficients 
) [private]

Definition at line 123 of file cubic_parameterized_trajectory.cpp.


Member Data Documentation

Definition at line 92 of file cubic_parameterized_trajectory.h.

const double spline_smoother::CubicParameterizedTrajectory::EPS_TRAJECTORY = 1.0e-8 [static, private]

Definition at line 90 of file cubic_parameterized_trajectory.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs


spline_smoother
Author(s): Mrinal Kalakrishnan / mail@mrinal.net
autogenerated on Fri Jan 11 09:15:18 2013