Difference between revisions of "PR2 Arm Control"
From Healthcare Robotics Wiki
(→Low-level Controllers) |
(→Low-level Controllers) |
||
| (2 intermediate revisions by one user not shown) | |||
| Line 91: | Line 91: | ||
! scope="row" | Monitors torque at each joint and softly scales the entire torque vector (saturation) | ! scope="row" | Monitors torque at each joint and softly scales the entire torque vector (saturation) | ||
| {{no}} || {{yes}} || {{yes}} || {{no}} || {{no}} | | {{no}} || {{yes}} || {{yes}} || {{no}} || {{no}} | ||
| + | |- | ||
| + | ! scope="row" | Supports collision detection? | ||
| + | | {{no}} || {{no}} || {{no}} || {{no}} || {{no}} | ||
| + | |- | ||
| + | ! scope="row" | Performance with low stiffness | ||
| + | | || || || || | ||
|- | |- | ||
! scope="row" | Pros | ! scope="row" | Pros | ||
Latest revision as of 14:31, 13 July 2011
[edit] Low-level Controllers
| Controller | Joint Spline Trajectory Controller | JTranspose Controller | JTranspose Task Controller | JInverse Controller | End Effector Cartesian Impedance Control |
|---|---|---|---|---|---|
| Designer | Stuart Glaser | Stuart Glaser | Adam Leeper | Stuart Glaser | MIT |
| Control Space | Joint space | Cartesian Space | Cartesian Space | Cartesian Space | Cartesian Space |
| Control Type | Joint position, velocity, acceleration control with PID | Controls force at the end effector with PD on the Cartesian error | Same as JTranspose, shaped stiffness matrix in end effector's frame | Position or Velocity Cartesian control with PD control on joint velocities | Force-stiffness hybrid control, JTranspose on some DOF, force control on others |
| Relevant Equations |
T = PID(spline(t, trajectory) - q_cur) |
T = J^T * PD(x_err) + Kff * J_null * (q_posture - q) |
Same but: PD(x_err) = R * Kp * R^T * x_err + R * Kd * R^T * x_dot |
T = Kp * (q_proxy - q) + Kd * (q_dot_des - q_dot) q_dot_des = J_pinv * x_dot + J_null * (q_posture - q) |
T = J^T * F F = PD(x_err) or F_des |
| Control reference (the goal the controller is trying to achieve) | joint angles | Cartesian pose of rigid transformation from end effector frame | Cartesian pose of rigid transformation from end effector frame | Cartesian pose of rigid transformation from end effector frame | Cartesian frame attached to end effector with origin at wrist |
| Requires IK solutions? | No | No | No | No | No |
| ROS Interface |
|
|
|
|
|
| Demonstrated Tasks |
|
|
|
| |
| Can provide trajectory as sequence of reference points, velocities, and durations, which it then uses to generate way points (rather than only a single reference) | Yes | No | No | No | Template:Maybe |
| Change Gains while the controller is running (through topic) | No | Yes | Yes | No | Yes, if using impedance control |
| Integral Control | Yes | No | No | No | No |
| Monitors Cartesian velocity and softly scales it (saturation) | No | Yes | Yes | No, not implemented yet | No |
| Monitors torque at each joint and softly scales the entire torque vector (saturation) | No | Yes | Yes | No | No |
| Supports collision detection? | No | No | No | No | No |
| Performance with low stiffness | |||||
| Pros |
|
|
|
| |
| Cons |
|
|
| ||
| Issues/Bugs |
|
||||
| Notes |
|
|
|