-
Notifications
You must be signed in to change notification settings - Fork 12
/
cart_pole_with_wall.py
executable file
·200 lines (165 loc) · 6.92 KB
/
cart_pole_with_wall.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
#!/usr/bin/env python
##
#
# A simple example to test Drake's new hydroelastic
# contact model: adding a wall to the cart-pole.
#
##
import time
import numpy as np
from pydrake.all import *
from ilqr import IterativeLinearQuadraticRegulator
import utils_derivs_interpolation
meshcat_visualisation = False
####################################
# Parameters
####################################
T = 1.0
dt = 1e-2
playback_rate = 0.2
# Parameters for derivative interpolation
use_derivative_interpolation = False # Use derivative interpolation
keypoint_method = 'setInterval' # 'setInterval, or 'adaptiveJerk' or 'iterativeError'
minN = 1 # Minimum interval between key-points
maxN = 100 # Maximum interval between key-points
jerk_threshold = 0.0007 # Jerk threshold to trigger new key-point (only used in adaptiveJerk)
iterative_error_threshold = 0.00005 # Error threshold to trigger new key-point (only used in iterativeError)
# Initial state
x0 = np.array([0,np.pi+0.5,0.0,0])
# Target state
x_nom = np.array([0,np.pi,0,0])
# Quadratic cost
Q = np.diag([0.1,1,0.01,0.01])
R = 0.001*np.eye(1)
Qf = np.diag([200,200,10,10])
# Contact model parameters
dissipation = 0.0 # controls "bounciness" of collisions: lower is bouncier
hydroelastic_modulus = 2e6 # controls "squishiness" of collisions: lower is squishier
resolution_hint = 0.05 # smaller means a finer mesh
penetration_allowance = 0.008 # controls "softenss" of collisions for point contact model
contact_model = ContactModel.kHydroelastic # Hydroelastic, Point, or HydroelasticWithFallback
mesh_type = HydroelasticContactRepresentation.kPolygon # Triangle or Polygon
####################################
# Tools for system setup
####################################
def create_system_model(plant):
# Add the cart-pole system
sdf = FindResourceOrThrow("drake/examples/multibody/cart_pole/cart_pole.sdf")
robot = Parser(plant=plant).AddModels(sdf)[0]
# Add a ball with compliant hydroelastic contact to the end of the cart-pole system
radius = 0.05
pole = plant.GetBodyByName("Pole")
X_BP = RigidTransform()
ball_props = ProximityProperties()
AddCompliantHydroelasticProperties(resolution_hint, hydroelastic_modulus, ball_props)
if contact_model == ContactModel.kPoint:
plant.set_penetration_allowance(penetration_allowance)
AddContactMaterial(friction=CoulombFriction(), properties=ball_props)
else:
AddContactMaterial(dissipation=dissipation, friction=CoulombFriction(), properties=ball_props)
plant.RegisterCollisionGeometry(pole, X_BP, Sphere(radius), "collision", ball_props)
orange = np.array([1.0, 0.55, 0.0, 0.5])
plant.RegisterVisualGeometry(pole, X_BP, Sphere(radius), "visual", orange)
# Add a wall with rigid hydroelastic contact
l,w,h = (0.1,1,2)
I_W = SpatialInertia(1, np.zeros(3), UnitInertia.SolidBox(l,w,h))
wall_instance = plant.AddModelInstance("wall")
wall = plant.AddRigidBody("wall", wall_instance, I_W)
wall_frame = plant.GetFrameByName("wall", wall_instance)
X_W = RigidTransform()
X_W.set_translation([-0.5,0,0])
plant.WeldFrames(plant.world_frame(), wall_frame, X_W)
plant.RegisterVisualGeometry(wall, RigidTransform(), Box(l,w,h), "wall_visual", orange)
wall_props = ProximityProperties()
AddRigidHydroelasticProperties(wall_props)
if contact_model == ContactModel.kPoint:
AddContactMaterial(friction=CoulombFriction(), properties=wall_props)
else:
AddContactMaterial(dissipation=dissipation, friction=CoulombFriction(), properties=wall_props)
plant.RegisterCollisionGeometry(wall, RigidTransform(),
Box(l,w,h), "wall_collision", wall_props)
# Choose contact model
plant.set_contact_surface_representation(mesh_type)
plant.set_contact_model(contact_model)
plant.Finalize()
return plant
####################################
# Create system diagram
####################################
builder = DiagramBuilder()
plant, scene_graph = AddMultibodyPlantSceneGraph(builder, dt)
plant = create_system_model(plant)
# Connect to visualizer
if meshcat_visualisation:
meshcat = StartMeshcat()
visualizer = MeshcatVisualizer.AddToBuilder(
builder, scene_graph, meshcat,
MeshcatVisualizerParams(role=Role.kPerception, prefix="visual"))
else:
DrakeVisualizer().AddToBuilder(builder, scene_graph)
ConnectContactResultsToDrakeVisualizer(builder, plant, scene_graph)
# Finailze the diagram
diagram = builder.Build()
diagram_context = diagram.CreateDefaultContext()
plant_context = diagram.GetMutableSubsystemContext(plant, diagram_context)
#####################################
## Solve Trajectory Optimization
#####################################
# Create system model for the solver to use. This system model
# has a single input port for the control and doesn't include
# any visualizer stuff.
builder_ = DiagramBuilder()
plant_, scene_graph_ = AddMultibodyPlantSceneGraph(builder_, dt)
plant_ = create_system_model(plant_)
builder_.ExportInput(plant_.get_actuation_input_port(), "control")
system_ = builder_.Build()
# Set up the optimizer
num_steps = int(T/dt)
if use_derivative_interpolation:
interpolation_method = utils_derivs_interpolation.derivs_interpolation(keypoint_method, minN, maxN, jerk_threshold, iterative_error_threshold)
else:
interpolation_method = None
ilqr = IterativeLinearQuadraticRegulator(system_, num_steps, beta=0.5, derivs_keypoint_method = interpolation_method)
# Define the optimization problem
ilqr.SetInitialState(x0)
ilqr.SetTargetState(x_nom)
ilqr.SetRunningCost(dt*Q, dt*R)
ilqr.SetTerminalCost(Qf)
# Set initial guess
#np.random.seed(0)
#u_guess = 0.01*np.random.normal(size=(1,num_steps-1))
u_guess = np.zeros((1,num_steps-1))
ilqr.SetInitialGuess(u_guess)
# Solve the optimization problem
states, inputs, solve_time, optimal_cost = ilqr.Solve()
print(f"Solved in {solve_time} seconds using iLQR")
print(f"Optimal cost: {optimal_cost}")
timesteps = np.arange(0.0,T,dt)
#####################################
# Playback
#####################################
while True:
plant.get_actuation_input_port().FixValue(plant_context, 0)
# Just keep playing back the trajectory
for i in range(len(timesteps)):
t = timesteps[i]
x = states[:,i]
diagram_context.SetTime(t)
plant.SetPositionsAndVelocities(plant_context, x)
diagram.ForcedPublish(diagram_context)
time.sleep(1/playback_rate*dt-4e-4)
time.sleep(1)
#####################################
## Run Simulation
#####################################
## Fix zero input for now
#plant.get_actuation_input_port().FixValue(plant_context, 0)
#
## Set initial state
#plant.SetPositionsAndVelocities(plant_context, x0)
#
## Simulate the system
#simulator = Simulator(diagram, diagram_context)
#simulator.set_target_realtime_rate(playback_rate)
#
#simulator.AdvanceTo(T)