|
| 1 | +[include "gazebo_left_hand_robotname.ini"] |
| 2 | + |
| 3 | +[WRAPPER] |
| 4 | +device controlboardwrapper2 |
| 5 | +period 10 |
| 6 | +name /${gazeboYarpPluginsRobotName}/left_hand_phys |
| 7 | + |
| 8 | +joints 11 |
| 9 | +networks ( left_hand_phys ) |
| 10 | +left_hand_phys 0 10 0 10 |
| 11 | +# Verbose output (on if present, off if commented out) |
| 12 | +#verbose |
| 13 | + |
| 14 | +[COUPLING] |
| 15 | +icub_hand_mk3 (0 1 2 3 4 5 6 7 8 9 10) (l_thumb_oppose l_thumb_rotate l_thumb l_hand_finger l_index l_middle l_pinky reserved reserved reserved reserved) |
| 16 | + |
| 17 | +# Specify configuration of MotorControl devices |
| 18 | +[left_hand_phys] |
| 19 | +device gazebo_controlboard |
| 20 | +name left_hand_pyhs |
| 21 | +jointNames l_hand_metacarpus_joint l_hand_thumb_rotation_joint l_hand_thumb_proximal_joint l_hand_thumb_distal_joint l_hand_index_adduction_joint l_hand_index_proximal_joint l_hand_index_distal_joint l_hand_medium_proximal_joint l_hand_medium_distal_joint l_hand_pinky_proximal_joint l_hand_pinky_distal_joint |
| 22 | + |
| 23 | +[LIMITS] |
| 24 | +jntVelMax 180.0 180.0 180.0 180.0 180.0 180.0 180.0 0 0 0 0 |
| 25 | +jntPosMax 62.0 0.0 140.0 10.0 200.3 200.3 200.3 0 0 0 0 |
| 26 | +jntPosMin 0.0 -70.0 0.0 0.0 0.0 0.0 0.0 0 0 0 0 |
| 27 | + |
| 28 | +[POSITION_CONTROL] |
| 29 | +controlUnits metric_units |
| 30 | +controlLaw joint_pid_gazebo_v1 |
| 31 | +kp 5.0 5.0 5.0 5.0 5.0 5.0 5.0 5.0 5.0 5.0 5.0 |
| 32 | +kd 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 |
| 33 | +ki 0.00 0.00 0.00 0.00 0.00 0.00 0.00 0.00 0.00 0.00 0.00 |
| 34 | +maxInt 9999 9999 9999 9999 9999 9999 9999 9999 9999 9999 9999 |
| 35 | +maxOutput 9999 9999 9999 9999 9999 9999 9999 9999 9999 9999 9999 |
| 36 | +shift 0 0 0 0 0 0 0 0 0 0 0 |
| 37 | +ko 0 0 0 0 0 0 0 0 0 0 0 |
| 38 | +stictionUp 0 0 0 0 0 0 0 0 0 0 0 |
| 39 | +stictionDwn 0 0 0 0 0 0 0 0 0 0 0 |
| 40 | + |
| 41 | +[VELOCITY_CONTROL] |
| 42 | +controlUnits metric_units |
| 43 | +controlLaw joint_pid_gazebo_v1 |
| 44 | +kp 20.0 20.0 20.0 20.0 20.0 20.0 20.0 20.0 20.0 20.0 20.0 |
| 45 | +kd 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 |
| 46 | +ki 0.01 0.01 0.01 0.01 0.01 0.01 0.01 0.01 0.01 0.01 0.01 |
| 47 | +maxInt 9999 9999 9999 9999 9999 9999 9999 9999 9999 9999 9999 |
| 48 | +maxOutput 9999 9999 9999 9999 9999 9999 9999 9999 9999 9999 9999 |
| 49 | +shift 0 0 0 0 0 0 0 0 0 0 0 |
| 50 | +ko 0 0 0 0 0 0 0 0 0 0 0 |
| 51 | +stictionUp 0 0 0 0 0 0 0 0 0 0 0 |
| 52 | +stictionDwn 0 0 0 0 0 0 0 0 0 0 0 |
| 53 | + |
| 54 | +[IMPEDANCE_CONTROL] |
| 55 | +controlUnits metric_units |
| 56 | +controlLaw joint_pid_gazebo_v1 |
| 57 | +stiffness 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 |
| 58 | +damping 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 |
| 59 | + |
0 commit comments