You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
IRB 1200 updates and experimental (MoveIt) support for 7/0.7 variant (#85)
This commit is the result of squashing a range of commits that introduced:
- support for the 7/0.7 variant of the IRB 1200
- MoveIt configurations for both the 5/0.9 and the 7/0.7
The range of commits was squashed to prevent repository bloat (due to overly complex and detailed meshes that received numerous edits and saw numerous revisions).
The following people contributed to these updates to the IRB 1200 support in ROS-Industrial:
- Andrew Short (@ajshort): initial PR and support for 7/0.7 and MoveIt
- Stephan Wirth (@stwirth): joints update in support pkg
- Bianca Homberg (@bhomberg): Collada meshes for 7/0.7
- Jonathan Binney (@jonbinney): fixes to Collada meshes
Squashed commits:
* Add ABB IRB 1200 moveit package
* IRB1200 moveit controllers and execution
* Add IRB1200 7-70 model
* Create IRB1200 7-70 moveit package
* Add IRB1200 7-70 moveit controllers
* Simplify collision models
* Correct reference to launch file
* Correct joint names file reference
* Decouple joint_names_irb1200.yaml for both robot variants.
* irb1200_support: be explicit about which variants are supported exactly.
* irb1200_support: refer to ABB doc ID.
* irb1200_7_70: fix mesh origins, scaling and normals.
* irb1200_7_70: use xacro pi.
* irb1200_7_70: subsample meshes.
* irb1200_moveit_cfg: make RRTConnect the default planner.
* irb1200_moveit_cfg: use standardised 'all_zero' name for all-zeros home pos.
* irb1200_moveit_cfg: fixup moveit_planning_execution launch file.
* irb1200_moveit_cfg: fixup package manifests.
* irb1200_moveit_cfg: use a more sane default RViz config.
* irb1200_moveit_cfg: use Trac IK as default IK plugin.
* irb1200_5_90: use xacro pi.
* Add all collada meshes
* irb1200_7_70: share even more meshes.
* irb1200: set yellow material on collision geometry.
<!--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
+
<robotname="abb_irb1200_5_90">
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
+
<groupname="manipulator">
13
+
<chainbase_link="base_link"tip_link="tool0" />
14
+
</group>
15
+
<!--GROUP STATES: Purpose: Define a named state for a particular group, in terms of joint values. This is useful to define states like 'folded arms'-->
16
+
<group_statename="all_zero"group="manipulator">
17
+
<jointname="joint_1"value="0" />
18
+
<jointname="joint_2"value="0" />
19
+
<jointname="joint_3"value="0" />
20
+
<jointname="joint_4"value="0" />
21
+
<jointname="joint_5"value="0" />
22
+
<jointname="joint_6"value="0" />
23
+
</group_state>
24
+
<!--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)-->
<!--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. -->
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
+
FMTkConfigDefault:
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
+
BFMTkConfigDefault:
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
+
PDSTkConfigDefault:
74
+
type: geometric::PDST
75
+
STRIDEkConfigDefault:
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
range: 0.0# Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
102
+
ProjESTkConfigDefault:
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
+
LazyPRMkConfigDefault:
107
+
type: geometric::LazyPRM
108
+
range: 0.0# Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
109
+
LazyPRMstarkConfigDefault:
110
+
type: geometric::LazyPRMstar
111
+
SPARSkConfigDefault:
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
+
SPARStwokConfigDefault:
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
0 commit comments