osc_controller
OperationalSpaceController
Bases: ManipulationController
Controller class to convert (delta or absolute) EEF commands into joint efforts using Operational Space Control
This controller expects 6DOF delta commands (dx, dy, dz, dax, day, daz), where the delta orientation commands are in axis-angle form, and outputs low-level torque commands.
Gains may also be considered part of the action space as well. In this case, the action space would be: ( dx, dy, dz, dax, day, daz <-- 6DOF delta eef commands [, kpx, kpy, kpz, kpax, kpay, kpaz] <-- kp gains [, drx dry, drz, drax, dray, draz] <-- damping ratio gains [, kpnx, kpny, kpnz, kpnax, kpnay, kpnaz] <-- kp null gains )
Note that in this case, we ASSUME that the inputted gains are normalized to be in the range [-1, 1], and will be mapped appropriately to their respective ranges, as defined by XX_limits
Alternatively, parameters (in this case, kp or damping_ratio) can either be set during initialization or provided from an external source; if the latter, the control_dict should include the respective parameter(s) as a part of its keys
Each controller step consists of the following
- Clip + Scale inputted command according to @command_input_limits and @command_output_limits
- Run OSC to back out joint efforts for a desired task frame command
- Clips the resulting command by the motor (effort) limits
Source code in omnigibson/controllers/osc_controller.py
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 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290 291 292 293 294 295 296 297 298 299 300 301 302 303 304 305 306 307 308 309 310 311 312 313 314 315 316 317 318 319 320 321 322 323 324 325 326 327 328 329 330 331 332 333 334 335 336 337 338 339 340 341 342 343 344 345 346 347 348 349 350 351 352 353 354 355 356 357 358 359 360 361 362 363 364 365 366 367 368 369 370 371 372 373 374 375 376 377 378 379 380 381 382 383 384 385 386 387 388 389 390 391 392 393 394 395 396 397 398 399 400 401 402 403 404 405 406 407 408 409 410 411 412 413 414 415 416 417 418 419 420 421 422 423 424 425 426 427 428 429 430 431 432 433 434 435 436 437 438 439 440 441 442 443 444 445 446 447 448 449 450 451 452 453 454 455 456 457 458 459 460 461 462 463 464 465 466 467 468 469 470 471 472 473 474 475 476 477 478 479 480 481 482 483 484 485 486 |
|
__init__(task_name, control_freq, reset_joint_pos, control_limits, dof_idx, command_input_limits='default', command_output_limits=((-0.2, -0.2, -0.2, -0.5, -0.5, -0.5), (0.2, 0.2, 0.2, 0.5, 0.5, 0.5)), kp=150.0, kp_limits=(10.0, 300.0), damping_ratio=1.0, damping_ratio_limits=(0.0, 2.0), kp_null=10.0, kp_null_limits=(0.0, 50.0), mode='pose_delta_ori', decouple_pos_ori=False, workspace_pose_limiter=None, use_gravity_compensation=False, use_cc_compensation=True)
Parameters:
Name | Type | Description | Default |
---|---|---|---|
task_name
|
str
|
name assigned to this task frame for computing OSC control. During control calculations, the inputted control_dict should include entries named <@task_name>_pos_relative and <@task_name>_quat_relative. See self._command_to_control() for what these values should entail. |
required |
control_freq
|
int
|
controller loop frequency |
required |
reset_joint_pos
|
Array[float]
|
reset joint positions, used as part of nullspace controller in IK. Note that this should correspond to ALL the joints; the exact indices will be extracted via @dof_idx |
required |
control_limits
|
Dict[str, Tuple[Array[float], Array[float]]]
|
The min/max limits to the outputted control signal. Should specify per-dof type limits, i.e.:
Values outside of this range will be clipped, if the corresponding joint index in has_limit is True. |
required |
dof_idx
|
Array[int]
|
specific dof indices controlled by this robot. Used for inferring controller-relevant values during control computations |
required |
command_input_limits
|
None or default or Tuple[float, float] or Tuple[Array[float], Array[float]]
|
if set, is the min/max acceptable inputted command. Values outside this range will be clipped. If None, no clipping will be used. If "default", range will be set to (-1, 1) |
'default'
|
command_output_limits
|
None or default or Tuple[float, float] or Tuple[Array[float], Array[float]]
|
if set, is the min/max scaled command. If both this value and @command_input_limits is not None, then all inputted command values will be scaled from the input range to the output range. If either is None, no scaling will be used. If "default", then this range will automatically be set to the @control_limits entry corresponding to self.control_type |
((-0.2, -0.2, -0.2, -0.5, -0.5, -0.5), (0.2, 0.2, 0.2, 0.5, 0.5, 0.5))
|
kp
|
None, int, float, or array
|
Gain values to apply to 6DOF error. If None, will be variable (part of action space) |
150.0
|
kp_limits
|
2 - array
|
(min, max) values of kp |
(10.0, 300.0)
|
damping_ratio
|
None, int, float, or array
|
Damping ratio to apply to 6DOF error controller gain If None, will be variable (part of action space) |
1.0
|
damping_ratio_limits
|
2 - array
|
(min, max) values of damping ratio |
(0.0, 2.0)
|
kp_null
|
None, int, float, or array
|
Gain applied when calculating null torques If None, will be variable (part of action space) |
10.0
|
kp_null_limits
|
2 - array
|
(min, max) values of kp_null |
(0.0, 50.0)
|
mode
|
str
|
mode to use when computing IK. In all cases, position commands are 3DOF delta (dx,dy,dz) cartesian values, relative to the robot base frame. Valid options are: - "pose_absolute_ori": 6DOF (dx,dy,dz,ax,ay,az) control over pose, where the orientation is given in absolute axis-angle coordinates - "pose_delta_ori": 6DOF (dx,dy,dz,dax,day,daz) control over pose - "position_fixed_ori": 3DOF (dx,dy,dz) control over position, with orientation commands being kept as fixed initial absolute orientation - "position_compliant_ori": 3DOF (dx,dy,dz) control over position, with orientation commands automatically being sent as 0s (so can drift over time) |
'pose_delta_ori'
|
decouple_pos_ori
|
bool
|
Whether to decouple position and orientation control or not |
False
|
workspace_pose_limiter
|
None or function
|
if specified, callback method that should clip absolute target (x,y,z) cartesian position and absolute quaternion orientation (x,y,z,w) to a specific workspace range (i.e.: this can be unique to each robot, and implemented by each embodiment). Function signature should be:
where target_pos is (x,y,z) cartesian position values, target_quat is (x,y,z,w) quarternion orientation values, and the returned tuple is the processed (pos, quat) command. |
None
|
use_gravity_compensation
|
bool
|
If True, will add gravity compensation to the computed efforts. This is an experimental feature that only works on fixed base robots. We do not recommend enabling this. |
False
|
use_cc_compensation
|
bool
|
If True, will add Coriolis / centrifugal compensation to the computed efforts. |
True
|
Source code in omnigibson/controllers/osc_controller.py
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 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250 |
|
compute_control(goal_dict, control_dict)
Computes low-level torque controls using internal eef goal pos / ori.
Parameters:
Name | Type | Description | Default |
---|---|---|---|
goal_dict
|
Dict[str, Any]
|
dictionary that should include any relevant keyword-mapped goals necessary for controller computation. Must include the following keys: target_pos: robot-frame (x,y,z) desired end effector position target_quat: robot-frame (x,y,z,w) desired end effector quaternion orientation |
required |
control_dict
|
Dict[str, Any]
|
dictionary that should include any relevant keyword-mapped states necessary for controller computation. Must include the following keys: joint_position: Array of current joint positions joint_velocity: Array of current joint velocities mass_matrix: (N_dof, N_dof) Current mass matrix <@self.task_name>_jacobian_relative: (6, N_dof) Current jacobian matrix for desired task frame <@self.task_name>_pos_relative: (x,y,z) relative cartesian position of the desired task frame to control, computed in its local frame (e.g.: robot base frame) <@self.task_name>_quat_relative: (x,y,z,w) relative quaternion orientation of the desired task frame to control, computed in its local frame (e.g.: robot base frame) <@self.task_name>_lin_vel_relative: (x,y,z) relative linear velocity of the desired task frame to control, computed in its local frame (e.g.: robot base frame) <@self.task_name>_ang_vel_relative: (ax, ay, az) relative angular velocity of the desired task frame to control, computed in its local frame (e.g.: robot base frame) |
required |
control_dict
|
dict
|
Dictionary of state tensors including relevant info for controller computation |
required |
Returns:
Type | Description |
---|---|
n - array
|
low-level effort control actions, NOT post-processed |
Source code in omnigibson/controllers/osc_controller.py
359 360 361 362 363 364 365 366 367 368 369 370 371 372 373 374 375 376 377 378 379 380 381 382 383 384 385 386 387 388 389 390 391 392 393 394 395 396 397 398 399 400 401 402 403 404 405 406 407 408 409 410 411 412 413 414 415 416 417 418 419 420 421 422 423 424 425 426 427 428 429 430 431 432 433 434 435 436 437 438 439 |
|