$search

walk Namespace Reference

Classes

class  BinaryReader
struct  BinaryReaderHelper
class  BinaryWriter
struct  BinaryWriterHelper
class  DiscretizedPatternGenerator2d
class  DiscretizedTrajectory
 A trajectory is a function which takes a time as its input and return a value. More...
class  PatternGenerator
 A pattern generator computes walking reference trajectories. More...
struct  PatternGeneratorTraits
struct  PatternGeneratorTraits< DiscretizedPatternGenerator2d >
struct  StampedFootprint
 Footprint with its associated timestamp. More...
struct  StampedPosition
 Position with its associated time duration. More...
class  YamlReader
 Unserialize data from a file into a specific pattern generator. More...
class  YamlWriter
 Write a YAML file to serialize a pattern generator computed trajectories. More...

Typedefs

typedef DiscretizedTrajectory
< StampedPosition2d
DiscretizedTrajectory2d
 DiscretizedTrajectory in $SO(2)$.
typedef DiscretizedTrajectory
< StampedPosition3d
DiscretizedTrajectory3d
 DiscretizedTrajectory in $SO(3)$.
typedef DiscretizedTrajectory
< StampedVectorNd
DiscretizedTrajectoryNd
 DiscretizedTrajectory in $R^n$.
typedef DiscretizedTrajectory
< StampedVector2d
DiscretizedTrajectoryV2d
 DiscretizedTrajectory in $R^2$.
typedef DiscretizedTrajectory
< StampedVector3d
DiscretizedTrajectoryV3d
 DiscretizedTrajectory in $R^3$.
typedef Eigen::Matrix< double, 3, 1 > Footprint2d
 2D footprint.
typedef Eigen::Matrix< double, 3, 3 > HomogeneousMatrix2d
 2D homogeneous matrix.
typedef Eigen::Matrix< double, 4, 4 > HomogeneousMatrix3d
 3D homogeneous matrix.
typedef Eigen::VectorXd Posture
 Posture (Eigen vector).
typedef StampedFootprint
< Footprint2d
StampedFootprint2d
 2d stamped footprints.
typedef StampedPosition
< HomogeneousMatrix2d
StampedPosition2d
 2d position with timestamp.
typedef StampedPosition
< HomogeneousMatrix3d
StampedPosition3d
 3d position with timestamp.
typedef StampedPosition
< Eigen::Vector2d > 
StampedVector2d
 2d vector with timestamp.
typedef StampedPosition
< Eigen::Vector3d > 
StampedVector3d
 3d vector with timestamp.
typedef StampedPosition
< Eigen::VectorXd > 
StampedVectorNd
 Nd vector with timestamp.
typedef boost::posix_time::ptime Time
 Time.
typedef
boost::posix_time::time_duration 
TimeDuration
 Duration.
typedef Eigen::Vector2d Vector2d
 2D vector.
typedef Eigen::Vector3d Vector3d
 3D vector.

Functions

template<typename T >
TimeDuration computeFootprintSequenceLength (const WALK_INTERFACES_EIGEN_STL_VECTOR(StampedFootprint< T >)&sequence)
 Compute a footprint sequence duration.
template<class T >
void convertToPosture (Posture &dst, const T &src)
 Convert a structure of any size to a Posture object.
template<class T >
void convertToTrans3d (HomogeneousMatrix3d &dst, const T &src)
 Convert a row-major homogeneous 3d matrix to a HomogeneousMatrix3d type.
template<class T >
void convertToVector2d (Vector2d &dst, const T &src)
 Convert a structure of size 2 to a Vector2d object.
template<class T >
void convertToVector3d (Vector3d &dst, const T &src)
 Convert a structure of size 3 to a Vector3d object.
template<class T >
void convertVector3dToTrans3d (HomogeneousMatrix3d &dst, const T &src)
 Convert a structure of size 3 to a Homogeneous 3d matrix.
template<typename T >
std::ostream & operator<< (std::ostream &os, const StampedPosition< T > &sp)
 Display a stamped position.
template<typename T >
std::ostream & operator<< (std::ostream &stream, const StampedFootprint< T > &sf)
 Display a stamped footprint.
template<typename T >
std::ostream & operator<< (std::ostream &stream, const PatternGenerator< T > &pg)
 Display a pattern generator.
template<typename T >
std::ostream & operator<< (std::ostream &stream, const DiscretizedTrajectory< T > &trajectory)
 Display a trajectory.
template<typename T >
BinaryWriterHelperoperator<< (BinaryWriterHelper &helper, const PatternGenerator< T > &pg)
template<typename T >
void operator>> (const YAML::Node &node, PatternGenerator< T > &pg)
 Unserialize pattern generator data.
template<typename T >
BinaryReaderHelperoperator>> (BinaryReaderHelper &helper, BinaryReader< T > &pg)
template<class U >
void trans2dToTrans3d (U &dst, const double &srcX, const double &srcY, const double &srcTh)
template<class U , class V >
void trans2dToTrans3d (U &dst, const V &src)
typedef WALK_INTERFACES_EIGEN_STL_VECTOR (Footprint2d) Footprint2dSequence
 Vector of 2d footprints.
typedef WALK_INTERFACES_EIGEN_STL_VECTOR (StampedFootprint< Footprint2d >) StampedFootprint2dSequence
 Vector of 2d stamped footprints.

Typedef Documentation

DiscretizedTrajectory in $SO(2)$.

Definition at line 68 of file discretized-trajectory.hh.

DiscretizedTrajectory in $SO(3)$.

Definition at line 66 of file discretized-trajectory.hh.

DiscretizedTrajectory in $R^n$.

Definition at line 74 of file discretized-trajectory.hh.

DiscretizedTrajectory in $R^2$.

Definition at line 70 of file discretized-trajectory.hh.

DiscretizedTrajectory in $R^3$.

Definition at line 72 of file discretized-trajectory.hh.

typedef Eigen::Matrix<double, 3, 1> walk::Footprint2d

2D footprint.

Definition at line 36 of file types.hh.

typedef Eigen::Matrix<double, 3, 3> walk::HomogeneousMatrix2d

2D homogeneous matrix.

3x3 matrix representing an element of $SO(2)$.

Definition at line 28 of file types.hh.

typedef Eigen::Matrix<double, 4, 4> walk::HomogeneousMatrix3d

3D homogeneous matrix.

4x4 matrix representing an element of $SO(3)$.

Definition at line 23 of file types.hh.

typedef Eigen::VectorXd walk::Posture

Posture (Eigen vector).

Definition at line 39 of file types.hh.

2d stamped footprints.

Definition at line 42 of file stamped-footprint.hh.

2d position with timestamp.

Definition at line 33 of file stamped-position.hh.

3d position with timestamp.

Definition at line 31 of file stamped-position.hh.

typedef StampedPosition<Eigen::Vector2d> walk::StampedVector2d

2d vector with timestamp.

Definition at line 35 of file stamped-position.hh.

typedef StampedPosition<Eigen::Vector3d> walk::StampedVector3d

3d vector with timestamp.

Definition at line 37 of file stamped-position.hh.

typedef StampedPosition<Eigen::VectorXd> walk::StampedVectorNd

Nd vector with timestamp.

Definition at line 39 of file stamped-position.hh.

typedef boost::posix_time::ptime walk::Time

Time.

Definition at line 42 of file types.hh.

typedef boost::posix_time::time_duration walk::TimeDuration

Duration.

Definition at line 44 of file types.hh.

typedef Eigen::Vector2d walk::Vector2d

2D vector.

Definition at line 31 of file types.hh.

typedef Eigen::Vector3d walk::Vector3d

3D vector.

Definition at line 33 of file types.hh.


Function Documentation

template<typename T >
TimeDuration walk::computeFootprintSequenceLength ( const WALK_INTERFACES_EIGEN_STL_VECTOR(StampedFootprint< T >)&  sequence  )  [inline]

Compute a footprint sequence duration.

A footprint sequence is defined as a sequence of stamped footprints.

The length (in time) of a footprint sequence is defined by the duration separating the begin time of the first footprint and the end time of the last footprint.

Template Parameters:
T Tootprint type.
template<class T >
void walk::convertToPosture ( Posture &  dst,
const T &  src 
) [inline]

Convert a structure of any size to a Posture object.

Parameters:
src input structure.
dst output vector of type Posture.

Definition at line 142 of file util.hh.

template<class T >
void walk::convertToTrans3d ( HomogeneousMatrix3d &  dst,
const T &  src 
) [inline]

Convert a row-major homogeneous 3d matrix to a HomogeneousMatrix3d type.

Parameters:
src input homogeneous 3d matrix.
dst output matrix of type Homogeneous3d.

Definition at line 96 of file util.hh.

template<class T >
void walk::convertToVector2d ( Vector2d &  dst,
const T &  src 
) [inline]

Convert a structure of size 2 to a Vector2d object.

Parameters:
src input structure.
dst output vector of type Vector2d.

Definition at line 115 of file util.hh.

template<class T >
void walk::convertToVector3d ( Vector3d &  dst,
const T &  src 
) [inline]

Convert a structure of size 3 to a Vector3d object.

Parameters:
src input structure.
dst output vector of type Vector3d.

Definition at line 128 of file util.hh.

template<class T >
void walk::convertVector3dToTrans3d ( HomogeneousMatrix3d &  dst,
const T &  src 
) [inline]

Convert a structure of size 3 to a Homogeneous 3d matrix.

Parameters:
src input structure.
dst output matrix of type Homogeneous3d.

Definition at line 75 of file util.hh.

template<typename T >
std::ostream& walk::operator<< ( std::ostream &  os,
const StampedPosition< T > &  sp 
) [inline]

Display a stamped position.

Parameters:
os Output stream.
sp Stamped position.

Definition at line 47 of file stamped-position.hh.

template<typename T >
std::ostream& walk::operator<< ( std::ostream &  stream,
const StampedFootprint< T > &  sf 
) [inline]

Display a stamped footprint.

Parameters:
stream Output stream.
sf Stamped footprint.
template<typename T >
std::ostream& walk::operator<< ( std::ostream &  stream,
const PatternGenerator< T > &  pg 
) [inline]

Display a pattern generator.

Parameters:
stream Output stream.
pg Pattern generator.
template<typename T >
std::ostream& walk::operator<< ( std::ostream &  stream,
const DiscretizedTrajectory< T > &  trajectory 
) [inline]

Display a trajectory.

Parameters:
stream Output stream
trajectory Displayed trajectory
template<typename T >
BinaryWriterHelper& walk::operator<< ( BinaryWriterHelper &  helper,
const PatternGenerator< T > &  pg 
) [inline]
template<typename T >
void walk::operator>> ( const YAML::Node &  node,
PatternGenerator< T > &  pg 
) [inline]

Unserialize pattern generator data.

template<typename T >
BinaryReaderHelper& walk::operator>> ( BinaryReaderHelper &  helper,
BinaryReader< T > &  pg 
) [inline]
template<class U >
void walk::trans2dToTrans3d ( U &  dst,
const double &  srcX,
const double &  srcY,
const double &  srcTh 
) [inline]

Definition at line 47 of file util.hh.

template<class U , class V >
void walk::trans2dToTrans3d ( U &  dst,
const V &  src 
) [inline]

Definition at line 16 of file util.hh.

typedef walk::WALK_INTERFACES_EIGEN_STL_VECTOR ( Footprint2d   ) 

Vector of 2d footprints.

typedef walk::WALK_INTERFACES_EIGEN_STL_VECTOR ( StampedFootprint< Footprint2d >   ) 

Vector of 2d stamped footprints.

 All Classes Namespaces Files Functions Variables Typedefs Enumerations Friends Defines


walk_interfaces
Author(s): Thomas Moulard/thomas.moulard@gmail.com, Antonio El Khoury
autogenerated on Fri Mar 1 15:43:01 2013