From 7fd2a7356b4d0e579ffc5ef0ce7d2f07bb128aaa Mon Sep 17 00:00:00 2001 From: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> Date: Wed, 26 Apr 2023 17:27:53 -0400 Subject: [PATCH] Add Gazebo site config package (#8) * Add Gazebo site config and fix licensing * Move switch panel outside robot URDF, add Push Button * Add comments from developing tutorial * Remove unused parameters * Fixes from doc PR review * Add launch_cameras_when_simulated params to config files * Add initial positions to base config * Add extra comment on launch_robot_state_publisher * Fix bad links and fix typos/capitalization * MoveIt Studio -> MoveIt Studio Agent --- LICENSE | 230 ++----------- src/picknik_ur_base_config/README.md | 4 +- .../config/base_config.yaml | 10 +- .../description/picknik_ur5e.xacro | 4 + .../launch/hardware.launch.py | 32 +- .../launch/robot_drivers_to_persist.launch.py | 30 +- .../launch/sim/hardware_sim.launch.py | 30 +- .../robot_drivers_to_persist_sim.launch.py | 30 +- src/picknik_ur_base_config/package.xml | 4 +- src/picknik_ur_gazebo_config/CMakeLists.txt | 22 ++ src/picknik_ur_gazebo_config/README.md | 7 + .../config/cameras.yaml | 40 +++ .../control/picknik_ur5e.ros2_control.yaml | 71 ++++ .../config/initial_positions.yaml | 6 + .../config/moveit/picknik_ur_gazebo.srdf | 181 ++++++++++ .../config/moveit/sensors_3d.yaml | 28 ++ .../config/moveit/ur5e_servo.yaml | 65 ++++ .../config/site_config.yaml | 104 ++++++ .../description/picknik_ur_gazebo.xacro | 198 +++++++++++ .../description/simulation_scene.urdf.xacro | 13 + .../launch/bringup.launch.py | 0 .../launch/sim/hardware_sim.launch.py | 316 ++++++++++++++++++ .../objectives/inspect_surface.xml | 18 + .../objectives/push_button.xml | 48 +++ .../objectives/push_button_config.yaml | 21 ++ .../objectives/take_snapshot.xml | 11 + src/picknik_ur_gazebo_config/package.xml | 33 ++ .../waypoints/waypoints.yaml | 91 +++++ src/picknik_ur_site_config/README.md | 4 +- src/picknik_ur_site_config/package.xml | 6 +- 30 files changed, 1431 insertions(+), 226 deletions(-) create mode 100644 src/picknik_ur_gazebo_config/CMakeLists.txt create mode 100644 src/picknik_ur_gazebo_config/README.md create mode 100644 src/picknik_ur_gazebo_config/config/cameras.yaml create mode 100644 src/picknik_ur_gazebo_config/config/control/picknik_ur5e.ros2_control.yaml create mode 100644 src/picknik_ur_gazebo_config/config/initial_positions.yaml create mode 100644 src/picknik_ur_gazebo_config/config/moveit/picknik_ur_gazebo.srdf create mode 100644 src/picknik_ur_gazebo_config/config/moveit/sensors_3d.yaml create mode 100644 src/picknik_ur_gazebo_config/config/moveit/ur5e_servo.yaml create mode 100644 src/picknik_ur_gazebo_config/config/site_config.yaml create mode 100644 src/picknik_ur_gazebo_config/description/picknik_ur_gazebo.xacro create mode 100644 src/picknik_ur_gazebo_config/description/simulation_scene.urdf.xacro create mode 100644 src/picknik_ur_gazebo_config/launch/bringup.launch.py create mode 100644 src/picknik_ur_gazebo_config/launch/sim/hardware_sim.launch.py create mode 100644 src/picknik_ur_gazebo_config/objectives/inspect_surface.xml create mode 100644 src/picknik_ur_gazebo_config/objectives/push_button.xml create mode 100644 src/picknik_ur_gazebo_config/objectives/push_button_config.yaml create mode 100644 src/picknik_ur_gazebo_config/objectives/take_snapshot.xml create mode 100644 src/picknik_ur_gazebo_config/package.xml create mode 100644 src/picknik_ur_gazebo_config/waypoints/waypoints.yaml diff --git a/LICENSE b/LICENSE index 261eeb9e..7c2e04eb 100644 --- a/LICENSE +++ b/LICENSE @@ -1,201 +1,29 @@ - Apache License - Version 2.0, January 2004 - http://www.apache.org/licenses/ - - TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION - - 1. Definitions. - - "License" shall mean the terms and conditions for use, reproduction, - and distribution as defined by Sections 1 through 9 of this document. - - "Licensor" shall mean the copyright owner or entity authorized by - the copyright owner that is granting the License. - - "Legal Entity" shall mean the union of the acting entity and all - other entities that control, are controlled by, or are under common - control with that entity. For the purposes of this definition, - "control" means (i) the power, direct or indirect, to cause the - direction or management of such entity, whether by contract or - otherwise, or (ii) ownership of fifty percent (50%) or more of the - outstanding shares, or (iii) beneficial ownership of such entity. - - "You" (or "Your") shall mean an individual or Legal Entity - exercising permissions granted by this License. - - "Source" form shall mean the preferred form for making modifications, - including but not limited to software source code, documentation - source, and configuration files. - - "Object" form shall mean any form resulting from mechanical - transformation or translation of a Source form, including but - not limited to compiled object code, generated documentation, - and conversions to other media types. - - "Work" shall mean the work of authorship, whether in Source or - Object form, made available under the License, as indicated by a - copyright notice that is included in or attached to the work - (an example is provided in the Appendix below). - - "Derivative Works" shall mean any work, whether in Source or Object - form, that is based on (or derived from) the Work and for which the - editorial revisions, annotations, elaborations, or other modifications - represent, as a whole, an original work of authorship. For the purposes - of this License, Derivative Works shall not include works that remain - separable from, or merely link (or bind by name) to the interfaces of, - the Work and Derivative Works thereof. - - "Contribution" shall mean any work of authorship, including - the original version of the Work and any modifications or additions - to that Work or Derivative Works thereof, that is intentionally - submitted to Licensor for inclusion in the Work by the copyright owner - or by an individual or Legal Entity authorized to submit on behalf of - the copyright owner. For the purposes of this definition, "submitted" - means any form of electronic, verbal, or written communication sent - to the Licensor or its representatives, including but not limited to - communication on electronic mailing lists, source code control systems, - and issue tracking systems that are managed by, or on behalf of, the - Licensor for the purpose of discussing and improving the Work, but - excluding communication that is conspicuously marked or otherwise - designated in writing by the copyright owner as "Not a Contribution." - - "Contributor" shall mean Licensor and any individual or Legal Entity - on behalf of whom a Contribution has been received by Licensor and - subsequently incorporated within the Work. - - 2. Grant of Copyright License. Subject to the terms and conditions of - this License, each Contributor hereby grants to You a perpetual, - worldwide, non-exclusive, no-charge, royalty-free, irrevocable - copyright license to reproduce, prepare Derivative Works of, - publicly display, publicly perform, sublicense, and distribute the - Work and such Derivative Works in Source or Object form. - - 3. Grant of Patent License. Subject to the terms and conditions of - this License, each Contributor hereby grants to You a perpetual, - worldwide, non-exclusive, no-charge, royalty-free, irrevocable - (except as stated in this section) patent license to make, have made, - use, offer to sell, sell, import, and otherwise transfer the Work, - where such license applies only to those patent claims licensable - by such Contributor that are necessarily infringed by their - Contribution(s) alone or by combination of their Contribution(s) - with the Work to which such Contribution(s) was submitted. If You - institute patent litigation against any entity (including a - cross-claim or counterclaim in a lawsuit) alleging that the Work - or a Contribution incorporated within the Work constitutes direct - or contributory patent infringement, then any patent licenses - granted to You under this License for that Work shall terminate - as of the date such litigation is filed. - - 4. Redistribution. You may reproduce and distribute copies of the - Work or Derivative Works thereof in any medium, with or without - modifications, and in Source or Object form, provided that You - meet the following conditions: - - (a) You must give any other recipients of the Work or - Derivative Works a copy of this License; and - - (b) You must cause any modified files to carry prominent notices - stating that You changed the files; and - - (c) You must retain, in the Source form of any Derivative Works - that You distribute, all copyright, patent, trademark, and - attribution notices from the Source form of the Work, - excluding those notices that do not pertain to any part of - the Derivative Works; and - - (d) If the Work includes a "NOTICE" text file as part of its - distribution, then any Derivative Works that You distribute must - include a readable copy of the attribution notices contained - within such NOTICE file, excluding those notices that do not - pertain to any part of the Derivative Works, in at least one - of the following places: within a NOTICE text file distributed - as part of the Derivative Works; within the Source form or - documentation, if provided along with the Derivative Works; or, - within a display generated by the Derivative Works, if and - wherever such third-party notices normally appear. The contents - of the NOTICE file are for informational purposes only and - do not modify the License. You may add Your own attribution - notices within Derivative Works that You distribute, alongside - or as an addendum to the NOTICE text from the Work, provided - that such additional attribution notices cannot be construed - as modifying the License. - - You may add Your own copyright statement to Your modifications and - may provide additional or different license terms and conditions - for use, reproduction, or distribution of Your modifications, or - for any such Derivative Works as a whole, provided Your use, - reproduction, and distribution of the Work otherwise complies with - the conditions stated in this License. - - 5. Submission of Contributions. Unless You explicitly state otherwise, - any Contribution intentionally submitted for inclusion in the Work - by You to the Licensor shall be under the terms and conditions of - this License, without any additional terms or conditions. - Notwithstanding the above, nothing herein shall supersede or modify - the terms of any separate license agreement you may have executed - with Licensor regarding such Contributions. - - 6. Trademarks. This License does not grant permission to use the trade - names, trademarks, service marks, or product names of the Licensor, - except as required for reasonable and customary use in describing the - origin of the Work and reproducing the content of the NOTICE file. - - 7. Disclaimer of Warranty. Unless required by applicable law or - agreed to in writing, Licensor provides the Work (and each - Contributor provides its Contributions) on an "AS IS" BASIS, - WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or - implied, including, without limitation, any warranties or conditions - of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A - PARTICULAR PURPOSE. You are solely responsible for determining the - appropriateness of using or redistributing the Work and assume any - risks associated with Your exercise of permissions under this License. - - 8. Limitation of Liability. In no event and under no legal theory, - whether in tort (including negligence), contract, or otherwise, - unless required by applicable law (such as deliberate and grossly - negligent acts) or agreed to in writing, shall any Contributor be - liable to You for damages, including any direct, indirect, special, - incidental, or consequential damages of any character arising as a - result of this License or out of the use or inability to use the - Work (including but not limited to damages for loss of goodwill, - work stoppage, computer failure or malfunction, or any and all - other commercial damages or losses), even if such Contributor - has been advised of the possibility of such damages. - - 9. Accepting Warranty or Additional Liability. While redistributing - the Work or Derivative Works thereof, You may choose to offer, - and charge a fee for, acceptance of support, warranty, indemnity, - or other liability obligations and/or rights consistent with this - License. However, in accepting such obligations, You may act only - on Your own behalf and on Your sole responsibility, not on behalf - of any other Contributor, and only if You agree to indemnify, - defend, and hold each Contributor harmless for any liability - incurred by, or claims asserted against, such Contributor by reason - of your accepting any such warranty or additional liability. - - END OF TERMS AND CONDITIONS - - APPENDIX: How to apply the Apache License to your work. - - To apply the Apache License to your work, attach the following - boilerplate notice, with the fields enclosed by brackets "[]" - replaced with your own identifying information. (Don't include - the brackets!) The text should be enclosed in the appropriate - comment syntax for the file format. We also recommend that a - file or class name and description of purpose be included on the - same "printed page" as the copyright notice for easier - identification within third-party archives. - - Copyright [yyyy] [name of copyright owner] - - Licensed under the Apache License, Version 2.0 (the "License"); - you may not use this file except in compliance with the License. - You may obtain a copy of the License at - - http://www.apache.org/licenses/LICENSE-2.0 - - Unless required by applicable law or agreed to in writing, software - distributed under the License is distributed on an "AS IS" BASIS, - WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - See the License for the specific language governing permissions and - limitations under the License. +BSD 3-Clause License + +Copyright (c) 2023 PickNik Inc. +All rights reserved. + +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. diff --git a/src/picknik_ur_base_config/README.md b/src/picknik_ur_base_config/README.md index 5b06bc8e..5e630de3 100644 --- a/src/picknik_ur_base_config/README.md +++ b/src/picknik_ur_base_config/README.md @@ -1,3 +1,5 @@ # picknik_ur_base_config -A MoveIt Studio base configuration for PickNik's UR5e simulation, for detailed documentation see: [MoveIt Studio Documentation](https://docs.picknik.ai/) +A MoveIt Studio base configuration for PickNik's UR5e simulation. + +For detailed documentation see: [MoveIt Studio Documentation](https://docs.picknik.ai/) diff --git a/src/picknik_ur_base_config/config/base_config.yaml b/src/picknik_ur_base_config/config/base_config.yaml index 31bb1a92..7a7ce028 100644 --- a/src/picknik_ur_base_config/config/base_config.yaml +++ b/src/picknik_ur_base_config/config/base_config.yaml @@ -17,14 +17,20 @@ hardware: # [Required] simulated: True - # If MoveIt Studio should launch the ros2 controller node. + # If the MoveIt Studio Agent should launch the ros2 controller node. # [Optional, default=True] launch_control_node: True - # If MoveIt Studio should launch the robot state publisher. + # If the MoveIt Studio Agent should launch the robot state publisher. + # This should be false if you are launching the robot state publisher as part of drivers. # [Optional, default=True] launch_robot_state_publisher: True + # If the MoveIt Studio Agent should launch cameras when simulated. + # This must be False when using mock hardware, since there are no cameras simulated. + # [Optional, default=True] + launch_cameras_when_simulated: False + # The robot's IP address. # [Required] ip: "0.0.0.0" diff --git a/src/picknik_ur_base_config/description/picknik_ur5e.xacro b/src/picknik_ur_base_config/description/picknik_ur5e.xacro index 2e4dfa94..1a9374b9 100644 --- a/src/picknik_ur_base_config/description/picknik_ur5e.xacro +++ b/src/picknik_ur_base_config/description/picknik_ur5e.xacro @@ -32,6 +32,9 @@ + + + picknik_ur_base_config - 1.11.0 + 2.0.0 - Base config package for a UR-5e that can be simulated with mock hardware + Base config package for a UR5e that can be simulated with mock hardware MoveIt Studio Maintainer diff --git a/src/picknik_ur_gazebo_config/CMakeLists.txt b/src/picknik_ur_gazebo_config/CMakeLists.txt new file mode 100644 index 00000000..a9d8301b --- /dev/null +++ b/src/picknik_ur_gazebo_config/CMakeLists.txt @@ -0,0 +1,22 @@ +cmake_minimum_required(VERSION 3.16.3) +project(picknik_ur_gazebo_config) + +find_package(ament_cmake REQUIRED) + +install( + DIRECTORY + config + description + launch + objectives + waypoints + DESTINATION + share/${PROJECT_NAME} +) + +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() +endif() + +ament_package() diff --git a/src/picknik_ur_gazebo_config/README.md b/src/picknik_ur_gazebo_config/README.md new file mode 100644 index 00000000..e610b044 --- /dev/null +++ b/src/picknik_ur_gazebo_config/README.md @@ -0,0 +1,7 @@ +# picknik_ur_gazebo_config + +A MoveIt Studio site configuration for a UR5e simulated in Gazebo, based on the `picknik_ur_base_config` package. + +This package follows the required structure described in [Creating a New Site Config Package](https://docs.picknik.ai/en/stable/concepts/config_package/config_package.html#creating-a-new-site-config-package), and may be used to add environments, Behaviors, and Objectives on top of the UR5e base configuration specified in `site_config.yaml`. + +For further documentation see: [MoveIt Studio Documentation](https://docs.picknik.ai/) diff --git a/src/picknik_ur_gazebo_config/config/cameras.yaml b/src/picknik_ur_gazebo_config/config/cameras.yaml new file mode 100644 index 00000000..0efba4da --- /dev/null +++ b/src/picknik_ur_gazebo_config/config/cameras.yaml @@ -0,0 +1,40 @@ +- wrist_mounted_camera: + camera_name: "wrist_mounted_camera" + type: "sim" + use: True + + # These values must match those specified in realsense_d415.urdf.xacro + image_width: 640 + image_height: 480 + + # information about the topics the camera publishes the raw image and info + rgb_info: "/wrist_mounted_camera/color/camera_info" + rgb_image: "/wrist_mounted_camera/color/image_raw" + + # By adding registered_rgb_depth_pair, this camera can be used for "Set Transform From Click" + # Since this is simulation, assume registered image is simply the raw image. + registered_rgb_depth_pair: + depth_info: "/wrist_mounted_camera/color/camera_info" + depth_image: "/wrist_mounted_camera/depth/image_rect_raw" + registered_info: "/wrist_mounted_camera/depth_registered/camera_info" + registered_image: "/wrist_mounted_camera/depth_registered/image_rect_raw" + +- scene_camera: + camera_name: "scene_camera" + type: "sim" + use: True + # These values must match those specified in realsense_d435.urdf.xacro + image_width: 640 + image_height: 480 + + # information about the topics the camera publishes the raw image and info + rgb_info: "/scene_camera/color/camera_info" + rgb_image: "/scene_camera/color/image_raw" + + # By adding registered_rgb_depth_pair, this camera can be used for "Set Transform From Click" + # Since this is simulation, assume registered image is simply the raw image. + registered_rgb_depth_pair: + depth_info: "/scene_camera/color/camera_info" + depth_image: "/scene_camera/depth/image_rect_raw" + registered_info: "/scene_camera/depth_registered/camera_info" + registered_image: "/scene_camera/depth_registered/image_rect_raw" diff --git a/src/picknik_ur_gazebo_config/config/control/picknik_ur5e.ros2_control.yaml b/src/picknik_ur_gazebo_config/config/control/picknik_ur5e.ros2_control.yaml new file mode 100644 index 00000000..3bebe184 --- /dev/null +++ b/src/picknik_ur_gazebo_config/config/control/picknik_ur5e.ros2_control.yaml @@ -0,0 +1,71 @@ +controller_manager: + ros__parameters: + update_rate: 200 # Hz + joint_state_broadcaster: + type: joint_state_broadcaster/JointStateBroadcaster + joint_trajectory_controller: + type: joint_trajectory_controller/JointTrajectoryController + robotiq_gripper_controller: + type: position_controllers/GripperActionController + streaming_controller: + type: position_controllers/JointGroupPositionController + +joint_trajectory_controller: + ros__parameters: + joints: + - shoulder_pan_joint + - shoulder_lift_joint + - elbow_joint + - wrist_1_joint + - wrist_2_joint + - wrist_3_joint + command_interfaces: + - position + state_interfaces: + - position + - velocity + command_joints: + - shoulder_pan_joint + - shoulder_lift_joint + - elbow_joint + - wrist_1_joint + - wrist_2_joint + - wrist_3_joint + state_publish_rate: 100.0 + action_monitor_rate: 20.0 + allow_partial_joints_goal: false + constraints: + stopped_velocity_tolerance: 0.0 + goal_time: 0.0 + shoulder_pan_joint: + goal: 0.05 + shoulder_lift_joint: + goal: 0.05 + elbow_joint: + goal: 0.05 + wrist_1_joint: + goal: 0.05 + wrist_2_joint: + goal: 0.05 + wrist_3_joint: + goal: 0.05 + +streaming_controller: + ros__parameters: + joints: + - shoulder_pan_joint + - shoulder_lift_joint + - elbow_joint + - wrist_1_joint + - wrist_2_joint + - wrist_3_joint + command_interfaces: + - position + state_interfaces: + - position + +robotiq_gripper_controller: + ros__parameters: + default: true + joint: robotiq_85_left_knuckle_joint + allow_stalling: true diff --git a/src/picknik_ur_gazebo_config/config/initial_positions.yaml b/src/picknik_ur_gazebo_config/config/initial_positions.yaml new file mode 100644 index 00000000..ace7747c --- /dev/null +++ b/src/picknik_ur_gazebo_config/config/initial_positions.yaml @@ -0,0 +1,6 @@ +shoulder_pan_joint: 0.0 +shoulder_lift_joint: -0.6 +elbow_joint: -1.4 +wrist_1_joint: -1.2 +wrist_2_joint: 1.7 +wrist_3_joint: 0.0 diff --git a/src/picknik_ur_gazebo_config/config/moveit/picknik_ur_gazebo.srdf b/src/picknik_ur_gazebo_config/config/moveit/picknik_ur_gazebo.srdf new file mode 100644 index 00000000..a2e235ae --- /dev/null +++ b/src/picknik_ur_gazebo_config/config/moveit/picknik_ur_gazebo.srdf @@ -0,0 +1,181 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/src/picknik_ur_gazebo_config/config/moveit/sensors_3d.yaml b/src/picknik_ur_gazebo_config/config/moveit/sensors_3d.yaml new file mode 100644 index 00000000..081fef62 --- /dev/null +++ b/src/picknik_ur_gazebo_config/config/moveit/sensors_3d.yaml @@ -0,0 +1,28 @@ +sensors: + - scene_scan_camera +scene_scan_camera: + # The name of the Octomap updater plugin that we are using. + sensor_plugin: "moveit_studio_plugins/PointCloudServiceOctomapUpdater" + # Specifies the topic to listen on for a point cloud. + # Set to an empty topic to disable. + point_cloud_service_name: "/point_cloud_service" + # Points further than this will not be used (in meters). + max_range: 1.5 + # Choose one of every 'point_subsample' points (select all if set to 1). + point_subsample: 1 + # Should always be >= 1.0. Scale up collision shapes in the scene before excluding them from the octomap. + padding_scale: 1.0 + # Absolute padding around scaled collision shapes when excluding them from the octomap (in meters). + padding_offset: 0.01 + # The octomap representation will be updated at rate less than or equal to this value. + max_update_rate: 0.1 + # This parameter is not required by moveit_studio_plugins/PointCloudServiceOctomapUpdater, but it is needed by the Studio UpdatePlanningScene behavior so we keep it in for now. + # TODO(10856): Delete this parameter + point_cloud_topic: "/scene_camera/depth/color/points/snapshot" + +# Specifies the resolution at which the octomap is maintained (in meters). +octomap_resolution: 0.01 +# Specifies the coordinate frame in which the Octomap representation will be stored. +# Note! When an OccupancyMonitor instance is initialized by the PlanningSceneMonitor, +# this frame parameter will not be used. Instead, the frame defaults to the planning frame. +octomap_frame: "base_link" diff --git a/src/picknik_ur_gazebo_config/config/moveit/ur5e_servo.yaml b/src/picknik_ur_gazebo_config/config/moveit/ur5e_servo.yaml new file mode 100644 index 00000000..663eae44 --- /dev/null +++ b/src/picknik_ur_gazebo_config/config/moveit/ur5e_servo.yaml @@ -0,0 +1,65 @@ +############################################### +# Modify all parameters related to servoing here +############################################### +use_gazebo: true # Whether the robot is started in a Gazebo simulation environment + +## Properties of incoming commands +command_in_type: "unitless" # "unitless"> in the range [-1:1], as if from joystick. "speed_units"> cmds are in m/s and rad/s +scale: + # Scale parameters are only used if command_in_type=="unitless" + linear: 2.0 # Max linear velocity. Meters per publish_period. Unit is [m/s]. Only used for Cartesian commands. + rotational: 3.0 # Max angular velocity. Rads per publish_period. Unit is [rad/s]. Only used for Cartesian commands. + # Max joint angular/linear velocity. Rads or Meters per publish period. Only used for joint commands on joint_command_in_topic. + joint: 2.0 + +# Disable Servo velocity scaling calculation and drive the arm at 50% max speed. +override_velocity_scaling_factor: 0.5 + +## Properties of outgoing commands +publish_period: 0.005 # 1/Nominal publish rate [seconds] +low_latency_mode: true # Set this to true to publish as soon as an incoming Twist command is received (publish_period is ignored) + +# What type of topic does your robot driver expect? +# Currently supported are std_msgs/Float64MultiArray or trajectory_msgs/JointTrajectory +command_out_type: std_msgs/Float64MultiArray + +# What to publish? Can save some bandwidth as most robots only require positions or velocities +publish_joint_positions: true +publish_joint_velocities: false +publish_joint_accelerations: false + +## Plugins for smoothing outgoing commands +smoothing_filter_plugin_name: "online_signal_smoothing::ButterworthFilterPlugin" + +## Incoming Joint State properties +low_pass_filter_coeff: 4.0 # Larger --> trust the filtered data more, trust the measurements less. + +## MoveIt properties +move_group_name: manipulator # Often 'manipulator' or 'arm' +planning_frame: base_link # The MoveIt planning frame. Often 'base_link' or 'world' +is_primary_planning_scene_monitor: false # The MoveGroup node maintains the planning scene, so Servo needs to get its world info from there. + +## Other frames +ee_frame_name: manual_grasp_link # The name of the end effector link, used to return the EE pose +robot_link_command_frame: base_link # commands must be given in the frame of a robot link. Usually either the base or end effector + +## Stopping behaviour +incoming_command_timeout: 0.1 # Stop servoing if X seconds elapse without a new command + +## Configure handling of singularities and joint limits +lower_singularity_threshold: 30.0 # Start decelerating when the condition number hits this (close to singularity) +hard_stop_singularity_threshold: 50.0 # Stop when the condition number hits this +joint_limit_margin: 0.1 # added as a buffer to joint limits [radians]. If moving quickly, make this larger. + +## Topic names +cartesian_command_in_topic: ~/delta_twist_cmds # Topic for incoming Cartesian twist commands +joint_command_in_topic: ~/delta_joint_cmds # Topic for incoming joint angle commands +joint_topic: /joint_states +status_topic: ~/status # Publish status to this topic +command_out_topic: /robot_controllers/commands # Publish outgoing commands here + +## Collision checking for the entire robot body +check_collisions: true # Check collisions? +collision_check_rate: 10.0 # [Hz] Collision-checking can easily bog down a CPU if done too often. +self_collision_proximity_threshold: 0.01 # Start decelerating when a self-collision is this far [m] +scene_collision_proximity_threshold: 0.02 # Start decelerating when a scene collision is this far [m] diff --git a/src/picknik_ur_gazebo_config/config/site_config.yaml b/src/picknik_ur_gazebo_config/config/site_config.yaml new file mode 100644 index 00000000..39ecb5ad --- /dev/null +++ b/src/picknik_ur_gazebo_config/config/site_config.yaml @@ -0,0 +1,104 @@ +# +# This contains information for a unique instance of a robot. +# + +# Name of the package to specialize +based_on_package: "picknik_ur_base_config" + +# Optional parameters that can be read in your launch files for specific functionality +optional_feature_params: + gazebo_world_name: "space_station.sdf" + gazebo_gui: False + gazebo_verbose: True + +# Enable simulation time so nodes are synced with the Gazebo block. +ros_global_params: + use_sim_time: True + +hardware: + # Used by the ur_description package to set kinematics and geometry for a specific robot type. + # You can change this to another UR model but you must update any configuration affected by the different arm size + # UR models in the ur_description package are ur3, ur3e, ur5, ur5e, ur10, ur10e, and ur16e. + type: "ur5e" + + # This is the only option for this site_config + simulated: True + + # Gazebo starts its own controller manager through the ros2_control plugin, so set this to False + launch_control_node: False + + # If the MoveIt Studio Agent should launch the robot state publisher + # This should be false if you are launching the robot state publisher as part of drivers. + launch_robot_state_publisher: True + + # If the MoveIt Studio Agent should launch cameras when simulated. + launch_cameras_when_simulated: True + + # The robot's IP address + ip: "0.0.0.0" + + # The following launch file is started when hardware.simulated is True + simulated_hardware_launch_file: + package: "picknik_ur_gazebo_config" + path: "launch/sim/hardware_sim.launch.py" + + # Override other parameters from the base config package, including + # the camera configuration and the robot description model. + camera_config_file: + package: "picknik_ur_gazebo_config" + path: "config/cameras.yaml" + robot_description: + srdf: + package: "picknik_ur_gazebo_config" + path: "config/moveit/picknik_ur_gazebo.srdf" + urdf: + package: "picknik_ur_gazebo_config" + path: "description/picknik_ur_gazebo.xacro" + urdf_params: + - name: "%>> hardware.type" + # Using the ogre renderer as it is compatible with most host hardware. + # ogre2 (which is the Gazebo default) is also an option if your system supports it. + - gazebo_renderer: ${GAZEBO_RENDERER:-ogre} + - kinematics_parameters_file: + package: "ur_description" + path: "config" + - physical_parameters_file: + package: "ur_description" + path: "config" + - visual_parameters_file: + package: "ur_description" + path: "config" + +# Override MoveIt parameters +moveit_params: + sensors_3d: + package: "picknik_ur_gazebo_config" + path: "config/moveit/sensors_3d.yaml" + servo: + package: "picknik_ur_gazebo_config" + path: "config/moveit/ur5e_servo.yaml" + +octomap_manager: + # Input point cloud topic name. The *output* point cloud topic published by + # the Octomap manager node is defined in sensors_3d.yaml. + input_point_cloud_topic: "/wrist_mounted_camera/depth/color/points" + +# This configures what controllers gets run at startup +ros2_control: + controllers_active_at_startup: + - "joint_state_broadcaster" + - "streaming_controller" + - "robotiq_gripper_controller" + controllers_inactive_at_startup: + - "joint_trajectory_controller" + +objectives: + # Override with a new set of waypoints based on the Gazebo world. + waypoints_file: + package_name: "picknik_ur_gazebo_config" + relative_path: "waypoints/waypoints.yaml" + # Add new simulation Objectives in addition to the one in the base config package. + objective_library_paths: + sim: + package_name: "picknik_ur_gazebo_config" + relative_path: "objectives" diff --git a/src/picknik_ur_gazebo_config/description/picknik_ur_gazebo.xacro b/src/picknik_ur_gazebo_config/description/picknik_ur_gazebo.xacro new file mode 100644 index 00000000..6bec95b4 --- /dev/null +++ b/src/picknik_ur_gazebo_config/description/picknik_ur_gazebo.xacro @@ -0,0 +1,198 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 1 + 50 + 0 + tcp_fts_sensor/ft_data + 0 0 0 0 0 0 + + child + parent_to_child + + + + 0 + 0 + + + + + 0 + 0 + + + + + 0 + 0 + + + + + + + 0 + 0 + + + + + 0 + 0 + + + + + 0 + 0 + + + + + + + + + + + $(find picknik_ur_gazebo_config)/config/control/picknik_ur5e.ros2_control.yaml + + /streaming_controller/commands:=/robot_controllers/commands + /joint_trajectory_controller/joint_trajectory:=/robot_controllers/joint_trajectory + + + + + + + ${gazebo_renderer} + + + + diff --git a/src/picknik_ur_gazebo_config/description/simulation_scene.urdf.xacro b/src/picknik_ur_gazebo_config/description/simulation_scene.urdf.xacro new file mode 100644 index 00000000..517bff7c --- /dev/null +++ b/src/picknik_ur_gazebo_config/description/simulation_scene.urdf.xacro @@ -0,0 +1,13 @@ + + + + + + + + + + + + + diff --git a/src/picknik_ur_gazebo_config/launch/bringup.launch.py b/src/picknik_ur_gazebo_config/launch/bringup.launch.py new file mode 100644 index 00000000..e69de29b diff --git a/src/picknik_ur_gazebo_config/launch/sim/hardware_sim.launch.py b/src/picknik_ur_gazebo_config/launch/sim/hardware_sim.launch.py new file mode 100644 index 00000000..576698ca --- /dev/null +++ b/src/picknik_ur_gazebo_config/launch/sim/hardware_sim.launch.py @@ -0,0 +1,316 @@ +# Copyright (c) 2023 PickNik Inc. +# All rights reserved. + +# 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. + + +import os +import re +import shlex + +from ament_index_python import get_package_share_directory +from launch import LaunchDescription +from launch.actions import IncludeLaunchDescription, OpaqueFunction +from launch_ros.actions import Node + +from moveit_studio_utils_py.launch_common import get_launch_file, get_ros_path, xacro_to_urdf +from moveit_studio_utils_py.system_config import get_config_folder, SystemConfigParser +from moveit_studio_utils_py.generate_camera_frames import generate_camera_frames + + +def path_pattern_change_for_ignition(urdf_string): + """ + Replaces strings in a URDF file such as + package://package_name/path/to/file + to the actual full path of the file. + """ + data = urdf_string + package_expressions = re.findall("(package://([^//]*))", data) + for expr in set(package_expressions): + data = data.replace(expr[0], get_ros_path(expr[1])) + return data + + +def generate_simulation_description(context, *args, **settings): + world_name = settings.get("gazebo_world_name", "space_station.sdf") + use_gui = settings.get("gazebo_gui", False) + is_verbose = settings.get("gazebo_verbose", False) + gz_renderer = os.environ.get("GAZEBO_RENDERER", "ogre") + + # Create a Gazebo world file that swaps out package:// paths with absolute path. + original_world_file = os.path.join( + get_package_share_directory("picknik_accessories"), + "descriptions", + "simulation_worlds", + world_name, + ) + modified_world_file = os.path.join( + get_config_folder(), "auto_created", "gazebo_world.sdf" + ) + with open(original_world_file, "r") as file: + world_sdf = path_pattern_change_for_ignition(file.read()) + with open(modified_world_file, "w") as file: + file.write(world_sdf) + + # Launch Gazebo. + print(f"Starting Gazebo with world {world_name}") + print(f"GUI: {use_gui}, Verbose: {is_verbose}") + + sim_args = f"-r --render-engine {gz_renderer}" + if is_verbose: + sim_args += " -v 4" + if not use_gui: + sim_args += " -s --headless-rendering" + + gazebo = IncludeLaunchDescription( + get_launch_file("ros_gz_sim", "launch/gz_sim.launch.py"), + launch_arguments=[("gz_args", [f"{sim_args} {modified_world_file}"])], + ) + return [gazebo] + + +def generate_launch_description(): + system_config_parser = SystemConfigParser() + optional_feature_setting = system_config_parser.get_optional_feature_configs() + cameras_config = system_config_parser.get_cameras_config() + + # The path to the auto_created urdf files + robot_urdf = system_config_parser.get_processed_urdf() + robot_urdf_ignition = path_pattern_change_for_ignition(robot_urdf) + + # Launch Gazebo + gazebo = OpaqueFunction( + function=generate_simulation_description, kwargs=optional_feature_setting + ) + + init_pose_args = shlex.split("-x 0.0 -y 0.0 -z 1.03 -R 0.0 -P 0.0 -Y 0.0") + spawn_robot = Node( + package="ros_gz_sim", + executable="create", + output="screen", + arguments=[ + "-string", + robot_urdf_ignition, + "-name", + "robot", + "-allow_renaming", + "true", + ] + + init_pose_args, + ) + + ######################## + # Camera Topic Bridges # + ######################## + # For the scene camera, enable RGB image topics only. + scene_image_rgb_ignition_bridge = Node( + package="ros_gz_image", + executable="image_bridge", + name="scene_image_rgb_ignition_bridge", + arguments=[ + "/scene_camera/image", + ], + remappings=[ + ("/scene_camera/image", "/scene_camera/color/image_raw"), + ], + parameters=[{"qos": "sensor_data"}], + output="screen", + ) + scene_image_depth_ignition_bridge = Node( + package="ros_gz_image", + executable="image_bridge", + name="scene_image_depth_ignition_bridge", + arguments=[ + "/scene_camera/depth_image", + ], + remappings=[ + ( + "/scene_camera/depth_image", + "/scene_camera/depth/image_rect_raw", + ), + ], + parameters=[{"qos": "sensor_data"}], + output="screen", + ) + + scene_camera_info_ignition_bridge = Node( + package="ros_gz_bridge", + executable="parameter_bridge", + name="scene_camera_info_ignition_bridge", + arguments=[ + "/scene_camera/camera_info@sensor_msgs/msg/CameraInfo[ignition.msgs.CameraInfo", + ], + remappings=[ + ("/scene_camera/camera_info", "/scene_camera/color/camera_info"), + ], + output="screen", + ) + + # For the wrist mounted camera, enable RGB and depth topics. + wrist_image_rgb_ignition_bridge = Node( + package="ros_gz_image", + executable="image_bridge", + name="wrist_image_rgb_ignition_bridge", + arguments=[ + "/wrist_mounted_camera/image", + ], + remappings=[ + ("/wrist_mounted_camera/image", "/wrist_mounted_camera/color/image_raw"), + ], + parameters=[{"qos": "sensor_data"}], + output="screen", + ) + wrist_image_depth_ignition_bridge = Node( + package="ros_gz_image", + executable="image_bridge", + name="wrist_image_depth_ignition_bridge", + arguments=[ + "/wrist_mounted_camera/depth_image", + ], + remappings=[ + ( + "/wrist_mounted_camera/depth_image", + "/wrist_mounted_camera/depth/image_rect_raw", + ), + ], + parameters=[{"qos": "sensor_data"}], + output="screen", + ) + wrist_camera_pointcloud_ignition_bridge = Node( + package="ros_gz_bridge", + executable="parameter_bridge", + name="wrist_camera_pointcloud_ignition_bridge", + arguments=[ + "/wrist_mounted_camera/points@sensor_msgs/msg/PointCloud2[ignition.msgs.PointCloudPacked", + ], + remappings=[ + ( + "/wrist_mounted_camera/points", + "/wrist_mounted_camera/depth/color/points", + ), + ], + output="screen", + ) + wrist_camera_info_ignition_bridge = Node( + package="ros_gz_bridge", + executable="parameter_bridge", + name="wrist_camera_info_ignition_bridge", + arguments=[ + "/wrist_mounted_camera/camera_info@sensor_msgs/msg/CameraInfo[ignition.msgs.CameraInfo", + ], + remappings=[ + ( + "/wrist_mounted_camera/camera_info", + "/wrist_mounted_camera/color/camera_info", + ), + ], + output="screen", + ) + + ####################### + # Force Torque Sensor # + ####################### + fts_bridge = Node( + package="ros_gz_bridge", + executable="parameter_bridge", + name="fts_bridge", + arguments=[ + "/tcp_fts_sensor/ft_data@geometry_msgs/msg/WrenchStamped[ignition.msgs.Wrench", + ], + remappings=[ + ( + "/tcp_fts_sensor/ft_data", + "/force_torque_sensor_broadcaster/wrench", + ), + ], + output="screen", + ) + + clock_bridge = Node( + package="ros_gz_bridge", + executable="parameter_bridge", + name="clock_bridge", + arguments=["/clock@rosgraph_msgs/msg/Clock[ignition.msgs.Clock"], + output="screen", + ) + + frame_pair_params = [ + { + "world_frame": "world", + "camera_frames": generate_camera_frames(cameras_config), + } + ] + + camera_transforms_node = Node( + package="moveit_studio_agent", + executable="camera_transforms_node", + name="camera_transforms_node", + output="screen", + parameters=frame_pair_params, + arguments=["--ros-args"], + ) + + ##################### + # Environment Scene # + ##################### + scene_xacro_path = get_ros_path( + "picknik_ur_gazebo_config", "description/simulation_scene.urdf.xacro" + ) + scene_urdf = xacro_to_urdf(scene_xacro_path, None) + scene_urdf_ignition = path_pattern_change_for_ignition(scene_urdf) + + spawn_scene = Node( + package="ros_gz_sim", + executable="create", + output="screen", + arguments=[ + "-string", + scene_urdf_ignition, + "-name", + "cabinet", + "-allow_renaming", + "true", + ] + + init_pose_args, + ) + + return LaunchDescription( + [ + scene_image_rgb_ignition_bridge, + scene_image_depth_ignition_bridge, + scene_camera_info_ignition_bridge, + wrist_image_rgb_ignition_bridge, + wrist_camera_info_ignition_bridge, + wrist_image_depth_ignition_bridge, + wrist_camera_pointcloud_ignition_bridge, + clock_bridge, + fts_bridge, + gazebo, + spawn_robot, + spawn_scene, + camera_transforms_node, + ] + ) diff --git a/src/picknik_ur_gazebo_config/objectives/inspect_surface.xml b/src/picknik_ur_gazebo_config/objectives/inspect_surface.xml new file mode 100644 index 00000000..404e08e0 --- /dev/null +++ b/src/picknik_ur_gazebo_config/objectives/inspect_surface.xml @@ -0,0 +1,18 @@ + + + + + + + + + + + + + + + + + + diff --git a/src/picknik_ur_gazebo_config/objectives/push_button.xml b/src/picknik_ur_gazebo_config/objectives/push_button.xml new file mode 100644 index 00000000..5d5acfc7 --- /dev/null +++ b/src/picknik_ur_gazebo_config/objectives/push_button.xml @@ -0,0 +1,48 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/src/picknik_ur_gazebo_config/objectives/push_button_config.yaml b/src/picknik_ur_gazebo_config/objectives/push_button_config.yaml new file mode 100644 index 00000000..ec3e8de0 --- /dev/null +++ b/src/picknik_ur_gazebo_config/objectives/push_button_config.yaml @@ -0,0 +1,21 @@ +IsForceWithinThreshold: + wrench_topic_name: "/force_torque_sensor_broadcaster/wrench" + hand_frame_name: "manual_grasp_link" + wrench_frame_name: "tool0" + minimum_consecutive_wrench_values: 10 + force_threshold: 10.0 # Newtons + +SetupMTCMoveAlongFrameAxis: + arm_group_name: "manipulator" + hand_frame_name: "manual_grasp_link" + velocity_acceleration_scaling_factor: 0.05 + +AllowGripperCollisionWithOctomap: + group_name: "gripper" + object_name: "" + allow_collision: true + +ForbidGripperCollisionWithOctomap: + group_name: "gripper" + object_name: "" + allow_collision: false diff --git a/src/picknik_ur_gazebo_config/objectives/take_snapshot.xml b/src/picknik_ur_gazebo_config/objectives/take_snapshot.xml new file mode 100644 index 00000000..924cf0bd --- /dev/null +++ b/src/picknik_ur_gazebo_config/objectives/take_snapshot.xml @@ -0,0 +1,11 @@ + + + + + + + + + + + diff --git a/src/picknik_ur_gazebo_config/package.xml b/src/picknik_ur_gazebo_config/package.xml new file mode 100644 index 00000000..a262786a --- /dev/null +++ b/src/picknik_ur_gazebo_config/package.xml @@ -0,0 +1,33 @@ + + + picknik_ur_gazebo_config + 2.0.0 + + Site config package for the simulated UR5e in PickNik's space station world simulated by Gazebo. + + MoveIt Studio Maintainer + + BSD-3-Clause + + ament_cmake + + picknik_ur_base_config + + moveit_ros_perception + ros_gz + ign_ros2_control + picknik_accessories + + ament_lint_auto + + ament_clang_format + ament_clang_tidy + ament_cmake_copyright + ament_cmake_lint_cmake + picknik_ament_copyright + ament_flake8 + + + ament_cmake + + diff --git a/src/picknik_ur_gazebo_config/waypoints/waypoints.yaml b/src/picknik_ur_gazebo_config/waypoints/waypoints.yaml new file mode 100644 index 00000000..13830b81 --- /dev/null +++ b/src/picknik_ur_gazebo_config/waypoints/waypoints.yaml @@ -0,0 +1,91 @@ +- name: Pick + description: "" + favorite: true + joint_state: + header: + frame_id: world + stamp: + sec: 0 + nanosec: 0 + name: [shoulder_pan_joint, shoulder_lift_joint, elbow_joint, wrist_1_joint, wrist_2_joint, wrist_3_joint] + position: [2.8157092106861623, -1.9585495223351144, -1.8538526703106895, -0.9022145649749891, 1.5886272630938514, -0.30698284674804727] + velocity: [] + effort: [] +- name: Place + description: "" + favorite: true + joint_state: + header: + frame_id: world + stamp: + sec: 0 + nanosec: 0 + name: [shoulder_pan_joint, shoulder_lift_joint, elbow_joint, wrist_1_joint, wrist_2_joint, wrist_3_joint] + position: [1.7077460201246053, -1.5006596832027697, -2.3454511166929226, -0.8653959721204787, 1.5428337120843727, 0.13671324329727] + velocity: [] + effort: [] +- name: Behind + description: "" + favorite: true + joint_state: + header: + frame_id: world + stamp: + sec: 0 + nanosec: 0 + name: [shoulder_pan_joint, shoulder_lift_joint, elbow_joint, wrist_1_joint, wrist_2_joint, wrist_3_joint] + position: [3.03, -0.78, -0.51, -2.39, 1.65, 0] + velocity: [] + effort: [] +- name: Forward Down + description: "" + favorite: true + joint_state: + header: + frame_id: world + stamp: + sec: 0 + nanosec: 0 + name: [shoulder_pan_joint, shoulder_lift_joint, elbow_joint, wrist_1_joint, wrist_2_joint, wrist_3_joint] + position: [0, -1.41, -0.7, -2.12, 1.67, 0] + velocity: [] + effort: [] +- name: Right Corner + description: "" + favorite: true + joint_state: + header: + frame_id: world + stamp: + sec: 0 + nanosec: 0 + name: [shoulder_pan_joint, shoulder_lift_joint, elbow_joint, wrist_1_joint, wrist_2_joint, wrist_3_joint] + position: [-0.61, -0.78, -0.45, -2.49, 1.64, 0] + velocity: [] + effort: [] +- name: Left Corner + description: "" + favorite: true + joint_state: + header: + frame_id: world + stamp: + sec: 0 + nanosec: 0 + name: [shoulder_pan_joint, shoulder_lift_joint, elbow_joint, wrist_1_joint, wrist_2_joint, wrist_3_joint] + position: [0.58, -0.78, -0.45, -2.33, 1.64, 0] + velocity: [] + effort: [] +- name: Home + description: "" + favorite: true + joint_state: + header: + frame_id: world + stamp: + sec: 0 + nanosec: 0 + name: [shoulder_pan_joint, shoulder_lift_joint, elbow_joint, wrist_1_joint, wrist_2_joint, wrist_3_joint] + position: [0, -0.78, -0.51, -2.4, 1.65, 0] + velocity: [] + effort: [] diff --git a/src/picknik_ur_site_config/README.md b/src/picknik_ur_site_config/README.md index dce3afc5..dc550c7c 100644 --- a/src/picknik_ur_site_config/README.md +++ b/src/picknik_ur_site_config/README.md @@ -1,5 +1,7 @@ # picknik_ur_site_config -A MoveIt Studio site configuration for UR5e based on the picknik_ur_base_config package available [here](https://github.com/PickNikRobotics/ur5e_sim_base_config). This package follows the required structure described in [Creating a New Site Config Package](https://docs.picknik.ai/en/stable/concepts/config_package/config_package.html#creating-a-new-site-config-package), and may be used to add environments, behaviors, and objectives on top of the UR5e base configuration specified in `site_config.yaml` +A MoveIt Studio site configuration for a UR5e based on the `picknik_ur_base_config` package. + +This package follows the required structure described in [Creating a New Site Config Package](https://docs.picknik.ai/en/stable/concepts/config_package/config_package.html#creating-a-new-site-config-package), and may be used to add environments, Behaviors, and Objectives on top of the UR5e base configuration specified in `site_config.yaml`. For further documentation see: [MoveIt Studio Documentation](https://docs.picknik.ai/) diff --git a/src/picknik_ur_site_config/package.xml b/src/picknik_ur_site_config/package.xml index 3f8ecdfd..c7ae74b8 100644 --- a/src/picknik_ur_site_config/package.xml +++ b/src/picknik_ur_site_config/package.xml @@ -1,9 +1,9 @@ picknik_ur_site_config - 1.11.0 + 2.0.0 - Site config package for a UR-5e + Site config package for a UR5e that can be simulated with mock hardware MoveIt Studio Maintainer @@ -11,7 +11,7 @@ ament_cmake - ur5e_sim_base_config + picknik_ur_base_config ament_cmake