-
Notifications
You must be signed in to change notification settings - Fork 19
/
Copy pathgazebo_icub_right_hand_finger.ini
71 lines (60 loc) · 1.97 KB
/
gazebo_icub_right_hand_finger.ini
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
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
[include "gazebo_icub_robotname.ini"]
# Verbose output (on if present, off if commented out)
#verbose
[WRAPPER]
device controlboardwrapper2
period 10
name /${gazeboYarpPluginsRobotName}/right_hand_finger
joints 4
networks ( right_hand_finger )
right_hand_finger 0 3 0 3
[TRAJECTORY_GENERATION]
trajectory_type minimum_jerk
[COUPLING]
fingers_abduction_control (0 1 2 3) (r_hand_fingers reserved reserved reserved reserved)
# Specify configuration of MotorControl devices
[right_hand_finger]
# name of the device to be instatiated by the factory
device gazebo_controlboard
#jointNames list
jointNames r_aij6 r_mj6 r_rij6 r_lij6
name right_hand_finger
min_stiffness 0.0 0.0 0.0 0.0
max_stiffness 1000.0 1000.0 1000.0 1000.0
min_damping 0.0 0.0 0.0 0.0
max_damping 100.0 100.0 100.0 100.0
#PIDs:
# this information is used to set the PID values in simulation for GAZEBO, we need only the first three values
[POSITION_CONTROL]
controlUnits metric_units
controlLaw joint_pid_gazebo_v1
kp 1.745 1.745 1.745 1.745
kd 0.0 0.0 0.0 0.0
ki 0.174 0.174 0.174 0.174
maxInt 9999 9999 9999 9999
maxOutput 9999 9999 9999 9999
shift 0.0 0.0 0.0 0.0
ko 0.0 0.0 0.0 0.0
stictionUp 0.0 0.0 0.0 0.0
stictionDwn 0.0 0.0 0.0 0.0
[VELOCITY_CONTROL]
controlUnits metric_units
controlLaw joint_pid_gazebo_v1
kp 8.726 8.726 8.726 5.236
kd 0.035 0.035 0.035 0.002
ki 0.002 0.002 0.002 0.0
maxInt 9999 9999 9999 9999
maxOutput 9999 9999 9999 9999
shift 0.0 0.0 0.0 0.0
ko 0.0 0.0 0.0 0.0
stictionUp 0.0 0.0 0.0 0.0
stictionDwn 0.0 0.0 0.0 0.0
[IMPEDANCE_CONTROL]
controlUnits metric_units
controlLaw joint_pid_gazebo_v1
stiffness 0.0 0.0 0.0 0.0
damping 0.0 0.0 0.0 0.0
[LIMITS]
jntPosMax 90.0 90.0 90.0 90.0
jntPosMin -90.0 -90.0 -90.0 -90.0
jntVelMax 100.0 100.0 100.0 100.0