Skip to content

Commit 34c6925

Browse files
committed
initial import of drivers for yumi. tested in simulation with robot studio. moveit seems to work fine with launch file demo_online
1 parent e92e09c commit 34c6925

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

44 files changed

+2232
-0
lines changed
+27
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,27 @@
1+
<?xml version="1.0"?>
2+
<robot name="yumi" xmlns:xacro="http://www.ros.org/wiki/xacro">
3+
<!-- Import Rviz colors -->
4+
<xacro:include filename="$(find yumi_description)/urdf/materials.xacro" />
5+
<!-- Import utilities -->
6+
<xacro:include filename="$(find yumi_description)/urdf/utilities.xacro" />
7+
<!--Import the yumi macro -->
8+
<xacro:include filename="$(find yumi_description)/urdf/yumi.xacro"/>
9+
<!--Import the yumi servo gripper macro -->
10+
<xacro:include filename="$(find yumi_description)/urdf/yumi_servo_gripper.xacro"/>
11+
12+
<!--yumi-->
13+
<xacro:yumi name="yumi" hardware_interface="PositionJointInterface" parent="world">
14+
<origin xyz="0 0 0.1" rpy="0 0 0" />
15+
</xacro:yumi>
16+
17+
<!--right gripper-->
18+
<xacro:yumi_servo_gripper name="gripper_r" hardware_interface="PositionJointInterface" parent="yumi_link_7_r">
19+
<origin xyz="0 0 0.007" rpy="0 0 ${PI}" />
20+
</xacro:yumi_servo_gripper>
21+
22+
<!--left gripper-->
23+
<xacro:yumi_servo_gripper name="gripper_l" hardware_interface="PositionJointInterface" parent="yumi_link_7_l">
24+
<origin xyz="0 0 0.007" rpy="0 0 ${PI}" />
25+
</xacro:yumi_servo_gripper>
26+
27+
</robot>

yumi_moveit_config/.setup_assistant

+8
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,8 @@
1+
moveit_setup_assistant_config:
2+
URDF:
3+
package: yumi_description
4+
relative_path: urdf/yumi.urdf
5+
SRDF:
6+
relative_path: config/yumi.srdf
7+
CONFIG:
8+
generated_timestamp: 1458079264

yumi_moveit_config/CMakeLists.txt

+9
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,9 @@
1+
cmake_minimum_required(VERSION 2.8.3)
2+
project(yumi_moveit_config)
3+
4+
find_package(catkin REQUIRED)
5+
6+
catkin_package()
7+
8+
install(DIRECTORY launch DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})
9+
install(DIRECTORY config DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})
+23
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,23 @@
1+
controller_list:
2+
- name: "left_arm"
3+
action_ns: joint_trajectory_action
4+
type: FollowJointTrajectory
5+
joints:
6+
- yumi_joint_1_l
7+
- yumi_joint_2_l
8+
- yumi_joint_7_l
9+
- yumi_joint_3_l
10+
- yumi_joint_4_l
11+
- yumi_joint_5_l
12+
- yumi_joint_6_l
13+
- name: "right_arm"
14+
action_ns: joint_trajectory_action
15+
type: FollowJointTrajectory
16+
joints:
17+
- yumi_joint_1_r
18+
- yumi_joint_2_r
19+
- yumi_joint_7_r
20+
- yumi_joint_3_r
21+
- yumi_joint_4_r
22+
- yumi_joint_5_r
23+
- yumi_joint_6_r
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,19 @@
1+
controller_list:
2+
- name: fake_left_arm_controller
3+
joints:
4+
- yumi_joint_1_l
5+
- yumi_joint_2_l
6+
- yumi_joint_7_l
7+
- yumi_joint_3_l
8+
- yumi_joint_4_l
9+
- yumi_joint_5_l
10+
- yumi_joint_6_l
11+
- name: fake_right_arm_controller
12+
joints:
13+
- yumi_joint_1_r
14+
- yumi_joint_2_r
15+
- yumi_joint_7_r
16+
- yumi_joint_3_r
17+
- yumi_joint_4_r
18+
- yumi_joint_5_r
19+
- yumi_joint_6_r
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,74 @@
1+
# joint_limits.yaml allows the dynamics properties specified in the URDF to be overwritten or augmented as needed
2+
# Specific joint properties can be changed with the keys [max_position, min_position, max_velocity, max_acceleration]
3+
# Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits]
4+
joint_limits:
5+
yumi_joint_1_l:
6+
has_velocity_limits: true
7+
max_velocity: 3.14159265359
8+
has_acceleration_limits: false
9+
max_acceleration: 0
10+
yumi_joint_1_r:
11+
has_velocity_limits: true
12+
max_velocity: 3.14159265359
13+
has_acceleration_limits: false
14+
max_acceleration: 0
15+
yumi_joint_2_l:
16+
has_velocity_limits: true
17+
max_velocity: 3.14159265359
18+
has_acceleration_limits: false
19+
max_acceleration: 0
20+
yumi_joint_2_r:
21+
has_velocity_limits: true
22+
max_velocity: 3.14159265359
23+
has_acceleration_limits: false
24+
max_acceleration: 0
25+
yumi_joint_3_l:
26+
has_velocity_limits: true
27+
max_velocity: 3.14159265359
28+
has_acceleration_limits: false
29+
max_acceleration: 0
30+
yumi_joint_3_r:
31+
has_velocity_limits: true
32+
max_velocity: 3.14159265359
33+
has_acceleration_limits: false
34+
max_acceleration: 0
35+
yumi_joint_4_l:
36+
has_velocity_limits: true
37+
max_velocity: 6.98131700798
38+
has_acceleration_limits: false
39+
max_acceleration: 0
40+
yumi_joint_4_r:
41+
has_velocity_limits: true
42+
max_velocity: 6.98131700798
43+
has_acceleration_limits: false
44+
max_acceleration: 0
45+
yumi_joint_5_l:
46+
has_velocity_limits: true
47+
max_velocity: 6.98131700798
48+
has_acceleration_limits: false
49+
max_acceleration: 0
50+
yumi_joint_5_r:
51+
has_velocity_limits: true
52+
max_velocity: 6.98131700798
53+
has_acceleration_limits: false
54+
max_acceleration: 0
55+
yumi_joint_6_l:
56+
has_velocity_limits: true
57+
max_velocity: 6.98131700798
58+
has_acceleration_limits: false
59+
max_acceleration: 0
60+
yumi_joint_6_r:
61+
has_velocity_limits: true
62+
max_velocity: 6.98131700798
63+
has_acceleration_limits: false
64+
max_acceleration: 0
65+
yumi_joint_7_l:
66+
has_velocity_limits: true
67+
max_velocity: 3.14159265359
68+
has_acceleration_limits: false
69+
max_acceleration: 0
70+
yumi_joint_7_r:
71+
has_velocity_limits: true
72+
max_velocity: 3.14159265359
73+
has_acceleration_limits: false
74+
max_acceleration: 0
+10
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,10 @@
1+
left_arm:
2+
kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin
3+
kinematics_solver_search_resolution: 0.005
4+
kinematics_solver_timeout: 0.005
5+
kinematics_solver_attempts: 3
6+
right_arm:
7+
kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin
8+
kinematics_solver_search_resolution: 0.005
9+
kinematics_solver_timeout: 0.005
10+
kinematics_solver_attempts: 3
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,80 @@
1+
planner_configs:
2+
SBLkConfigDefault:
3+
type: geometric::SBL
4+
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
5+
ESTkConfigDefault:
6+
type: geometric::EST
7+
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0 setup()
8+
goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05
9+
LBKPIECEkConfigDefault:
10+
type: geometric::LBKPIECE
11+
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
12+
border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9
13+
min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5
14+
BKPIECEkConfigDefault:
15+
type: geometric::BKPIECE
16+
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
17+
border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9
18+
failed_expansion_score_factor: 0.5 # When extending motion fails, scale score by factor. default: 0.5
19+
min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5
20+
KPIECEkConfigDefault:
21+
type: geometric::KPIECE
22+
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
23+
goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05
24+
border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 (0.0,1.]
25+
failed_expansion_score_factor: 0.5 # When extending motion fails, scale score by factor. default: 0.5
26+
min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5
27+
RRTkConfigDefault:
28+
type: geometric::RRT
29+
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
30+
goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05
31+
RRTConnectkConfigDefault:
32+
type: geometric::RRTConnect
33+
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
34+
RRTstarkConfigDefault:
35+
type: geometric::RRTstar
36+
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
37+
goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05
38+
delay_collision_checking: 1 # Stop collision checking as soon as C-free parent found. default 1
39+
TRRTkConfigDefault:
40+
type: geometric::TRRT
41+
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
42+
goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05
43+
max_states_failed: 10 # when to start increasing temp. default: 10
44+
temp_change_factor: 2.0 # how much to increase or decrease temp. default: 2.0
45+
min_temperature: 10e-10 # lower limit of temp change. default: 10e-10
46+
init_temperature: 10e-6 # initial temperature. default: 10e-6
47+
frountier_threshold: 0.0 # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup()
48+
frountierNodeRatio: 0.1 # 1/10, or 1 nonfrontier for every 10 frontier. default: 0.1
49+
k_constant: 0.0 # value used to normalize expresssion. default: 0.0 set in setup()
50+
PRMkConfigDefault:
51+
type: geometric::PRM
52+
max_nearest_neighbors: 10 # use k nearest neighbors. default: 10
53+
PRMstarkConfigDefault:
54+
type: geometric::PRMstar
55+
left_arm:
56+
planner_configs:
57+
- SBLkConfigDefault
58+
- ESTkConfigDefault
59+
- LBKPIECEkConfigDefault
60+
- BKPIECEkConfigDefault
61+
- KPIECEkConfigDefault
62+
- RRTkConfigDefault
63+
- RRTConnectkConfigDefault
64+
- RRTstarkConfigDefault
65+
- TRRTkConfigDefault
66+
- PRMkConfigDefault
67+
- PRMstarkConfigDefault
68+
right_arm:
69+
planner_configs:
70+
- SBLkConfigDefault
71+
- ESTkConfigDefault
72+
- LBKPIECEkConfigDefault
73+
- BKPIECEkConfigDefault
74+
- KPIECEkConfigDefault
75+
- RRTkConfigDefault
76+
- RRTConnectkConfigDefault
77+
- RRTstarkConfigDefault
78+
- TRRTkConfigDefault
79+
- PRMkConfigDefault
80+
- PRMstarkConfigDefault

yumi_moveit_config/config/yumi.srdf

+77
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,77 @@
1+
<?xml version="1.0" ?>
2+
<!--This does not replace URDF, and is not an extension of URDF.
3+
This is a format for representing semantic information about the robot structure.
4+
A URDF file must exist for this robot as well, where the joints and the links that are referenced are defined
5+
-->
6+
<robot name="yumi">
7+
<!--GROUPS: Representation of a set of joints and links. This can be useful for specifying DOF to plan for, defining arms, end effectors, etc-->
8+
<!--LINKS: When a link is specified, the parent joint of that link (if it exists) is automatically included-->
9+
<!--JOINTS: When a joint is specified, the child link of that joint (which will always exist) is automatically included-->
10+
<!--CHAINS: When a chain is specified, all the links along the chain (including endpoints) are included in the group. Additionally, all the joints that are parents to included links are also included. This means that joints along the chain and the parent joint of the base link are included in the group-->
11+
<!--SUBGROUPS: Groups can also be formed by referencing to already defined group names-->
12+
<group name="left_arm">
13+
<joint name="world_joint" />
14+
<joint name="yumi_joint_1_l" />
15+
<joint name="yumi_joint_2_l" />
16+
<joint name="yumi_joint_7_l" />
17+
<joint name="yumi_joint_3_l" />
18+
<joint name="yumi_joint_4_l" />
19+
<joint name="yumi_joint_5_l" />
20+
<joint name="yumi_joint_6_l" />
21+
<joint name="yumi_link_7_l_joint" />
22+
</group>
23+
<group name="right_arm">
24+
<joint name="world_joint" />
25+
<joint name="yumi_joint_1_r" />
26+
<joint name="yumi_joint_2_r" />
27+
<joint name="yumi_joint_7_r" />
28+
<joint name="yumi_joint_3_r" />
29+
<joint name="yumi_joint_4_r" />
30+
<joint name="yumi_joint_5_r" />
31+
<joint name="yumi_joint_6_r" />
32+
<joint name="yumi_link_7_r_joint" />
33+
</group>
34+
<!--VIRTUAL JOINT: Purpose: this element defines a virtual joint between a robot link and an external frame of reference (considered fixed with respect to the robot)-->
35+
<virtual_joint name="world_joint" type="fixed" parent_frame="world" child_link="yumi_body" />
36+
<!--DISABLE COLLISIONS: By default it is assumed that any link of the robot could potentially come into collision with any other link in the robot. This tag disables collision checking between a specified pair of links. -->
37+
<disable_collisions link1="gripper_l_base" link2="gripper_l_finger_l" reason="Adjacent" />
38+
<disable_collisions link1="gripper_l_base" link2="gripper_l_finger_r" reason="Adjacent" />
39+
<disable_collisions link1="gripper_l_base" link2="yumi_link_6_l" reason="Never" />
40+
<disable_collisions link1="gripper_l_base" link2="yumi_link_7_l" reason="Adjacent" />
41+
<disable_collisions link1="gripper_l_finger_l" link2="gripper_l_finger_r" reason="Default" />
42+
<disable_collisions link1="gripper_l_finger_l" link2="yumi_link_5_l" reason="Never" />
43+
<disable_collisions link1="gripper_l_finger_l" link2="yumi_link_6_l" reason="Never" />
44+
<disable_collisions link1="gripper_l_finger_l" link2="yumi_link_7_l" reason="Never" />
45+
<disable_collisions link1="gripper_l_finger_r" link2="yumi_link_5_l" reason="Never" />
46+
<disable_collisions link1="gripper_l_finger_r" link2="yumi_link_6_l" reason="Never" />
47+
<disable_collisions link1="gripper_l_finger_r" link2="yumi_link_7_l" reason="Never" />
48+
<disable_collisions link1="gripper_r_base" link2="gripper_r_finger_l" reason="Adjacent" />
49+
<disable_collisions link1="gripper_r_base" link2="gripper_r_finger_r" reason="Adjacent" />
50+
<disable_collisions link1="gripper_r_base" link2="yumi_link_5_l" reason="Default" />
51+
<disable_collisions link1="gripper_r_base" link2="yumi_link_6_l" reason="Default" />
52+
<disable_collisions link1="gripper_r_base" link2="yumi_link_6_r" reason="Never" />
53+
<disable_collisions link1="gripper_r_base" link2="yumi_link_7_r" reason="Adjacent" />
54+
<disable_collisions link1="gripper_r_finger_l" link2="gripper_r_finger_r" reason="Default" />
55+
<disable_collisions link1="gripper_r_finger_l" link2="yumi_link_5_r" reason="Never" />
56+
<disable_collisions link1="gripper_r_finger_l" link2="yumi_link_6_r" reason="Never" />
57+
<disable_collisions link1="gripper_r_finger_l" link2="yumi_link_7_r" reason="Never" />
58+
<disable_collisions link1="gripper_r_finger_r" link2="yumi_link_5_r" reason="Never" />
59+
<disable_collisions link1="gripper_r_finger_r" link2="yumi_link_6_r" reason="Never" />
60+
<disable_collisions link1="gripper_r_finger_r" link2="yumi_link_7_r" reason="Never" />
61+
<disable_collisions link1="yumi_body" link2="yumi_link_1_l" reason="Adjacent" />
62+
<disable_collisions link1="yumi_body" link2="yumi_link_1_r" reason="Adjacent" />
63+
<disable_collisions link1="yumi_link_1_l" link2="yumi_link_2_l" reason="Adjacent" />
64+
<disable_collisions link1="yumi_link_1_r" link2="yumi_link_2_r" reason="Adjacent" />
65+
<disable_collisions link1="yumi_link_2_l" link2="yumi_link_3_l" reason="Adjacent" />
66+
<disable_collisions link1="yumi_link_2_r" link2="yumi_link_3_r" reason="Adjacent" />
67+
<disable_collisions link1="yumi_link_3_l" link2="yumi_link_4_l" reason="Adjacent" />
68+
<disable_collisions link1="yumi_link_3_r" link2="yumi_link_4_r" reason="Adjacent" />
69+
<disable_collisions link1="yumi_link_4_l" link2="yumi_link_5_l" reason="Adjacent" />
70+
<disable_collisions link1="yumi_link_4_r" link2="yumi_link_5_r" reason="Adjacent" />
71+
<disable_collisions link1="yumi_link_5_l" link2="yumi_link_6_l" reason="Adjacent" />
72+
<disable_collisions link1="yumi_link_5_l" link2="yumi_link_7_l" reason="Never" />
73+
<disable_collisions link1="yumi_link_5_r" link2="yumi_link_6_r" reason="Adjacent" />
74+
<disable_collisions link1="yumi_link_5_r" link2="yumi_link_7_r" reason="Never" />
75+
<disable_collisions link1="yumi_link_6_l" link2="yumi_link_7_l" reason="Adjacent" />
76+
<disable_collisions link1="yumi_link_6_r" link2="yumi_link_7_r" reason="Adjacent" />
77+
</robot>
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,15 @@
1+
<launch>
2+
3+
<arg name="reset" default="false"/>
4+
<!-- If not specified, we'll use a default database location -->
5+
<arg name="moveit_warehouse_database_path" default="$(find yumi_moveit_config)/default_warehouse_mongo_db" />
6+
7+
<!-- Launch the warehouse with the configured database location -->
8+
<include file="$(find yumi_moveit_config)/launch/warehouse.launch">
9+
<arg name="moveit_warehouse_database_path" value="$(arg moveit_warehouse_database_path)" />
10+
</include>
11+
12+
<!-- If we want to reset the database, run this node -->
13+
<node if="$(arg reset)" name="$(anon moveit_default_db_reset)" type="moveit_init_demo_warehouse" pkg="moveit_ros_warehouse" respawn="false" output="screen" />
14+
15+
</launch>

0 commit comments

Comments
 (0)