Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

ur_description and ur_gazebo are improved and simplified #624

Open
wants to merge 15 commits into
base: melodic-devel-staging
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -92,7 +92,7 @@ Don't forget to source the correct setup shell files and use a new terminal for

To bring up the simulated robot in Gazebo, run:

```roslaunch ur_gazebo ur5_bringup.launch```
```roslaunch ur_gazebo bringup.launch model:=ur5```


___MoveIt! with a simulated robot___
Expand Down
4 changes: 2 additions & 2 deletions ur10_moveit_config/.setup_assistant
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
moveit_setup_assistant_config:
URDF:
package: ur_description
relative_path: urdf/ur10.xacro
xacro_args: ""
relative_path: urdf/ur.xacro
xacro_args: model:=ur10
SRDF:
relative_path: config/ur10.srdf
CONFIG:
Expand Down
6 changes: 3 additions & 3 deletions ur10_moveit_config/config/ur10.srdf
Original file line number Diff line number Diff line change
Expand Up @@ -32,9 +32,9 @@
<!--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)-->
<virtual_joint name="fixed_base" type="fixed" parent_frame="world" child_link="base_link" />
<!--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. -->
<disable_collisions link1="base_link_inertia" link2="shoulder_link" reason="Adjacent" />
<disable_collisions link1="base_link_inertia" link2="upper_arm_link" reason="Never" />
<disable_collisions link1="base_link_inertia" link2="wrist_1_link" reason="Never" />
<disable_collisions link1="base_inertia_link" link2="shoulder_link" reason="Adjacent" />
<disable_collisions link1="base_inertia_link" link2="upper_arm_link" reason="Never" />
<disable_collisions link1="base_inertia_link" link2="wrist_1_link" reason="Never" />
<disable_collisions link1="forearm_link" link2="upper_arm_link" reason="Adjacent" />
<disable_collisions link1="forearm_link" link2="wrist_1_link" reason="Adjacent" />
<disable_collisions link1="shoulder_link" link2="upper_arm_link" reason="Adjacent" />
Expand Down
4 changes: 2 additions & 2 deletions ur10_moveit_config/launch/moveit.rviz
Original file line number Diff line number Diff line change
Expand Up @@ -80,7 +80,7 @@ Visualization Manager:
Alpha: 1
Show Axes: false
Show Trail: false
base_link_inertia:
base_inertia_link:
Alpha: 1
Show Axes: false
Show Trail: false
Expand Down Expand Up @@ -176,7 +176,7 @@ Visualization Manager:
Alpha: 1
Show Axes: false
Show Trail: false
base_link_inertia:
base_inertia_link:
Alpha: 1
Show Axes: false
Show Trail: false
Expand Down
2 changes: 1 addition & 1 deletion ur10_moveit_config/launch/planning_context.launch
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
<arg name="robot_description" default="robot_description"/>

<!-- Load universal robot description format (URDF) -->
<param if="$(arg load_robot_description)" name="$(arg robot_description)" command="xacro '$(find ur_description)/urdf/ur10.xacro'"/>
<param if="$(arg load_robot_description)" name="$(arg robot_description)" command="xacro '$(find ur_description)/urdf/ur.xacro' model:=ur10"/>

<!-- The semantic description that corresponds to the URDF -->
<param name="$(arg robot_description)_semantic" textfile="$(find ur10_moveit_config)/config/ur10.srdf" />
Expand Down
4 changes: 2 additions & 2 deletions ur10e_moveit_config/.setup_assistant
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
moveit_setup_assistant_config:
URDF:
package: ur_description
relative_path: urdf/ur10e.xacro
xacro_args: ""
relative_path: urdf/ur.xacro
xacro_args: model:=ur10e
SRDF:
relative_path: config/ur10e.srdf
CONFIG:
Expand Down
6 changes: 3 additions & 3 deletions ur10e_moveit_config/config/ur10e.srdf
Original file line number Diff line number Diff line change
Expand Up @@ -32,9 +32,9 @@
<!--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)-->
<virtual_joint name="fixed_base" type="fixed" parent_frame="world" child_link="base_link" />
<!--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. -->
<disable_collisions link1="base_link_inertia" link2="shoulder_link" reason="Adjacent" />
<disable_collisions link1="base_link_inertia" link2="upper_arm_link" reason="Never" />
<disable_collisions link1="base_link_inertia" link2="wrist_1_link" reason="Never" />
<disable_collisions link1="base_inertia_link" link2="shoulder_link" reason="Adjacent" />
<disable_collisions link1="base_inertia_link" link2="upper_arm_link" reason="Never" />
<disable_collisions link1="base_inertia_link" link2="wrist_1_link" reason="Never" />
<disable_collisions link1="forearm_link" link2="upper_arm_link" reason="Adjacent" />
<disable_collisions link1="forearm_link" link2="wrist_1_link" reason="Adjacent" />
<disable_collisions link1="shoulder_link" link2="upper_arm_link" reason="Adjacent" />
Expand Down
4 changes: 2 additions & 2 deletions ur10e_moveit_config/launch/moveit.rviz
Original file line number Diff line number Diff line change
Expand Up @@ -80,7 +80,7 @@ Visualization Manager:
Alpha: 1
Show Axes: false
Show Trail: false
base_link_inertia:
base_inertia_link:
Alpha: 1
Show Axes: false
Show Trail: false
Expand Down Expand Up @@ -176,7 +176,7 @@ Visualization Manager:
Alpha: 1
Show Axes: false
Show Trail: false
base_link_inertia:
base_inertia_link:
Alpha: 1
Show Axes: false
Show Trail: false
Expand Down
2 changes: 1 addition & 1 deletion ur10e_moveit_config/launch/planning_context.launch
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
<arg name="robot_description" default="robot_description"/>

<!-- Load universal robot description format (URDF) -->
<param if="$(arg load_robot_description)" name="$(arg robot_description)" command="xacro '$(find ur_description)/urdf/ur10e.xacro'"/>
<param if="$(arg load_robot_description)" name="$(arg robot_description)" command="xacro '$(find ur_description)/urdf/ur.xacro' model:=ur10e"/>

<!-- The semantic description that corresponds to the URDF -->
<param name="$(arg robot_description)_semantic" textfile="$(find ur10e_moveit_config)/config/ur10e.srdf" />
Expand Down
4 changes: 2 additions & 2 deletions ur16e_moveit_config/.setup_assistant
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
moveit_setup_assistant_config:
URDF:
package: ur_description
relative_path: urdf/ur16e.xacro
xacro_args: ""
relative_path: urdf/ur.xacro
xacro_args: model:=ur16e
SRDF:
relative_path: config/ur16e.srdf
CONFIG:
Expand Down
6 changes: 3 additions & 3 deletions ur16e_moveit_config/config/ur16e.srdf
Original file line number Diff line number Diff line change
Expand Up @@ -32,9 +32,9 @@
<!--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)-->
<virtual_joint name="fixed_base" type="fixed" parent_frame="world" child_link="base_link" />
<!--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. -->
<disable_collisions link1="base_link_inertia" link2="shoulder_link" reason="Adjacent" />
<disable_collisions link1="base_link_inertia" link2="upper_arm_link" reason="Never" />
<disable_collisions link1="base_link_inertia" link2="wrist_1_link" reason="Never" />
<disable_collisions link1="base_inertia_link" link2="shoulder_link" reason="Adjacent" />
<disable_collisions link1="base_inertia_link" link2="upper_arm_link" reason="Never" />
<disable_collisions link1="base_inertia_link" link2="wrist_1_link" reason="Never" />
<disable_collisions link1="forearm_link" link2="upper_arm_link" reason="Adjacent" />
<disable_collisions link1="forearm_link" link2="wrist_1_link" reason="Adjacent" />
<disable_collisions link1="shoulder_link" link2="upper_arm_link" reason="Adjacent" />
Expand Down
4 changes: 2 additions & 2 deletions ur16e_moveit_config/launch/moveit.rviz
Original file line number Diff line number Diff line change
Expand Up @@ -80,7 +80,7 @@ Visualization Manager:
Alpha: 1
Show Axes: false
Show Trail: false
base_link_inertia:
base_inertia_link:
Alpha: 1
Show Axes: false
Show Trail: false
Expand Down Expand Up @@ -176,7 +176,7 @@ Visualization Manager:
Alpha: 1
Show Axes: false
Show Trail: false
base_link_inertia:
base_inertia_link:
Alpha: 1
Show Axes: false
Show Trail: false
Expand Down
2 changes: 1 addition & 1 deletion ur16e_moveit_config/launch/planning_context.launch
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
<arg name="robot_description" default="robot_description"/>

<!-- Load universal robot description format (URDF) -->
<param if="$(arg load_robot_description)" name="$(arg robot_description)" command="xacro '$(find ur_description)/urdf/ur16e.xacro'"/>
<param if="$(arg load_robot_description)" name="$(arg robot_description)" command="xacro '$(find ur_description)/urdf/ur.xacro' model:=ur16e"/>

<!-- The semantic description that corresponds to the URDF -->
<param name="$(arg robot_description)_semantic" textfile="$(find ur16e_moveit_config)/config/ur16e.srdf" />
Expand Down
4 changes: 2 additions & 2 deletions ur3_moveit_config/.setup_assistant
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
moveit_setup_assistant_config:
URDF:
package: ur_description
relative_path: urdf/ur3.xacro
xacro_args: ""
relative_path: urdf/ur.xacro
xacro_args: model:=ur3
SRDF:
relative_path: config/ur3.srdf
CONFIG:
Expand Down
6 changes: 3 additions & 3 deletions ur3_moveit_config/config/ur3.srdf
Original file line number Diff line number Diff line change
Expand Up @@ -32,9 +32,9 @@
<!--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)-->
<virtual_joint name="fixed_base" type="fixed" parent_frame="world" child_link="base_link" />
<!--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. -->
<disable_collisions link1="base_link_inertia" link2="shoulder_link" reason="Adjacent" />
<disable_collisions link1="base_link_inertia" link2="upper_arm_link" reason="Never" />
<disable_collisions link1="base_link_inertia" link2="wrist_1_link" reason="Never" />
<disable_collisions link1="base_inertia_link" link2="shoulder_link" reason="Adjacent" />
<disable_collisions link1="base_inertia_link" link2="upper_arm_link" reason="Never" />
<disable_collisions link1="base_inertia_link" link2="wrist_1_link" reason="Never" />
<disable_collisions link1="forearm_link" link2="upper_arm_link" reason="Adjacent" />
<disable_collisions link1="forearm_link" link2="wrist_1_link" reason="Adjacent" />
<disable_collisions link1="shoulder_link" link2="upper_arm_link" reason="Adjacent" />
Expand Down
4 changes: 2 additions & 2 deletions ur3_moveit_config/launch/moveit.rviz
Original file line number Diff line number Diff line change
Expand Up @@ -80,7 +80,7 @@ Visualization Manager:
Alpha: 1
Show Axes: false
Show Trail: false
base_link_inertia:
base_inertia_link:
Alpha: 1
Show Axes: false
Show Trail: false
Expand Down Expand Up @@ -176,7 +176,7 @@ Visualization Manager:
Alpha: 1
Show Axes: false
Show Trail: false
base_link_inertia:
base_inertia_link:
Alpha: 1
Show Axes: false
Show Trail: false
Expand Down
2 changes: 1 addition & 1 deletion ur3_moveit_config/launch/planning_context.launch
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
<arg name="robot_description" default="robot_description"/>

<!-- Load universal robot description format (URDF) -->
<param if="$(arg load_robot_description)" name="$(arg robot_description)" command="xacro '$(find ur_description)/urdf/ur3.xacro'"/>
<param if="$(arg load_robot_description)" name="$(arg robot_description)" command="xacro '$(find ur_description)/urdf/ur.xacro' model:=ur3"/>

<!-- The semantic description that corresponds to the URDF -->
<param name="$(arg robot_description)_semantic" textfile="$(find ur3_moveit_config)/config/ur3.srdf" />
Expand Down
4 changes: 2 additions & 2 deletions ur3e_moveit_config/.setup_assistant
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
moveit_setup_assistant_config:
URDF:
package: ur_description
relative_path: urdf/ur3e.xacro
xacro_args: ""
relative_path: urdf/ur.xacro
xacro_args: model:=ur3e
SRDF:
relative_path: config/ur3e.srdf
CONFIG:
Expand Down
6 changes: 3 additions & 3 deletions ur3e_moveit_config/config/ur3e.srdf
Original file line number Diff line number Diff line change
Expand Up @@ -32,9 +32,9 @@
<!--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)-->
<virtual_joint name="fixed_base" type="fixed" parent_frame="world" child_link="base_link" />
<!--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. -->
<disable_collisions link1="base_link_inertia" link2="shoulder_link" reason="Adjacent" />
<disable_collisions link1="base_link_inertia" link2="upper_arm_link" reason="Never" />
<disable_collisions link1="base_link_inertia" link2="wrist_1_link" reason="Never" />
<disable_collisions link1="base_inertia_link" link2="shoulder_link" reason="Adjacent" />
<disable_collisions link1="base_inertia_link" link2="upper_arm_link" reason="Never" />
<disable_collisions link1="base_inertia_link" link2="wrist_1_link" reason="Never" />
<disable_collisions link1="forearm_link" link2="upper_arm_link" reason="Adjacent" />
<disable_collisions link1="forearm_link" link2="wrist_1_link" reason="Adjacent" />
<disable_collisions link1="shoulder_link" link2="upper_arm_link" reason="Adjacent" />
Expand Down
4 changes: 2 additions & 2 deletions ur3e_moveit_config/launch/moveit.rviz
Original file line number Diff line number Diff line change
Expand Up @@ -80,7 +80,7 @@ Visualization Manager:
Alpha: 1
Show Axes: false
Show Trail: false
base_link_inertia:
base_inertia_link:
Alpha: 1
Show Axes: false
Show Trail: false
Expand Down Expand Up @@ -176,7 +176,7 @@ Visualization Manager:
Alpha: 1
Show Axes: false
Show Trail: false
base_link_inertia:
base_inertia_link:
Alpha: 1
Show Axes: false
Show Trail: false
Expand Down
2 changes: 1 addition & 1 deletion ur3e_moveit_config/launch/planning_context.launch
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
<arg name="robot_description" default="robot_description"/>

<!-- Load universal robot description format (URDF) -->
<param if="$(arg load_robot_description)" name="$(arg robot_description)" command="xacro '$(find ur_description)/urdf/ur3e.xacro'"/>
<param if="$(arg load_robot_description)" name="$(arg robot_description)" command="xacro '$(find ur_description)/urdf/ur.xacro' model:=ur3e"/>

<!-- The semantic description that corresponds to the URDF -->
<param name="$(arg robot_description)_semantic" textfile="$(find ur3e_moveit_config)/config/ur3e.srdf" />
Expand Down
4 changes: 2 additions & 2 deletions ur5_moveit_config/.setup_assistant
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
moveit_setup_assistant_config:
URDF:
package: ur_description
relative_path: urdf/ur5.xacro
xacro_args: ""
relative_path: urdf/ur.xacro
xacro_args: model:=ur5
SRDF:
relative_path: config/ur5.srdf
CONFIG:
Expand Down
6 changes: 3 additions & 3 deletions ur5_moveit_config/config/ur5.srdf
Original file line number Diff line number Diff line change
Expand Up @@ -32,9 +32,9 @@
<!--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)-->
<virtual_joint name="fixed_base" type="fixed" parent_frame="world" child_link="base_link" />
<!--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. -->
<disable_collisions link1="base_link_inertia" link2="shoulder_link" reason="Adjacent" />
<disable_collisions link1="base_link_inertia" link2="upper_arm_link" reason="Never" />
<disable_collisions link1="base_link_inertia" link2="wrist_1_link" reason="Never" />
<disable_collisions link1="base_inertia_link" link2="shoulder_link" reason="Adjacent" />
<disable_collisions link1="base_inertia_link" link2="upper_arm_link" reason="Never" />
<disable_collisions link1="base_inertia_link" link2="wrist_1_link" reason="Never" />
<disable_collisions link1="forearm_link" link2="upper_arm_link" reason="Adjacent" />
<disable_collisions link1="forearm_link" link2="wrist_1_link" reason="Adjacent" />
<disable_collisions link1="shoulder_link" link2="upper_arm_link" reason="Adjacent" />
Expand Down
4 changes: 2 additions & 2 deletions ur5_moveit_config/launch/moveit.rviz
Original file line number Diff line number Diff line change
Expand Up @@ -80,7 +80,7 @@ Visualization Manager:
Alpha: 1
Show Axes: false
Show Trail: false
base_link_inertia:
base_inertia_link:
Alpha: 1
Show Axes: false
Show Trail: false
Expand Down Expand Up @@ -176,7 +176,7 @@ Visualization Manager:
Alpha: 1
Show Axes: false
Show Trail: false
base_link_inertia:
base_inertia_link:
Alpha: 1
Show Axes: false
Show Trail: false
Expand Down
2 changes: 1 addition & 1 deletion ur5_moveit_config/launch/planning_context.launch
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
<arg name="robot_description" default="robot_description"/>

<!-- Load universal robot description format (URDF) -->
<param if="$(arg load_robot_description)" name="$(arg robot_description)" command="xacro '$(find ur_description)/urdf/ur5.xacro'"/>
<param if="$(arg load_robot_description)" name="$(arg robot_description)" command="xacro '$(find ur_description)/urdf/ur.xacro' model:=ur3"/>

<!-- The semantic description that corresponds to the URDF -->
<param name="$(arg robot_description)_semantic" textfile="$(find ur5_moveit_config)/config/ur5.srdf" />
Expand Down
4 changes: 2 additions & 2 deletions ur5e_moveit_config/.setup_assistant
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
moveit_setup_assistant_config:
URDF:
package: ur_description
relative_path: urdf/ur5e.xacro
xacro_args: ""
relative_path: urdf/ur.xacro
xacro_args: model:=ur5e
SRDF:
relative_path: config/ur5e.srdf
CONFIG:
Expand Down
6 changes: 3 additions & 3 deletions ur5e_moveit_config/config/ur5e.srdf
Original file line number Diff line number Diff line change
Expand Up @@ -32,9 +32,9 @@
<!--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)-->
<virtual_joint name="fixed_base" type="fixed" parent_frame="world" child_link="base_link" />
<!--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. -->
<disable_collisions link1="base_link_inertia" link2="shoulder_link" reason="Adjacent" />
<disable_collisions link1="base_link_inertia" link2="upper_arm_link" reason="Never" />
<disable_collisions link1="base_link_inertia" link2="wrist_1_link" reason="Never" />
<disable_collisions link1="base_inertia_link" link2="shoulder_link" reason="Adjacent" />
<disable_collisions link1="base_inertia_link" link2="upper_arm_link" reason="Never" />
<disable_collisions link1="base_inertia_link" link2="wrist_1_link" reason="Never" />
<disable_collisions link1="forearm_link" link2="upper_arm_link" reason="Adjacent" />
<disable_collisions link1="forearm_link" link2="wrist_1_link" reason="Adjacent" />
<disable_collisions link1="shoulder_link" link2="upper_arm_link" reason="Adjacent" />
Expand Down
4 changes: 2 additions & 2 deletions ur5e_moveit_config/launch/moveit.rviz
Original file line number Diff line number Diff line change
Expand Up @@ -80,7 +80,7 @@ Visualization Manager:
Alpha: 1
Show Axes: false
Show Trail: false
base_link_inertia:
base_inertia_link:
Alpha: 1
Show Axes: false
Show Trail: false
Expand Down Expand Up @@ -176,7 +176,7 @@ Visualization Manager:
Alpha: 1
Show Axes: false
Show Trail: false
base_link_inertia:
base_inertia_link:
Alpha: 1
Show Axes: false
Show Trail: false
Expand Down
2 changes: 1 addition & 1 deletion ur5e_moveit_config/launch/planning_context.launch
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
<arg name="robot_description" default="robot_description"/>

<!-- Load universal robot description format (URDF) -->
<param if="$(arg load_robot_description)" name="$(arg robot_description)" command="xacro '$(find ur_description)/urdf/ur5e.xacro'"/>
<param if="$(arg load_robot_description)" name="$(arg robot_description)" command="xacro '$(find ur_description)/urdf/ur.xacro' model:=ur5e"/>

<!-- The semantic description that corresponds to the URDF -->
<param name="$(arg robot_description)_semantic" textfile="$(find ur5e_moveit_config)/config/ur5e.srdf" />
Expand Down
14 changes: 4 additions & 10 deletions ur_description/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,20 +1,14 @@
cmake_minimum_required(VERSION 3.0.2)
project(ur_description)

find_package(catkin REQUIRED)

catkin_package()

if (CATKIN_ENABLE_TESTING)
find_package(roslaunch REQUIRED)
roslaunch_add_file_check(tests/roslaunch_test_ur10e.xml)
roslaunch_add_file_check(tests/roslaunch_test_ur10.xml)
roslaunch_add_file_check(tests/roslaunch_test_ur16e.xml)
roslaunch_add_file_check(tests/roslaunch_test_ur3e.xml)
roslaunch_add_file_check(tests/roslaunch_test_ur3.xml)
roslaunch_add_file_check(tests/roslaunch_test_ur5e.xml)
roslaunch_add_file_check(tests/roslaunch_test_ur5.xml)
foreach(model ur3 ur3e ur5 ur5e ur10 ur10e ur16e)
roslaunch_add_file_check(launch/test.launch model=${model})
endforeach()
endif()

install(DIRECTORY cfg config launch meshes urdf
install(DIRECTORY config launch meshes urdf
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})
Loading