Skip to content
This repository has been archived by the owner on Dec 13, 2024. It is now read-only.

Add Machine Tending Mock Hardware Configuration #72

Merged
merged 19 commits into from
Jul 26, 2023
Merged
Show file tree
Hide file tree
Changes from 18 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
Original file line number Diff line number Diff line change
Expand Up @@ -4,4 +4,4 @@ be under the 3-Clause BSD License, as dictated by that

# Contributing to this Repository

Thanks for getting involved! If you want to add to this base config, please reach out to [email protected]
Thanks for getting involved! If you want to add to this repository, please reach out to [email protected].
31 changes: 18 additions & 13 deletions README.md
Original file line number Diff line number Diff line change
@@ -1,27 +1,32 @@
# MoveIt Studio Workspace

This is a sample user workspace for running MoveIt Studio with a generic Universal Robots arm.
This is a sample user workspace for running MoveIt Studio with a generic Universal Robots (UR) arm.
For more information, refer to the [MoveIt Studio Documentation](https://docs.picknik.ai/).

Instructions for building your own MoveIt Studio configuration can be found [in the getting started guides.](https://docs.picknik.ai/en/stable/getting_started/getting_started.html)

MoveIt Studio can be used with real robots and full simulators such as Gazebo and NVIDIA Isaac Sim.
For testing purposes, you can also use the [ROS 2 Control Mock Components](https://control.ros.org/master/doc/ros2_control/hardware_interface/doc/mock_components_userdoc.html), which is what this repo is configured to use.

---
## MoveIt Studio Configuration

This package follows the recommended layout of a MoveIt Studio configuration package.
Any configuration package or custom Behavior implementation can be included in the `src/` directory.
Packages in `src/` will be compiled and sourced by MoveIt Studio at first launch.
This workspace offers a reasonable starting point for those users looking to develop with MoveIt Studio using custom base and site configurations.
For more information refer to the [online documentation](https://docs.picknik.ai/en/stable/).

### Concepts
## Universal Robots Configuration Packages

MoveIt Studio supports two types of site configuration packages, a base config and site config.
This workspace contains several MoveIt Studio configuration packages for UR arms that inherit from each other for different applications.

[Base configs](src/picknik_ur_base_config/README.md) are used to configure all of the system components that remain unchanged when deploying the robot to a new location.
```mermaid
graph TB
Base[picknik_ur_base_config] --> Site[picknik_ur_site_config]
eholum marked this conversation as resolved.
Show resolved Hide resolved
Base --> Mock[picknik_ur_mock_hw_config]
Site --> Gazebo[picknik_ur_gazebo_config]
Site --> Picknik[Other PickNik configs]
```

[Site configs](src/picknik_ur_site_config/README.md) are used to override any parameters of the base configuration, or add additional features or constraints for a particular installation.
Specifically:

This workspace offers a reasonable starting point for those users looking to develop with MoveIt Studio using custom base and site configurations.
For more information refer to the [online documentation](https://docs.picknik.ai/en/stable/).
* `picknik_ur_base_config` contains common configuration for all UR arms, real or simulated.
* `picknik_ur_mock_hw_config` provides overrides for a machine tending application simulated using mock components (no physics).
* `picknik_ur_site_config` extends the base configuration with capabilities for robots with physics and perception.
* `picknik_ur_gazebo_config` extends the site configuration with support for the Gazebo simulator.
* Other hardware-specific configurations, such as the ones used on PickNik's UR arms, inherit from `picknik_ur_site_config`.
2 changes: 1 addition & 1 deletion src/moveit_studio_agent_examples/package.xml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<package format="3">
<name>moveit_studio_agent_examples</name>
<version>2.4.0</version>
<version>2.5.0</version>
<description>Package containing scripts for interacting with MoveIt Studio Agent</description>

<maintainer email="[email protected]">Chance Cardona</maintainer>
Expand Down
2 changes: 1 addition & 1 deletion src/picknik_ur_base_config/README.md
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
# picknik_ur_base_config

A MoveIt Studio base configuration for PickNik's UR5e simulation.
A MoveIt Studio base configuration for PickNik's Universal Robots (UR) arms.

For detailed documentation see: [MoveIt Studio Documentation](https://docs.picknik.ai/)
2 changes: 1 addition & 1 deletion src/picknik_ur_base_config/config/config.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@ hardware:

# The robot's IP address.
# [Required]
ip: "!!! Please set the IP address of the robot"
ip: "0.0.0.0"

# Specify additional launch files for running the robot with real hardware.
# [Optional, defaults to a blank launch file if not specified]
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,28 +5,28 @@
<Control ID="Sequence">
<!-- Clear snapshot, move to center pose, and open gripper -->
<Action ID="ClearSnapshot" />
<Action ID="MoveToJointState" waypoint_name="Look at Table" planning_group_name="manipulator" controller_names="/joint_trajectory_controller /robotiq_gripper_controller"/>
<Action ID="MoveToJointState" waypoint_name="Look at Table" planning_group_name="manipulator" controller_names="/joint_trajectory_controller /robotiq_gripper_controller" use_all_planners="true"/>
<Action ID="MoveGripperAction" gripper_command_action_name="/robotiq_gripper_controller/gripper_cmd" position="0"/>
<!-- Keep executing the pick and place sequence until failure -->
<Decorator ID="KeepRunningUntilFailure">
<Control ID="Sequence">
<!-- Pick object from "Grab", put it down at "Place", and go back to center pose -->
<Control ID="Sequence">
<Action ID="MoveToJointState" waypoint_name="Pick Block" planning_group_name="manipulator" controller_names="/joint_trajectory_controller /robotiq_gripper_controller"/>
<Action ID="MoveToJointState" waypoint_name="Pick Block" planning_group_name="manipulator" controller_names="/joint_trajectory_controller /robotiq_gripper_controller" use_all_planners="true"/>
<Action ID="MoveGripperAction" gripper_command_action_name="/robotiq_gripper_controller/gripper_cmd" position="0.7929"/>
<Action ID="MoveToJointState" waypoint_name="Look at Table" planning_group_name="manipulator" controller_names="/joint_trajectory_controller /robotiq_gripper_controller"/>
<Action ID="MoveToJointState" waypoint_name="Place Block" planning_group_name="manipulator" controller_names="/joint_trajectory_controller /robotiq_gripper_controller"/>
<Action ID="MoveToJointState" waypoint_name="Look at Table" planning_group_name="manipulator" controller_names="/joint_trajectory_controller /robotiq_gripper_controller" use_all_planners="true"/>
<Action ID="MoveToJointState" waypoint_name="Place Block" planning_group_name="manipulator" controller_names="/joint_trajectory_controller /robotiq_gripper_controller" use_all_planners="true"/>
<Action ID="MoveGripperAction" gripper_command_action_name="/robotiq_gripper_controller/gripper_cmd" position="0"/>
<Action ID="MoveToJointState" waypoint_name="Look at Table" planning_group_name="manipulator" controller_names="/joint_trajectory_controller /robotiq_gripper_controller"/>
<Action ID="MoveToJointState" waypoint_name="Look at Table" planning_group_name="manipulator" controller_names="/joint_trajectory_controller /robotiq_gripper_controller" use_all_planners="true"/>
</Control>
<!-- Pick object from "Place", put it down at "Grab", and go back to center pose -->
<Control ID="Sequence">
<Action ID="MoveToJointState" waypoint_name="Place Block" planning_group_name="manipulator" controller_names="/joint_trajectory_controller /robotiq_gripper_controller"/>
<Action ID="MoveToJointState" waypoint_name="Place Block" planning_group_name="manipulator" controller_names="/joint_trajectory_controller /robotiq_gripper_controller" use_all_planners="true"/>
<Action ID="MoveGripperAction" gripper_command_action_name="/robotiq_gripper_controller/gripper_cmd" position="0.7929"/>
<Action ID="MoveToJointState" waypoint_name="Look at Table" planning_group_name="manipulator" controller_names="/joint_trajectory_controller /robotiq_gripper_controller"/>
<Action ID="MoveToJointState" waypoint_name="Pick Block" planning_group_name="manipulator" controller_names="/joint_trajectory_controller /robotiq_gripper_controller"/>
<Action ID="MoveToJointState" waypoint_name="Look at Table" planning_group_name="manipulator" controller_names="/joint_trajectory_controller /robotiq_gripper_controller" use_all_planners="true"/>
<Action ID="MoveToJointState" waypoint_name="Pick Block" planning_group_name="manipulator" controller_names="/joint_trajectory_controller /robotiq_gripper_controller" use_all_planners="true"/>
<Action ID="MoveGripperAction" gripper_command_action_name="/robotiq_gripper_controller/gripper_cmd" position="0"/>
<Action ID="MoveToJointState" waypoint_name="Look at Table" planning_group_name="manipulator" controller_names="/joint_trajectory_controller /robotiq_gripper_controller"/>
<Action ID="MoveToJointState" waypoint_name="Look at Table" planning_group_name="manipulator" controller_names="/joint_trajectory_controller /robotiq_gripper_controller" use_all_planners="true"/>
</Control>
</Control>
</Decorator>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,8 +3,8 @@
<BehaviorTree ID="Cycle Between Waypoints" _description="Cycles between two waypoints until failure">
<Decorator ID="KeepRunningUntilFailure">
<Control ID="Sequence">
<Action ID="MoveToJointState" waypoint_name="Right Corner" planning_group_name="manipulator" controller_names="/joint_trajectory_controller /robotiq_gripper_controller"/>
<Action ID="MoveToJointState" waypoint_name="Place" planning_group_name="manipulator" controller_names="/joint_trajectory_controller /robotiq_gripper_controller"/>
<Action ID="MoveToJointState" waypoint_name="Right Corner" planning_group_name="manipulator" controller_names="/joint_trajectory_controller /robotiq_gripper_controller" use_all_planners="true"/>
<Action ID="MoveToJointState" waypoint_name="Place" planning_group_name="manipulator" controller_names="/joint_trajectory_controller /robotiq_gripper_controller" use_all_planners="true"/>
</Control>
</Decorator>
</BehaviorTree>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
<BehaviorTree ID="Move to Joint State" _description="Single-node behavior to move to a specified joint state">
<Control ID="Sequence">
<Action ID="GetStringFromUser" parameter_name="move_to_joint_state.waypoint_name" parameter_value="{waypoint_name}" />
<Action ID="MoveToJointState" controller_names="/joint_trajectory_controller /robotiq_gripper_controller" planning_group_name="manipulator" waypoint_name="{waypoint_name}" />
<Action ID="MoveToJointState" controller_names="/joint_trajectory_controller /robotiq_gripper_controller" planning_group_name="manipulator" waypoint_name="{waypoint_name}" use_all_planners="true"/>
</Control>
</BehaviorTree>
</root>
4 changes: 2 additions & 2 deletions src/picknik_ur_base_config/package.xml
Original file line number Diff line number Diff line change
@@ -1,9 +1,9 @@
<?xml version="1.0"?>
<package format="3">
<name>picknik_ur_base_config</name>
<version>2.4.0</version>
<version>2.5.0</version>

<description>Base config package for a UR5e that can be simulated with mock hardware</description>
<description>Base configuration package for Picknik's UR robot arms</description>

<maintainer email="[email protected]">MoveIt Studio Maintainer</maintainer>

Expand Down
25 changes: 25 additions & 0 deletions src/picknik_ur_gazebo_config/LICENSE
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
Redistribution and use in source and binary forms, with or without
modification, are permitted provided that the following conditions are met:

* Redistributions of source code must retain the above copyright
notice, this list of conditions and the following disclaimer.

* Redistributions in binary form must reproduce the above copyright
notice, this list of conditions and the following disclaimer in the
documentation and/or other materials provided with the distribution.

* Neither the name of the copyright holder nor the names of its
contributors may be used to endorse or promote products derived from
this software without specific prior written permission.

THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
POSSIBILITY OF SUCH DAMAGE.
Original file line number Diff line number Diff line change
Expand Up @@ -5,28 +5,28 @@
<Control ID="Sequence">
<!-- Clear snapshot, move to center pose, and open gripper -->
<Action ID="ClearSnapshot" />
<Action ID="MoveToJointState" waypoint_name="Look at Table" planning_group_name="manipulator" controller_names="/joint_trajectory_controller /robotiq_gripper_controller"/>
<Action ID="MoveToJointState" waypoint_name="Look at Table" planning_group_name="manipulator" controller_names="/joint_trajectory_controller /robotiq_gripper_controller" use_all_planners="true"/>
<Action ID="MoveGripperAction" gripper_command_action_name="/robotiq_gripper_controller/gripper_cmd" position="0"/>
<!-- Keep executing the pick and place sequence until failure -->
<Decorator ID="KeepRunningUntilFailure">
<Control ID="Sequence">
<!-- Pick object from "Pick", put it down at "Place", and go back to center pose -->
<Control ID="Sequence">
<Action ID="MoveToJointState" waypoint_name="Pick" planning_group_name="manipulator" controller_names="/joint_trajectory_controller /robotiq_gripper_controller"/>
<Action ID="MoveToJointState" waypoint_name="Pick" planning_group_name="manipulator" controller_names="/joint_trajectory_controller /robotiq_gripper_controller" use_all_planners="true"/>
<Action ID="MoveGripperAction" gripper_command_action_name="/robotiq_gripper_controller/gripper_cmd" position="0.7929"/>
<Action ID="MoveToJointState" waypoint_name="Look at Table" planning_group_name="manipulator" controller_names="/joint_trajectory_controller /robotiq_gripper_controller"/>
<Action ID="MoveToJointState" waypoint_name="Place" planning_group_name="manipulator" controller_names="/joint_trajectory_controller /robotiq_gripper_controller"/>
<Action ID="MoveToJointState" waypoint_name="Look at Table" planning_group_name="manipulator" controller_names="/joint_trajectory_controller /robotiq_gripper_controller" use_all_planners="true"/>
<Action ID="MoveToJointState" waypoint_name="Place" planning_group_name="manipulator" controller_names="/joint_trajectory_controller /robotiq_gripper_controller" use_all_planners="true"/>
<Action ID="MoveGripperAction" gripper_command_action_name="/robotiq_gripper_controller/gripper_cmd" position="0"/>
<Action ID="MoveToJointState" waypoint_name="Look at Table" planning_group_name="manipulator" controller_names="/joint_trajectory_controller /robotiq_gripper_controller"/>
<Action ID="MoveToJointState" waypoint_name="Look at Table" planning_group_name="manipulator" controller_names="/joint_trajectory_controller /robotiq_gripper_controller" use_all_planners="true"/>
</Control>
<!-- Pick object from "Place", put it down at "Pick", and go back to center pose -->
<Control ID="Sequence">
<Action ID="MoveToJointState" waypoint_name="Place" planning_group_name="manipulator" controller_names="/joint_trajectory_controller /robotiq_gripper_controller"/>
<Action ID="MoveToJointState" waypoint_name="Place" planning_group_name="manipulator" controller_names="/joint_trajectory_controller /robotiq_gripper_controller" use_all_planners="true"/>
<Action ID="MoveGripperAction" gripper_command_action_name="/robotiq_gripper_controller/gripper_cmd" position="0.7929"/>
<Action ID="MoveToJointState" waypoint_name="Look at Table" planning_group_name="manipulator" controller_names="/joint_trajectory_controller /robotiq_gripper_controller"/>
<Action ID="MoveToJointState" waypoint_name="Pick" planning_group_name="manipulator" controller_names="/joint_trajectory_controller /robotiq_gripper_controller"/>
<Action ID="MoveToJointState" waypoint_name="Look at Table" planning_group_name="manipulator" controller_names="/joint_trajectory_controller /robotiq_gripper_controller" use_all_planners="true"/>
<Action ID="MoveToJointState" waypoint_name="Pick" planning_group_name="manipulator" controller_names="/joint_trajectory_controller /robotiq_gripper_controller" use_all_planners="true"/>
<Action ID="MoveGripperAction" gripper_command_action_name="/robotiq_gripper_controller/gripper_cmd" position="0"/>
<Action ID="MoveToJointState" waypoint_name="Look at Table" planning_group_name="manipulator" controller_names="/joint_trajectory_controller /robotiq_gripper_controller"/>
<Action ID="MoveToJointState" waypoint_name="Look at Table" planning_group_name="manipulator" controller_names="/joint_trajectory_controller /robotiq_gripper_controller" use_all_planners="true"/>
</Control>
</Control>
</Decorator>
Expand Down
4 changes: 2 additions & 2 deletions src/picknik_ur_gazebo_config/package.xml
Original file line number Diff line number Diff line change
@@ -1,9 +1,9 @@
<?xml version="1.0"?>
<package format="3">
<name>picknik_ur_gazebo_config</name>
<version>2.4.0</version>
<version>2.5.0</version>
sea-bass marked this conversation as resolved.
Show resolved Hide resolved

<description>Site config package for the simulated UR5e in PickNik's space station world simulated by Gazebo.</description>
<description>Site configuration package for the UR5e in PickNik's space station world simulated by Gazebo.</description>

<maintainer email="[email protected]">MoveIt Studio Maintainer</maintainer>

Expand Down
22 changes: 22 additions & 0 deletions src/picknik_ur_mock_hw_config/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,22 @@
cmake_minimum_required(VERSION 3.22)
project(picknik_ur_mock_hw_config)

find_package(ament_cmake REQUIRED)

install(
DIRECTORY
config
description
meshes
objectives
waypoints
DESTINATION
share/${PROJECT_NAME}
)

if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
ament_lint_auto_find_test_dependencies()
endif()

ament_package()
Loading