Public Member Functions | Private Attributes
KDL::Path_Line Class Reference

#include <path_line.hpp>

Inheritance diagram for KDL::Path_Line:
Inheritance graph
[legend]

List of all members.

Public Member Functions

virtual Twist Acc (double s, double sd, double sdd) const
virtual PathClone ()
virtual IdentifierType getIdentifier () const
double LengthToS (double length)
 Path_Line (const Frame &F_base_start, const Frame &F_base_end, RotationalInterpolation *orient, double eqradius, bool _aggregate=true)
 Path_Line (const Frame &F_base_start, const Twist &twist_in_base, RotationalInterpolation *orient, double eqradius, bool _aggregate=true)
virtual double PathLength ()
virtual Frame Pos (double s) const
virtual Twist Vel (double s, double sd) const
virtual void Write (std::ostream &os)
virtual ~Path_Line ()

Private Attributes

bool aggregate
double eqradius
RotationalInterpolationorient
double pathlength
double scalelin
double scalerot
Vector V_base_end
Vector V_base_start
Vector V_start_end

Detailed Description

A path representing a line from A to B.

Definition at line 59 of file path_line.hpp.


Constructor & Destructor Documentation

KDL::Path_Line::Path_Line ( const Frame F_base_start,
const Frame F_base_end,
RotationalInterpolation orient,
double  eqradius,
bool  _aggregate = true 
)

Constructs a Line Path F_base_start and F_base_end give the begin and end frame wrt the base orient gives the method of rotation interpolation eqradius : equivalent radius : serves to compare rotations and translations. the "amount of motion"(pos,vel,acc) of the rotation is taken to be the amount motion of a point at distance eqradius from the rotation axis.

Eqradius is introduced because it is unavoidable that you have to compare rotations and translations : e.g. : You can have motions that only contain rotation, and motions that only contain translations. The motion planning goes as follows :

  • translation is planned with the given parameters
  • rotation is planned planned with the parameters calculated with eqradius.
  • The longest of the previous two remains unchanged, the shortest in duration is scaled to take as long as the longest. This guarantees that the geometric path in 6D space remains independent of the motion profile parameters.

RotationalInterpolation_SingleAxis() has the advantage that it is independent of the frame in which you express your path. Other implementations for RotationalInterpolations COULD be (not implemented) (yet) : 1) quaternion interpolation : but this is more difficult for the human to interprete 2) 3-axis interpolation : express the orientation of the frame in e.g. euler zyx angles alfa,beta, gamma and interpolate these parameters. But this is dependent of the frame you choose as a reference and their can occur representation singularities.

Definition at line 47 of file path_line.cpp.

KDL::Path_Line::Path_Line ( const Frame F_base_start,
const Twist twist_in_base,
RotationalInterpolation orient,
double  eqradius,
bool  _aggregate = true 
)

Definition at line 86 of file path_line.cpp.

Definition at line 148 of file path_line.cpp.


Member Function Documentation

Twist KDL::Path_Line::Acc ( double  s,
double  sd,
double  sdd 
) const [virtual]

Returns the acceleration twist at path length s and with derivative of s == sd, and 2nd derivative of s == sdd

Implements KDL::Path.

Definition at line 143 of file path_line.cpp.

Path * KDL::Path_Line::Clone ( ) [virtual]

Virtual constructor, constructing by copying, Returns a deep copy of this Path Object

Implements KDL::Path.

Definition at line 153 of file path_line.cpp.

virtual IdentifierType KDL::Path_Line::getIdentifier ( ) const [inline, virtual]

gets an identifier indicating the type of this Path object

Implements KDL::Path.

Definition at line 128 of file path_line.hpp.

double KDL::Path_Line::LengthToS ( double  length) [virtual]

LengthToS() converts a physical length along the trajectory to the parameter s used in Pos, Vel and Acc. This is used because in cases with large rotations the parameter s does NOT correspond to the lineair length along the trajectory. User should be sure that the lineair distance travelled by this path object is NOT zero, when using this method ! (e.g. the case of only rotational change) throws Error_MotionPlanning_Not_Applicable if used on composed path objects.

Implements KDL::Path.

Definition at line 129 of file path_line.cpp.

double KDL::Path_Line::PathLength ( ) [virtual]

Returns the total path length of the trajectory (has dimension LENGTH) This is not always a physical length , ie when dealing with rotations that are dominant.

Implements KDL::Path.

Definition at line 132 of file path_line.cpp.

Frame KDL::Path_Line::Pos ( double  s) const [virtual]

Returns the Frame at the current path length s

Implements KDL::Path.

Definition at line 135 of file path_line.cpp.

Twist KDL::Path_Line::Vel ( double  s,
double  sd 
) const [virtual]

Returns the velocity twist at path length s theta and with derivative of s == sd

Implements KDL::Path.

Definition at line 139 of file path_line.cpp.

void KDL::Path_Line::Write ( std::ostream &  os) [virtual]

Writes one of the derived objects to the stream

Implements KDL::Path.

Definition at line 173 of file path_line.cpp.


Member Data Documentation

bool KDL::Path_Line::aggregate [private]

Definition at line 76 of file path_line.hpp.

double KDL::Path_Line::eqradius [private]

Definition at line 69 of file path_line.hpp.

Definition at line 62 of file path_line.hpp.

double KDL::Path_Line::pathlength [private]

Definition at line 72 of file path_line.hpp.

double KDL::Path_Line::scalelin [private]

Definition at line 73 of file path_line.hpp.

double KDL::Path_Line::scalerot [private]

Definition at line 74 of file path_line.hpp.

Definition at line 66 of file path_line.hpp.

Definition at line 65 of file path_line.hpp.

Definition at line 67 of file path_line.hpp.


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


orocos_kdl
Author(s):
autogenerated on Mon Oct 6 2014 03:11:17