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

Commit 94ca642

Browse files
Merge pull request #283 from project-march/fix/test-joint-yaml
Fix/test joint yaml
2 parents 2ea1a36 + c4eb02d commit 94ca642

File tree

4 files changed

+20
-1
lines changed

4 files changed

+20
-1
lines changed

march_hardware_builder/robots/test_joint_rotational.yaml

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,9 +1,10 @@
11
testsetup:
22
ifName: enp2s0
33
ecatCycleTime: 4
4+
ecatSlaveTimeout: 50
45
joints:
56
- rotational_joint:
6-
actuationMode: position
7+
actuationMode: torque
78
allowActuation: true
89
imotioncube:
910
slaveIndex: 1

march_hardware_builder/test/allowed_robot_test.cpp

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -36,3 +36,10 @@ TEST(AllowedRobotTest, TestTestLinearSetupCreation)
3636
urdf.initFile(ros::package::getPath("march_description").append("/urdf/test_joint_linear.urdf"));
3737
ASSERT_NO_THROW(HardwareBuilder(AllowedRobot::test_joint_linear, urdf).createMarchRobot());
3838
}
39+
40+
TEST(AllowedRobotTest, TestTestRotationalSetupCreation)
41+
{
42+
urdf::Model urdf;
43+
urdf.initFile(ros::package::getPath("march_description").append("/urdf/test_joint_rotational.urdf"));
44+
ASSERT_NO_THROW(HardwareBuilder(AllowedRobot::test_joint_rotational, urdf).createMarchRobot());
45+
}

march_hardware_interface/config/test_joint_linear/controllers.yaml

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -17,3 +17,9 @@ march:
1717
# gains: # Required because we're controlling an effort interface
1818
# test_joint: {p: 50, i: 0, d: 10, i_clamp: 10, publish_state: true, antiwindup: true}
1919
# Note: these gains are tuned for the KFE joints in the exoskeleton
20+
21+
constraints:
22+
linear_joint:
23+
margin_soft_limit_error: 0.5
24+
trajectory: 0.305
25+
goal: 0.305

march_hardware_interface/config/test_joint_rotational/controllers.yaml

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -13,3 +13,8 @@ march:
1313
type: position_controllers/JointTrajectoryController
1414
joints:
1515
- rotational_joint
16+
constraints:
17+
rotational_joint:
18+
margin_soft_limit_error: 0.5
19+
trajectory: 0.305
20+
goal: 0.305

0 commit comments

Comments
 (0)