#include <vector>#include <Eigen/Core>#include <boost/date_time/posix_time/posix_time.hpp>

Go to the source code of this file.
| Namespaces | |
| namespace | walk | 
| Defines | |
| #define | WALK_INTERFACES_EIGEN_STL_VECTOR(T) std::vector<T, Eigen::aligned_allocator<std::pair<const int, T> > > | 
| Define a vector of elements containing Eigen objects. | |
| Typedefs | |
| typedef Eigen::Matrix< double, 3, 1 > | walk::Footprint2d | 
| 2D footprint. | |
| typedef Eigen::Matrix< double, 3, 3 > | walk::HomogeneousMatrix2d | 
| 2D homogeneous matrix. | |
| typedef Eigen::Matrix< double, 4, 4 > | walk::HomogeneousMatrix3d | 
| 3D homogeneous matrix. | |
| typedef Eigen::VectorXd | walk::Posture | 
| Posture (Eigen vector). | |
| typedef boost::posix_time::ptime | walk::Time | 
| Time. | |
| typedef boost::posix_time::time_duration | walk::TimeDuration | 
| Duration. | |
| typedef Eigen::Vector2d | walk::Vector2d | 
| 2D vector. | |
| typedef Eigen::Vector3d | walk::Vector3d | 
| 3D vector. | |
| Functions | |
| typedef | walk::WALK_INTERFACES_EIGEN_STL_VECTOR (Footprint2d) Footprint2dSequence | 
| Vector of 2d footprints. | |
| #define WALK_INTERFACES_EIGEN_STL_VECTOR | ( | T | ) | std::vector<T, Eigen::aligned_allocator<std::pair<const int, T> > > | 
Define a vector of elements containing Eigen objects.
The STL containers containing Eigen matrices must use a specific allocator. This macro wraps the type definition.
It is not possible to use a typedef in this case as templated typedef are not supported in C++03 (unlike C++11).