Namespaces | Classes | Typedefs | Enumerations | Functions | Variables
xpp Namespace Reference

Namespaces

 biped
 
 quad
 

Classes

struct  Convert
 Converts between xpp-states types and xpp-messages. More...
 
class  Endeffectors
 Data structure to assign values to each endeffector. More...
 
class  EndeffectorsContact
 Bundles the contact state of all endeffectors. More...
 
class  EndeffectorsMotion
 Bundles the position, velocity and acceleration of all endeffectors. as well as appending a EndeffectorMotion specific convenience function. More...
 
class  Joints
 Container to access joint values of each endeffectors. More...
 
class  RobotStateCartesian
 Defines a complete robot state in Cartesian space. More...
 
class  RobotStateJoint
 Defines a complete robot state in joint space. More...
 
class  State3d
 6D-State (linear+angular) of an object in 3-dimensional space, where the angular part is expressed by a Quaternion. More...
 
class  State3dEuler
 6D-state (linear+angular) of an object in 3-dimensional space, where the angular part is expressed by Euler angles. More...
 
class  StateAng3d
 Angular state of an object in 3-dimensional space. More...
 
class  StateLin1d
 
class  StateLin2d
 
class  StateLin3d
 
class  StateLinXd
 Represents position, velocity and acceleration in x-dimensions. More...
 

Typedefs

using EndeffectorID = uint
 
using EndeffectorsAcc = Endeffectors< Eigen::Vector3d >
 
using EndeffectorsPos = Endeffectors< Eigen::Vector3d >
 
using EndeffectorsVel = Endeffectors< Eigen::Vector3d >
 
using Quaterniond = Eigen::Quaterniond
 
using Vector2d = Eigen::Vector2d
 
using Vector3d = Eigen::Vector3d
 
using Vector6d = Eigen::Matrix< double, 6, 1 >
 
using VectorXd = Eigen::VectorXd
 

Enumerations

enum  Coords2D { X_ =0, Y_ }
 
enum  Coords3D { X =0, Y, Z }
 
enum  Coords6D {
  AX =0, AY, AZ, LX,
  LY, LZ
}
 
enum  MotionDerivative { kPos =0, kVel, kAcc, kJerk }
 

Functions

static Vector3d GetEulerZYXAngles (const Quaterniond &q)
 Converts an orientation to Euler ZY'X'' convention. More...
 
static Quaterniond GetQuaternionFromEulerZYX (double yaw, double pitch, double roll)
 Converts an orientation to Quaternion from Euler ZY'X'' convention. More...
 
StateLinXd operator* (double mult, const StateLinXd &rhs)
 
StateLinXd operator+ (const StateLinXd &lhs, const StateLinXd &rhs)
 
std::ostream & operator<< (std::ostream &out, const StateLinXd &pos)
 
template<typename T >
std::ostream & operator<< (std::ostream &stream, Endeffectors< T > endeffectors)
 
std::ostream & operator<< (std::ostream &out, const StateAng3d &ori)
 
std::ostream & operator<< (std::ostream &out, const State3d &pose)
 
static Coords2D To2D (Coords3D dim)
 

Variables

static const Coords6D AllDim6D [] = {AX, AY, AZ, LX, LY, LZ}
 
static constexpr int kDim2d = 2
 
static constexpr int kDim3d = 3
 
static constexpr int kDim6d = 6
 

Typedef Documentation

using xpp::EndeffectorID = typedef uint

Definition at line 41 of file endeffectors.h.

using xpp::EndeffectorsAcc = typedef Endeffectors<Eigen::Vector3d>

Definition at line 119 of file endeffectors.h.

using xpp::EndeffectorsPos = typedef Endeffectors<Eigen::Vector3d>

Definition at line 117 of file endeffectors.h.

using xpp::EndeffectorsVel = typedef Endeffectors<Eigen::Vector3d>

Definition at line 118 of file endeffectors.h.

using xpp::Quaterniond = typedef Eigen::Quaterniond

Definition at line 51 of file state.h.

using xpp::Vector2d = typedef Eigen::Vector2d

Definition at line 47 of file state.h.

using xpp::Vector3d = typedef Eigen::Vector3d

Definition at line 48 of file state.h.

using xpp::Vector6d = typedef Eigen::Matrix<double,6,1>

Definition at line 49 of file state.h.

using xpp::VectorXd = typedef Eigen::VectorXd

Definition at line 50 of file state.h.

Enumeration Type Documentation

Enumerator
X_ 
Y_ 

Definition at line 45 of file cartesian_declarations.h.

Enumerator

Definition at line 49 of file cartesian_declarations.h.

Enumerator
AX 
AY 
AZ 
LX 
LY 
LZ 

Definition at line 59 of file cartesian_declarations.h.

Enumerator
kPos 
kVel 
kAcc 
kJerk 

Definition at line 53 of file state.h.

Function Documentation

static Vector3d xpp::GetEulerZYXAngles ( const Quaterniond q)
static

Converts an orientation to Euler ZY'X'' convention.

First rotate around z-axis, then around new y' axis, finally around newest x'' axis.

Parameters
qQuaternion expressing current orientation.
Returns
first element is roll angle in radians, then pitch, then yaw

Definition at line 206 of file state.h.

static Quaterniond xpp::GetQuaternionFromEulerZYX ( double  yaw,
double  pitch,
double  roll 
)
static

Converts an orientation to Quaternion from Euler ZY'X'' convention.

First rotate around z-axis, then around new y' axis, finally around newest x'' axis.

Definition at line 219 of file state.h.

StateLinXd xpp::operator* ( double  mult,
const StateLinXd rhs 
)
inline

Definition at line 251 of file state.h.

StateLinXd xpp::operator+ ( const StateLinXd lhs,
const StateLinXd rhs 
)
inline

Definition at line 242 of file state.h.

std::ostream& xpp::operator<< ( std::ostream &  out,
const StateLinXd pos 
)
inline

Definition at line 234 of file state.h.

template<typename T >
std::ostream& xpp::operator<< ( std::ostream &  stream,
Endeffectors< T >  endeffectors 
)

Definition at line 257 of file endeffectors.h.

std::ostream& xpp::operator<< ( std::ostream &  out,
const StateAng3d ori 
)
inline

Definition at line 273 of file state.h.

std::ostream& xpp::operator<< ( std::ostream &  out,
const State3d pose 
)
inline

Definition at line 283 of file state.h.

static Coords2D xpp::To2D ( Coords3D  dim)
static

Definition at line 50 of file cartesian_declarations.h.

Variable Documentation

const Coords6D xpp::AllDim6D[] = {AX, AY, AZ, LX, LY, LZ}
static

Definition at line 60 of file cartesian_declarations.h.

constexpr int xpp::kDim2d = 2
static

Definition at line 44 of file cartesian_declarations.h.

constexpr int xpp::kDim3d = 3
static

Definition at line 48 of file cartesian_declarations.h.

constexpr int xpp::kDim6d = 6
static

Definition at line 58 of file cartesian_declarations.h.



xpp_states
Author(s): Alexander W. Winkler
autogenerated on Tue Dec 8 2020 03:10:29