Difference between revisions of "PR2 Arm Control"
From Healthcare Robotics Wiki
(→Low-level Controllers) |
(→Low-level Controllers) |
||
| (17 intermediate revisions by 3 users not shown) | |||
| Line 22: | Line 22: | ||
T = PID(spline(t, trajectory) - q_cur) | T = PID(spline(t, trajectory) - q_cur) | ||
|| | || | ||
| − | T = J^T * PD(x_err) + J_null * (q_posture - q) | + | 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 | Same but: PD(x_err) = R * Kp * R^T * x_err + R * Kd * R^T * x_dot | ||
| Line 34: | Line 34: | ||
F = PD(x_err) or F_des | F = PD(x_err) or F_des | ||
|- | |- | ||
| − | ! scope="row" | | + | ! scope="row" | 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 | ||
| + | |- | ||
| + | ! scope="row" | Requires IK solutions? | ||
| + | | {{no}} || {{no}} || {{no}} || {{no}} || {{no}} | ||
| + | |- | ||
| + | ! scope="row" | ROS Interface | ||
| | | | ||
* Actionlib | * Actionlib | ||
| Line 54: | Line 60: | ||
* Trajectory playback | * Trajectory playback | ||
* Overhead grasping | * Overhead grasping | ||
| + | * Current THEP low-level control | ||
|| | || | ||
* Lightswitch | * Lightswitch | ||
* Interactive grasping | * Interactive grasping | ||
| − | |||
* Door opening | * Door opening | ||
| + | * Old THEP low-level control | ||
|| | || | ||
* Invisible surface | * Invisible surface | ||
| Line 70: | Line 77: | ||
* Door opening (not smoothly) | * Door opening (not smoothly) | ||
|- | |- | ||
| − | ! scope="row" | | + | ! scope="row" | 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}} || {{ | + | | {{yes}} || {{no}} || {{no}} || {{no}} || {{maybe}} |
|- | |- | ||
| − | ! scope="row" | Change Gains | + | ! scope="row" | Change Gains while the controller is running (through topic) |
| {{no}} || {{yes}} || {{yes}} || {{no}} || {{yes}}, if using impedance control | | {{no}} || {{yes}} || {{yes}} || {{no}} || {{yes}}, if using impedance control | ||
|- | |- | ||
| Line 79: | Line 86: | ||
| {{yes}} || {{no}} || {{no}} || {{no}} || {{no}} | | {{yes}} || {{no}} || {{no}} || {{no}} || {{no}} | ||
|- | |- | ||
| − | ! scope="row" | Cartesian | + | ! scope="row" | Monitors Cartesian velocity and softly scales it (saturation) |
| {{no}} || {{yes}} || {{yes}} || {{no}}, not implemented yet || {{no}} | | {{no}} || {{yes}} || {{yes}} || {{no}}, not implemented yet || {{no}} | ||
|- | |- | ||
| − | ! scope="row" | | + | ! 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 | ||
| + | || | ||
| + | * Repeatable | ||
| + | * Control of extra DOF stronger | ||
| + | * Detecting collisions easy and equally constrained | ||
| + | || | ||
| + | * Easier to control extra DOF in general | ||
| + | * Cartesian impedance control | ||
| + | || | ||
| + | * Impedance control makes more sense in tool's frame | ||
| + | || | ||
| + | || | ||
| + | * Has several videos with different applications | ||
| + | |- | ||
| + | ! scope="row" | Cons | ||
| + | || | ||
| + | * Difficult to control elbow in general | ||
| + | * Joint space impedance control doesn't make sense | ||
| + | * Working with IK has been difficult (solved by KDL?) | ||
| + | || | ||
| + | * Competing forces (pose and posture) | ||
| + | * Elbow drifts over time if posture gain too low | ||
| + | * "Bouncing" in elbow when arm stops moving | ||
| + | * Difficult to detect collision using joint errors | ||
| + | * Singularity issues | ||
| + | || | ||
| + | || | ||
| + | || | ||
| + | * Seems like a volatile controller | ||
| + | * Still in development (not all interfaces implemented) | ||
| + | * No saturation limits | ||
| + | |- | ||
| + | ! scope="row" | Issues/Bugs | ||
| + | || | ||
| + | || | ||
| + | * Can sometimes demonstrate unexpected behavior when in kinematically constrained situations | ||
| + | * Sometimes one of the arms doesn't respond to commands (reported by Marc) | ||
| + | || | ||
| + | || | ||
| + | || | ||
|- | |- | ||
! scope="row" | Notes | ! scope="row" | Notes | ||
| Line 91: | Line 145: | ||
|| | || | ||
|| | || | ||
| + | * Don't set derivative gains to 0 (division by zero error) | ||
|| | || | ||
|| | || | ||
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 |
|
|
|