Skip to content
This repository was archived by the owner on Dec 1, 2020. It is now read-only.

Commit 4b3f917

Browse files
committed
Set testjoint controllers yaml to torque mode
1 parent adee044 commit 4b3f917

File tree

2 files changed

+5
-3
lines changed

2 files changed

+5
-3
lines changed

march_hardware_builder/robots/test_joint_rotational.yaml

+2-2
Original file line numberDiff line numberDiff line change
@@ -10,8 +10,8 @@ testsetup:
1010
slaveIndex: 1
1111
absoluteEncoder:
1212
resolution: 17
13-
minPositionIU: 97242
14-
maxPositionIU: 119617
13+
minPositionIU: 29266
14+
maxPositionIU: 52948
1515
incrementalEncoder:
1616
resolution: 12
1717
transmission: 101

march_hardware_interface/config/test_joint_rotational/controllers.yaml

+3-1
Original file line numberDiff line numberDiff line change
@@ -10,11 +10,13 @@ march:
1010
type: march_pdb_state_controller/MarchPdbStateController
1111
publish_rate: 50
1212
trajectory:
13-
type: position_controllers/JointTrajectoryController
13+
type: effort_controllers/JointTrajectoryController
1414
joints:
1515
- rotational_joint
1616
constraints:
1717
rotational_joint:
1818
margin_soft_limit_error: 0.5
1919
trajectory: 0.305
2020
goal: 0.305
21+
gains: # Required because we're controlling an effort interface
22+
rotational_joint: {p: 150, i: 0, d: 10, i_clamp: 100, publish_state: true, antiwindup: true}

0 commit comments

Comments
 (0)