Go to the documentation of this file.
39 p_ = VectorXd::Zero(dim);
40 v_ = VectorXd::Zero(dim);
41 a_ = VectorXd::Zero(dim);
47 :StateLinXd(_p.rows())
55 :StateLinXd(_p.rows())
64 case kPos:
return p_;
break;
65 case kVel:
return v_;
break;
66 case kAcc:
return a_;
break;
67 default:
throw std::runtime_error(
"[StateLinXd::GetByIndex] derivative not part of state");
75 case kPos:
return p_;
break;
76 case kVel:
return v_;
break;
77 case kAcc:
return a_;
break;
78 default:
throw std::runtime_error(
"[StateLinXd::GetByIndex] derivative not part of state");
105 h_xd.segment(
AX, 3) =
ang.
w;
const VectorXd GetByIndex(MotionDerivative deriv) const
Read either position, velocity of acceleration by index.
StateLin3d lin
linear position, velocity and acceleration
VectorXd a_
position, velocity and acceleration
Vector3d w
angular velocity (omega).
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.
static constexpr int kDim2d
Eigen::Matrix< double, 6, 1 > Vector6d
Represents position, velocity and acceleration in x-dimensions.
StateLinXd(int _dim=0)
Constructs an object of dimensions _dim.
Vector3d wd
angular acceleration (omega dot).
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