Go to the documentation of this file.
30 #ifndef _XPP_STATES_STATE_H_
31 #define _XPP_STATES_STATE_H_
34 #include <Eigen/Dense>
49 using Vector6d = Eigen::Matrix<double,6,1>;
122 class StateLin2d :
public StateLinXd {
128 class StateLin3d :
public StateLinXd {
166 :
q(_q),
w(_w),
wd(_wd) {}
208 Vector3d yaw_pitch_roll = q.normalized().toRotationMatrix().eulerAngles(
Z,
Y,
X);
209 return yaw_pitch_roll.reverse();
221 using namespace Eigen;
224 q = AngleAxisd(yaw, Vector3d::UnitZ())
225 * AngleAxisd(pitch, Vector3d::UnitY())
226 * AngleAxisd(roll, Vector3d::UnitX());
236 out <<
"p=" << pos.p_.transpose() <<
" "
237 <<
"v=" << pos.v_.transpose() <<
" "
238 <<
"a=" << pos.a_.transpose();
242 inline StateLinXd
operator+(
const StateLinXd& lhs,
const StateLinXd& rhs)
244 StateLinXd ret(lhs.kNumDim);
245 ret.p_ = lhs.p_ + rhs.p_;
246 ret.v_ = lhs.v_ + rhs.v_;
247 ret.a_ = lhs.a_ + rhs.a_;
251 inline StateLinXd
operator*(
double mult,
const StateLinXd& rhs)
253 StateLinXd ret(rhs.kNumDim);
254 ret.p_ = mult * rhs.p_;
255 ret.v_ = mult * rhs.v_;
256 ret.a_ = mult * rhs.a_;
262 bool all_equal = (
p_==other.p_
270 return !(*
this == other);
273 inline std::ostream&
operator<<(std::ostream& out,
const StateAng3d& ori)
277 out <<
"rpy=" << rpy_rad.transpose() <<
" "
278 <<
"v=" << ori.w.transpose() <<
" "
279 <<
"a=" << ori.wd.transpose();
283 inline std::ostream&
operator<<(std::ostream& out,
const State3d& pose)
285 out <<
"\tPos: " << pose.lin <<
"\n"
286 <<
"\tOri: " << pose.ang;
292 #endif // _XPP_STATES_STATE_H_
const VectorXd GetByIndex(MotionDerivative deriv) const
Read either position, velocity of acceleration by index.
StateLinXd operator+(const StateLinXd &lhs, const StateLinXd &rhs)
6D-State (linear+angular) of an object in 3-dimensional space, where the angular part is expressed by...
std::ostream & operator<<(std::ostream &stream, Endeffectors< T > endeffectors)
StateLin3d lin
linear position, velocity and acceleration
VectorXd a_
position, velocity and acceleration
6D-state (linear+angular) of an object in 3-dimensional space, where the angular part is expressed by...
Angular state of an object in 3-dimensional space.
StateLin3d lin
linear position, velocity and acceleration
Vector3d w
angular velocity (omega).
static Vector3d GetEulerZYXAngles(const Quaterniond &q)
Converts an orientation to Euler ZY'X'' convention.
bool operator==(const StateLinXd &other) const
Returns true if this state has all same pos,vel and acc as other.
StateLin2d Get2D() const
Extracts only the 2-dimensional part (x,y) from this 3-D state.
Vector6d Get6dVel() const
Vector6d Get6dAcc() const
StateAng3d ang
Quaternion, velocity and acceleration.
StateLin3d ang
roll-pitch-yaw Euler angles, rates- and rate derivatives.
bool operator!=(const StateLinXd &other) const
Returns true if just one value in this state differs from other.
StateLinXd operator*(double mult, const StateLinXd &rhs)
virtual ~StateLinXd()=default
Eigen::Matrix< double, 6, 1 > Vector6d
static Quaterniond GetQuaternionFromEulerZYX(double yaw, double pitch, double roll)
Converts an orientation to Quaternion from Euler ZY'X'' convention.
Represents position, velocity and acceleration in x-dimensions.
StateAng3d(Quaterniond _q=Quaterniond(1.0, 0.0, 0.0, 0.0), Vector3d _w=Vector3d::Zero(), Vector3d _wd=Vector3d::Zero())
Builds an angular state.
StateLinXd(int _dim=0)
Constructs an object of dimensions _dim.
Eigen::Quaterniond Quaterniond
Vector3d wd
angular acceleration (omega dot).
Quaterniond q
orientation expressed as Quaternion.
int kNumDim
the number of dimenions this state represents.
xpp_states
Author(s): Alexander W. Winkler
autogenerated on Wed Mar 2 2022 01:14:14