constraint_aware_spline_smoother::CubicSplineShortCutter< T > Class Template Reference

Scales the time intervals stretching them if necessary so that the trajectory conforms to velocity limits. More...

#include <cubic_spline_shortcutter.h>

List of all members.

Public Member Functions

virtual bool configure ()
 Configure the filter with the discretization for returned trajectories.
 CubicSplineShortCutter ()
 Construct the smoother.
virtual bool smooth (const T &trajectory_in, T &trajectory_out) const
virtual ~CubicSplineShortCutter ()

Private Member Functions

bool addToTrajectory (trajectory_msgs::JointTrajectory &trajectory_out, const trajectory_msgs::JointTrajectoryPoint &trajectory_point, const ros::Duration &delta_time) const
void discretizeAndAppendSegment (const spline_smoother::SplineTrajectorySegment &spline_segment, const double &discretization, trajectory_msgs::JointTrajectory &joint_trajectory, const ros::Duration &segment_start_time, const bool &include_segment_end) const
void discretizeTrajectory (const spline_smoother::SplineTrajectory &spline, const double &discretization, trajectory_msgs::JointTrajectory &joint_trajectory) const
bool findTrajectoryPointsInInterval (const trajectory_msgs::JointTrajectory &trajectory, const double &segment_start_time, const double &segment_end_time, int &index_1, int &index_2) const
int getRandomInt (int min, int max) const
double getRandomTimeStamp (double min, double max) const
bool getWaypoints (const spline_smoother::SplineTrajectory &spline, trajectory_msgs::JointTrajectory &joint_trajectory) const
double maxLInfDistance (const trajectory_msgs::JointTrajectoryPoint &start, const trajectory_msgs::JointTrajectoryPoint &end) const
void printTrajectory (const trajectory_msgs::JointTrajectory &joint_trajectory) const
void refineTrajectory (T &trajectory) const
bool setupCollisionEnvironment ()
bool trimTrajectory (trajectory_msgs::JointTrajectory &trajectory_out, const double &segment_start_time, const double &segment_end_time) const

Private Attributes

bool active_
planning_environment::CollisionModels * collision_models_
double discretization_
ros::NodeHandle node_handle_
planning_environment::PlanningMonitor * planning_monitor_
tf::TransformListener tf_

Detailed Description

template<typename T>
class constraint_aware_spline_smoother::CubicSplineShortCutter< T >

Scales the time intervals stretching them if necessary so that the trajectory conforms to velocity limits.

Definition at line 51 of file cubic_spline_shortcutter.h.


Constructor & Destructor Documentation

Construct the smoother.

Definition at line 122 of file cubic_spline_shortcutter.h.

template<typename T >
constraint_aware_spline_smoother::CubicSplineShortCutter< T >::~CubicSplineShortCutter (  )  [inline, virtual]

Definition at line 131 of file cubic_spline_shortcutter.h.


Member Function Documentation

template<typename T >
bool constraint_aware_spline_smoother::CubicSplineShortCutter< T >::addToTrajectory ( trajectory_msgs::JointTrajectory &  trajectory_out,
const trajectory_msgs::JointTrajectoryPoint &  trajectory_point,
const ros::Duration &  delta_time 
) const [inline, private]

Definition at line 540 of file cubic_spline_shortcutter.h.

template<typename T >
bool constraint_aware_spline_smoother::CubicSplineShortCutter< T >::configure (  )  [inline, virtual]

Configure the filter with the discretization for returned trajectories.

Todo:
check length

Definition at line 107 of file cubic_spline_shortcutter.h.

template<typename T >
void constraint_aware_spline_smoother::CubicSplineShortCutter< T >::discretizeAndAppendSegment ( const spline_smoother::SplineTrajectorySegment &  spline_segment,
const double &  discretization,
trajectory_msgs::JointTrajectory &  joint_trajectory,
const ros::Duration &  segment_start_time,
const bool &  include_segment_end 
) const [inline, private]

Definition at line 396 of file cubic_spline_shortcutter.h.

template<typename T >
void constraint_aware_spline_smoother::CubicSplineShortCutter< T >::discretizeTrajectory ( const spline_smoother::SplineTrajectory &  spline,
const double &  discretization,
trajectory_msgs::JointTrajectory &  joint_trajectory 
) const [inline, private]

Definition at line 376 of file cubic_spline_shortcutter.h.

template<typename T >
bool constraint_aware_spline_smoother::CubicSplineShortCutter< T >::findTrajectoryPointsInInterval ( const trajectory_msgs::JointTrajectory &  trajectory,
const double &  segment_start_time,
const double &  segment_end_time,
int &  index_1,
int &  index_2 
) const [inline, private]

Definition at line 484 of file cubic_spline_shortcutter.h.

template<typename T >
int constraint_aware_spline_smoother::CubicSplineShortCutter< T >::getRandomInt ( int  min,
int  max 
) const [inline, private]

Definition at line 136 of file cubic_spline_shortcutter.h.

template<typename T >
double constraint_aware_spline_smoother::CubicSplineShortCutter< T >::getRandomTimeStamp ( double  min,
double  max 
) const [inline, private]

Definition at line 144 of file cubic_spline_shortcutter.h.

template<typename T >
bool constraint_aware_spline_smoother::CubicSplineShortCutter< T >::getWaypoints ( const spline_smoother::SplineTrajectory &  spline,
trajectory_msgs::JointTrajectory &  joint_trajectory 
) const [inline, private]

Definition at line 522 of file cubic_spline_shortcutter.h.

template<typename T >
double constraint_aware_spline_smoother::CubicSplineShortCutter< T >::maxLInfDistance ( const trajectory_msgs::JointTrajectoryPoint &  start,
const trajectory_msgs::JointTrajectoryPoint &  end 
) const [inline, private]

Definition at line 440 of file cubic_spline_shortcutter.h.

template<typename T >
void constraint_aware_spline_smoother::CubicSplineShortCutter< T >::printTrajectory ( const trajectory_msgs::JointTrajectory &  joint_trajectory  )  const [inline, private]

Definition at line 332 of file cubic_spline_shortcutter.h.

template<typename T >
void constraint_aware_spline_smoother::CubicSplineShortCutter< T >::refineTrajectory ( T &  trajectory  )  const [inline, private]

Definition at line 303 of file cubic_spline_shortcutter.h.

template<typename T >
bool constraint_aware_spline_smoother::CubicSplineShortCutter< T >::setupCollisionEnvironment (  )  [inline, private]

Definition at line 590 of file cubic_spline_shortcutter.h.

template<typename T >
bool constraint_aware_spline_smoother::CubicSplineShortCutter< T >::smooth ( const T &  trajectory_in,
T &  trajectory_out 
) const [inline, virtual]

Definition at line 152 of file cubic_spline_shortcutter.h.

template<typename T >
bool constraint_aware_spline_smoother::CubicSplineShortCutter< T >::trimTrajectory ( trajectory_msgs::JointTrajectory &  trajectory_out,
const double &  segment_start_time,
const double &  segment_end_time 
) const [inline, private]

Definition at line 456 of file cubic_spline_shortcutter.h.


Member Data Documentation

template<typename T >
bool constraint_aware_spline_smoother::CubicSplineShortCutter< T >::active_ [private]

Definition at line 58 of file cubic_spline_shortcutter.h.

template<typename T >
planning_environment::CollisionModels* constraint_aware_spline_smoother::CubicSplineShortCutter< T >::collision_models_ [private]

Definition at line 61 of file cubic_spline_shortcutter.h.

template<typename T >
double constraint_aware_spline_smoother::CubicSplineShortCutter< T >::discretization_ [private]

Definition at line 59 of file cubic_spline_shortcutter.h.

template<typename T >
ros::NodeHandle constraint_aware_spline_smoother::CubicSplineShortCutter< T >::node_handle_ [private]

Definition at line 63 of file cubic_spline_shortcutter.h.

template<typename T >
planning_environment::PlanningMonitor* constraint_aware_spline_smoother::CubicSplineShortCutter< T >::planning_monitor_ [private]

Definition at line 62 of file cubic_spline_shortcutter.h.

template<typename T >
tf::TransformListener constraint_aware_spline_smoother::CubicSplineShortCutter< T >::tf_ [private]

Definition at line 64 of file cubic_spline_shortcutter.h.


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


constraint_aware_spline_smoother
Author(s): Sachin Chitta
autogenerated on Fri Jan 11 09:41:18 2013