simulation-inverted-pendulum.py
Go to the documentation of this file.
1 import pinocchio as pin
2 import hppfcl as fcl
3 import numpy as np
4 import math
5 import time
6 import sys
7 
8 N = 10 # number of pendulums
9 model = pin.Model()
10 geom_model = pin.GeometryModel()
11 
12 parent_id = 0
13 joint_placement = pin.SE3.Identity()
14 body_mass = 1.0
15 body_radius = 0.1
16 
17 shape0 = fcl.Sphere(body_radius)
18 geom0_obj = pin.GeometryObject("base", 0, pin.SE3.Identity(), shape0)
19 geom0_obj.meshColor = np.array([1.0, 0.1, 0.1, 1.0])
20 geom_model.addGeometryObject(geom0_obj)
21 
22 for k in range(N):
23  joint_name = "joint_" + str(k + 1)
24  joint_id = model.addJoint(
25  parent_id, pin.JointModelRY(), joint_placement, joint_name
26  )
27 
28  body_inertia = pin.Inertia.FromSphere(body_mass, body_radius)
29  body_placement = joint_placement.copy()
30  body_placement.translation[2] = 1.0
31  model.appendBodyToJoint(joint_id, body_inertia, body_placement)
32 
33  geom1_name = "ball_" + str(k + 1)
34  shape1 = fcl.Sphere(body_radius)
35  geom1_obj = pin.GeometryObject(geom1_name, joint_id, body_placement, shape1)
36  geom1_obj.meshColor = np.ones((4))
37  geom_model.addGeometryObject(geom1_obj)
38 
39  geom2_name = "bar_" + str(k + 1)
40  shape2 = fcl.Cylinder(body_radius / 4.0, body_placement.translation[2])
41  shape2_placement = body_placement.copy()
42  shape2_placement.translation[2] /= 2.0
43 
44  geom2_obj = pin.GeometryObject(geom2_name, joint_id, shape2_placement, shape2)
45  geom2_obj.meshColor = np.array([0.0, 0.0, 0.0, 1.0])
46  geom_model.addGeometryObject(geom2_obj)
47 
48  parent_id = joint_id
49  joint_placement = body_placement.copy()
50 
51 from pinocchio.visualize import GepettoVisualizer
52 
53 visual_model = geom_model
54 viz = GepettoVisualizer(model, geom_model, visual_model)
55 
56 # Initialize the viewer.
57 try:
58  viz.initViewer()
59 except ImportError as err:
60  print(
61  "Error while initializing the viewer. It seems you should install gepetto-viewer"
62  )
63  print(err)
64  sys.exit(0)
65 
66 try:
67  viz.loadViewerModel("pinocchio")
68 except AttributeError as err:
69  print(
70  "Error while loading the viewer model. It seems you should start gepetto-viewer"
71  )
72  print(err)
73  sys.exit(0)
74 
75 # Display a robot configuration.
76 q0 = pin.neutral(model)
77 viz.display(q0)
78 
79 # Play a bit with the simulation
80 dt = 0.01
81 T = 5
82 
83 N = math.floor(T / dt)
84 
85 model.lowerPositionLimit.fill(-math.pi)
86 model.upperPositionLimit.fill(+math.pi)
87 q = pin.randomConfiguration(model)
88 v = np.zeros((model.nv))
89 
90 t = 0.0
91 data_sim = model.createData()
92 for k in range(N):
93  tau_control = np.zeros((model.nv))
94  a = pin.aba(model, data_sim, q, v, tau_control) # Forward dynamics
95 
96  v += a * dt
97  # q += v*dt
98  q = pin.integrate(model, q, v * dt)
99 
100  viz.display(q)
101  time.sleep(dt)
102  t += dt
pinocchio.visualize
Definition: bindings/python/pinocchio/visualize/__init__.py:1
pinocchio.visualize.gepetto_visualizer.GepettoVisualizer
Definition: gepetto_visualizer.py:20


pinocchio
Author(s):
autogenerated on Tue Jun 25 2024 02:42:40