cassie-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("cassie")
9 
10 constraint_models = robot.constraint_models
11 
12 data = pinocchio.Data(robot.model)
13 
14 pinocchio.forwardKinematics(robot.model, robot.data, robot.q0)
15 
16 foot_joints = ["left-plantar-foot-joint", "right-plantar-foot-joint"]
17 foot_joint_ids = [robot.model.getJointId(joint_name) for joint_name in foot_joints]
18 
19 front_placement = pinocchio.SE3(np.identity(3), np.array([-0.1, 0.11, 0.0]))
20 
21 back_placement = pinocchio.SE3(np.identity(3), np.array([0.03, -0.0, 0.0]))
22 
23 foot_length = np.linalg.norm(front_placement.translation - back_placement.translation)
24 
25 
26 # Add contact robot.model for contact with ground
27 
28 mid_point = np.zeros(3)
29 
30 for joint_id in foot_joint_ids:
31  joint2_placement = robot.data.oMi[joint_id] * front_placement
32  joint2_placement.translation[2] = 0
33  contact_model_lf1 = pinocchio.RigidConstraintModel(
34  pinocchio.ContactType.CONTACT_3D,
35  robot.model,
36  joint_id,
37  front_placement,
38  0,
39  joint2_placement,
40  pinocchio.ReferenceFrame.LOCAL,
41  )
42 
43  mid_point += joint2_placement.translation
44  joint2_placement.translation[0] -= foot_length
45 
46  contact_model_lf2 = pinocchio.RigidConstraintModel(
47  pinocchio.ContactType.CONTACT_3D,
48  robot.model,
49  joint_id,
50  back_placement,
51  0,
52  joint2_placement,
53  pinocchio.ReferenceFrame.LOCAL,
54  )
55 
56  mid_point += joint2_placement.translation
57  constraint_models.extend([contact_model_lf1, contact_model_lf2])
58 
59 mid_point /= 4.0
60 
61 
62 robot.setVisualizer(GepettoVisualizer())
63 robot.initViewer()
64 robot.loadViewerModel("pinocchio")
65 gui = robot.viewer.gui
66 robot.display(robot.q0)
67 q0 = robot.q0.copy()
68 constraint_datas = pinocchio.StdVec_RigidConstraintData()
69 for cm in constraint_models:
70  constraint_datas.append(cm.createData())
71 
72 
73 def update_axis(q):
74  pinocchio.forwardKinematics(robot.model, robot.data, q)
75  for j, cm in enumerate(robot.constraint_models):
76  pos1 = robot.data.oMi[cm.joint1_id] * cm.joint1_placement
77  pos2 = robot.data.oMi[cm.joint2_id] * cm.joint2_placement
78  name1 = "hpp-gui/cm1_" + str(j)
79  name2 = "hpp-gui/cm2_" + str(j)
80  gui.applyConfiguration(name1, list(pinocchio.SE3ToXYZQUAT(pos1)))
81  gui.applyConfiguration(name2, list(pinocchio.SE3ToXYZQUAT(pos2)))
82  gui.refresh()
83 
84 
85 def check_joint(model, nj):
86  for k in range(model.joints[nj].nv):
87  for res in range(200):
88  q1 = robot.q0.copy()
89  theta = res * 2.0 * np.pi / 200.0
90  v = np.zeros(robot.model.nv)
91  v[robot.model.idx_vs[nj] + k] = theta
92  q1 = pinocchio.integrate(robot.model, q1, v)
93  robot.display(q1)
94  update_axis(q1)
95  sleep(0.005)
96 
97 
98 q = q0.copy()
99 
100 pinocchio.computeAllTerms(robot.model, robot.data, q, np.zeros(robot.model.nv))
101 kkt_constraint = pinocchio.ContactCholeskyDecomposition(robot.model, constraint_models)
102 constraint_dim = sum([cm.size() for cm in constraint_models])
103 N = 1000
104 eps = 1e-6
105 mu = 1e-4
106 # q_sol = (q[:] + np.pi) % np.pi - np.pi
107 q_sol = q.copy()
108 
109 window_id = robot.viewer.gui.getWindowID("python-pinocchio")
110 robot.viewer.gui.setBackgroundColor1(window_id, [1.0, 1.0, 1.0, 1.0])
111 robot.viewer.gui.setBackgroundColor2(window_id, [1.0, 1.0, 1.0, 1.0])
112 robot.viewer.gui.addFloor("hpp-gui/floor")
113 robot.viewer.gui.setScale("hpp-gui/floor", [0.5, 0.5, 0.5])
114 robot.viewer.gui.setColor("hpp-gui/floor", [0.7, 0.7, 0.7, 1.0])
115 robot.viewer.gui.setLightingMode("hpp-gui/floor", "OFF")
116 
117 
118 axis_size = 0.08
119 radius = 0.005
120 transparency = 0.5
121 
122 for j, cm in enumerate(constraint_models):
123  pos1 = robot.data.oMi[cm.joint1_id] * cm.joint1_placement
124  pos2 = robot.data.oMi[cm.joint2_id] * cm.joint2_placement
125  name1 = "hpp-gui/cm1_" + str(j)
126  name2 = "hpp-gui/cm2_" + str(j)
127  red_color = 1.0 * float(j) / float(len(constraint_models))
128  print(red_color)
129  robot.viewer.gui.addXYZaxis(
130  name1, [red_color, 1.0, 1.0 - red_color, transparency], radius, axis_size
131  )
132  robot.viewer.gui.addXYZaxis(
133  name2, [red_color, 1.0, 1.0 - red_color, transparency], radius, axis_size
134  )
135 
136  gui.applyConfiguration(name1, list(pinocchio.SE3ToXYZQUAT(pos1)))
137  gui.applyConfiguration(name2, list(pinocchio.SE3ToXYZQUAT(pos2)))
138  gui.refresh()
139  gui.setVisibility(name1, "OFF")
140  gui.setVisibility(name2, "OFF")
141 
142 
143 mid_point_name = "hpp-gui/mid_point"
144 mid_point_pos = pinocchio.SE3(np.identity(3), mid_point)
145 robot.viewer.gui.addXYZaxis(
146  mid_point_name, [0.0, 0.0, 1.0, transparency], radius, axis_size
147 )
148 
149 
150 gui.applyConfiguration(mid_point_name, list(pinocchio.SE3ToXYZQUAT(mid_point_pos)))
151 gui.setVisibility(mid_point_name, "ALWAYS_ON_TOP")
152 
153 robot.display(q_sol)
154 
155 # Bring CoM between the two feet.
156 
157 mass = robot.data.mass[0]
158 
159 com_base = robot.data.com[0].copy()
160 com_base[:2] = mid_point[:2]
161 com_drop_amp = 0.1
162 
163 
164 def com_des(k):
165  return com_base - np.array([0.0, 0.0, np.abs(com_drop_amp)])
166 
167 
168 def squashing(model, data, q_in, Nin=N, epsin=eps, verbose=True):
169  q = q_in.copy()
170  y = np.ones(constraint_dim)
171 
172  _N_full = 200
173 
174  # Decrease CoMz by 0.2
175  pinocchio.computeAllTerms(robot.model, robot.data, q, np.zeros(robot.model.nv))
176  kp = np.array([1.0, 1.0, 0.1])
177 
178  for k in range(Nin):
179  pinocchio.computeAllTerms(robot.model, robot.data, q, np.zeros(robot.model.nv))
180  pinocchio.computeJointJacobians(robot.model, robot.data, q)
181  com_act = robot.data.com[0].copy()
182  com_err = com_act - com_des(k)
183  kkt_constraint.compute(
184  robot.model, robot.data, constraint_models, constraint_datas, mu
185  )
186  constraint_value1 = np.concatenate(
187  [pinocchio.log(cd.c1Mc2) for cd in constraint_datas[:-4]]
188  )
189  constraint_value2 = np.concatenate(
190  [cd.c1Mc2.translation for cd in constraint_datas[-4:]]
191  )
192  constraint_value = np.concatenate([constraint_value1, constraint_value2])
193 
194  J1 = np.vstack(
195  [
197  robot.model,
198  data,
199  cm.joint1_id,
200  cm.joint1_placement,
201  cm.reference_frame,
202  )
203  for cm in constraint_models[:-4]
204  ]
205  )
206  J2 = np.vstack(
207  [
209  robot.model,
210  data,
211  cm.joint1_id,
212  cm.joint1_placement,
213  cm.reference_frame,
214  )[:3, :]
215  for cm in constraint_models[-4:]
216  ]
217  )
218  J = np.vstack([J1, J2])
219  primal_feas = np.linalg.norm(constraint_value, np.inf)
220 
221  dual_feas = np.linalg.norm(J.T.dot(constraint_value + y), np.inf)
222  if primal_feas < epsin and dual_feas < epsin:
223  print("Convergence achieved")
224  break
225  if verbose:
226  print("constraint_value:", np.linalg.norm(constraint_value))
227  print("com_error:", np.linalg.norm(com_err))
228  print("com_des", com_des(k))
229  print("com_act", com_act)
230  rhs = np.concatenate(
231  [-constraint_value - y * mu, kp * com_err, np.zeros(robot.model.nv - 3)]
232  )
233  dz = kkt_constraint.solve(rhs)
234  dy = dz[:constraint_dim]
235  dq = dz[constraint_dim:]
236  alpha = 1.0
237  q = pinocchio.integrate(robot.model, q, -alpha * dq)
238  y -= alpha * (-dy + y)
239  robot.display(q)
240  update_axis(q)
241  gui.applyConfiguration(
242  mid_point_name,
243  list(pinocchio.SE3ToXYZQUAT(pinocchio.SE3(np.identity(3), com_des(k)))),
244  )
245  sleep(0.0)
246  return q
247 
248 
249 qin = robot.q0.copy()
250 for k in range(1000):
251  qout = squashing(robot.model, data, qin)
252  qout[3:6] = 0.0
253  qout[6] = 1.0
254  qin = qout.copy()
255 
256 qout = squashing(robot.model, data, qin, Nin=100000, epsin=1e-10, verbose=False)
cassie-simulation.com_des
def com_des(k)
Definition: cassie-simulation.py:164
pinocchio::DataTpl
Definition: context/generic.hpp:25
pinocchio.visualize
Definition: bindings/python/pinocchio/visualize/__init__.py:1
pinocchio::SE3Tpl< context::Scalar, context::Options >
cassie-simulation.squashing
def squashing(model, data, q_in, Nin=N, epsin=eps, verbose=True)
Definition: cassie-simulation.py:168
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
cassie-simulation.check_joint
def check_joint(model, nj)
Definition: cassie-simulation.py:85
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::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
cassie-simulation.update_axis
def update_axis(q)
Definition: cassie-simulation.py:73


pinocchio
Author(s):
autogenerated on Sun Dec 22 2024 03:41:06