Public Member Functions | Private Member Functions | Private Attributes
constraint_aware_spline_smoother::LinearSplineShortCutter< T > Class Template Reference

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

#include <linear_spline_shortcutter.h>

Inheritance diagram for constraint_aware_spline_smoother::LinearSplineShortCutter< T >:
Inheritance graph
[legend]

List of all members.

Public Member Functions

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

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::CollisionModelsInterfacecollision_models_interface_
double discretization_
ros::NodeHandle node_handle_

Detailed Description

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

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

Definition at line 57 of file linear_spline_shortcutter.h.


Constructor & Destructor Documentation

Construct the smoother.

Definition at line 126 of file linear_spline_shortcutter.h.

Definition at line 135 of file linear_spline_shortcutter.h.


Member Function Documentation

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

Definition at line 538 of file linear_spline_shortcutter.h.

template<typename T >
bool constraint_aware_spline_smoother::LinearSplineShortCutter< T >::configure ( void  ) [virtual]

Configure the filter with the discretization for returned trajectories.

Todo:
check length

Reimplemented from spline_smoother::SplineSmoother< T >.

Definition at line 111 of file linear_spline_shortcutter.h.

template<typename T >
void constraint_aware_spline_smoother::LinearSplineShortCutter< 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 [private]

Definition at line 394 of file linear_spline_shortcutter.h.

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

Definition at line 374 of file linear_spline_shortcutter.h.

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

Definition at line 482 of file linear_spline_shortcutter.h.

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

Definition at line 140 of file linear_spline_shortcutter.h.

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

Definition at line 148 of file linear_spline_shortcutter.h.

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

Definition at line 520 of file linear_spline_shortcutter.h.

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

Definition at line 438 of file linear_spline_shortcutter.h.

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

Definition at line 330 of file linear_spline_shortcutter.h.

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

Definition at line 301 of file linear_spline_shortcutter.h.

Definition at line 580 of file linear_spline_shortcutter.h.

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

Implements spline_smoother::SplineSmoother< T >.

Definition at line 156 of file linear_spline_shortcutter.h.

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

Definition at line 454 of file linear_spline_shortcutter.h.


Member Data Documentation

Definition at line 71 of file linear_spline_shortcutter.h.

Definition at line 74 of file linear_spline_shortcutter.h.

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

Definition at line 72 of file linear_spline_shortcutter.h.

Definition at line 75 of file linear_spline_shortcutter.h.


The documentation for this class was generated from the following file:


constraint_aware_spline_smoother
Author(s): Sachin Chitta
autogenerated on Thu Dec 12 2013 11:10:27