talos-simulation.py
Go to the documentation of this file.
1 from time import sleep
2 
3 import example_robot_data
4 import numpy as np
5 import pinocchio
6 from pinocchio.visualize import GepettoVisualizer
7 
8 robot = example_robot_data.load("talos")
9 model = robot.model
10 data = robot.data
11 
12 state_name = "half_sitting"
13 
14 robot.q0 = robot.model.referenceConfigurations[state_name]
15 
16 pinocchio.forwardKinematics(model, data, robot.q0)
17 
18 lfFoot, rfFoot, lhFoot, rhFoot = (
19  "left_sole_link",
20  "right_sole_link",
21  "gripper_left_fingertip_3_link",
22  "gripper_right_fingertip_3_link",
23 )
24 
25 foot_frames = [lfFoot, rfFoot, lhFoot, rhFoot]
26 foot_frame_ids = [robot.model.getFrameId(frame_name) for frame_name in foot_frames]
27 foot_joint_ids = [
28  robot.model.frames[robot.model.getFrameId(frame_name)].parent
29  for frame_name in foot_frames
30 ]
31 pinocchio.forwardKinematics(model, data, robot.q0)
32 pinocchio.framesForwardKinematics(model, data, robot.q0)
33 
34 constraint_models = []
35 
36 for j, frame_id in enumerate(foot_frame_ids):
37  contact_model_lf1 = pinocchio.RigidConstraintModel(
38  pinocchio.ContactType.CONTACT_6D,
39  robot.model,
40  foot_joint_ids[j],
41  robot.model.frames[frame_id].placement,
42  0,
43  data.oMf[frame_id],
44  )
45  constraint_models.extend([contact_model_lf1])
46 
47 # Change arm position
48 constraint_models[3].joint2_placement = pinocchio.SE3(
49  pinocchio.rpy.rpyToMatrix(np.array([0.0, -np.pi / 2, 0.0])),
50  np.array([0.6, -0.40, 1.0]),
51 )
52 
53 constraint_models[2].joint2_placement = pinocchio.SE3(
54  pinocchio.rpy.rpyToMatrix(np.array([0, -np.pi / 2, 0.0])), np.array([0.6, 0.4, 1.0])
55 )
56 
57 robot.setVisualizer(GepettoVisualizer())
58 robot.initViewer()
59 robot.loadViewerModel("pinocchio")
60 gui = robot.viewer.gui
61 robot.display(robot.q0)
62 window_id = robot.viewer.gui.getWindowID("python-pinocchio")
63 
64 robot.viewer.gui.setBackgroundColor1(window_id, [1.0, 1.0, 1.0, 1.0])
65 robot.viewer.gui.setBackgroundColor2(window_id, [1.0, 1.0, 1.0, 1.0])
66 robot.viewer.gui.addFloor("hpp-gui/floor")
67 
68 robot.viewer.gui.setScale("hpp-gui/floor", [0.5, 0.5, 0.5])
69 robot.viewer.gui.setColor("hpp-gui/floor", [0.7, 0.7, 0.7, 1.0])
70 robot.viewer.gui.setLightingMode("hpp-gui/floor", "OFF")
71 
72 robot.display(robot.q0)
73 
74 constraint_datas = [cm.createData() for cm in constraint_models]
75 
76 q = robot.q0.copy()
77 
78 pinocchio.computeAllTerms(model, data, q, np.zeros(model.nv))
79 kkt_constraint = pinocchio.ContactCholeskyDecomposition(model, constraint_models)
80 constraint_dim = sum([cm.size() for cm in constraint_models])
81 N = 100000
82 eps = 1e-10
83 mu = 1e-8 # 0.
84 # q_sol = (q[:] + np.pi) % np.pi - np.pi
85 q_sol = q.copy()
86 robot.display(q_sol)
87 
88 # Bring CoM between the two feet.
89 
90 mass = data.mass[0]
91 
92 
93 def squashing(model, data, q_in):
94  q = q_in.copy()
95  y = np.ones(constraint_dim)
96 
97  N_full = 200
98 
99  # Decrease CoMz by 0.2
100  com_drop_amp = 0.1
101  pinocchio.computeAllTerms(model, data, q, np.zeros(model.nv))
102  com_base = data.com[0].copy()
103  kp = 1.0
104  speed = 1.0
105 
106  def com_des(k):
107  return com_base - np.array(
108  [
109  0.0,
110  0.0,
111  np.abs(com_drop_amp * np.sin(2.0 * np.pi * k * speed / (N_full))),
112  ]
113  )
114 
115  for k in range(N):
116  pinocchio.computeAllTerms(model, data, q, np.zeros(model.nv))
117  pinocchio.computeJointJacobians(model, data, q)
118  pinocchio.computeJointJacobians(model, data, q)
119  com_act = data.com[0].copy()
120  com_err = com_act - com_des(k)
121  kkt_constraint.compute(model, data, constraint_models, constraint_datas, mu)
122  constraint_value = np.concatenate(
123  [pinocchio.log6(cd.c1Mc2) for cd in constraint_datas]
124  )
125  J = np.vstack(
126  [
128  model, data, cm.joint1_id, cm.joint1_placement, cm.reference_frame
129  )
130  for cm in constraint_models
131  ]
132  )
133  primal_feas = np.linalg.norm(constraint_value, np.inf)
134  print(J.shape, constraint_value.shape, y.shape)
135  dual_feas = np.linalg.norm(J.T.dot(constraint_value + y), np.inf)
136  print("primal_feas:", primal_feas)
137  print("dual_feas:", dual_feas)
138  # if primal_feas < eps and dual_feas < eps:
139  # print("Convergence achieved")
140  # break
141  print("constraint_value:", np.linalg.norm(constraint_value))
142  print("com_error:", np.linalg.norm(com_err))
143  rhs = np.concatenate(
144  [-constraint_value - y * mu, kp * mass * com_err, np.zeros(model.nv - 3)]
145  )
146  dz = kkt_constraint.solve(rhs)
147  dy = dz[:constraint_dim]
148  dq = dz[constraint_dim:]
149  alpha = 1.0
150  q = pinocchio.integrate(model, q, -alpha * dq)
151  y -= alpha * (-dy + y)
152  robot.display(q)
153  sleep(0.05)
154  return q
155 
156 
157 q_new = squashing(model, data, robot.q0)
talos-simulation.squashing
def squashing(model, data, q_in)
Definition: talos-simulation.py:93
cassie-simulation.com_des
def com_des(k)
Definition: cassie-simulation.py:164
pinocchio.visualize
Definition: bindings/python/pinocchio/visualize/__init__.py:1
pinocchio::SE3Tpl< context::Scalar, context::Options >
pinocchio::rpy::rpyToMatrix
Eigen::Matrix< typename Vector3Like::Scalar, 3, 3, PINOCCHIO_EIGEN_PLAIN_TYPE(Vector3Like)::Options > rpyToMatrix(const Eigen::MatrixBase< Vector3Like > &rpy)
Convert from Roll, Pitch, Yaw to rotation Matrix.
pinocchio::forwardKinematics
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...
pinocchio::RigidConstraintModelTpl
Definition: algorithm/constraints/fwd.hpp:14
pinocchio::integrate
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.
pinocchio::framesForwardKinematics
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....
pinocchio::computeJointJacobians
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....
pinocchio::getFrameJacobian
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,...
Definition: frames.hpp:394
pinocchio::copy
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...
Definition: copy.hpp:42
pinocchio::ContactCholeskyDecompositionTpl< context::Scalar, context::Options >
pinocchio::computeAllTerms
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.visualize.gepetto_visualizer.GepettoVisualizer
Definition: gepetto_visualizer.py:18
pinocchio::log6
MotionTpl< typename Matrix4Like::Scalar, Eigen::internal::traits< Matrix4Like >::Options > log6(const Eigen::MatrixBase< Matrix4Like > &M)
Log: SE3 -> se3.
Definition: spatial/explog.hpp:475


pinocchio
Author(s):
autogenerated on Fri Nov 1 2024 02:41:48