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

UR20 description and meshes #657

Merged
merged 12 commits into from
Dec 18, 2023
Merged
Show file tree
Hide file tree
Changes from 8 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
14 changes: 13 additions & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -3,13 +3,25 @@
[![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)
[![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)

[![license - apache 2.0](https://img.shields.io/:license-Apache%202.0-yellowgreen.svg)](https://opensource.org/licenses/Apache-2.0)
[![License - apache 2.0](https://img.shields.io/:license-Apache%202.0-yellowgreen.svg)](https://opensource.org/licenses/Apache-2.0)
[![License](https://img.shields.io/badge/License-BSD%203--Clause-blue.svg)](https://opensource.org/licenses/BSD-3-Clause)

[![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)
Copy link
Member

@gavanderhoorn gavanderhoorn Nov 23, 2023

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Should we instead make this point to the ur_description/meshes/ur20/LICENSE.txt file? The online version could be changed at any time. The files in this repository would fall under the version of the license as it is right now, in this PR. It would make sense to me to make this badge link to the version the files would fall under.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

From what I understood, the license is structured such that the latest version always is relevant (see point 1.4)

... If you download a software package that includes the Graphical Documentation, your use of the Graphical Documentation will be subject to and governed by the latest version of the T&Cs, which can be found here: ...

Given that clause I think it does make sense to link to the online version.

Copy link
Member

@gavanderhoorn gavanderhoorn Nov 24, 2023

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I'm not sure that's legal. There would be no change notification to current users, UR would be able to silently, unilaterally change the complete license without anyone being aware of it, and with all licenses I've worked with (and in the jurisdictions I've had to work with licenses), once you have a copy of the artefacts under that license, that copy and/or version will always fall under the version of the license as it was when you agreed to it.

I have seen licenses where there are provisions for updates made by the licensor, but those always include some sort of notification period, allowing current licensees to terminate their use of whatever is under the existing license if they feel they can't, or don't want to, agree to the new version.

Additionally, there is already a copy of the current version in the repository -- or at least there will be, after merging this PR.

It's best practice to include a copy of the license in all cases, even with OSS licenses. We don't do that currently in this repository, but that's an omission and should be fixed (in a later PR).

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The same section 1.4 also states:

However, you may only make the Graphical Documentation or any whole or partial copies thereof available to the public via download if it is part of a downloadable software package that includes a copy of the T&Cs.

which is what this PR will result in: a copy will be included.

So it doesn't seem strange to me to then point to that copy, and not the online version.

That seems like it would just lead to confusing situations.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

You have a point. Though the motivation was to remove the burden from the repo owner to ensure that the license is up to date.


[![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)

fmauch marked this conversation as resolved.
Show resolved Hide resolved
[![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)

[ROS-Industrial](https://wiki.ros.org/Industrial) Universal Robot meta-package. See the [ROS wiki](https://wiki.ros.org/universal_robots) page for compatibility information and other more information.

__License__
urrsk marked this conversation as resolved.
Show resolved Hide resolved

The [UR20 meshes](ur_description/meshes/ur20) constitutes “Graphical Documentation” the use of which is subject to and governed by our “[Terms and Conditions for use of Graphical Documentation](https://www.universal-robots.com/legal/terms-and-conditions/terms_and_conditions_for_use_of_graphical_documentation.txt)”.\
urrsk marked this conversation as resolved.
Show resolved Hide resolved
If you have any questions regarding the license or the license doesn't fit you use-case, please contact [legal@universal-robots.com](mailto:legal@universal-robots.com).
fmauch marked this conversation as resolved.
Show resolved Hide resolved

All other content is licensed under the BSD-3-Clause license or Apache-2.0 respectively.



__Installation__

Expand Down
1 change: 1 addition & 0 deletions universal_robots/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@
<exec_depend>ur10e_moveit_config</exec_depend>
<exec_depend>ur10_moveit_config</exec_depend>
<exec_depend>ur16e_moveit_config</exec_depend>
<exec_depend>ur20_moveit_config</exec_depend>
<exec_depend>ur3e_moveit_config</exec_depend>
<exec_depend>ur3_moveit_config</exec_depend>
<exec_depend>ur5e_moveit_config</exec_depend>
Expand Down
11 changes: 11 additions & 0 deletions ur20_moveit_config/.setup_assistant
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
moveit_setup_assistant_config:
URDF:
package: ur_description
relative_path: urdf/ur20.xacro
xacro_args: ""
SRDF:
relative_path: config/ur20.srdf
CONFIG:
author_name: Felix Exner
author_email: felix@fexner.de
generated_timestamp: 1611154369
14 changes: 14 additions & 0 deletions ur20_moveit_config/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,14 @@
cmake_minimum_required(VERSION 3.0.2)
project(ur20_moveit_config)

find_package(catkin REQUIRED)

catkin_package()

if (CATKIN_ENABLE_TESTING)
find_package(roslaunch REQUIRED)
roslaunch_add_file_check(tests/moveit_planning_execution.xml)
endif()

install(DIRECTORY launch DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})
install(DIRECTORY config DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})
18 changes: 18 additions & 0 deletions ur20_moveit_config/config/chomp_planning.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
planning_time_limit: 10.0
max_iterations: 200
max_iterations_after_collision_free: 5
smoothness_cost_weight: 0.1
obstacle_cost_weight: 1.0
learning_rate: 0.01
smoothness_cost_velocity: 0.0
smoothness_cost_acceleration: 1.0
smoothness_cost_jerk: 0.0
ridge_factor: 0.01
use_pseudo_inverse: false
pseudo_inverse_ridge_factor: 1e-4
joint_update_limit: 0.1
collision_clearence: 0.2
collision_threshold: 0.07
use_stochastic_descent: true
enable_failure_recovery: true
max_recovery_attempts: 5
12 changes: 12 additions & 0 deletions ur20_moveit_config/config/fake_controllers.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,12 @@
controller_list:
- name: fake_manipulator_controller
joints:
- shoulder_pan_joint
- shoulder_lift_joint
- elbow_joint
- wrist_1_joint
- wrist_2_joint
- wrist_3_joint
initial: # Define initial robot poses.
- group: manipulator
pose: home
34 changes: 34 additions & 0 deletions ur20_moveit_config/config/joint_limits.yaml
fmauch marked this conversation as resolved.
Show resolved Hide resolved
Original file line number Diff line number Diff line change
@@ -0,0 +1,34 @@
# joint_limits.yaml allows the dynamics properties specified in the URDF to be overwritten or augmented as needed
# Specific joint properties can be changed with the keys [max_position, min_position, max_velocity, max_acceleration]
# Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits]
joint_limits:
elbow_joint:
has_velocity_limits: true
max_velocity: 3.1415926535897931
has_acceleration_limits: false
max_acceleration: 0
shoulder_lift_joint:
has_velocity_limits: true
max_velocity: 2.0943951023931953
has_acceleration_limits: false
max_acceleration: 0
shoulder_pan_joint:
has_velocity_limits: true
max_velocity: 2.0943951023931953
has_acceleration_limits: false
max_acceleration: 0
wrist_1_joint:
has_velocity_limits: true
max_velocity: 3.1415926535897931
has_acceleration_limits: false
max_acceleration: 0
wrist_2_joint:
has_velocity_limits: true
max_velocity: 3.1415926535897931
has_acceleration_limits: false
max_acceleration: 0
wrist_3_joint:
has_velocity_limits: true
max_velocity: 3.1415926535897931
has_acceleration_limits: false
max_acceleration: 0
5 changes: 5 additions & 0 deletions ur20_moveit_config/config/kinematics.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
manipulator:
kinematics_solver: trac_ik_kinematics_plugin/TRAC_IKKinematicsPlugin
solve_type: Distance
kinematics_solver_search_resolution: 0.005
kinematics_solver_timeout: 0.005
149 changes: 149 additions & 0 deletions ur20_moveit_config/config/ompl_planning.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,149 @@
planner_configs:
SBL:
type: geometric::SBL
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
EST:
type: geometric::EST
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0 setup()
goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05
LBKPIECE:
type: geometric::LBKPIECE
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9
min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5
BKPIECE:
type: geometric::BKPIECE
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9
failed_expansion_score_factor: 0.5 # When extending motion fails, scale score by factor. default: 0.5
min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5
KPIECE:
type: geometric::KPIECE
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05
border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 (0.0,1.]
failed_expansion_score_factor: 0.5 # When extending motion fails, scale score by factor. default: 0.5
min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5
RRT:
type: geometric::RRT
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05
RRTConnect:
type: geometric::RRTConnect
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
RRTstar:
type: geometric::RRTstar
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05
delay_collision_checking: 1 # Stop collision checking as soon as C-free parent found. default 1
TRRT:
type: geometric::TRRT
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05
max_states_failed: 10 # when to start increasing temp. default: 10
temp_change_factor: 2.0 # how much to increase or decrease temp. default: 2.0
min_temperature: 10e-10 # lower limit of temp change. default: 10e-10
init_temperature: 10e-6 # initial temperature. default: 10e-6
frountier_threshold: 0.0 # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup()
frountierNodeRatio: 0.1 # 1/10, or 1 nonfrontier for every 10 frontier. default: 0.1
k_constant: 0.0 # value used to normalize expresssion. default: 0.0 set in setup()
PRM:
type: geometric::PRM
max_nearest_neighbors: 10 # use k nearest neighbors. default: 10
PRMstar:
type: geometric::PRMstar
FMT:
type: geometric::FMT
num_samples: 1000 # number of states that the planner should sample. default: 1000
radius_multiplier: 1.1 # multiplier used for the nearest neighbors search radius. default: 1.1
nearest_k: 1 # use Knearest strategy. default: 1
cache_cc: 1 # use collision checking cache. default: 1
heuristics: 0 # activate cost to go heuristics. default: 0
extended_fmt: 1 # activate the extended FMT*: adding new samples if planner does not finish successfully. default: 1
BFMT:
type: geometric::BFMT
num_samples: 1000 # number of states that the planner should sample. default: 1000
radius_multiplier: 1.0 # multiplier used for the nearest neighbors search radius. default: 1.0
nearest_k: 1 # use the Knearest strategy. default: 1
balanced: 0 # exploration strategy: balanced true expands one tree every iteration. False will select the tree with lowest maximum cost to go. default: 1
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
heuristics: 1 # activates cost to go heuristics. default: 1
cache_cc: 1 # use the collision checking cache. default: 1
extended_fmt: 1 # Activates the extended FMT*: adding new samples if planner does not finish successfully. default: 1
PDST:
type: geometric::PDST
STRIDE:
type: geometric::STRIDE
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05
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
degree: 16 # desired degree of a node in the Geometric Near-neightbor Access Tree (GNAT). default: 16
max_degree: 18 # max degree of a node in the GNAT. default: 12
min_degree: 12 # min degree of a node in the GNAT. default: 12
max_pts_per_leaf: 6 # max points per leaf in the GNAT. default: 6
estimated_dimension: 0.0 # estimated dimension of the free space. default: 0.0
min_valid_path_fraction: 0.2 # Accept partially valid moves above fraction. default: 0.2
BiTRRT:
type: geometric::BiTRRT
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
temp_change_factor: 0.1 # how much to increase or decrease temp. default: 0.1
init_temperature: 100 # initial temperature. default: 100
frountier_threshold: 0.0 # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup()
frountier_node_ratio: 0.1 # 1/10, or 1 nonfrontier for every 10 frontier. default: 0.1
cost_threshold: 1e300 # the cost threshold. Any motion cost that is not better will not be expanded. default: inf
LBTRRT:
type: geometric::LBTRRT
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05
epsilon: 0.4 # optimality approximation factor. default: 0.4
BiEST:
type: geometric::BiEST
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
ProjEST:
type: geometric::ProjEST
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05
LazyPRM:
type: geometric::LazyPRM
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
LazyPRMstar:
type: geometric::LazyPRMstar
SPARS:
type: geometric::SPARS
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
sparse_delta_fraction: 0.25 # delta fraction for connection distance. This value represents the visibility range of sparse samples. default: 0.25
dense_delta_fraction: 0.001 # delta fraction for interface detection. default: 0.001
max_failures: 1000 # maximum consecutive failure limit. default: 1000
SPARStwo:
type: geometric::SPARStwo
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
sparse_delta_fraction: 0.25 # delta fraction for connection distance. This value represents the visibility range of sparse samples. default: 0.25
dense_delta_fraction: 0.001 # delta fraction for interface detection. default: 0.001
max_failures: 5000 # maximum consecutive failure limit. default: 5000
manipulator:
longest_valid_segment_fraction: 0.01
default_planner_config: RRTConnect
planner_configs:
- SBL
- EST
- LBKPIECE
- BKPIECE
- KPIECE
- RRT
- RRTConnect
- RRTstar
- TRRT
- PRM
- PRMstar
- FMT
- BFMT
- PDST
- STRIDE
- BiTRRT
- LBTRRT
- BiEST
- ProjEST
- LazyPRM
- LazyPRMstar
- SPARS
- SPARStwo
11 changes: 11 additions & 0 deletions ur20_moveit_config/config/ros_controllers.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
controller_list:
- name: "scaled_pos_joint_traj_controller"
action_ns: follow_joint_trajectory
type: FollowJointTrajectory
joints:
- shoulder_pan_joint
- shoulder_lift_joint
- elbow_joint
- wrist_1_joint
- wrist_2_joint
- wrist_3_joint
46 changes: 46 additions & 0 deletions ur20_moveit_config/config/ur20.srdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,46 @@
<?xml version="1.0" ?>
<!--This does not replace URDF, and is not an extension of URDF.
This is a format for representing semantic information about the robot structure.
A URDF file must exist for this robot as well, where the joints and the links that are referenced are defined
-->
<robot name="ur20_robot">
<!--GROUPS: Representation of a set of joints and links. This can be useful for specifying DOF to plan for, defining arms, end effectors, etc-->
<!--LINKS: When a link is specified, the parent joint of that link (if it exists) is automatically included-->
<!--JOINTS: When a joint is specified, the child link of that joint (which will always exist) is automatically included-->
<!--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-->
<!--SUBGROUPS: Groups can also be formed by referencing to already defined group names-->
<group name="manipulator">
<chain base_link="base_link" tip_link="tool0" />
</group>
<!--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'-->
<group_state name="home" group="manipulator">
<joint name="elbow_joint" value="0" />
<joint name="shoulder_lift_joint" value="0" />
<joint name="shoulder_pan_joint" value="0" />
<joint name="wrist_1_joint" value="0" />
<joint name="wrist_2_joint" value="0" />
<joint name="wrist_3_joint" value="0" />
</group_state>
<group_state name="up" group="manipulator">
<joint name="elbow_joint" value="0" />
<joint name="shoulder_lift_joint" value="-1.5707" />
<joint name="shoulder_pan_joint" value="0" />
<joint name="wrist_1_joint" value="-1.5707" />
<joint name="wrist_2_joint" value="0" />
<joint name="wrist_3_joint" value="0" />
</group_state>
<!--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="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" />
<disable_collisions link1="shoulder_link" link2="wrist_1_link" reason="Never" />
<disable_collisions link1="shoulder_link" link2="wrist_2_link" reason="Never" />
<disable_collisions link1="wrist_1_link" link2="wrist_2_link" reason="Adjacent" />
<disable_collisions link1="wrist_1_link" link2="wrist_3_link" reason="Never" />
<disable_collisions link1="wrist_2_link" link2="wrist_3_link" reason="Adjacent" />
</robot>
20 changes: 20 additions & 0 deletions ur20_moveit_config/launch/chomp_planning_pipeline.launch.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,20 @@
<launch>
<!-- CHOMP Plugin for MoveIt! -->
<arg name="planning_plugin" value="chomp_interface/CHOMPPlanner" />
<arg name="start_state_max_bounds_error" value="0.1" />
<!-- The request adapters (plugins) used when planning.
ORDER MATTERS -->
<arg name="planning_adapters"
value="default_planner_request_adapters/AddTimeParameterization
default_planner_request_adapters/FixWorkspaceBounds
default_planner_request_adapters/FixStartStateBounds
default_planner_request_adapters/FixStartStateCollision
default_planner_request_adapters/FixStartStatePathConstraints"
/>

<param name="planning_plugin" value="$(arg planning_plugin)" />
<param name="request_adapters" value="$(arg planning_adapters)" />
<param name="start_state_max_bounds_error" value="$(arg start_state_max_bounds_error)" />

<rosparam command="load" file="$(find ur20_moveit_config)/config/chomp_planning.yaml" />
</launch>
15 changes: 15 additions & 0 deletions ur20_moveit_config/launch/default_warehouse_db.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,15 @@
<launch>

<arg name="reset" default="false"/>
<!-- If not specified, we'll use a default database location -->
<arg name="moveit_warehouse_database_path" default="$(find ur20_moveit_config)/default_warehouse_mongo_db" />

<!-- Launch the warehouse with the configured database location -->
<include file="$(find ur20_moveit_config)/launch/warehouse.launch">
<arg name="moveit_warehouse_database_path" value="$(arg moveit_warehouse_database_path)" />
</include>

<!-- If we want to reset the database, run this node -->
<node if="$(arg reset)" name="$(anon moveit_default_db_reset)" type="moveit_init_demo_warehouse" pkg="moveit_ros_warehouse" respawn="false" output="screen" />

</launch>
Loading