Skip to content

Commit f749600

Browse files
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.
1 parent 77587e1 commit f749600

File tree

73 files changed

+2547
-21
lines changed

Some content is hidden

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

73 files changed

+2547
-21
lines changed
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,10 @@
1+
moveit_setup_assistant_config:
2+
URDF:
3+
package: abb_irb1200_support
4+
relative_path: urdf/irb1200_5_90.xacro
5+
SRDF:
6+
relative_path: config/abb_irb1200_5_90.srdf
7+
CONFIG:
8+
author_name: Andrew Short
9+
author_email: [email protected]
10+
generated_timestamp: 1505444071
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,10 @@
1+
cmake_minimum_required(VERSION 2.8.3)
2+
project(abb_irb1200_5_90_moveit_config)
3+
4+
find_package(catkin REQUIRED)
5+
6+
catkin_package()
7+
8+
install(DIRECTORY launch DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
9+
PATTERN "setup_assistant.launch" EXCLUDE)
10+
install(DIRECTORY config DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,37 @@
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="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+
<group name="manipulator">
13+
<chain base_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_state name="all_zero" group="manipulator">
17+
<joint name="joint_1" value="0" />
18+
<joint name="joint_2" value="0" />
19+
<joint name="joint_3" value="0" />
20+
<joint name="joint_4" value="0" />
21+
<joint name="joint_5" value="0" />
22+
<joint name="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)-->
25+
<virtual_joint name="fixed_base" type="fixed" parent_frame="world" child_link="base_link" />
26+
<!--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. -->
27+
<disable_collisions link1="base_link" link2="link_1" reason="Adjacent" />
28+
<disable_collisions link1="link_1" link2="link_2" reason="Adjacent" />
29+
<disable_collisions link1="link_2" link2="link_3" reason="Adjacent" />
30+
<disable_collisions link1="link_2" link2="link_5" reason="Never" />
31+
<disable_collisions link1="link_2" link2="link_6" reason="Never" />
32+
<disable_collisions link1="link_3" link2="link_4" reason="Adjacent" />
33+
<disable_collisions link1="link_3" link2="link_5" reason="Never" />
34+
<disable_collisions link1="link_3" link2="link_6" reason="Never" />
35+
<disable_collisions link1="link_4" link2="link_5" reason="Adjacent" />
36+
<disable_collisions link1="link_5" link2="link_6" reason="Adjacent" />
37+
</robot>
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,5 @@
1+
controller_list:
2+
- name: ""
3+
action_ns: joint_trajectory_action
4+
type: FollowJointTrajectory
5+
joints: [joint_1, joint_2, joint_3, joint_4, joint_5, joint_6]
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,9 @@
1+
controller_list:
2+
- name: fake_manipulator_controller
3+
joints:
4+
- joint_1
5+
- joint_2
6+
- joint_3
7+
- joint_4
8+
- joint_5
9+
- joint_6
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+
joint_1:
6+
has_velocity_limits: true
7+
max_velocity: 5.027
8+
has_acceleration_limits: false
9+
max_acceleration: 0
10+
joint_2:
11+
has_velocity_limits: true
12+
max_velocity: 4.189
13+
has_acceleration_limits: false
14+
max_acceleration: 0
15+
joint_3:
16+
has_velocity_limits: true
17+
max_velocity: 5.236
18+
has_acceleration_limits: false
19+
max_acceleration: 0
20+
joint_4:
21+
has_velocity_limits: true
22+
max_velocity: 6.981
23+
has_acceleration_limits: false
24+
max_acceleration: 0
25+
joint_5:
26+
has_velocity_limits: true
27+
max_velocity: 7.069
28+
has_acceleration_limits: false
29+
max_acceleration: 0
30+
joint_6:
31+
has_velocity_limits: true
32+
max_velocity: 10.472
33+
has_acceleration_limits: false
34+
max_acceleration: 0
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,5 @@
1+
manipulator:
2+
kinematics_solver: trac_ik_kinematics_plugin/TRAC_IKKinematicsPlugin
3+
kinematics_solver_search_resolution: 0.005
4+
kinematics_solver_timeout: 0.005
5+
kinematics_solver_attempts: 3
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,150 @@
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+
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
85+
min_valid_path_fraction: 0.2 # Accept partially valid moves above fraction. default: 0.2
86+
BiTRRTkConfigDefault:
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+
LBTRRTkConfigDefault:
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+
BiESTkConfigDefault:
100+
type: geometric::BiEST
101+
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
123+
manipulator:
124+
default_planner_config: RRTConnectkConfigDefault
125+
planner_configs:
126+
- SBLkConfigDefault
127+
- ESTkConfigDefault
128+
- LBKPIECEkConfigDefault
129+
- BKPIECEkConfigDefault
130+
- KPIECEkConfigDefault
131+
- RRTkConfigDefault
132+
- RRTConnectkConfigDefault
133+
- RRTstarkConfigDefault
134+
- TRRTkConfigDefault
135+
- PRMkConfigDefault
136+
- PRMstarkConfigDefault
137+
- FMTkConfigDefault
138+
- BFMTkConfigDefault
139+
- PDSTkConfigDefault
140+
- STRIDEkConfigDefault
141+
- BiTRRTkConfigDefault
142+
- LBTRRTkConfigDefault
143+
- BiESTkConfigDefault
144+
- ProjESTkConfigDefault
145+
- LazyPRMkConfigDefault
146+
- LazyPRMstarkConfigDefault
147+
- SPARSkConfigDefault
148+
- SPARStwokConfigDefault
149+
projection_evaluator: joints(joint_1,joint_2)
150+
longest_valid_segment_fraction: 0.005
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,7 @@
1+
<launch>
2+
<arg name="moveit_controller_manager"
3+
default="moveit_simple_controller_manager/MoveItSimpleControllerManager" />
4+
<param name="moveit_controller_manager"
5+
value="$(arg moveit_controller_manager)" />
6+
<rosparam file="$(find abb_irb1200_5_90_moveit_config)/config/controllers.yaml" />
7+
</launch>
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,3 @@
1+
<launch>
2+
3+
</launch>
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 abb_irb1200_5_90_moveit_config)/default_warehouse_mongo_db" />
6+
7+
<!-- Launch the warehouse with the configured database location -->
8+
<include file="$(find abb_irb1200_5_90_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>
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,57 @@
1+
<launch>
2+
3+
<!-- By default, we do not start a database (it can be large) -->
4+
<arg name="db" default="false" />
5+
<!-- Allow user to specify database location -->
6+
<arg name="db_path" default="$(find abb_irb1200_5_90_moveit_config)/default_warehouse_mongo_db" />
7+
8+
<!-- By default, we are not in debug mode -->
9+
<arg name="debug" default="false" />
10+
11+
<!--
12+
By default, hide joint_state_publisher's GUI
13+
14+
MoveIt!'s "demo" mode replaces the real robot driver with the joint_state_publisher.
15+
The latter one maintains and publishes the current joint configuration of the simulated robot.
16+
It also provides a GUI to move the simulated robot around "manually".
17+
This corresponds to moving around the real robot without the use of MoveIt.
18+
-->
19+
<arg name="use_gui" default="false" />
20+
21+
<!-- Load the URDF, SRDF and other .yaml configuration files on the param server -->
22+
<include file="$(find abb_irb1200_5_90_moveit_config)/launch/planning_context.launch">
23+
<arg name="load_robot_description" value="true"/>
24+
</include>
25+
26+
<!-- If needed, broadcast static tf for robot root -->
27+
28+
29+
<!-- We do not have a robot connected, so publish fake joint states -->
30+
<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher">
31+
<param name="/use_gui" value="$(arg use_gui)"/>
32+
<rosparam param="/source_list">[/move_group/fake_controller_joint_states]</rosparam>
33+
</node>
34+
35+
<!-- Given the published joint states, publish tf for the robot links -->
36+
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" respawn="true" output="screen" />
37+
38+
<!-- Run the main MoveIt executable without trajectory execution (we do not have controllers configured by default) -->
39+
<include file="$(find abb_irb1200_5_90_moveit_config)/launch/move_group.launch">
40+
<arg name="allow_trajectory_execution" value="true"/>
41+
<arg name="fake_execution" value="true"/>
42+
<arg name="info" value="true"/>
43+
<arg name="debug" value="$(arg debug)"/>
44+
</include>
45+
46+
<!-- Run Rviz and load the default config to see the state of the move_group node -->
47+
<include file="$(find abb_irb1200_5_90_moveit_config)/launch/moveit_rviz.launch">
48+
<arg name="config" value="true"/>
49+
<arg name="debug" value="$(arg debug)"/>
50+
</include>
51+
52+
<!-- If database loading was enabled, start mongodb as well -->
53+
<include file="$(find abb_irb1200_5_90_moveit_config)/launch/default_warehouse_db.launch" if="$(arg db)">
54+
<arg name="moveit_warehouse_database_path" value="$(arg db_path)"/>
55+
</include>
56+
57+
</launch>
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,9 @@
1+
<launch>
2+
3+
<!-- Set the param that trajectory_execution_manager needs to find the controller plugin -->
4+
<param name="moveit_controller_manager" value="moveit_fake_controller_manager/MoveItFakeControllerManager"/>
5+
6+
<!-- The rest of the params are specific to this plugin -->
7+
<rosparam file="$(find abb_irb1200_5_90_moveit_config)/config/fake_controllers.yaml"/>
8+
9+
</launch>
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,17 @@
1+
<launch>
2+
<!-- See moveit_ros/visualization/doc/joystick.rst for documentation -->
3+
4+
<arg name="dev" default="/dev/input/js0" />
5+
6+
<!-- Launch joy node -->
7+
<node pkg="joy" type="joy_node" name="joy">
8+
<param name="dev" value="$(arg dev)" /> <!-- Customize this to match the location your joystick is plugged in on-->
9+
<param name="deadzone" value="0.2" />
10+
<param name="autorepeat_rate" value="40" />
11+
<param name="coalesce_interval" value="0.025" />
12+
</node>
13+
14+
<!-- Launch python interface -->
15+
<node pkg="moveit_ros_visualization" type="moveit_joy.py" output="screen" name="moveit_joy"/>
16+
17+
</launch>

0 commit comments

Comments
 (0)