diff --git a/config/panda_control.yaml b/config/panda_control.yaml index 65fcaf7fd3133a7aa88e41a322718ec51db7ecd0..dae5e66cc440ab3698ca9845146da8a85ab8773d 100644 --- a/config/panda_control.yaml +++ b/config/panda_control.yaml @@ -20,11 +20,15 @@ state_publish_rate: 100 panda_hand_controller: - type: position_controllers/JointTrajectoryController + type: effort_controllers/JointTrajectoryController joints: - panda_finger_joint1 - panda_finger_joint2 + gains: + panda_finger_joint1: { p: 5, d: 3.0, i: 0, i_clamp: 1 } + panda_finger_joint2: { p: 5, d: 1.0, i: 0, i_clamp: 1 } + state_publish_rate: 25 joint_position_controller: diff --git a/worlds/simulator.world b/worlds/simulator.world index 4ee170e5e83221f06b0d95daf5c791511a51af20..a1dd28bca8d465a408b581c6421acc50892cccf4 100644 --- a/worlds/simulator.world +++ b/worlds/simulator.world @@ -12,10 +12,10 @@ <physics name='default_physics' default='0' type='ode'> <!-- the max step size is set to 0.001 by default. --> <!-- When increasing it, the simulation quality may suffer. --> - <max_step_size>0.002</max_step_size> + <max_step_size>0.001</max_step_size> <!-- this factor actually is computed by multiplying the other two --> - <real_time_factor>0.2</real_time_factor> - <real_time_update_rate>100</real_time_update_rate> + <real_time_factor>1.0</real_time_factor> + <real_time_update_rate>1000</real_time_update_rate> </physics> </world> </sdf>