forked from moveit/moveit
-
Notifications
You must be signed in to change notification settings - Fork 0
/
panda-kdl.test
48 lines (42 loc) · 2.08 KB
/
panda-kdl.test
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
<?xml version="1.0"?>
<launch>
<!-- This test file serves both, the standard KDL solver and the LMA solver -->
<arg name="ik_plugin" default="kdl_kinematics_plugin/KDLKinematicsPlugin"/>
<arg name="tolerance" default="1e-5"/>
<arg name="name" value="$(eval 'panda_' + arg('ik_plugin')[0:3])"/>
<group ns="panda">
<include file="$(find moveit_resources_panda_moveit_config)/launch/planning_context.launch">
<arg name="load_robot_description" value="true"/>
</include>
<param name="root_link" value="panda_link0"/>
<param name="tip_link" value="panda_link8"/>
<param name="group" value="panda_arm"/>
<param name="ik_timeout" value="0.2"/>
<param name="tolerance" value="$(arg tolerance)"/>
<rosparam param="joint_names">[panda_joint1, panda_joint2, panda_joint3, panda_joint4, panda_joint5, panda_joint6, panda_joint7]</rosparam>
<!-- KDL-specific solver parameters -->
<param name="ik_plugin_name" value="$(arg ik_plugin)"/>
<param name="robot_description_kinematics/panda_arm/max_solver_iterations" value="100"/>
<!-- by default disable all tests: enable selectively with private parameters -->
<param name="num_fk_tests" value="0"/>
<param name="num_ik_tests" value="0"/>
<param name="num_ik_cb_tests" value="0"/>
<param name="num_ik_multiple_tests" value="0"/>
<param name="num_nearest_ik_tests" value="0"/>
<test test-name="$(arg name)" pkg="moveit_kinematics" type="test_kinematics_plugin" time-limit="180">
<!-- enable basic FK and IK tests -->
<param name="num_fk_tests" value="100"/>
<param name="num_ik_tests" value="100"/>
<!-- use a non-singular seed -->
<rosparam param="seed">[-0.5, -0.5, 0.3, -2, 0.8, 1.8, 1.9]</rosparam>
<rosparam param="consistency_limits">[0.4, 0.4, 0.4, 0.4, 0.4, 0.4, 0.4]</rosparam>
</test>
<test test-name="$(arg name)_singular" pkg="moveit_kinematics" type="test_kinematics_plugin" time-limit="180">
<param name="ik_timeout" value="1.0"/>
<rosparam param="seed">[0, 0, 0, 0, 0, 0, 0]</rosparam> <!-- zero pose is singular -->
<rosparam param="unit_tests">
- pos.z: -0.1
</rosparam>
</test>
</group>
</launch>