I am trying to compute product of \dot{J}\dot{q} in drake, where J is augmented form of angular and linear jacobian. For linear part only, I know that it can be done by CalcBiasTranslationalAcceleration function. The return type is Eigen::Vector3d
Eigen::Vector3d mdJv_dq = mplant.CalcBiasTranslationalAcceleration(*mContext,
multibody::JacobianWrtVariable::kV,
*mFrame_EE,
Eigen::Vector3d::Zero(),
mplant.world_frame(),
mplant.world_frame()
);
However, if I need to calculate both the linear and angular jacobain bias, I have to use SpatialAcceleration MultibodyPlant::CalcBiasSpatialAcceleration() and the function is as follow
multibody::SpatialAcceleration<double> mdJ_Aug_dq_robot1 = mplant.CalcBiasSpatialAcceleration(*mContext,
multibody::JacobianWrtVariable::kQDot,
*mFrame_EE,
Eigen::Vector3d::Zero(),
mplant.world_frame(),
mplant.world_frame()
);
Now the return type is spatialacceleration. If we need to use it along with Eigen::Matrix<double, 6,1> like subtracting the two quantities, we get an error as follow
no match for 'operator-' (operand types are 'Eigen::Matrix<double, 6, 1>' and 'drake::multibody::SpatialAcceleration<double>')
I could not find a method to utilize both of them togethor or converting spatialAcceleration quantity to Eigen. Any help and guidance will be appreciated.
You should be able to use get_coeffs()
method of SpatialAcceleration
to get the Eigen vector out then use normal Eigen operations. doxygen link
Or you can call SpatialAcceleration(my_other_eigen_vector)
to lift your Eigen vector up into a SpatialAcceleration
.