Skip to content

Commit 468e3e1

Browse files
committed
UR20 description and meshes
The UR20 meshes are added under Universal Robots A/S’ Terms and Conditions for Use of Graphical Documentation
1 parent 6507bb6 commit 468e3e1

File tree

70 files changed

+5494
-6
lines changed

Some content is hidden

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

70 files changed

+5494
-6
lines changed

README.md

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -3,8 +3,9 @@
33
[![Build Status: Ubuntu Bionic (Actions)](https://github.com/ros-industrial/universal_robot/workflows/CI%20-%20Ubuntu%20Bionic/badge.svg?branch=melodic-devel)](https://github.com/ros-industrial/universal_robot/actions?query=workflow%3A%22CI+-+Ubuntu+Bionic%22)
44
[![Build Status: Ubuntu Focal (Actions)](https://github.com/ros-industrial/universal_robot/workflows/CI%20-%20Ubuntu%20Focal/badge.svg?branch=melodic-devel)](https://github.com/ros-industrial/universal_robot/actions?query=workflow%3A%22CI+-+Ubuntu+Focal%22)
55

6-
[![license - apache 2.0](https://img.shields.io/:license-Apache%202.0-yellowgreen.svg)](https://opensource.org/licenses/Apache-2.0)
6+
[![License - apache 2.0](https://img.shields.io/:license-Apache%202.0-yellowgreen.svg)](https://opensource.org/licenses/Apache-2.0)
77
[![License](https://img.shields.io/badge/License-BSD%203--Clause-blue.svg)](https://opensource.org/licenses/BSD-3-Clause)
8+
[![License](https://img.shields.io/badge/License-Universal%20Robots%20A/S%E2%80%99%20Terms%20and%20Conditions%20for%20Use%20of%20Graphical%20Documentation-blue.svg)](https://www.universal-robots.com/legal/terms-and-conditions/terms_and_conditions_for_use_of_graphical_documentation.txt)
89

910
[![support level: community](https://img.shields.io/badge/support%20level-community-lightgray.png)](http://rosindustrial.org/news/2016/10/7/better-supporting-a-growing-ros-industrial-software-platform)
1011

universal_robots/package.xml

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -23,6 +23,7 @@
2323
<exec_depend>ur10e_moveit_config</exec_depend>
2424
<exec_depend>ur10_moveit_config</exec_depend>
2525
<exec_depend>ur16e_moveit_config</exec_depend>
26+
<exec_depend>ur20_moveit_config</exec_depend>
2627
<exec_depend>ur3e_moveit_config</exec_depend>
2728
<exec_depend>ur3_moveit_config</exec_depend>
2829
<exec_depend>ur5e_moveit_config</exec_depend>
Lines changed: 11 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,11 @@
1+
moveit_setup_assistant_config:
2+
URDF:
3+
package: ur_description
4+
relative_path: urdf/ur20.xacro
5+
xacro_args: ""
6+
SRDF:
7+
relative_path: config/ur20.srdf
8+
CONFIG:
9+
author_name: Felix Exner
10+
author_email: [email protected]
11+
generated_timestamp: 1611154369

ur20_moveit_config/CHANGELOG.rst

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,3 @@
1+
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
2+
Changelog for package ur20_moveit_config
3+
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

ur20_moveit_config/CMakeLists.txt

Lines changed: 14 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,14 @@
1+
cmake_minimum_required(VERSION 2.8.3)
2+
project(ur20_moveit_config)
3+
4+
find_package(catkin REQUIRED)
5+
6+
catkin_package()
7+
8+
if (CATKIN_ENABLE_TESTING)
9+
find_package(roslaunch REQUIRED)
10+
roslaunch_add_file_check(tests/moveit_planning_execution.xml)
11+
endif()
12+
13+
install(DIRECTORY launch DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})
14+
install(DIRECTORY config DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})
Lines changed: 18 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,18 @@
1+
planning_time_limit: 10.0
2+
max_iterations: 200
3+
max_iterations_after_collision_free: 5
4+
smoothness_cost_weight: 0.1
5+
obstacle_cost_weight: 1.0
6+
learning_rate: 0.01
7+
smoothness_cost_velocity: 0.0
8+
smoothness_cost_acceleration: 1.0
9+
smoothness_cost_jerk: 0.0
10+
ridge_factor: 0.01
11+
use_pseudo_inverse: false
12+
pseudo_inverse_ridge_factor: 1e-4
13+
joint_update_limit: 0.1
14+
collision_clearence: 0.2
15+
collision_threshold: 0.07
16+
use_stochastic_descent: true
17+
enable_failure_recovery: true
18+
max_recovery_attempts: 5
Lines changed: 12 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,12 @@
1+
controller_list:
2+
- name: fake_manipulator_controller
3+
joints:
4+
- shoulder_pan_joint
5+
- shoulder_lift_joint
6+
- elbow_joint
7+
- wrist_1_joint
8+
- wrist_2_joint
9+
- wrist_3_joint
10+
initial: # Define initial robot poses.
11+
- group: manipulator
12+
pose: home
Lines changed: 34 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,34 @@
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+
elbow_joint:
6+
has_velocity_limits: true
7+
max_velocity: 3.1415926535897931
8+
has_acceleration_limits: false
9+
max_acceleration: 0
10+
shoulder_lift_joint:
11+
has_velocity_limits: true
12+
max_velocity: 2.0943951023931953
13+
has_acceleration_limits: false
14+
max_acceleration: 0
15+
shoulder_pan_joint:
16+
has_velocity_limits: true
17+
max_velocity: 2.0943951023931953
18+
has_acceleration_limits: false
19+
max_acceleration: 0
20+
wrist_1_joint:
21+
has_velocity_limits: true
22+
max_velocity: 3.1415926535897931
23+
has_acceleration_limits: false
24+
max_acceleration: 0
25+
wrist_2_joint:
26+
has_velocity_limits: true
27+
max_velocity: 3.1415926535897931
28+
has_acceleration_limits: false
29+
max_acceleration: 0
30+
wrist_3_joint:
31+
has_velocity_limits: true
32+
max_velocity: 3.1415926535897931
33+
has_acceleration_limits: false
34+
max_acceleration: 0
Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,5 @@
1+
manipulator:
2+
kinematics_solver: trac_ik_kinematics_plugin/TRAC_IKKinematicsPlugin
3+
solve_type: Distance
4+
kinematics_solver_search_resolution: 0.005
5+
kinematics_solver_timeout: 0.005
Lines changed: 149 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,149 @@
1+
planner_configs:
2+
SBL:
3+
type: geometric::SBL
4+
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
5+
EST:
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+
LBKPIECE:
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+
BKPIECE:
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+
KPIECE:
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+
RRT:
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+
RRTConnect:
32+
type: geometric::RRTConnect
33+
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
34+
RRTstar:
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+
TRRT:
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+
PRM:
51+
type: geometric::PRM
52+
max_nearest_neighbors: 10 # use k nearest neighbors. default: 10
53+
PRMstar:
54+
type: geometric::PRMstar
55+
FMT:
56+
type: geometric::FMT
57+
num_samples: 1000 # number of states that the planner should sample. default: 1000
58+
radius_multiplier: 1.1 # multiplier used for the nearest neighbors search radius. default: 1.1
59+
nearest_k: 1 # use Knearest strategy. default: 1
60+
cache_cc: 1 # use collision checking cache. default: 1
61+
heuristics: 0 # activate cost to go heuristics. default: 0
62+
extended_fmt: 1 # activate the extended FMT*: adding new samples if planner does not finish successfully. default: 1
63+
BFMT:
64+
type: geometric::BFMT
65+
num_samples: 1000 # number of states that the planner should sample. default: 1000
66+
radius_multiplier: 1.0 # multiplier used for the nearest neighbors search radius. default: 1.0
67+
nearest_k: 1 # use the Knearest strategy. default: 1
68+
balanced: 0 # exploration strategy: balanced true expands one tree every iteration. False will select the tree with lowest maximum cost to go. default: 1
69+
optimality: 1 # termination strategy: optimality true finishes when the best possible path is found. Otherwise, the algorithm will finish when the first feasible path is found. default: 1
70+
heuristics: 1 # activates cost to go heuristics. default: 1
71+
cache_cc: 1 # use the collision checking cache. default: 1
72+
extended_fmt: 1 # Activates the extended FMT*: adding new samples if planner does not finish successfully. default: 1
73+
PDST:
74+
type: geometric::PDST
75+
STRIDE:
76+
type: geometric::STRIDE
77+
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
78+
goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05
79+
use_projected_distance: 0 # whether nearest neighbors are computed based on distances in a projection of the state rather distances in the state space itself. default: 0
80+
degree: 16 # desired degree of a node in the Geometric Near-neightbor Access Tree (GNAT). default: 16
81+
max_degree: 18 # max degree of a node in the GNAT. default: 12
82+
min_degree: 12 # min degree of a node in the GNAT. default: 12
83+
max_pts_per_leaf: 6 # max points per leaf in the GNAT. default: 6
84+
estimated_dimension: 0.0 # estimated dimension of the free space. default: 0.0
85+
min_valid_path_fraction: 0.2 # Accept partially valid moves above fraction. default: 0.2
86+
BiTRRT:
87+
type: geometric::BiTRRT
88+
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
89+
temp_change_factor: 0.1 # how much to increase or decrease temp. default: 0.1
90+
init_temperature: 100 # initial temperature. default: 100
91+
frountier_threshold: 0.0 # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup()
92+
frountier_node_ratio: 0.1 # 1/10, or 1 nonfrontier for every 10 frontier. default: 0.1
93+
cost_threshold: 1e300 # the cost threshold. Any motion cost that is not better will not be expanded. default: inf
94+
LBTRRT:
95+
type: geometric::LBTRRT
96+
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
97+
goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05
98+
epsilon: 0.4 # optimality approximation factor. default: 0.4
99+
BiEST:
100+
type: geometric::BiEST
101+
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
102+
ProjEST:
103+
type: geometric::ProjEST
104+
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
105+
goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05
106+
LazyPRM:
107+
type: geometric::LazyPRM
108+
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
109+
LazyPRMstar:
110+
type: geometric::LazyPRMstar
111+
SPARS:
112+
type: geometric::SPARS
113+
stretch_factor: 3.0 # roadmap spanner stretch factor. multiplicative upper bound on path quality. It does not make sense to make this parameter more than 3. default: 3.0
114+
sparse_delta_fraction: 0.25 # delta fraction for connection distance. This value represents the visibility range of sparse samples. default: 0.25
115+
dense_delta_fraction: 0.001 # delta fraction for interface detection. default: 0.001
116+
max_failures: 1000 # maximum consecutive failure limit. default: 1000
117+
SPARStwo:
118+
type: geometric::SPARStwo
119+
stretch_factor: 3.0 # roadmap spanner stretch factor. multiplicative upper bound on path quality. It does not make sense to make this parameter more than 3. default: 3.0
120+
sparse_delta_fraction: 0.25 # delta fraction for connection distance. This value represents the visibility range of sparse samples. default: 0.25
121+
dense_delta_fraction: 0.001 # delta fraction for interface detection. default: 0.001
122+
max_failures: 5000 # maximum consecutive failure limit. default: 5000
123+
manipulator:
124+
longest_valid_segment_fraction: 0.01
125+
default_planner_config: RRTConnect
126+
planner_configs:
127+
- SBL
128+
- EST
129+
- LBKPIECE
130+
- BKPIECE
131+
- KPIECE
132+
- RRT
133+
- RRTConnect
134+
- RRTstar
135+
- TRRT
136+
- PRM
137+
- PRMstar
138+
- FMT
139+
- BFMT
140+
- PDST
141+
- STRIDE
142+
- BiTRRT
143+
- LBTRRT
144+
- BiEST
145+
- ProjEST
146+
- LazyPRM
147+
- LazyPRMstar
148+
- SPARS
149+
- SPARStwo

0 commit comments

Comments
 (0)