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


pinocchio
Author(s):
autogenerated on Sat Sep 28 2024 02:41:16