Using an operational space controller#
Sometimes, controlling the end-effector pose of the robot using a differential IK controller is not sufficient. For example, we might want to enforce a very specific pose tracking error dynamics in the task space, actuate the robot with joint effort/torque commands, or apply a contact force at a specific direction while controlling the motion of the other directions (e.g., washing the surface of the table with a cloth). In such tasks, we can use an operational space controller (OSC).
References for the operational space control:
O Khatib. A unified approach for motion and force control of robot manipulators: The operational space formulation. IEEE Journal of Robotics and Automation, 3(1):43–53, 1987. URL http://dx.doi.org/10.1109/JRA.1987.1087068.
Robot Dynamics Lecture Notes by Marco Hutter (ETH Zurich). URL https://ethz.ch/content/dam/ethz/special-interest/mavt/robotics-n-intelligent-systems/rsl-dam/documents/RobotDynamics2017/RD_HS2017script.pdf
In this tutorial, we will learn how to use an OSC to control the robot.
We will use the controllers.OperationalSpaceController class to apply a constant force perpendicular to a
tilted wall surface while tracking a desired end-effector pose in all the other directions.
The Code#
The tutorial corresponds to the run_osc.py script in the
scripts/tutorials/05_controllers directory.
Code for run_osc.py
1# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md).
2# All rights reserved.
3#
4# SPDX-License-Identifier: BSD-3-Clause
5
6"""
7This script demonstrates how to use the operational space controller (OSC) with the simulator.
8
9The OSC controller can be configured in different modes. It uses the dynamical quantities such as Jacobians and
10mass matricescomputed by PhysX.
11
12.. code-block:: bash
13
14 # Usage
15 ./isaaclab.sh -p scripts/tutorials/05_controllers/run_osc.py
16
17"""
18
19"""Launch Isaac Sim Simulator first."""
20
21import argparse
22
23import warp as wp
24
25from isaaclab.app import AppLauncher
26
27# add argparse arguments
28parser = argparse.ArgumentParser(description="Tutorial on using the operational space controller.")
29parser.add_argument("--num_envs", type=int, default=128, help="Number of environments to spawn.")
30# append AppLauncher cli args
31AppLauncher.add_app_launcher_args(parser)
32# parse the arguments
33args_cli = parser.parse_args()
34
35# launch omniverse app
36app_launcher = AppLauncher(args_cli)
37simulation_app = app_launcher.app
38
39"""Rest everything follows."""
40
41import torch
42
43import isaaclab.sim as sim_utils
44from isaaclab.assets import Articulation, AssetBaseCfg
45from isaaclab.controllers import OperationalSpaceController, OperationalSpaceControllerCfg
46from isaaclab.markers import VisualizationMarkers
47from isaaclab.markers.config import FRAME_MARKER_CFG
48from isaaclab.scene import InteractiveScene, InteractiveSceneCfg
49from isaaclab.sensors import ContactSensorCfg
50from isaaclab.utils import configclass
51from isaaclab.utils.math import (
52 combine_frame_transforms,
53 matrix_from_quat,
54 quat_apply_inverse,
55 quat_inv,
56 subtract_frame_transforms,
57)
58
59##
60# Pre-defined configs
61##
62from isaaclab_assets import FRANKA_PANDA_HIGH_PD_CFG # isort:skip
63
64
65@configclass
66class SceneCfg(InteractiveSceneCfg):
67 """Configuration for a simple scene with a tilted wall."""
68
69 # ground plane
70 ground = AssetBaseCfg(
71 prim_path="/World/defaultGroundPlane",
72 spawn=sim_utils.GroundPlaneCfg(),
73 )
74
75 # lights
76 dome_light = AssetBaseCfg(
77 prim_path="/World/Light", spawn=sim_utils.DomeLightCfg(intensity=3000.0, color=(0.75, 0.75, 0.75))
78 )
79
80 # Tilted wall
81 tilted_wall = AssetBaseCfg(
82 prim_path="{ENV_REGEX_NS}/TiltedWall",
83 spawn=sim_utils.CuboidCfg(
84 size=(2.0, 1.5, 0.01),
85 collision_props=sim_utils.CollisionPropertiesCfg(),
86 visual_material=sim_utils.PreviewSurfaceCfg(diffuse_color=(1.0, 0.0, 0.0), opacity=0.1),
87 rigid_props=sim_utils.RigidBodyPropertiesCfg(kinematic_enabled=True),
88 activate_contact_sensors=True,
89 ),
90 init_state=AssetBaseCfg.InitialStateCfg(
91 pos=(0.6 + 0.085, 0.0, 0.3), rot=(0.0, -0.3826834324, 0.0, 0.9238795325)
92 ),
93 )
94
95 contact_forces = ContactSensorCfg(
96 prim_path="/World/envs/env_.*/TiltedWall",
97 update_period=0.0,
98 history_length=2,
99 debug_vis=False,
100 )
101
102 robot = FRANKA_PANDA_HIGH_PD_CFG.replace(prim_path="{ENV_REGEX_NS}/Robot")
103 robot.actuators["panda_shoulder"].stiffness = 0.0
104 robot.actuators["panda_shoulder"].damping = 0.0
105 robot.actuators["panda_forearm"].stiffness = 0.0
106 robot.actuators["panda_forearm"].damping = 0.0
107 robot.spawn.rigid_props.disable_gravity = True
108
109
110def run_simulator(sim: sim_utils.SimulationContext, scene: InteractiveScene):
111 """Runs the simulation loop.
112
113 Args:
114 sim: (SimulationContext) Simulation context.
115 scene: (InteractiveScene) Interactive scene.
116 """
117
118 # Extract scene entities for readability.
119 robot = scene["robot"]
120 contact_forces = scene["contact_forces"]
121
122 # Obtain indices for the end-effector and arm joints
123 ee_frame_name = "panda_leftfinger"
124 arm_joint_names = ["panda_joint.*"]
125 ee_frame_idx = robot.find_bodies(ee_frame_name)[0][0]
126 arm_joint_ids = robot.find_joints(arm_joint_names)[0]
127
128 # Create the OSC
129 osc_cfg = OperationalSpaceControllerCfg(
130 target_types=["pose_abs", "wrench_abs"],
131 impedance_mode="variable_kp",
132 inertial_dynamics_decoupling=True,
133 partial_inertial_dynamics_decoupling=False,
134 gravity_compensation=False,
135 motion_damping_ratio_task=1.0,
136 contact_wrench_stiffness_task=[0.0, 0.0, 0.1, 0.0, 0.0, 0.0],
137 motion_control_axes_task=[1, 1, 0, 1, 1, 1],
138 contact_wrench_control_axes_task=[0, 0, 1, 0, 0, 0],
139 nullspace_control="position",
140 )
141 osc = OperationalSpaceController(osc_cfg, num_envs=scene.num_envs, device=sim.device)
142
143 # Markers
144 frame_marker_cfg = FRAME_MARKER_CFG.copy()
145 frame_marker_cfg.markers["frame"].scale = (0.1, 0.1, 0.1)
146 ee_marker = VisualizationMarkers(frame_marker_cfg.replace(prim_path="/Visuals/ee_current"))
147 goal_marker = VisualizationMarkers(frame_marker_cfg.replace(prim_path="/Visuals/ee_goal"))
148
149 # Define targets for the arm (x,y,z,qx,qy,qz,qw)
150 ee_goal_pose_set_tilted_b = torch.tensor(
151 [
152 [0.6, 0.15, 0.3, 0.0, 0.38268343, 0.0, 0.92387953],
153 [0.6, -0.3, 0.3, 0.0, 0.38268343, 0.0, 0.92387953],
154 [0.8, 0.0, 0.5, 0.0, 0.38268343, 0.0, 0.92387953],
155 ],
156 device=sim.device,
157 )
158 ee_goal_wrench_set_tilted_task = torch.tensor(
159 [
160 [0.0, 0.0, 10.0, 0.0, 0.0, 0.0],
161 [0.0, 0.0, 10.0, 0.0, 0.0, 0.0],
162 [0.0, 0.0, 10.0, 0.0, 0.0, 0.0],
163 ],
164 device=sim.device,
165 )
166 kp_set_task = torch.tensor(
167 [
168 [360.0, 360.0, 360.0, 360.0, 360.0, 360.0],
169 [420.0, 420.0, 420.0, 420.0, 420.0, 420.0],
170 [320.0, 320.0, 320.0, 320.0, 320.0, 320.0],
171 ],
172 device=sim.device,
173 )
174 ee_target_set = torch.cat([ee_goal_pose_set_tilted_b, ee_goal_wrench_set_tilted_task, kp_set_task], dim=-1)
175
176 # Define simulation stepping
177 sim_dt = sim.get_physics_dt()
178
179 # Update existing buffers
180 # Note: We need to update buffers before the first step for the controller.
181 robot.update(dt=sim_dt)
182
183 # Get the center of the robot soft joint limits
184 joint_centers = torch.mean(wp.to_torch(robot.data.soft_joint_pos_limits)[:, arm_joint_ids, :], dim=-1)
185
186 # get the updated states
187 (
188 jacobian_b,
189 mass_matrix,
190 gravity,
191 ee_pose_b,
192 ee_vel_b,
193 root_pose_w,
194 ee_pose_w,
195 ee_force_b,
196 joint_pos,
197 joint_vel,
198 ) = update_states(sim, scene, robot, ee_frame_idx, arm_joint_ids, contact_forces)
199
200 # Track the given target command
201 current_goal_idx = 0 # Current goal index for the arm
202 command = torch.zeros(
203 scene.num_envs, osc.action_dim, device=sim.device
204 ) # Generic target command, which can be pose, position, force, etc.
205 ee_target_pose_b = torch.zeros(scene.num_envs, 7, device=sim.device) # Target pose in the body frame
206 ee_target_pose_w = torch.zeros(scene.num_envs, 7, device=sim.device) # Target pose in the world frame (for marker)
207
208 # Set joint efforts to zero
209 zero_joint_efforts = torch.zeros(scene.num_envs, robot.num_joints, device=sim.device)
210 joint_efforts = torch.zeros(scene.num_envs, len(arm_joint_ids), device=sim.device)
211
212 count = 0
213 # Simulation loop
214 while simulation_app.is_running():
215 # reset every 500 steps
216 if count % 500 == 0:
217 # reset joint state to default
218 default_joint_pos = wp.to_torch(robot.data.default_joint_pos).clone()
219 default_joint_vel = wp.to_torch(robot.data.default_joint_vel).clone()
220 robot.write_joint_position_to_sim_index(position=default_joint_pos)
221 robot.write_joint_velocity_to_sim_index(velocity=default_joint_vel)
222 robot.set_joint_effort_target_index(target=zero_joint_efforts) # Set zero torques in the initial step
223 robot.write_data_to_sim()
224 robot.reset()
225 # reset contact sensor
226 contact_forces.reset()
227 # reset target pose
228 robot.update(sim_dt)
229 _, _, _, ee_pose_b, _, _, _, _, _, _ = update_states(
230 sim, scene, robot, ee_frame_idx, arm_joint_ids, contact_forces
231 ) # at reset, the jacobians are not updated to the latest state
232 command, ee_target_pose_b, ee_target_pose_w, current_goal_idx = update_target(
233 sim, scene, osc, root_pose_w, ee_target_set, current_goal_idx
234 )
235 # set the osc command
236 osc.reset()
237 command, task_frame_pose_b = convert_to_task_frame(osc, command=command, ee_target_pose_b=ee_target_pose_b)
238 osc.set_command(command=command, current_ee_pose_b=ee_pose_b, current_task_frame_pose_b=task_frame_pose_b)
239 else:
240 # get the updated states
241 (
242 jacobian_b,
243 mass_matrix,
244 gravity,
245 ee_pose_b,
246 ee_vel_b,
247 root_pose_w,
248 ee_pose_w,
249 ee_force_b,
250 joint_pos,
251 joint_vel,
252 ) = update_states(sim, scene, robot, ee_frame_idx, arm_joint_ids, contact_forces)
253 # compute the joint commands
254 joint_efforts = osc.compute(
255 jacobian_b=jacobian_b,
256 current_ee_pose_b=ee_pose_b,
257 current_ee_vel_b=ee_vel_b,
258 current_ee_force_b=ee_force_b,
259 mass_matrix=mass_matrix,
260 gravity=gravity,
261 current_joint_pos=joint_pos,
262 current_joint_vel=joint_vel,
263 nullspace_joint_pos_target=joint_centers,
264 )
265 # apply actions
266 robot.set_joint_effort_target_index(target=joint_efforts, joint_ids=arm_joint_ids)
267 robot.write_data_to_sim()
268
269 # update marker positions
270 ee_marker.visualize(ee_pose_w[:, 0:3], ee_pose_w[:, 3:7])
271 goal_marker.visualize(ee_target_pose_w[:, 0:3], ee_target_pose_w[:, 3:7])
272
273 # perform step
274 sim.step(render=True)
275 # update robot buffers
276 robot.update(sim_dt)
277 # update buffers
278 scene.update(sim_dt)
279 # update sim-time
280 count += 1
281
282
283# Update robot states
284def update_states(
285 sim: sim_utils.SimulationContext,
286 scene: InteractiveScene,
287 robot: Articulation,
288 ee_frame_idx: int,
289 arm_joint_ids: list[int],
290 contact_forces,
291):
292 """Update the robot states.
293
294 Args:
295 sim: (SimulationContext) Simulation context.
296 scene: (InteractiveScene) Interactive scene.
297 robot: (Articulation) Robot articulation.
298 ee_frame_idx: (int) End-effector frame index.
299 arm_joint_ids: (list[int]) Arm joint indices.
300 contact_forces: (ContactSensor) Contact sensor.
301
302 Returns:
303 jacobian_b (torch.tensor): Jacobian in the body frame.
304 mass_matrix (torch.tensor): Mass matrix.
305 gravity (torch.tensor): Gravity vector.
306 ee_pose_b (torch.tensor): End-effector pose in the body frame.
307 ee_vel_b (torch.tensor): End-effector velocity in the body frame.
308 root_pose_w (torch.tensor): Root pose in the world frame.
309 ee_pose_w (torch.tensor): End-effector pose in the world frame.
310 ee_force_b (torch.tensor): End-effector force in the body frame.
311 joint_pos (torch.tensor): The joint positions.
312 joint_vel (torch.tensor): The joint velocities.
313
314 Raises:
315 ValueError: Undefined target_type.
316 """
317 # obtain dynamics related quantities from simulation
318 ee_jacobi_idx = ee_frame_idx - 1
319 jacobian_w = robot.root_view.get_jacobians()[:, ee_jacobi_idx, :, arm_joint_ids]
320 mass_matrix = robot.root_view.get_generalized_mass_matrices()[:, arm_joint_ids, :][:, :, arm_joint_ids]
321 gravity = robot.root_view.get_gravity_compensation_forces()[:, arm_joint_ids]
322 # Convert the Jacobian from world to root frame
323 jacobian_b = jacobian_w.clone()
324 root_rot_matrix = matrix_from_quat(quat_inv(wp.to_torch(robot.data.root_quat_w)))
325 jacobian_b[:, :3, :] = torch.bmm(root_rot_matrix, jacobian_b[:, :3, :])
326 jacobian_b[:, 3:, :] = torch.bmm(root_rot_matrix, jacobian_b[:, 3:, :])
327
328 # Compute current pose of the end-effector
329 root_pos_w = wp.to_torch(robot.data.root_pos_w)
330 root_quat_w = wp.to_torch(robot.data.root_quat_w)
331 ee_pos_w = wp.to_torch(robot.data.body_pos_w)[:, ee_frame_idx]
332 ee_quat_w = wp.to_torch(robot.data.body_quat_w)[:, ee_frame_idx]
333 ee_pos_b, ee_quat_b = subtract_frame_transforms(root_pos_w, root_quat_w, ee_pos_w, ee_quat_w)
334 root_pose_w = torch.cat([root_pos_w, root_quat_w], dim=-1)
335 ee_pose_w = torch.cat([ee_pos_w, ee_quat_w], dim=-1)
336 ee_pose_b = torch.cat([ee_pos_b, ee_quat_b], dim=-1)
337
338 # Compute the current velocity of the end-effector
339 ee_vel_w = wp.to_torch(robot.data.body_vel_w)[
340 :, ee_frame_idx, :
341 ] # Extract end-effector velocity in the world frame
342 root_vel_w = wp.to_torch(robot.data.root_vel_w) # Extract root velocity in the world frame
343 relative_vel_w = ee_vel_w - root_vel_w # Compute the relative velocity in the world frame
344 ee_lin_vel_b = quat_apply_inverse(
345 wp.to_torch(robot.data.root_quat_w), relative_vel_w[:, 0:3]
346 ) # From world to root frame
347 ee_ang_vel_b = quat_apply_inverse(wp.to_torch(robot.data.root_quat_w), relative_vel_w[:, 3:6])
348 ee_vel_b = torch.cat([ee_lin_vel_b, ee_ang_vel_b], dim=-1)
349
350 # Calculate the contact force
351 ee_force_w = torch.zeros(scene.num_envs, 3, device=sim.device)
352 sim_dt = sim.get_physics_dt()
353 contact_forces.update(sim_dt) # update contact sensor
354 # Calculate the contact force by averaging over last four time steps (i.e., to smoothen) and
355 # taking the max of three surfaces as only one should be the contact of interest
356 ee_force_w, _ = torch.max(torch.mean(contact_forces.data.net_forces_w_history, dim=1), dim=1)
357
358 # This is a simplification, only for the sake of testing.
359 ee_force_b = ee_force_w
360
361 # Get joint positions and velocities
362 joint_pos = wp.to_torch(robot.data.joint_pos)[:, arm_joint_ids]
363 joint_vel = wp.to_torch(robot.data.joint_vel)[:, arm_joint_ids]
364
365 return (
366 jacobian_b,
367 mass_matrix,
368 gravity,
369 ee_pose_b,
370 ee_vel_b,
371 root_pose_w,
372 ee_pose_w,
373 ee_force_b,
374 joint_pos,
375 joint_vel,
376 )
377
378
379# Update the target commands
380def update_target(
381 sim: sim_utils.SimulationContext,
382 scene: InteractiveScene,
383 osc: OperationalSpaceController,
384 root_pose_w: torch.tensor,
385 ee_target_set: torch.tensor,
386 current_goal_idx: int,
387):
388 """Update the targets for the operational space controller.
389
390 Args:
391 sim: (SimulationContext) Simulation context.
392 scene: (InteractiveScene) Interactive scene.
393 osc: (OperationalSpaceController) Operational space controller.
394 root_pose_w: (torch.tensor) Root pose in the world frame.
395 ee_target_set: (torch.tensor) End-effector target set.
396 current_goal_idx: (int) Current goal index.
397
398 Returns:
399 command (torch.tensor): Updated target command.
400 ee_target_pose_b (torch.tensor): Updated target pose in the body frame.
401 ee_target_pose_w (torch.tensor): Updated target pose in the world frame.
402 next_goal_idx (int): Next goal index.
403
404 Raises:
405 ValueError: Undefined target_type.
406 """
407
408 # update the ee desired command
409 command = torch.zeros(scene.num_envs, osc.action_dim, device=sim.device)
410 command[:] = ee_target_set[current_goal_idx]
411
412 # update the ee desired pose
413 ee_target_pose_b = torch.zeros(scene.num_envs, 7, device=sim.device)
414 for target_type in osc.cfg.target_types:
415 if target_type == "pose_abs":
416 ee_target_pose_b[:] = command[:, :7]
417 elif target_type == "wrench_abs":
418 pass # ee_target_pose_b could stay at the root frame for force control, what matters is ee_target_b
419 else:
420 raise ValueError("Undefined target_type within update_target().")
421
422 # update the target desired pose in world frame (for marker)
423 ee_target_pos_w, ee_target_quat_w = combine_frame_transforms(
424 root_pose_w[:, 0:3], root_pose_w[:, 3:7], ee_target_pose_b[:, 0:3], ee_target_pose_b[:, 3:7]
425 )
426 ee_target_pose_w = torch.cat([ee_target_pos_w, ee_target_quat_w], dim=-1)
427
428 next_goal_idx = (current_goal_idx + 1) % len(ee_target_set)
429
430 return command, ee_target_pose_b, ee_target_pose_w, next_goal_idx
431
432
433# Convert the target commands to the task frame
434def convert_to_task_frame(osc: OperationalSpaceController, command: torch.tensor, ee_target_pose_b: torch.tensor):
435 """Converts the target commands to the task frame.
436
437 Args:
438 osc: OperationalSpaceController object.
439 command: Command to be converted.
440 ee_target_pose_b: Target pose in the body frame.
441
442 Returns:
443 command (torch.tensor): Target command in the task frame.
444 task_frame_pose_b (torch.tensor): Target pose in the task frame.
445
446 Raises:
447 ValueError: Undefined target_type.
448 """
449 command = command.clone()
450 task_frame_pose_b = ee_target_pose_b.clone()
451
452 cmd_idx = 0
453 for target_type in osc.cfg.target_types:
454 if target_type == "pose_abs":
455 command[:, :3], command[:, 3:7] = subtract_frame_transforms(
456 task_frame_pose_b[:, :3], task_frame_pose_b[:, 3:], command[:, :3], command[:, 3:7]
457 )
458 cmd_idx += 7
459 elif target_type == "wrench_abs":
460 # These are already defined in target frame for ee_goal_wrench_set_tilted_task (since it is
461 # easier), so not transforming
462 cmd_idx += 6
463 else:
464 raise ValueError("Undefined target_type within _convert_to_task_frame().")
465
466 return command, task_frame_pose_b
467
468
469def main():
470 """Main function."""
471 # Load kit helper
472 sim_cfg = sim_utils.SimulationCfg(dt=0.01, device=args_cli.device)
473 sim = sim_utils.SimulationContext(sim_cfg)
474 # Set main camera
475 sim.set_camera_view([2.5, 2.5, 2.5], [0.0, 0.0, 0.0])
476 # Design scene
477 scene_cfg = SceneCfg(num_envs=args_cli.num_envs, env_spacing=2.0)
478 scene = InteractiveScene(scene_cfg)
479 # Play the simulator
480 sim.reset()
481 # Now we are ready!
482 print("[INFO]: Setup complete...")
483 # Run the simulator
484 run_simulator(sim, scene)
485
486
487if __name__ == "__main__":
488 # run the main function
489 main()
490 # close sim app
491 simulation_app.close()
Creating an Operational Space Controller#
The OperationalSpaceController class computes the joint
efforts/torques for a robot to do simultaneous motion and force control in task space.
The reference frame of this task space could be an arbitrary coordinate frame in Euclidean space. By default,
it is the robot’s base frame. However, in certain cases, it could be easier to define target coordinates w.r.t. a
different frame. In such cases, the pose of this task reference frame, w.r.t. to the robot’s base frame, should be
provided in the set_command method’s current_task_frame_pose_b argument. For example, in this tutorial, it
makes sense to define the target commands w.r.t. a frame that is parallel to the wall surface, as the force control
direction would be then only nonzero in the z-axis of this frame. The target pose, which is set to have the same
orientation as the wall surface, is such a candidate and is used as the task frame in this tutorial. Therefore, all
the arguments to the OperationalSpaceControllerCfg should be set with this task reference frame
in mind.
For the motion control, the task space targets could be given as absolute (i.e., defined w.r.t. the robot base,
target_types: "pose_abs") or relative the the end-effector’s current pose (i.e., target_types: "pose_rel").
For the force control, the task space targets could be given as absolute (i.e., defined w.r.t. the robot base,
target_types: "force_abs"). If it is desired to apply pose and force control simultaneously, the target_types
should be a list such as ["pose_abs", "wrench_abs"] or ["pose_rel", "wrench_abs"].
The axes that the motion and force control will be applied can be specified using the motion_control_axes_task and
force_control_axes_task arguments, respectively. These lists should consist of 0/1 for all six axes (position and
rotation) and be complementary to each other (e.g., for the x-axis, if the motion_control_axes_task is 0, the
force_control_axes_task should be 1).
For the motion control axes, desired stiffness, and damping ratio values can be specified using the
motion_control_stiffness and motion_damping_ratio_task arguments, which can be a scalar (same value for all
axes) or a list of six scalars, one value corresponding to each axis. If desired, the stiffness and damping ratio
values could be a command parameter (e.g., to learn the values using RL or change them on the go). For this,
impedance_mode should be either "variable_kp" to include the stiffness values within the command or
"variable" to include both the stiffness and damping ratio values. In these cases, motion_stiffness_limits_task
and motion_damping_limits_task should be set as well, which puts bounds on the stiffness and damping ratio values.
For contact force control, it is possible to apply an open-loop force control by not setting the
contact_wrench_stiffness_task, or apply a closed-loop force control (with the feed-forward term) by setting
the desired stiffness values using the contact_wrench_stiffness_task argument, which can be a scalar or a list
of six scalars. Please note that, currently, only the linear part of the contact wrench (hence the first three
elements of the contact_wrench_stiffness_task) is considered in the closed-loop control, as the rotational part
cannot be measured with the contact sensors.
For the motion control, inertial_dynamics_decoupling should be set to True to use the robot’s inertia matrix
to decouple the desired accelerations in the task space. This is important for the motion control to be accurate,
especially for rapid movements. This inertial decoupling accounts for the coupling between all the six motion axes.
If desired, the inertial coupling between the translational and rotational axes could be ignored by setting the
partial_inertial_dynamics_decoupling to True.
If it is desired to include the gravity compensation in the operational space command, the gravity_compensation
should be set to True.
A final consideration regarding the operational space control is what to do with the null-space of redundant robots.
The null-space is the subspace of the joint space that does not affect the task space coordinates. If nothing is done
to control the null-space, the robot joints will float without moving the end-effector. This might be undesired (e.g.,
the robot joints might get close to their limits), and one might want to control the robot behaviour within its
null-space. One way to do is to set nullspace_control to "position" (by default it is "none") which
integrates a null-space PD controller to attract the robot joints to desired targets without affecting the task
space. The behaviour of this null-space controller can be defined using the nullspace_stiffness and
nullspace_damping_ratio arguments. Please note that theoretical decoupling of the null-space and task space
accelerations is only possible when inertial_dynamics_decoupling is set to True and
partial_inertial_dynamics_decoupling is set to False.
The included OSC implementation performs the computation in a batched format and uses PyTorch operations.
In this tutorial, we will use "pose_abs" for controlling the motion in all axes except the z-axis and
"wrench_abs" for controlling the force in the z-axis. Moreover, we will include the full inertia decoupling in
the motion control and not include the gravity compensation, as the gravity is disabled from the robot configuration.
We set the impedance mode to "variable_kp" to dynamically change the stiffness values
(motion_damping_ratio_task is set to 1: the kd values adapt according to kp values to maintain a critically
damped response). Finally, nullspace_control is set to use "position" where the joint set points are provided
to be the center of the joint position limits.
# Create the OSC
osc_cfg = OperationalSpaceControllerCfg(
target_types=["pose_abs", "wrench_abs"],
impedance_mode="variable_kp",
inertial_dynamics_decoupling=True,
partial_inertial_dynamics_decoupling=False,
gravity_compensation=False,
motion_damping_ratio_task=1.0,
contact_wrench_stiffness_task=[0.0, 0.0, 0.1, 0.0, 0.0, 0.0],
motion_control_axes_task=[1, 1, 0, 1, 1, 1],
contact_wrench_control_axes_task=[0, 0, 1, 0, 0, 0],
nullspace_control="position",
)
osc = OperationalSpaceController(osc_cfg, num_envs=scene.num_envs, device=sim.device)
Updating the states of the robot#
The OSC implementation is a computation-only class. Thus, it expects the user to provide the necessary information about the robot. This includes the robot’s Jacobian matrix, mass/inertia matrix, end-effector pose, velocity, contact force (all in the root frame), and finally, the joint positions and velocities. Moreover, the user should provide gravity compensation vector and null-space joint position targets if required.
# Update robot states
def update_states(
sim: sim_utils.SimulationContext,
scene: InteractiveScene,
robot: Articulation,
ee_frame_idx: int,
arm_joint_ids: list[int],
contact_forces,
):
"""Update the robot states.
Args:
sim: (SimulationContext) Simulation context.
scene: (InteractiveScene) Interactive scene.
robot: (Articulation) Robot articulation.
ee_frame_idx: (int) End-effector frame index.
arm_joint_ids: (list[int]) Arm joint indices.
contact_forces: (ContactSensor) Contact sensor.
Returns:
jacobian_b (torch.tensor): Jacobian in the body frame.
mass_matrix (torch.tensor): Mass matrix.
gravity (torch.tensor): Gravity vector.
ee_pose_b (torch.tensor): End-effector pose in the body frame.
ee_vel_b (torch.tensor): End-effector velocity in the body frame.
root_pose_w (torch.tensor): Root pose in the world frame.
ee_pose_w (torch.tensor): End-effector pose in the world frame.
ee_force_b (torch.tensor): End-effector force in the body frame.
joint_pos (torch.tensor): The joint positions.
joint_vel (torch.tensor): The joint velocities.
Raises:
ValueError: Undefined target_type.
"""
# obtain dynamics related quantities from simulation
ee_jacobi_idx = ee_frame_idx - 1
jacobian_w = robot.root_view.get_jacobians()[:, ee_jacobi_idx, :, arm_joint_ids]
mass_matrix = robot.root_view.get_generalized_mass_matrices()[:, arm_joint_ids, :][:, :, arm_joint_ids]
gravity = robot.root_view.get_gravity_compensation_forces()[:, arm_joint_ids]
# Convert the Jacobian from world to root frame
jacobian_b = jacobian_w.clone()
root_rot_matrix = matrix_from_quat(quat_inv(wp.to_torch(robot.data.root_quat_w)))
jacobian_b[:, :3, :] = torch.bmm(root_rot_matrix, jacobian_b[:, :3, :])
jacobian_b[:, 3:, :] = torch.bmm(root_rot_matrix, jacobian_b[:, 3:, :])
# Compute current pose of the end-effector
root_pos_w = wp.to_torch(robot.data.root_pos_w)
root_quat_w = wp.to_torch(robot.data.root_quat_w)
ee_pos_w = wp.to_torch(robot.data.body_pos_w)[:, ee_frame_idx]
ee_quat_w = wp.to_torch(robot.data.body_quat_w)[:, ee_frame_idx]
ee_pos_b, ee_quat_b = subtract_frame_transforms(root_pos_w, root_quat_w, ee_pos_w, ee_quat_w)
root_pose_w = torch.cat([root_pos_w, root_quat_w], dim=-1)
ee_pose_w = torch.cat([ee_pos_w, ee_quat_w], dim=-1)
ee_pose_b = torch.cat([ee_pos_b, ee_quat_b], dim=-1)
# Compute the current velocity of the end-effector
ee_vel_w = wp.to_torch(robot.data.body_vel_w)[
:, ee_frame_idx, :
] # Extract end-effector velocity in the world frame
root_vel_w = wp.to_torch(robot.data.root_vel_w) # Extract root velocity in the world frame
relative_vel_w = ee_vel_w - root_vel_w # Compute the relative velocity in the world frame
ee_lin_vel_b = quat_apply_inverse(
wp.to_torch(robot.data.root_quat_w), relative_vel_w[:, 0:3]
) # From world to root frame
ee_ang_vel_b = quat_apply_inverse(wp.to_torch(robot.data.root_quat_w), relative_vel_w[:, 3:6])
ee_vel_b = torch.cat([ee_lin_vel_b, ee_ang_vel_b], dim=-1)
# Calculate the contact force
ee_force_w = torch.zeros(scene.num_envs, 3, device=sim.device)
sim_dt = sim.get_physics_dt()
contact_forces.update(sim_dt) # update contact sensor
# Calculate the contact force by averaging over last four time steps (i.e., to smoothen) and
# taking the max of three surfaces as only one should be the contact of interest
ee_force_w, _ = torch.max(torch.mean(contact_forces.data.net_forces_w_history, dim=1), dim=1)
# This is a simplification, only for the sake of testing.
ee_force_b = ee_force_w
# Get joint positions and velocities
joint_pos = wp.to_torch(robot.data.joint_pos)[:, arm_joint_ids]
joint_vel = wp.to_torch(robot.data.joint_vel)[:, arm_joint_ids]
return (
jacobian_b,
mass_matrix,
gravity,
ee_pose_b,
ee_vel_b,
root_pose_w,
ee_pose_w,
ee_force_b,
joint_pos,
joint_vel,
)
Computing robot command#
The OSC separates the operation of setting the desired command and computing the desired joint positions.
To set the desired command, the user should provide command vector, which includes the target commands
(i.e., in the order they appear in the target_types argument of the OSC configuration),
and the desired stiffness and damping ratio values if the impedance_mode is set to "variable_kp" or "variable".
They should be all in the same coordinate frame as the task frame (e.g., indicated with _task subscript) and
concatanated together.
In this tutorial, the desired wrench is already defined w.r.t. the task frame, and the desired pose is transformed to the task frame as the following:
# Convert the target commands to the task frame
def convert_to_task_frame(osc: OperationalSpaceController, command: torch.tensor, ee_target_pose_b: torch.tensor):
"""Converts the target commands to the task frame.
Args:
osc: OperationalSpaceController object.
command: Command to be converted.
ee_target_pose_b: Target pose in the body frame.
Returns:
command (torch.tensor): Target command in the task frame.
task_frame_pose_b (torch.tensor): Target pose in the task frame.
Raises:
ValueError: Undefined target_type.
"""
command = command.clone()
task_frame_pose_b = ee_target_pose_b.clone()
cmd_idx = 0
for target_type in osc.cfg.target_types:
if target_type == "pose_abs":
command[:, :3], command[:, 3:7] = subtract_frame_transforms(
task_frame_pose_b[:, :3], task_frame_pose_b[:, 3:], command[:, :3], command[:, 3:7]
)
cmd_idx += 7
elif target_type == "wrench_abs":
# These are already defined in target frame for ee_goal_wrench_set_tilted_task (since it is
# easier), so not transforming
cmd_idx += 6
else:
raise ValueError("Undefined target_type within _convert_to_task_frame().")
return command, task_frame_pose_b
The OSC command is set with the command vector in the task frame, the end-effector pose in the base frame, and the task (reference) frame pose in the base frame as the following. This information is needed, as the internal computations are done in the base frame.
# set the osc command
osc.reset()
command, task_frame_pose_b = convert_to_task_frame(osc, command=command, ee_target_pose_b=ee_target_pose_b)
osc.set_command(command=command, current_ee_pose_b=ee_pose_b, current_task_frame_pose_b=task_frame_pose_b)
The joint effort/torque values are computed using the provided robot states and the desired command as the following:
# compute the joint commands
joint_efforts = osc.compute(
jacobian_b=jacobian_b,
current_ee_pose_b=ee_pose_b,
current_ee_vel_b=ee_vel_b,
current_ee_force_b=ee_force_b,
mass_matrix=mass_matrix,
gravity=gravity,
current_joint_pos=joint_pos,
current_joint_vel=joint_vel,
nullspace_joint_pos_target=joint_centers,
)
The computed joint effort/torque targets can then be applied on the robot.
# apply actions
robot.set_joint_effort_target_index(target=joint_efforts, joint_ids=arm_joint_ids)
robot.write_data_to_sim()
The Code Execution#
You can now run the script and see the result:
./isaaclab.sh -p scripts/tutorials/05_controllers/run_osc.py --num_envs 128
The script will start a simulation with 128 robots. The robots will be controlled using the OSC. The current and desired end-effector poses should be displayed using frame markers in addition to the red tilted wall. You should see that the robot reaches the desired pose while applying a constant force perpendicular to the wall surface.
To stop the simulation, you can either close the window or press Ctrl+C in the terminal.