Go to the documentation of this file.
20 #include <pinocchio/multibody/model.hpp>
21 #include <pinocchio/parsers/urdf.hpp>
34 RobotWrapper::RobotWrapper(
const std::string&
filename,
35 const std::vector<std::string>&,
bool verbose)
46 const std::vector<std::string>&,
108 data.M.triangularView<Eigen::StrictlyLower>() =
109 data.M.transpose().triangularView<Eigen::StrictlyLower>();
125 "The size of the rotor_inertias vector is incorrect!");
134 "The size of the gear_ratios vector is incorrect!");
178 "The index needs to be less than the size of the oMi vector");
186 "The index needs to be less than the size of the v vector");
194 "The index needs to be less than the size of the a vector");
203 "The index needs to be less than the size of the oMi vector");
212 "The index needs to be less than the size of the oMi vector");
219 "Frame index greater than size of frame "
220 "vector in model - frame may not exist");
222 return data.oMi[
f.parent].act(
f.placement);
227 SE3& framePosition)
const {
229 "Frame index greater than size of frame "
230 "vector in model - frame may not exist");
238 "Frame index greater than size of frame "
239 "vector in model - frame may not exist");
241 return f.placement.actInv(
data.v[
f.parent]);
246 Motion& frameVelocity)
const {
248 "Frame index greater than size of frame "
249 "vector in model - frame may not exist");
257 SE3 oMi, oMi_rotation_only;
260 oMi_rotation_only.rotation(oMi.rotation());
261 v_world = oMi_rotation_only.act(v_local);
268 "Frame index greater than size of frame "
269 "vector in model - frame may not exist");
271 return f.placement.actInv(
data.a[
f.parent]);
276 Motion& frameAcceleration)
const {
278 "Frame index greater than size of frame "
279 "vector in model - frame may not exist");
287 SE3 oMi, oMi_rotation_only;
290 oMi_rotation_only.rotation(oMi.rotation());
291 a_world = oMi_rotation_only.act(a_local);
298 "Frame index greater than size of frame "
299 "vector in model - frame may not exist");
303 a.linear() +=
v.angular().cross(
v.linear());
309 Motion& frameAcceleration)
const {
311 "Frame index greater than size of frame "
312 "vector in model - frame may not exist");
322 SE3 oMi, oMi_rotation_only;
325 oMi_rotation_only.rotation(oMi.rotation());
326 a_world = oMi_rotation_only.act(a_local);
333 "Frame index greater than size of frame "
334 "vector in model - frame may not exist");
341 "Frame index greater than size of frame "
342 "vector in model - frame may not exist");
SE3 framePosition(const Data &data, const Model::FrameIndex index) const
virtual bool is_fixed_base() const
Motion frameVelocity(const Data &data, const Model::FrameIndex index) const
Motion frameClassicAccelerationWorldOriented(const Data &data, const Model::FrameIndex index) const
const Matrix & mass(const Data &data)
#define PINOCCHIO_CHECK_INPUT_ARGUMENT(...)
void frameJacobianWorld(Data &data, const Model::FrameIndex index, Data::Matrix6x &J) const
const Vector & nonLinearEffects(const Data &data) const
const Motion & velocity(const Data &data, const Model::JointIndex index) const
Vector3 angularMomentumTimeVariation(const Data &data) const
Eigen::Matrix< Scalar, 6, Eigen::Dynamic, Options > getJointJacobian(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const JointIndex joint_id, const ReferenceFrame reference_frame)
void setGravity(const Motion &gravity)
Model m_model
Robot model.
const Vector & gear_ratios() const
const Vector & rotor_inertias() const
pinocchio::JointIndex JointIndex
math::ConstRefVector ConstRefVector
Motion frameClassicAcceleration(const Data &data, const Model::FrameIndex index) const
virtual int nq_actuated() const
const Model & model() const
Accessor to model.
void updateFramePlacements(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data)
JointCollectionDefault::JointModelVariant JointModelVariant
void com(const Data &data, RefVector com_pos, RefVector com_vel, RefVector com_acc) const
const DataTpl< Scalar, Options, JointCollectionTpl >::Matrix6x & ccrba(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v)
pinocchio::FrameIndex FrameIndex
math::RefVector RefVector
void frameJacobianLocal(Data &data, const Model::FrameIndex index, Data::Matrix6x &J) const
const DataTpl< Scalar, Options, JointCollectionTpl >::Force & computeCentroidalMomentumTimeVariation(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data)
std::string m_model_filename
ModelTpl< Scalar, Options, JointCollectionTpl > & buildModel(const std::shared_ptr<::urdf::ModelInterface > urdfTree, const typename ModelTpl< Scalar, Options, JointCollectionTpl >::JointModel &rootJoint, const std::string &rootJointName, ModelTpl< Scalar, Options, JointCollectionTpl > &model, const bool verbose=false, const bool mimic=false)
const Data::Matrix6x & momentumJacobian(const Data &data) const
void computeAllTerms(Data &data, const Vector &q, const Vector &v) const
const DataTpl< Scalar, Options, JointCollectionTpl >::Vector3 & centerOfMass(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const bool computeSubtreeComs=true)
void jacobianLocal(const Data &data, const Model::JointIndex index, Data::Matrix6x &J) const
Eigen::Matrix< Scalar, 6, Eigen::Dynamic, Options > getFrameJacobian(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const FrameIndex frame_id, const ReferenceFrame reference_frame)
void jacobianWorld(const Data &data, const Model::JointIndex index, Data::Matrix6x &J) const
Motion frameVelocityWorldOriented(const Data &data, const Model::FrameIndex index) const
const Motion & acceleration(const Data &data, const Model::JointIndex index) const
const Matrix3x & Jcom(const Data &data) const
Eigen::Matrix< Scalar, 6, Eigen::Dynamic, Options > Matrix6x
RobotWrapper(const std::string &filename, const std::vector< std::string > &package_dirs, bool verbose=false)
Matrix m_M
diagonal part of inertia matrix due to rotor inertias
enum tsid::robots::RobotWrapper::e_RootJointType RootJointType
const Vector3 & com_acc(const Data &data) const
const Vector3 & com_vel(const Data &data) const
const SE3 & position(const Data &data, const Model::JointIndex index) const
void computeAllTerms(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v)
Motion frameAccelerationWorldOriented(const Data &data, const Model::FrameIndex index) const
Motion frameAcceleration(const Data &data, const Model::FrameIndex index) const
tsid
Author(s): Andrea Del Prete, Justin Carpentier
autogenerated on Thu Apr 3 2025 02:47:15