Go to the documentation of this file.
5 from example_robot_data
import load
11 state_name =
"standing"
13 robot.q0 = robot.model.referenceConfigurations[state_name]
17 lfFoot, rfFoot, lhFoot, rhFoot =
"LF_FOOT",
"RF_FOOT",
"LH_FOOT",
"RH_FOOT"
19 foot_frames = [lfFoot, rfFoot, lhFoot, rhFoot]
20 foot_frame_ids = [robot.model.getFrameId(frame_name)
for frame_name
in foot_frames]
22 robot.model.frames[robot.model.getFrameId(frame_name)].parent
23 for frame_name
in foot_frames
28 constraint_models = []
30 for j, frame_id
in enumerate(foot_frame_ids):
32 pinocchio.ContactType.CONTACT_3D,
35 robot.model.frames[frame_id].placement,
40 constraint_models.extend([contact_model_lf1])
43 robot.loadViewerModel(
"pinocchio")
44 robot.display(robot.q0)
46 constraint_datas = [cm.createData()
for cm
in constraint_models]
52 constraint_dim = sum([cm.size()
for cm
in constraint_models])
67 y = np.ones(constraint_dim)
74 com_base = data.com[0].
copy()
79 return com_base - np.array(
83 np.abs(com_drop_amp * np.sin(2.0 * np.pi * k * speed / (N_full))),
91 com_act = data.com[0].
copy()
93 kkt_constraint.compute(model, data, constraint_models, constraint_datas, mu)
94 constraint_value = np.concatenate(
95 [cd.c1Mc2.translation
for cd
in constraint_datas]
103 model, data, cm.joint1_id, cm.joint1_placement, cm.reference_frame
105 for cm
in constraint_models
108 primal_feas = np.linalg.norm(constraint_value, np.inf)
109 dual_feas = np.linalg.norm(J.T.dot(constraint_value + y), np.inf)
110 print(
"primal_feas:", primal_feas)
111 print(
"dual_feas:", dual_feas)
115 print(
"constraint_value:", np.linalg.norm(constraint_value))
116 print(
"com_error:", np.linalg.norm(com_err))
117 rhs = np.concatenate(
118 [-constraint_value - y * mu, kp * mass * com_err, np.zeros(model.nv - 3)]
120 dz = kkt_constraint.solve(rhs)
121 dy = dz[:constraint_dim]
122 dq = dz[constraint_dim:]
125 y -= alpha * (-dy + y)
void load(Archive &ar, Eigen::array< _IndexType, _NumIndices > &a, const unsigned int)
void forwardKinematics(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType1 > &v, const Eigen::MatrixBase< TangentVectorType2 > &a)
Update the joint placements, spatial velocities and spatial accelerations according to the current jo...
def squashing(model, data, q_in)
void integrate(const LieGroupGenericTpl< LieGroupCollection > &lg, const Eigen::MatrixBase< ConfigIn_t > &q, const Eigen::MatrixBase< Tangent_t > &v, const Eigen::MatrixBase< ConfigOut_t > &qout)
Visit a LieGroupVariant to call its integrate method.
void framesForwardKinematics(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q)
First calls the forwardKinematics on the model, then computes the placement of each frame....
const DataTpl< Scalar, Options, JointCollectionTpl >::Matrix6x & computeJointJacobians(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data)
Computes the full model Jacobian, i.e. the stack of all motion subspace expressed in the world frame....
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)
Returns the jacobian of the frame expressed either expressed in the local frame coordinate system,...
void copy(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &origin, DataTpl< Scalar, Options, JointCollectionTpl > &dest, KinematicLevel kinematic_level)
Copy part of the data from origin to dest. Template parameter can be used to select at which differen...
void computeAllTerms(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v)
Computes efficiently all the terms needed for dynamic simulation. It is equivalent to the call at the...
pinocchio
Author(s):
autogenerated on Sun Dec 22 2024 03:41:06