├── .gitignore ├── LICENSE ├── README.md ├── interactive_marker ├── CMakeLists.txt ├── config │ └── interactive_marker.rviz ├── launch │ └── interactive_marker.launch.py └── package.xml ├── panda_resources ├── panda_description │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── LICENSE │ ├── README.md │ ├── meshes │ │ ├── collision │ │ │ ├── finger.stl │ │ │ ├── hand.stl │ │ │ ├── link0.stl │ │ │ ├── link1.stl │ │ │ ├── link2.stl │ │ │ ├── link3.stl │ │ │ ├── link4.stl │ │ │ ├── link5.stl │ │ │ ├── link6.stl │ │ │ └── link7.stl │ │ └── visual │ │ │ ├── finger.dae │ │ │ ├── hand.dae │ │ │ ├── link0.dae │ │ │ ├── link1.dae │ │ │ ├── link2.dae │ │ │ ├── link3.dae │ │ │ ├── link4.dae │ │ │ ├── link5.dae │ │ │ ├── link6.dae │ │ │ └── link7.dae │ ├── package.xml │ └── urdf │ │ └── panda.urdf ├── panda_moveit_config │ ├── .setup_assistant │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── README.md │ ├── config │ │ ├── chomp_planning.yaml │ │ ├── gripper_moveit_controllers.yaml │ │ ├── hand.xacro │ │ ├── initial_positions.yaml │ │ ├── joint_limits.yaml │ │ ├── kinematics.yaml │ │ ├── lerp_planning.yaml │ │ ├── moveit_controllers.yaml │ │ ├── ompl_planning.yaml │ │ ├── panda.ros2_control.xacro │ │ ├── panda.srdf │ │ ├── panda.urdf.xacro │ │ ├── panda_arm.srdf.xacro │ │ ├── panda_arm.xacro │ │ ├── panda_arm_hand.srdf.xacro │ │ ├── panda_hand.ros2_control.xacro │ │ ├── pilz_cartesian_limits.yaml │ │ ├── pilz_industrial_motion_planner_planning.yaml │ │ ├── ros2_controllers.yaml │ │ ├── sensors_kinect_depthmap.yaml │ │ ├── sensors_kinect_pointcloud.yaml │ │ └── trajopt_planning.yaml │ ├── launch │ │ ├── demo.launch.py │ │ ├── moveit.rviz │ │ ├── moveit_empty.rviz │ │ └── moveit_rviz.launch.py │ └── package.xml └── panda_mujoco │ ├── CMakeLists.txt │ ├── franka_emika_panda │ ├── LICENSE │ ├── README.md │ ├── assets │ │ ├── bevel_peg.stl │ │ ├── finger_0.obj │ │ ├── finger_1.obj │ │ ├── geometry_0.stl │ │ ├── geometry_1.stl │ │ ├── geometry_10.stl │ │ ├── geometry_11.stl │ │ ├── geometry_12.stl │ │ ├── geometry_13.stl │ │ ├── geometry_14.stl │ │ ├── geometry_15.stl │ │ ├── geometry_16.stl │ │ ├── geometry_17.stl │ │ ├── geometry_18.stl │ │ ├── geometry_19.stl │ │ ├── geometry_2.stl │ │ ├── geometry_20.stl │ │ ├── geometry_21.stl │ │ ├── geometry_22.stl │ │ ├── geometry_23.stl │ │ ├── geometry_24.stl │ │ ├── geometry_25.stl │ │ ├── geometry_26.stl │ │ ├── geometry_27.stl │ │ ├── geometry_28.stl │ │ ├── geometry_29.stl │ │ ├── geometry_3.stl │ │ ├── geometry_30.stl │ │ ├── geometry_31.stl │ │ ├── geometry_32.stl │ │ ├── geometry_33.stl │ │ ├── geometry_34.stl │ │ ├── geometry_35.stl │ │ ├── geometry_36.stl │ │ ├── geometry_37.stl │ │ ├── geometry_38.stl │ │ ├── geometry_39.stl │ │ ├── geometry_4.stl │ │ ├── geometry_40.stl │ │ ├── geometry_41.stl │ │ ├── geometry_42.stl │ │ ├── geometry_43.stl │ │ ├── geometry_44.stl │ │ ├── geometry_45.stl │ │ ├── geometry_46.stl │ │ ├── geometry_47.stl │ │ ├── geometry_48.stl │ │ ├── geometry_49.stl │ │ ├── geometry_5.stl │ │ ├── geometry_50.stl │ │ ├── geometry_51.stl │ │ ├── geometry_52.stl │ │ ├── geometry_53.stl │ │ ├── geometry_54.stl │ │ ├── geometry_55.stl │ │ ├── geometry_56.stl │ │ ├── geometry_57.stl │ │ ├── geometry_58.stl │ │ ├── geometry_59.stl │ │ ├── geometry_6.stl │ │ ├── geometry_60.stl │ │ ├── geometry_61.stl │ │ ├── geometry_62.stl │ │ ├── geometry_63.stl │ │ ├── geometry_64.stl │ │ ├── geometry_65.stl │ │ ├── geometry_66.stl │ │ ├── geometry_67.stl │ │ ├── geometry_68.stl │ │ ├── geometry_69.stl │ │ ├── geometry_7.stl │ │ ├── geometry_70.stl │ │ ├── geometry_71.stl │ │ ├── geometry_72.stl │ │ ├── geometry_73.stl │ │ ├── geometry_74.stl │ │ ├── geometry_75.stl │ │ ├── geometry_76.stl │ │ ├── geometry_77.stl │ │ ├── geometry_78.stl │ │ ├── geometry_79.stl │ │ ├── geometry_8.stl │ │ ├── geometry_9.stl │ │ ├── hand.stl │ │ ├── hand_0.obj │ │ ├── hand_1.obj │ │ ├── hand_2.obj │ │ ├── hand_3.obj │ │ ├── hand_4.obj │ │ ├── link0.stl │ │ ├── link0_0.obj │ │ ├── link0_1.obj │ │ ├── link0_10.obj │ │ ├── link0_11.obj │ │ ├── link0_2.obj │ │ ├── link0_3.obj │ │ ├── link0_4.obj │ │ ├── link0_5.obj │ │ ├── link0_7.obj │ │ ├── link0_8.obj │ │ ├── link0_9.obj │ │ ├── link1.obj │ │ ├── link1.stl │ │ ├── link2.obj │ │ ├── link2.stl │ │ ├── link3.stl │ │ ├── link3_0.obj │ │ ├── link3_1.obj │ │ ├── link3_2.obj │ │ ├── link3_3.obj │ │ ├── link4.stl │ │ ├── link4_0.obj │ │ ├── link4_1.obj │ │ ├── link4_2.obj │ │ ├── link4_3.obj │ │ ├── link5_0.obj │ │ ├── link5_1.obj │ │ ├── link5_2.obj │ │ ├── link5_collision_0.obj │ │ ├── link5_collision_1.obj │ │ ├── link5_collision_2.obj │ │ ├── link6.stl │ │ ├── link6_0.obj │ │ ├── link6_1.obj │ │ ├── link6_10.obj │ │ ├── link6_11.obj │ │ ├── link6_12.obj │ │ ├── link6_13.obj │ │ ├── link6_14.obj │ │ ├── link6_15.obj │ │ ├── link6_16.obj │ │ ├── link6_2.obj │ │ ├── link6_3.obj │ │ ├── link6_4.obj │ │ ├── link6_5.obj │ │ ├── link6_6.obj │ │ ├── link6_7.obj │ │ ├── link6_8.obj │ │ ├── link6_9.obj │ │ ├── link7.stl │ │ ├── link7_0.obj │ │ ├── link7_1.obj │ │ ├── link7_2.obj │ │ ├── link7_3.obj │ │ ├── link7_4.obj │ │ ├── link7_5.obj │ │ ├── link7_6.obj │ │ └── link7_7.obj │ ├── hand.xml │ ├── panda.xml │ ├── panda_nohand.xml │ └── scene.xml │ └── package.xml └── peg_in_hole ├── CMakeLists.txt ├── launch └── peg_in_hole.launch.py ├── package.xml └── src └── controller.cpp /.gitignore: -------------------------------------------------------------------------------- 1 | # ros2 build 2 | build/ 3 | install/ 4 | log/ 5 | 6 | # vscode 7 | **/.vscode 8 | **/.devcontainer 9 | 10 | # mujoco log 11 | **/MUJOCO_LOG.TXT 12 | 13 | # ros2bag data 14 | rosbag2_*/ -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | # mujoco_ros2_control_examples 2 | 3 | ## How to run 4 | 5 | ### Clone and build relevant repositories 6 | 7 | 1. `mujoco_ros2_control` 8 | 9 | Before clone the repo, please make sure you have [mujoco](https://github.com/google-deepmind/mujoco/releases) installed. 10 | ``` 11 | git clone https://github.com/sangteak601/mujoco_ros2_control.git -b humble-devel 12 | cd mujoco_ros2_control 13 | # update this according to your env 14 | export MUJOCO_DIR=/PATH/TO/MUJOCO/mujoco-3.x.x 15 | colcon build 16 | source install/setup.bash 17 | ``` 18 | 19 | ### Clone and build example repository 20 | ``` 21 | git clone https://github.com/sangteak601/mujoco_ros2_control_examples.git 22 | cd mujoco_ros2_control_examples 23 | colcon build 24 | source install/setup.bash 25 | ``` 26 | 27 | ### Running demos 28 | ``` 29 | ros2 launch interactive_marker interactive_marker.launch.py 30 | ros2 launch peg_in_hole peg_in_hole.launch.py 31 | ``` -------------------------------------------------------------------------------- /interactive_marker/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.5) 2 | project(interactive_marker) 3 | 4 | # Default to C++14 5 | if(NOT CMAKE_CXX_STANDARD) 6 | set(CMAKE_CXX_STANDARD 14) 7 | set(CMAKE_CXX_STANDARD_REQUIRED ON) 8 | endif() 9 | 10 | if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") 11 | add_compile_options(-Wall -Wextra -Wpedantic) 12 | endif() 13 | 14 | # find dependencies 15 | find_package(ament_cmake REQUIRED) 16 | 17 | install(DIRECTORY 18 | launch 19 | config 20 | DESTINATION share/${PROJECT_NAME}/ 21 | ) 22 | 23 | if(BUILD_TESTING) 24 | find_package(ament_lint_auto REQUIRED) 25 | set(ament_cmake_copyright_FOUND TRUE) 26 | set(ament_cmake_cpplint_FOUND TRUE) 27 | ament_lint_auto_find_test_dependencies() 28 | endif() 29 | 30 | ament_package() -------------------------------------------------------------------------------- /interactive_marker/launch/interactive_marker.launch.py: -------------------------------------------------------------------------------- 1 | import os 2 | from launch import LaunchDescription 3 | from launch_ros.actions import Node 4 | from launch.actions import RegisterEventHandler 5 | from launch.event_handlers import OnProcessStart, OnProcessExit 6 | from ament_index_python.packages import get_package_share_directory 7 | from moveit_configs_utils import MoveItConfigsBuilder 8 | 9 | def generate_launch_description(): 10 | 11 | moveit_config = ( 12 | MoveItConfigsBuilder("moveit_resources_panda") 13 | .robot_description( 14 | file_path="config/panda.urdf.xacro", 15 | mappings={ 16 | "ros2_control_hardware_type": "mujoco" 17 | }, 18 | ) 19 | .robot_description_semantic(file_path="config/panda.srdf") 20 | .trajectory_execution(file_path="config/gripper_moveit_controllers.yaml") 21 | .planning_pipelines(pipelines=["ompl", "pilz_industrial_motion_planner"]) 22 | .to_moveit_configs() 23 | ) 24 | 25 | # Start the actual move_group node/action server 26 | move_group_node = Node( 27 | package="moveit_ros_move_group", 28 | executable="move_group", 29 | output="screen", 30 | parameters=[moveit_config.to_dict(), {"use_sim_time": True}] 31 | ) 32 | 33 | # RViz 34 | rviz_config_file = os.path.join( 35 | get_package_share_directory("interactive_marker"), 36 | "config", 37 | "interactive_marker.rviz", 38 | ) 39 | 40 | rviz_node = Node( 41 | package="rviz2", 42 | executable="rviz2", 43 | name="rviz2", 44 | output="log", 45 | arguments=["-d", rviz_config_file], 46 | parameters=[ 47 | moveit_config.robot_description, 48 | moveit_config.robot_description_semantic, 49 | moveit_config.robot_description_kinematics, 50 | moveit_config.planning_pipelines, 51 | moveit_config.joint_limits, 52 | {"use_sim_time": True} 53 | ], 54 | ) 55 | 56 | # Static TF 57 | world2robot_tf_node = Node( 58 | package="tf2_ros", 59 | executable="static_transform_publisher", 60 | name="static_transform_publisher", 61 | output="log", 62 | arguments=["--frame-id", "world", "--child-frame-id", "panda_link0"], 63 | parameters=[{"use_sim_time": True}] 64 | ) 65 | 66 | # Publish TF 67 | robot_state_publisher = Node( 68 | package="robot_state_publisher", 69 | executable="robot_state_publisher", 70 | name="robot_state_publisher", 71 | output="both", 72 | parameters=[moveit_config.robot_description, {"use_sim_time": True}], 73 | ) 74 | 75 | # ros2_control using FakeSystem as hardware 76 | ros2_controllers_path = os.path.join( 77 | get_package_share_directory("moveit_resources_panda_moveit_config"), 78 | "config", 79 | "ros2_controllers.yaml", 80 | ) 81 | 82 | node_mujoco_ros2_control = Node( 83 | package='mujoco_ros2_control', 84 | executable='mujoco_ros2_control', 85 | output='screen', 86 | parameters=[ 87 | moveit_config.robot_description, 88 | ros2_controllers_path, 89 | {'mujoco_model_path':os.path.join(get_package_share_directory('panda_mujoco'), 'franka_emika_panda', 'scene.xml')}, 90 | {"use_sim_time": True} 91 | ] 92 | ) 93 | 94 | joint_state_broadcaster_spawner = Node( 95 | package="controller_manager", 96 | executable="spawner", 97 | arguments=[ 98 | "joint_state_broadcaster", 99 | "--controller-manager", 100 | "/controller_manager", 101 | ], 102 | ) 103 | 104 | panda_arm_controller_spawner = Node( 105 | package="controller_manager", 106 | executable="spawner", 107 | arguments=["panda_arm_controller", "-c", "/controller_manager"], 108 | ) 109 | 110 | panda_hand_controller_spawner = Node( 111 | package="controller_manager", 112 | executable="spawner", 113 | arguments=["panda_hand_controller", "-c", "/controller_manager"], 114 | ) 115 | # Without spawning admittance controller, panda arm controller is not working. 116 | # Admittance controller is disabled in default, so it shouldn't apply until enabled. 117 | admittance_controller_spawner = Node( 118 | package="controller_manager", 119 | executable="spawner", 120 | arguments=["admittance_controller", "-c", "/controller_manager"], 121 | ) 122 | 123 | return LaunchDescription( 124 | [ 125 | RegisterEventHandler( 126 | event_handler=OnProcessStart( 127 | target_action=node_mujoco_ros2_control, 128 | on_start=[joint_state_broadcaster_spawner], 129 | ) 130 | ), 131 | RegisterEventHandler( 132 | event_handler=OnProcessExit( 133 | target_action=joint_state_broadcaster_spawner, 134 | on_exit=[admittance_controller_spawner,panda_hand_controller_spawner], 135 | ) 136 | ), 137 | RegisterEventHandler( 138 | event_handler=OnProcessExit( 139 | target_action=admittance_controller_spawner, 140 | on_exit=[panda_arm_controller_spawner], 141 | ) 142 | ), 143 | rviz_node, 144 | world2robot_tf_node, 145 | robot_state_publisher, 146 | move_group_node, 147 | node_mujoco_ros2_control 148 | ] 149 | ) -------------------------------------------------------------------------------- /interactive_marker/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 5 | 6 | interactive_marker 7 | 0.1.0 8 | interactive_marker 9 | 10 | Sangtaek Lee 11 | 12 | MIT 13 | 14 | Sangtaek Lee 15 | 16 | ament_cmake 17 | 18 | controller_manager 19 | moveit 20 | moveit_ros_move_group 21 | moveit_configs_utils 22 | moveit_resources_panda_description 23 | moveit_resources_panda_moveit_config 24 | moveit_simple_controller_manager 25 | position_controllers 26 | gripper_controllers 27 | moveit_planners_ompl 28 | pilz_industrial_motion_planner 29 | rviz2 30 | 31 | ament_lint_auto 32 | ament_lint_common 33 | 34 | 35 | ament_cmake 36 | 37 | -------------------------------------------------------------------------------- /panda_resources/panda_description/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package moveit_resources_panda_description 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 2.0.7 (2024-04-03) 6 | ------------------ 7 | 8 | 2.0.6 (2022-07-18) 9 | ------------------ 10 | 11 | 2.0.5 (2022-06-25) 12 | ------------------ 13 | 14 | 2.0.4 (2022-05-19) 15 | ------------------ 16 | 17 | 2.0.3 (2021-09-16) 18 | ------------------ 19 | 20 | 2.0.2 (2021-05-24) 21 | ------------------ 22 | 23 | 2.0.1 (2021-04-09) 24 | ------------------ 25 | 26 | 2.0.0 (2020-11-20) 27 | ------------------ 28 | * Port and modernize CMakeLists.txt + package.xml for ROS2 (`#26 `_, `#31 `_) 29 | * Contributors: Henning Kayser, Jafar Abdi, Mike Lautman, Nathan Brooks 30 | 31 | 0.7.1 (2020-10-09) 32 | ------------------ 33 | 34 | 0.7.0 (2020-08-13) 35 | ------------------ 36 | * Split resources into multiple packages (`#36 `_) 37 | * Contributors: Robert Haschke, Michael Görner 38 | -------------------------------------------------------------------------------- /panda_resources/panda_description/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.10.2) 2 | project(moveit_resources_panda_description) 3 | find_package(ament_cmake REQUIRED) 4 | 5 | ament_package() 6 | 7 | install(DIRECTORY meshes urdf DESTINATION share/${PROJECT_NAME}) 8 | -------------------------------------------------------------------------------- /panda_resources/panda_description/LICENSE: -------------------------------------------------------------------------------- 1 | Apache License 2 | Version 2.0, January 2004 3 | http://www.apache.org/licenses/ 4 | 5 | TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION 6 | 7 | 1. Definitions. 8 | 9 | "License" shall mean the terms and conditions for use, reproduction, 10 | and distribution as defined by Sections 1 through 9 of this document. 11 | 12 | "Licensor" shall mean the copyright owner or entity authorized by 13 | the copyright owner that is granting the License. 14 | 15 | "Legal Entity" shall mean the union of the acting entity and all 16 | other entities that control, are controlled by, or are under common 17 | control with that entity. For the purposes of this definition, 18 | "control" means (i) the power, direct or indirect, to cause the 19 | direction or management of such entity, whether by contract or 20 | otherwise, or (ii) ownership of fifty percent (50%) or more of the 21 | outstanding shares, or (iii) beneficial ownership of such entity. 22 | 23 | "You" (or "Your") shall mean an individual or Legal Entity 24 | exercising permissions granted by this License. 25 | 26 | "Source" form shall mean the preferred form for making modifications, 27 | including but not limited to software source code, documentation 28 | source, and configuration files. 29 | 30 | "Object" form shall mean any form resulting from mechanical 31 | transformation or translation of a Source form, including but 32 | not limited to compiled object code, generated documentation, 33 | and conversions to other media types. 34 | 35 | "Work" shall mean the work of authorship, whether in Source or 36 | Object form, made available under the License, as indicated by a 37 | copyright notice that is included in or attached to the work 38 | (an example is provided in the Appendix below). 39 | 40 | "Derivative Works" shall mean any work, whether in Source or Object 41 | form, that is based on (or derived from) the Work and for which the 42 | editorial revisions, annotations, elaborations, or other modifications 43 | represent, as a whole, an original work of authorship. For the purposes 44 | of this License, Derivative Works shall not include works that remain 45 | separable from, or merely link (or bind by name) to the interfaces of, 46 | the Work and Derivative Works thereof. 47 | 48 | "Contribution" shall mean any work of authorship, including 49 | the original version of the Work and any modifications or additions 50 | to that Work or Derivative Works thereof, that is intentionally 51 | submitted to Licensor for inclusion in the Work by the copyright owner 52 | or by an individual or Legal Entity authorized to submit on behalf of 53 | the copyright owner. For the purposes of this definition, "submitted" 54 | means any form of electronic, verbal, or written communication sent 55 | to the Licensor or its representatives, including but not limited to 56 | communication on electronic mailing lists, source code control systems, 57 | and issue tracking systems that are managed by, or on behalf of, the 58 | Licensor for the purpose of discussing and improving the Work, but 59 | excluding communication that is conspicuously marked or otherwise 60 | designated in writing by the copyright owner as "Not a Contribution." 61 | 62 | "Contributor" shall mean Licensor and any individual or Legal Entity 63 | on behalf of whom a Contribution has been received by Licensor and 64 | subsequently incorporated within the Work. 65 | 66 | 2. Grant of Copyright License. Subject to the terms and conditions of 67 | this License, each Contributor hereby grants to You a perpetual, 68 | worldwide, non-exclusive, no-charge, royalty-free, irrevocable 69 | copyright license to reproduce, prepare Derivative Works of, 70 | publicly display, publicly perform, sublicense, and distribute the 71 | Work and such Derivative Works in Source or Object form. 72 | 73 | 3. Grant of Patent License. Subject to the terms and conditions of 74 | this License, each Contributor hereby grants to You a perpetual, 75 | worldwide, non-exclusive, no-charge, royalty-free, irrevocable 76 | (except as stated in this section) patent license to make, have made, 77 | use, offer to sell, sell, import, and otherwise transfer the Work, 78 | where such license applies only to those patent claims licensable 79 | by such Contributor that are necessarily infringed by their 80 | Contribution(s) alone or by combination of their Contribution(s) 81 | with the Work to which such Contribution(s) was submitted. If You 82 | institute patent litigation against any entity (including a 83 | cross-claim or counterclaim in a lawsuit) alleging that the Work 84 | or a Contribution incorporated within the Work constitutes direct 85 | or contributory patent infringement, then any patent licenses 86 | granted to You under this License for that Work shall terminate 87 | as of the date such litigation is filed. 88 | 89 | 4. Redistribution. You may reproduce and distribute copies of the 90 | Work or Derivative Works thereof in any medium, with or without 91 | modifications, and in Source or Object form, provided that You 92 | meet the following conditions: 93 | 94 | (a) You must give any other recipients of the Work or 95 | Derivative Works a copy of this License; and 96 | 97 | (b) You must cause any modified files to carry prominent notices 98 | stating that You changed the files; and 99 | 100 | (c) You must retain, in the Source form of any Derivative Works 101 | that You distribute, all copyright, patent, trademark, and 102 | attribution notices from the Source form of the Work, 103 | excluding those notices that do not pertain to any part of 104 | the Derivative Works; and 105 | 106 | (d) If the Work includes a "NOTICE" text file as part of its 107 | distribution, then any Derivative Works that You distribute must 108 | include a readable copy of the attribution notices contained 109 | within such NOTICE file, excluding those notices that do not 110 | pertain to any part of the Derivative Works, in at least one 111 | of the following places: within a NOTICE text file distributed 112 | as part of the Derivative Works; within the Source form or 113 | documentation, if provided along with the Derivative Works; or, 114 | within a display generated by the Derivative Works, if and 115 | wherever such third-party notices normally appear. The contents 116 | of the NOTICE file are for informational purposes only and 117 | do not modify the License. You may add Your own attribution 118 | notices within Derivative Works that You distribute, alongside 119 | or as an addendum to the NOTICE text from the Work, provided 120 | that such additional attribution notices cannot be construed 121 | as modifying the License. 122 | 123 | You may add Your own copyright statement to Your modifications and 124 | may provide additional or different license terms and conditions 125 | for use, reproduction, or distribution of Your modifications, or 126 | for any such Derivative Works as a whole, provided Your use, 127 | reproduction, and distribution of the Work otherwise complies with 128 | the conditions stated in this License. 129 | 130 | 5. Submission of Contributions. Unless You explicitly state otherwise, 131 | any Contribution intentionally submitted for inclusion in the Work 132 | by You to the Licensor shall be under the terms and conditions of 133 | this License, without any additional terms or conditions. 134 | Notwithstanding the above, nothing herein shall supersede or modify 135 | the terms of any separate license agreement you may have executed 136 | with Licensor regarding such Contributions. 137 | 138 | 6. Trademarks. This License does not grant permission to use the trade 139 | names, trademarks, service marks, or product names of the Licensor, 140 | except as required for reasonable and customary use in describing the 141 | origin of the Work and reproducing the content of the NOTICE file. 142 | 143 | 7. Disclaimer of Warranty. Unless required by applicable law or 144 | agreed to in writing, Licensor provides the Work (and each 145 | Contributor provides its Contributions) on an "AS IS" BASIS, 146 | WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or 147 | implied, including, without limitation, any warranties or conditions 148 | of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A 149 | PARTICULAR PURPOSE. You are solely responsible for determining the 150 | appropriateness of using or redistributing the Work and assume any 151 | risks associated with Your exercise of permissions under this License. 152 | 153 | 8. Limitation of Liability. In no event and under no legal theory, 154 | whether in tort (including negligence), contract, or otherwise, 155 | unless required by applicable law (such as deliberate and grossly 156 | negligent acts) or agreed to in writing, shall any Contributor be 157 | liable to You for damages, including any direct, indirect, special, 158 | incidental, or consequential damages of any character arising as a 159 | result of this License or out of the use or inability to use the 160 | Work (including but not limited to damages for loss of goodwill, 161 | work stoppage, computer failure or malfunction, or any and all 162 | other commercial damages or losses), even if such Contributor 163 | has been advised of the possibility of such damages. 164 | 165 | 9. Accepting Warranty or Additional Liability. While redistributing 166 | the Work or Derivative Works thereof, You may choose to offer, 167 | and charge a fee for, acceptance of support, warranty, indemnity, 168 | or other liability obligations and/or rights consistent with this 169 | License. However, in accepting such obligations, You may act only 170 | on Your own behalf and on Your sole responsibility, not on behalf 171 | of any other Contributor, and only if You agree to indemnify, 172 | defend, and hold each Contributor harmless for any liability 173 | incurred by, or claims asserted against, such Contributor by reason 174 | of your accepting any such warranty or additional liability. 175 | 176 | END OF TERMS AND CONDITIONS 177 | -------------------------------------------------------------------------------- /panda_resources/panda_description/README.md: -------------------------------------------------------------------------------- 1 | # panda_description 2 | 3 | The URDF model and meshes contained in this package were copied from the frankaemika `franka_ros` package and adapted for use with `moveit_resources`. 4 | 5 | All imported files were released under the Apache-2.0 license. 6 | -------------------------------------------------------------------------------- /panda_resources/panda_description/meshes/collision/finger.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_description/meshes/collision/finger.stl -------------------------------------------------------------------------------- /panda_resources/panda_description/meshes/collision/hand.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_description/meshes/collision/hand.stl -------------------------------------------------------------------------------- /panda_resources/panda_description/meshes/collision/link0.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_description/meshes/collision/link0.stl -------------------------------------------------------------------------------- /panda_resources/panda_description/meshes/collision/link1.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_description/meshes/collision/link1.stl -------------------------------------------------------------------------------- /panda_resources/panda_description/meshes/collision/link2.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_description/meshes/collision/link2.stl -------------------------------------------------------------------------------- /panda_resources/panda_description/meshes/collision/link3.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_description/meshes/collision/link3.stl -------------------------------------------------------------------------------- /panda_resources/panda_description/meshes/collision/link4.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_description/meshes/collision/link4.stl -------------------------------------------------------------------------------- /panda_resources/panda_description/meshes/collision/link5.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_description/meshes/collision/link5.stl -------------------------------------------------------------------------------- /panda_resources/panda_description/meshes/collision/link6.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_description/meshes/collision/link6.stl -------------------------------------------------------------------------------- /panda_resources/panda_description/meshes/collision/link7.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_description/meshes/collision/link7.stl -------------------------------------------------------------------------------- /panda_resources/panda_description/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | moveit_resources_panda_description 4 | 2.0.7 5 | panda Resources used for MoveIt testing 6 | 7 | Ioan Sucan 8 | Acorn Pooley 9 | 10 | Dave Coleman 11 | 12 | BSD 13 | http://moveit.ros.org 14 | https://github.com/ros-planning/moveit-resources/issues 15 | https://github.com/ros-planning/moveit-resources 16 | 17 | ament_cmake 18 | 19 | 20 | ament_cmake 21 | 22 | 23 | -------------------------------------------------------------------------------- /panda_resources/panda_description/urdf/panda.urdf: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | 42 | 43 | 44 | 45 | 46 | 47 | 48 | 49 | 50 | 51 | 52 | 53 | 54 | 55 | 56 | 57 | 58 | 59 | 60 | 61 | 62 | 63 | 64 | 65 | 66 | 67 | 68 | 69 | 70 | 71 | 72 | 73 | 74 | 75 | 76 | 77 | 78 | 79 | 80 | 81 | 82 | 83 | 84 | 85 | 86 | 87 | 88 | 89 | 90 | 91 | 92 | 93 | 94 | 95 | 96 | 97 | 98 | 99 | 100 | 101 | 102 | 103 | 104 | 105 | 106 | 107 | 108 | 109 | 110 | 111 | 112 | 113 | 114 | 115 | 116 | 117 | 118 | 119 | 120 | 121 | 122 | 123 | 124 | 125 | 126 | 127 | 128 | 129 | 130 | 131 | 132 | 133 | 134 | 135 | 136 | 137 | 138 | 139 | 140 | 141 | 142 | 143 | 144 | 145 | 146 | 147 | 148 | 149 | 150 | 151 | 152 | 153 | 154 | 155 | 156 | 157 | 158 | 159 | 160 | 161 | 162 | 163 | 164 | 165 | 166 | 167 | 168 | 169 | 170 | 171 | 172 | 173 | 174 | 175 | 176 | 177 | 178 | 179 | 180 | 181 | 182 | 183 | 184 | 185 | 186 | 187 | 188 | 189 | 190 | 191 | 192 | 193 | 194 | 195 | 196 | 197 | 198 | 199 | 200 | 201 | 202 | 203 | 204 | 205 | 206 | 207 | 208 | 209 | 210 | 211 | 212 | 213 | 214 | 215 | 216 | 217 | 218 | 219 | 220 | 221 | 222 | 223 | 224 | 225 | -------------------------------------------------------------------------------- /panda_resources/panda_moveit_config/.setup_assistant: -------------------------------------------------------------------------------- 1 | moveit_setup_assistant_config: 2 | URDF: 3 | package: moveit_resources_panda_description 4 | relative_path: urdf/panda.urdf 5 | SRDF: 6 | relative_path: config/panda_arm_hand.srdf.xacro 7 | CONFIG: 8 | author_name: Mike Lautman 9 | author_email: mike@picknik.ai 10 | generated_timestamp: 1519152260 11 | -------------------------------------------------------------------------------- /panda_resources/panda_moveit_config/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package moveit_resources_panda_moveit_config 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 2.0.7 (2024-04-03) 6 | ------------------ 7 | * Update ros2 control usage (`#192 `_) (`#193 `_) 8 | * Replace Isaac with TopicBased (`#163 `_) 9 | * Add execution_duration_monitoring param to the example config (`#160 `_) 10 | * Fix xacro deprecation warning: use xacro.load_yaml() (`#156 `_) 11 | * Add Pilz to panda launch (`#154 `_) 12 | * Add pilz_industrial_motion_planner_planning.yaml (`#151 `_) 13 | * Contributors: AndyZe, Giovanni, Jafar, Sebastian Jahr, Stephanie Eng 14 | 15 | 2.0.6 (2022-07-18) 16 | ------------------ 17 | * fake_components -> mock_components (`#147 `_) 18 | * Rename cartesian_limits.yaml (`#146 `_) 19 | * Contributors: AndyZe, Tyler Weaver 20 | 21 | 2.0.5 (2022-06-25) 22 | ------------------ 23 | * Fix a typo in chomp_planning.yaml (`#143 `_) 24 | * Update ros2_control launching (`#140 `_) 25 | * Proper scoping for controllers in Panda Config (`#132 `_) 26 | * Contributors: AndyZe, David V. Lu!!, Stephanie Eng 27 | 28 | 2.0.4 (2022-05-19) 29 | ------------------ 30 | * Explicitly use CHOMP and OMPL planners (`#135 `_) 31 | * Rename Panda Controller Files (`#127 `_) 32 | * Fix controller_manager node's output type (`#129 `_) 33 | * Black Formatting for Launch Files (`#128 `_) 34 | * Refactor panda demo.launch to use moveit_configs_utils (`#119 `_) 35 | * Remove stomp configuration file (`#126 `_) 36 | * Restore panda_gripper_controllers.yaml. Rename panda_moveit_controllers.yaml (`#117 `_) 37 | * Delete deprecated Panda config and launch files (`#98 `_) 38 | * No initial velocity conditions (`#111 `_) 39 | * ros2_control update: initial_position -> initial_value (`#110 `_) 40 | * Update yaml parameters for moveit_configs_utils (`#108 `_) 41 | * Port PRBT packages for PILZ planner tests (`#101 `_) 42 | * Adding RPBT config (`#43 `_) 43 | to speed up test time by skipping trajectory in fake execution 44 | * Contributors: AndyZe, Christian Henkel, David V. Lu!!, Henning Kayser, Jafar, Jafar Abdi, Sebastian Jahr, Stephanie Eng 45 | 46 | 2.0.3 (2021-09-16) 47 | ------------------ 48 | * Migrate to joint state broadcaster 49 | * Add panda_hand_controller to demo.launch.py (`#87 `_) 50 | * Add fake controller for panda_hand (`#73 `_) 51 | * Contributors: Jafar Abdi, Marq Rasmussen, Vatan Aksoy Tezer 52 | 53 | 2.0.2 (2021-05-24) 54 | ------------------ 55 | * Add missing ros2_control parameters (`#74 `_) 56 | * Add Panda demo.launch.py and RViz config (`#64 `_) 57 | * Remove move group prefixes from rviz configs (`#62 `_) 58 | * Ensure panda joint limits have the proper type (`#63 `_) 59 | * Contributors: AndyZe, Henning Kayser, Vatan Aksoy Tezer 60 | 61 | 2.0.1 (2021-04-09) 62 | ------------------ 63 | * Update panda configs for ros2_control (`#51 `_) 64 | * Contributors: Jafar Abdi, Tyler Weaver 65 | 66 | 2.0.0 (2020-11-20) 67 | ------------------ 68 | * Port and modernize CMakeLists.txt + package.xml for ROS2 (`#26 `_, `#31 `_) 69 | * Contributors: Henning Kayser, Jafar Abdi, Mike Lautman, Nathan Brooks 70 | 71 | 0.7.1 (2020-10-09) 72 | ------------------ 73 | * Fix self-colliding 'extended' pose (`#42 `_) 74 | * Contributors: Henning Kayser 75 | 76 | 0.7.0 (2020-08-13) 77 | ------------------ 78 | * Split resources into multiple packages (`#36 `_) 79 | * Remove solver attempts (`#35 `_) 80 | * Contributors: Michael Görner, Robert Haschke 81 | -------------------------------------------------------------------------------- /panda_resources/panda_moveit_config/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.10.2) 2 | project(moveit_resources_panda_moveit_config) 3 | find_package(ament_cmake REQUIRED) 4 | 5 | ament_package() 6 | 7 | install(DIRECTORY launch DESTINATION share/${PROJECT_NAME}) 8 | install(DIRECTORY config DESTINATION share/${PROJECT_NAME}) 9 | install(FILES .setup_assistant DESTINATION share/${PROJECT_NAME}) 10 | -------------------------------------------------------------------------------- /panda_resources/panda_moveit_config/README.md: -------------------------------------------------------------------------------- 1 | ## MoveIt Resources for testing: Franka Emika Panda 2 | 3 | A project-internal moveit configuration for testing in MoveIt. 4 | 5 | Use the official panda_moveit_config if you actually want to work with the robot! 6 | -------------------------------------------------------------------------------- /panda_resources/panda_moveit_config/config/chomp_planning.yaml: -------------------------------------------------------------------------------- 1 | planning_plugin: chomp_interface/CHOMPPlanner 2 | request_adapters: >- 3 | default_planner_request_adapters/AddTimeOptimalParameterization 4 | default_planner_request_adapters/FixWorkspaceBounds 5 | default_planner_request_adapters/FixStartStateBounds 6 | default_planner_request_adapters/FixStartStateCollision 7 | default_planner_request_adapters/FixStartStatePathConstraints 8 | start_state_max_bounds_error: 0.1 9 | planning_time_limit: 10.0 10 | max_iterations: 200 11 | max_iterations_after_collision_free: 5 12 | smoothness_cost_weight: 0.1 13 | obstacle_cost_weight: 1.0 14 | learning_rate: 0.01 15 | animate_path: true 16 | add_randomness: false 17 | smoothness_cost_velocity: 0.0 18 | smoothness_cost_acceleration: 1.0 19 | smoothness_cost_jerk: 0.0 20 | hmc_discretization: 0.01 21 | hmc_stochasticity: 0.01 22 | hmc_annealing_factor: 0.99 23 | use_hamiltonian_monte_carlo: false 24 | ridge_factor: 0.0 25 | use_pseudo_inverse: false 26 | pseudo_inverse_ridge_factor: 1e-4 27 | animate_endeffector: false 28 | animate_endeffector_segment: "panda_rightfinger" 29 | joint_update_limit: 0.1 30 | collision_clearance: 0.2 31 | collision_threshold: 0.07 32 | random_jump_amount: 1.0 33 | use_stochastic_descent: true 34 | enable_failure_recovery: false 35 | max_recovery_attempts: 5 36 | trajectory_initialization_method: "quintic-spline" 37 | -------------------------------------------------------------------------------- /panda_resources/panda_moveit_config/config/gripper_moveit_controllers.yaml: -------------------------------------------------------------------------------- 1 | # MoveIt uses this configuration for controller management 2 | trajectory_execution: 3 | allowed_execution_duration_scaling: 2.0 4 | allowed_goal_duration_margin: 1.0 5 | allowed_start_tolerance: 0.03 6 | 7 | moveit_controller_manager: moveit_simple_controller_manager/MoveItSimpleControllerManager 8 | 9 | moveit_simple_controller_manager: 10 | controller_names: 11 | - panda_arm_controller 12 | - panda_hand_controller 13 | 14 | panda_arm_controller: 15 | action_ns: follow_joint_trajectory 16 | type: FollowJointTrajectory 17 | default: true 18 | joints: 19 | - panda_joint1 20 | - panda_joint2 21 | - panda_joint3 22 | - panda_joint4 23 | - panda_joint5 24 | - panda_joint6 25 | - panda_joint7 26 | 27 | panda_hand_controller: 28 | action_ns: gripper_cmd 29 | type: GripperCommand 30 | default: true 31 | joints: 32 | - panda_finger_joint1 33 | -------------------------------------------------------------------------------- /panda_resources/panda_moveit_config/config/hand.xacro: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | -------------------------------------------------------------------------------- /panda_resources/panda_moveit_config/config/initial_positions.yaml: -------------------------------------------------------------------------------- 1 | # Default initial positions for the panda arm's ros2_control fake system 2 | initial_positions: 3 | panda_joint1: 0.0 4 | panda_joint2: -0.785 5 | panda_joint3: 0.0 6 | panda_joint4: -2.356 7 | panda_joint5: 0.0 8 | panda_joint6: 1.571 9 | panda_joint7: 0.785 10 | -------------------------------------------------------------------------------- /panda_resources/panda_moveit_config/config/joint_limits.yaml: -------------------------------------------------------------------------------- 1 | # joint_limits.yaml allows the dynamics properties specified in the URDF to be overwritten or augmented as needed 2 | # Specific joint properties can be changed with the keys [max_position, min_position, max_velocity, max_acceleration] 3 | # Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits] 4 | 5 | # As MoveIt! does not support jerk limits, the acceleration limits provided here are the highest values that guarantee 6 | # that no jerk limits will be violated. More precisely, applying Euler differentiation in the worst case (from min accel 7 | # to max accel in 1 ms) the acceleration limits are the ones that satisfy 8 | # max_jerk = (max_acceleration - min_acceleration) / 0.001 9 | 10 | joint_limits: 11 | panda_joint1: 12 | has_velocity_limits: true 13 | max_velocity: 2.1750 14 | has_acceleration_limits: true 15 | max_acceleration: 3.75 16 | panda_joint2: 17 | has_velocity_limits: true 18 | max_velocity: 2.1750 19 | has_acceleration_limits: true 20 | max_acceleration: 1.875 21 | panda_joint3: 22 | has_velocity_limits: true 23 | max_velocity: 2.1750 24 | has_acceleration_limits: true 25 | max_acceleration: 2.5 26 | panda_joint4: 27 | has_velocity_limits: true 28 | max_velocity: 2.1750 29 | has_acceleration_limits: true 30 | max_acceleration: 3.125 31 | panda_joint5: 32 | has_velocity_limits: true 33 | max_velocity: 2.6100 34 | has_acceleration_limits: true 35 | max_acceleration: 3.75 36 | panda_joint6: 37 | has_velocity_limits: true 38 | max_velocity: 2.6100 39 | has_acceleration_limits: true 40 | max_acceleration: 5.0 41 | panda_joint7: 42 | has_velocity_limits: true 43 | max_velocity: 2.6100 44 | has_acceleration_limits: true 45 | max_acceleration: 5.0 46 | panda_finger_joint1: 47 | has_velocity_limits: true 48 | max_velocity: 0.1 49 | has_acceleration_limits: false 50 | max_acceleration: 0.0 51 | panda_finger_joint2: 52 | has_velocity_limits: true 53 | max_velocity: 0.1 54 | has_acceleration_limits: false 55 | max_acceleration: 0.0 56 | -------------------------------------------------------------------------------- /panda_resources/panda_moveit_config/config/kinematics.yaml: -------------------------------------------------------------------------------- 1 | panda_arm: 2 | kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin 3 | kinematics_solver_search_resolution: 0.005 4 | kinematics_solver_timeout: 0.05 5 | -------------------------------------------------------------------------------- /panda_resources/panda_moveit_config/config/lerp_planning.yaml: -------------------------------------------------------------------------------- 1 | planning_plugin: lerp_interface/LERPPlanner 2 | request_adapters: >- 3 | default_planner_request_adapters/AddTimeOptimalParameterization 4 | default_planner_request_adapters/FixWorkspaceBounds 5 | default_planner_request_adapters/FixStartStateBounds 6 | default_planner_request_adapters/FixStartStateCollision 7 | default_planner_request_adapters/FixStartStatePathConstraints 8 | start_state_max_bounds_error: 0.1 9 | num_steps: 40 10 | -------------------------------------------------------------------------------- /panda_resources/panda_moveit_config/config/moveit_controllers.yaml: -------------------------------------------------------------------------------- 1 | # MoveIt uses this configuration for controller management 2 | trajectory_execution: 3 | allowed_execution_duration_scaling: 1.2 4 | allowed_goal_duration_margin: 0.5 5 | allowed_start_tolerance: 0.01 6 | trajectory_duration_monitoring: true 7 | 8 | moveit_controller_manager: moveit_simple_controller_manager/MoveItSimpleControllerManager 9 | 10 | moveit_simple_controller_manager: 11 | controller_names: 12 | - panda_arm_controller 13 | 14 | panda_arm_controller: 15 | action_ns: follow_joint_trajectory 16 | type: FollowJointTrajectory 17 | default: true 18 | joints: 19 | - panda_joint1 20 | - panda_joint2 21 | - panda_joint3 22 | - panda_joint4 23 | - panda_joint5 24 | - panda_joint6 25 | - panda_joint7 26 | -------------------------------------------------------------------------------- /panda_resources/panda_moveit_config/config/panda.ros2_control.xacro: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | mock_components/GenericSystem 11 | 12 | 13 | topic_based_ros2_control/TopicBasedSystem 14 | /isaac_joint_commands 15 | /isaac_joint_states 16 | 17 | 18 | mujoco_ros2_control/MujocoSystem 19 | 20 | 21 | 22 | 23 | 3000 24 | 1 25 | 100 26 | 10000 27 | 28 | 29 | 30 | 31 | 32 | 33 | ${initial_positions['panda_joint1']} 34 | 35 | 36 | 0.0 37 | 38 | 39 | 40 | 41 | 3000 42 | 1 43 | 100 44 | 10000 45 | 46 | 47 | 48 | 49 | 50 | 51 | ${initial_positions['panda_joint2']} 52 | 53 | 54 | 0.0 55 | 56 | 57 | 58 | 59 | 3000 60 | 1 61 | 100 62 | 10000 63 | 64 | 65 | 66 | 67 | 68 | 69 | ${initial_positions['panda_joint3']} 70 | 71 | 72 | 0.0 73 | 74 | 75 | 76 | 77 | 3000 78 | 1 79 | 100 80 | 10000 81 | 82 | 83 | 84 | 85 | 86 | 87 | ${initial_positions['panda_joint4']} 88 | 89 | 90 | 0.0 91 | 92 | 93 | 94 | 95 | 3000 96 | 1 97 | 100 98 | 10000 99 | 100 | 101 | 102 | 103 | 104 | 105 | ${initial_positions['panda_joint5']} 106 | 107 | 108 | 0.0 109 | 110 | 111 | 112 | 113 | 3000 114 | 1 115 | 100 116 | 10000 117 | 118 | 119 | 120 | 121 | 122 | 123 | ${initial_positions['panda_joint6']} 124 | 125 | 126 | 0.0 127 | 128 | 129 | 130 | 131 | 3000 132 | 1 133 | 100 134 | 10000 135 | 136 | 137 | 138 | 139 | 140 | 141 | ${initial_positions['panda_joint7']} 142 | 143 | 144 | 0.0 145 | 146 | 147 | 148 | 149 | 150 | 151 | 152 | 153 | 154 | ft_sensor 155 | 156 | 157 | 158 | 159 | -------------------------------------------------------------------------------- /panda_resources/panda_moveit_config/config/panda.srdf: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | 42 | 43 | 44 | 45 | 46 | 47 | 48 | 49 | 50 | 51 | 52 | 53 | 54 | 55 | 56 | 57 | 58 | 59 | 60 | 61 | 62 | 63 | 64 | 65 | 66 | 67 | 68 | 69 | 70 | 71 | 72 | 73 | 74 | 75 | 76 | 77 | 78 | 79 | 80 | 81 | 82 | 83 | 84 | 85 | 86 | 87 | 88 | 89 | 90 | 91 | 92 | 93 | 94 | 95 | 96 | 97 | 98 | 99 | 100 | 101 | 102 | 103 | 104 | 105 | 106 | 107 | 108 | 109 | 110 | 111 | 112 | 113 | 114 | 115 | 116 | 117 | 118 | 119 | 120 | 121 | -------------------------------------------------------------------------------- /panda_resources/panda_moveit_config/config/panda.urdf.xacro: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | -------------------------------------------------------------------------------- /panda_resources/panda_moveit_config/config/panda_arm.srdf.xacro: -------------------------------------------------------------------------------- 1 | 2 | 6 | 7 | 8 | 9 | 10 | -------------------------------------------------------------------------------- /panda_resources/panda_moveit_config/config/panda_arm.xacro: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | 42 | 43 | 44 | 45 | 46 | 47 | 48 | 49 | 50 | 51 | 52 | 53 | 54 | 55 | 56 | 57 | 58 | 59 | 60 | 61 | 62 | 63 | 64 | 65 | -------------------------------------------------------------------------------- /panda_resources/panda_moveit_config/config/panda_arm_hand.srdf.xacro: -------------------------------------------------------------------------------- 1 | 2 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | 42 | 43 | 44 | -------------------------------------------------------------------------------- /panda_resources/panda_moveit_config/config/panda_hand.ros2_control.xacro: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | mock_components/GenericSystem 9 | 10 | 11 | topic_based_ros2_control/TopicBasedSystem 12 | /isaac_joint_commands 13 | /isaac_joint_states 14 | 15 | 16 | mujoco_ros2_control/MujocoSystem 17 | 18 | 19 | 20 | 21 | 3000 22 | 1 23 | 100 24 | 10000 25 | 26 | 27 | 28 | 29 | 30 | 31 | 0.0 32 | 33 | 34 | 0.0 35 | 36 | 37 | 38 | panda_finger_joint1 39 | 1 40 | 41 | 3000 42 | 1 43 | 100 44 | 10000 45 | 46 | 47 | 48 | 49 | 50 | 51 | 0.0 52 | 53 | 54 | 0.0 55 | 56 | 57 | 58 | 59 | 60 | 61 | -------------------------------------------------------------------------------- /panda_resources/panda_moveit_config/config/pilz_cartesian_limits.yaml: -------------------------------------------------------------------------------- 1 | # Cartesian limits for the Pilz planner 2 | cartesian_limits: 3 | max_trans_vel: 1.0 4 | max_trans_acc: 2.25 5 | max_trans_dec: -5.0 6 | max_rot_vel: 1.57 7 | -------------------------------------------------------------------------------- /panda_resources/panda_moveit_config/config/pilz_industrial_motion_planner_planning.yaml: -------------------------------------------------------------------------------- 1 | planning_plugin: pilz_industrial_motion_planner/CommandPlanner 2 | request_adapters: >- 3 | default_planner_request_adapters/FixWorkspaceBounds 4 | default_planner_request_adapters/FixStartStateBounds 5 | default_planner_request_adapters/FixStartStateCollision 6 | default_planner_request_adapters/FixStartStatePathConstraints 7 | default_planner_config: PTP 8 | capabilities: >- 9 | pilz_industrial_motion_planner/MoveGroupSequenceAction 10 | pilz_industrial_motion_planner/MoveGroupSequenceService 11 | -------------------------------------------------------------------------------- /panda_resources/panda_moveit_config/config/ros2_controllers.yaml: -------------------------------------------------------------------------------- 1 | # This config file is used by ros2_control 2 | controller_manager: 3 | ros__parameters: 4 | # Set at least above 200 Hz for effort command interface. 5 | update_rate: 100 # Hz 6 | 7 | panda_arm_controller: 8 | type: joint_trajectory_controller/JointTrajectoryController 9 | 10 | panda_hand_controller: 11 | type: position_controllers/GripperActionController 12 | 13 | joint_state_broadcaster: 14 | type: joint_state_broadcaster/JointStateBroadcaster 15 | 16 | force_torque_broadcaster: 17 | type: force_torque_sensor_broadcaster/ForceTorqueSensorBroadcaster 18 | 19 | admittance_controller: 20 | type: admittance_controller/AdmittanceController 21 | 22 | 23 | panda_arm_controller: 24 | ros__parameters: 25 | command_interfaces: 26 | - position 27 | state_interfaces: 28 | - position 29 | - velocity 30 | joints: 31 | - panda_joint1 32 | - panda_joint2 33 | - panda_joint3 34 | - panda_joint4 35 | - panda_joint5 36 | - panda_joint6 37 | - panda_joint7 38 | command_joints: 39 | - admittance_controller/panda_joint1 40 | - admittance_controller/panda_joint2 41 | - admittance_controller/panda_joint3 42 | - admittance_controller/panda_joint4 43 | - admittance_controller/panda_joint5 44 | - admittance_controller/panda_joint6 45 | - admittance_controller/panda_joint7 46 | constraints: 47 | panda_joint1: 48 | goal: 0.03 49 | trajectory: 0.5 50 | panda_joint2: 51 | goal: 0.03 52 | trajectory: 0.5 53 | panda_joint3: 54 | goal: 0.03 55 | trajectory: 0.5 56 | panda_joint4: 57 | goal: 0.03 58 | trajectory: 0.5 59 | panda_joint5: 60 | goal: 0.03 61 | trajectory: 0.5 62 | panda_joint6: 63 | goal: 0.03 64 | trajectory: 0.5 65 | panda_joint7: 66 | goal: 0.03 67 | trajectory: 0.5 68 | 69 | panda_hand_controller: 70 | ros__parameters: 71 | joint: panda_finger_joint1 72 | 73 | force_torque_broadcaster: 74 | ros__parameters: 75 | frame_id: ft_sensor 76 | sensor_name: ft_sensor 77 | 78 | admittance_controller: 79 | ros__parameters: 80 | joints: 81 | - panda_joint1 82 | - panda_joint2 83 | - panda_joint3 84 | - panda_joint4 85 | - panda_joint5 86 | - panda_joint6 87 | - panda_joint7 88 | command_interfaces: 89 | - position 90 | state_interfaces: 91 | - position 92 | - velocity 93 | chainable_command_interfaces: 94 | - position 95 | - velocity 96 | kinematics: 97 | plugin_name: kinematics_interface_kdl/KinematicsInterfaceKDL 98 | plugin_package: kinematics_interface 99 | base: panda_link0 # Assumed to be stationary 100 | tip: panda_hand # The end effector frame 101 | alpha: 0.05 102 | ft_sensor: 103 | name: ft_sensor 104 | frame: 105 | id: panda_link7 # Wrench measurements are in this frame 106 | filter_coefficient: 0.1 107 | control: 108 | frame: 109 | id: panda_link7 # Admittance calcs (displacement etc) are done in this frame. Usually the tool or end-effector 110 | fixed_world_frame: 111 | frame: # Gravity points down (neg. Z) in this frame (Usually: world or base_link) 112 | id: panda_link0 113 | gravity_compensation: 114 | frame: 115 | id: panda_link7 116 | CoG: # specifies the center of gravity of the end effector 117 | pos: 118 | - 0.0 # x 119 | - 0.0 # y 120 | - 0.0 # z 121 | force: 15. # mass * 9.81 122 | admittance: 123 | selected_axes: 124 | - false # x 125 | - false # y 126 | - false # z 127 | - false # rx 128 | - false # ry 129 | - false # rz 130 | # Having ".0" at the end is MUST, otherwise there is a loading error 131 | # F = M*a + D*v + S*(x - x_d) 132 | mass: 133 | - 8.0 # x 134 | - 8.0 # y 135 | - 8.0 # z 136 | - 8.0 # rx 137 | - 8.0 # ry 138 | - 8.0 # rz 139 | damping_ratio: # damping can be used instead: zeta = D / (2 * sqrt( M * S )) 140 | - 30. # x 141 | - 30. # y 142 | - 30. # z 143 | - 30. # rx 144 | - 30. # ry 145 | - 30. # rz 146 | stiffness: 147 | - 60. # x 148 | - 60. # y 149 | - 60. # z 150 | - 60. # rx 151 | - 60. # ry 152 | - 60. # rz 153 | # general settings 154 | enable_parameter_update_without_reactivation: true 155 | -------------------------------------------------------------------------------- /panda_resources/panda_moveit_config/config/sensors_kinect_depthmap.yaml: -------------------------------------------------------------------------------- 1 | sensors: 2 | - sensor_plugin: occupancy_map_monitor/DepthImageOctomapUpdater 3 | image_topic: /camera/depth_registered/image_raw 4 | queue_size: 5 5 | near_clipping_plane_distance: 0.3 6 | far_clipping_plane_distance: 5.0 7 | shadow_threshold: 0.2 8 | padding_scale: 4.0 9 | padding_offset: 0.03 10 | max_update_rate: 1.0 11 | filtered_cloud_topic: filtered_cloud 12 | -------------------------------------------------------------------------------- /panda_resources/panda_moveit_config/config/sensors_kinect_pointcloud.yaml: -------------------------------------------------------------------------------- 1 | sensors: 2 | - sensor_plugin: occupancy_map_monitor/PointCloudOctomapUpdater 3 | point_cloud_topic: /camera/depth_registered/points 4 | max_range: 5.0 5 | point_subsample: 1 6 | padding_offset: 0.1 7 | padding_scale: 1.0 8 | max_update_rate: 1.0 9 | filtered_cloud_topic: filtered_cloud 10 | -------------------------------------------------------------------------------- /panda_resources/panda_moveit_config/config/trajopt_planning.yaml: -------------------------------------------------------------------------------- 1 | planning_plugin: trajopt_interface/TrajOptPlanner 2 | request_adapters: >- 3 | default_planner_request_adapters/AddTimeOptimalParameterization 4 | default_planner_request_adapters/FixWorkspaceBounds 5 | default_planner_request_adapters/FixStartStateBounds 6 | default_planner_request_adapters/FixStartStateCollision 7 | default_planner_request_adapters/FixStartStatePathConstraints 8 | start_state_max_bounds_error: 0.1 9 | trajopt_param: 10 | improve_ratio_threshold: 0.25 # minimum ratio true_improve/approx_improve to accept step. [Research Paper] TrueImprove/ModelImprove > c 11 | min_trust_box_size: 1e-4 # if trust region gets any smaller, exit and report convergence. [Research Paper] xtol 12 | min_approx_improve: 1e-4 # if model improves less than this, exit and report convergence 13 | min_approx_improve_frac: -.Inf # if model improves less than this, exit and report convergence 14 | max_iter: 100 # The max number of iterations 15 | trust_shrink_ratio: 0.1 # if improvement is less than improve_ratio_threshold, shrink trust region by this ratio. [Research Paper] tao- 16 | trust_expand_ratio: 1.5 # if improvement is less than improve_ratio_threshold, shrink trust region by this ratio. [Research Paper] tao+ 17 | cnt_tolerance: 1e-4 # after convergence of penalty subproblem, if constraint violation is less than this, we're done. [Research Paper] ctol 18 | max_merit_coeff_increases: 5 # number of times that we jack up penalty coefficient. [Reasearch Paper] Max iteration in PenaltyIteration loop 19 | merit_coeff_increase_ratio: 10 # ratio that we increate coeff each time. [Researcy Paper] Penalty scaling factory (italic kappa) 20 | max_time: .inf # not yet implemented 21 | merit_error_coeff: 10 # initial penalty coefficient. [Research Paper] mu_0 22 | trust_box_size: 1e-1 # current size of trust region (component-wise). [Research Paper] s 23 | 24 | problem_info: 25 | basic_info: 26 | n_steps: 20 # 2 * steps_per_phase 27 | dt_upper_lim: 2.0 # The upper limit of 1/dt values allowed in the optimization 28 | dt_lower_lim: 100.0 # The lower limit of 1/dt values allowed in the optimization 29 | start_fixed: true # if true, start pose is the current pose at timestep = 0 30 | # if false, the start pose is the one given by req.start_state 31 | use_time: false # if false, it means the timestep is unit, meaning x1-x0 is the velocity for example 32 | # if true, then cost_infos ro cnt_infos should have TT_USE_TIME for their term_type 33 | convex_solver: 1 # which convex solver to use 34 | # 1 = AUTO_SOLVER, 2 = BPMPD, 3 = OSQP, 4 = QPOASES, 5 = GUROBI 35 | 36 | init_info: 37 | type: 3 # 1 = STATIONARY, 2 = JOINT_INTERPOLATED, 3 = GIVEN_TRAJ 38 | # request.start_state should be provided for JOINT_INTERPOLATED and GIVEN_TRAJ 39 | dt: 0.5 40 | 41 | joint_pos_term_info: 42 | start_pos: # from req.start_state 43 | name: start_pos 44 | first_timestep: 10 # First time step to which the term is applied. 45 | last_timestep: 10 # Last time step to which the term is applied. 46 | # if start_fixed is trure then we can not set the first_timestep to 0 for start_pos as it is going 47 | # to be ignored and only the current pose would be the constraint at timestep = 0. 48 | term_type: 2 # 1 = TT_COST, 2 = TT_CNT, 3 = TT_USE_TIME 49 | middle_pos: 50 | name: middle_pos 51 | first_timestep: 15 52 | last_timestep: 15 53 | term_type: 2 54 | goal_pos: 55 | name: goal_pos 56 | first_timestep: 19 57 | last_timestep: 19 58 | term_type: 2 59 | goal_tmp: # If the constraint from request does not have any name, for example when using MotionPlanning Display in Rviz, 60 | # goal_tmp is assigned as the name of the constraint. 61 | # In this case: start_fixed = false and start_pos should be applied at timestep 0 62 | # OR: start_fixed = true and start_pos can be applies at any timestep 63 | name: goal_tmp 64 | first_timestep: 19 # n_steps - 1 65 | last_timestep: 19 # n_steps - 1 66 | term_type: 2 67 | -------------------------------------------------------------------------------- /panda_resources/panda_moveit_config/launch/demo.launch.py: -------------------------------------------------------------------------------- 1 | import os 2 | from launch import LaunchDescription 3 | from launch.actions import DeclareLaunchArgument 4 | from launch.substitutions import LaunchConfiguration 5 | from launch.conditions import IfCondition, UnlessCondition 6 | from launch_ros.actions import Node 7 | from launch.actions import ExecuteProcess 8 | from ament_index_python.packages import get_package_share_directory 9 | from moveit_configs_utils import MoveItConfigsBuilder 10 | 11 | 12 | def generate_launch_description(): 13 | 14 | # Command-line arguments 15 | tutorial_arg = DeclareLaunchArgument( 16 | "rviz_tutorial", default_value="False", description="Tutorial flag" 17 | ) 18 | 19 | db_arg = DeclareLaunchArgument( 20 | "db", default_value="False", description="Database flag" 21 | ) 22 | 23 | ros2_control_hardware_type = DeclareLaunchArgument( 24 | "ros2_control_hardware_type", 25 | default_value="mock_components", 26 | description="ROS2 control hardware interface type to use for the launch file -- possible values: [mock_components, isaac]", 27 | ) 28 | 29 | moveit_config = ( 30 | MoveItConfigsBuilder("moveit_resources_panda") 31 | .robot_description( 32 | file_path="config/panda.urdf.xacro", 33 | mappings={ 34 | "ros2_control_hardware_type": LaunchConfiguration( 35 | "ros2_control_hardware_type" 36 | ) 37 | }, 38 | ) 39 | .robot_description_semantic(file_path="config/panda.srdf") 40 | .trajectory_execution(file_path="config/gripper_moveit_controllers.yaml") 41 | .planning_pipelines( 42 | pipelines=["ompl", "chomp", "pilz_industrial_motion_planner"] 43 | ) 44 | .to_moveit_configs() 45 | ) 46 | 47 | # Start the actual move_group node/action server 48 | move_group_node = Node( 49 | package="moveit_ros_move_group", 50 | executable="move_group", 51 | output="screen", 52 | parameters=[moveit_config.to_dict()], 53 | arguments=["--ros-args", "--log-level", "info"], 54 | ) 55 | 56 | # RViz 57 | tutorial_mode = LaunchConfiguration("rviz_tutorial") 58 | rviz_base = os.path.join( 59 | get_package_share_directory("moveit_resources_panda_moveit_config"), "launch" 60 | ) 61 | rviz_full_config = os.path.join(rviz_base, "moveit.rviz") 62 | rviz_empty_config = os.path.join(rviz_base, "moveit_empty.rviz") 63 | rviz_node_tutorial = Node( 64 | package="rviz2", 65 | executable="rviz2", 66 | name="rviz2", 67 | output="log", 68 | arguments=["-d", rviz_empty_config], 69 | parameters=[ 70 | moveit_config.robot_description, 71 | moveit_config.robot_description_semantic, 72 | moveit_config.planning_pipelines, 73 | moveit_config.robot_description_kinematics, 74 | ], 75 | condition=IfCondition(tutorial_mode), 76 | ) 77 | rviz_node = Node( 78 | package="rviz2", 79 | executable="rviz2", 80 | name="rviz2", 81 | output="log", 82 | arguments=["-d", rviz_full_config], 83 | parameters=[ 84 | moveit_config.robot_description, 85 | moveit_config.robot_description_semantic, 86 | moveit_config.planning_pipelines, 87 | moveit_config.robot_description_kinematics, 88 | ], 89 | condition=UnlessCondition(tutorial_mode), 90 | ) 91 | 92 | # Static TF 93 | static_tf_node = Node( 94 | package="tf2_ros", 95 | executable="static_transform_publisher", 96 | name="static_transform_publisher", 97 | output="log", 98 | arguments=["0.0", "0.0", "0.0", "0.0", "0.0", "0.0", "world", "panda_link0"], 99 | ) 100 | 101 | # Publish TF 102 | robot_state_publisher = Node( 103 | package="robot_state_publisher", 104 | executable="robot_state_publisher", 105 | name="robot_state_publisher", 106 | output="both", 107 | parameters=[moveit_config.robot_description], 108 | ) 109 | 110 | # ros2_control using FakeSystem as hardware 111 | ros2_controllers_path = os.path.join( 112 | get_package_share_directory("moveit_resources_panda_moveit_config"), 113 | "config", 114 | "ros2_controllers.yaml", 115 | ) 116 | ros2_control_node = Node( 117 | package="controller_manager", 118 | executable="ros2_control_node", 119 | parameters=[ros2_controllers_path], 120 | remappings=[ 121 | ("/controller_manager/robot_description", "/robot_description"), 122 | ], 123 | output="screen", 124 | ) 125 | 126 | joint_state_broadcaster_spawner = Node( 127 | package="controller_manager", 128 | executable="spawner", 129 | arguments=[ 130 | "joint_state_broadcaster", 131 | "--controller-manager", 132 | "/controller_manager", 133 | ], 134 | ) 135 | 136 | panda_arm_controller_spawner = Node( 137 | package="controller_manager", 138 | executable="spawner", 139 | arguments=["panda_arm_controller", "-c", "/controller_manager"], 140 | ) 141 | 142 | panda_hand_controller_spawner = Node( 143 | package="controller_manager", 144 | executable="spawner", 145 | arguments=["panda_hand_controller", "-c", "/controller_manager"], 146 | ) 147 | 148 | # Warehouse mongodb server 149 | db_config = LaunchConfiguration("db") 150 | mongodb_server_node = Node( 151 | package="warehouse_ros_mongo", 152 | executable="mongo_wrapper_ros.py", 153 | parameters=[ 154 | {"warehouse_port": 33829}, 155 | {"warehouse_host": "localhost"}, 156 | {"warehouse_plugin": "warehouse_ros_mongo::MongoDatabaseConnection"}, 157 | ], 158 | output="screen", 159 | condition=IfCondition(db_config), 160 | ) 161 | 162 | return LaunchDescription( 163 | [ 164 | tutorial_arg, 165 | db_arg, 166 | ros2_control_hardware_type, 167 | rviz_node, 168 | rviz_node_tutorial, 169 | static_tf_node, 170 | robot_state_publisher, 171 | move_group_node, 172 | ros2_control_node, 173 | joint_state_broadcaster_spawner, 174 | panda_arm_controller_spawner, 175 | panda_hand_controller_spawner, 176 | mongodb_server_node, 177 | ] 178 | ) 179 | -------------------------------------------------------------------------------- /panda_resources/panda_moveit_config/launch/moveit_empty.rviz: -------------------------------------------------------------------------------- 1 | Panels: 2 | - Class: rviz_common/Displays 3 | Help Height: 78 4 | Name: Displays 5 | Property Tree Widget: 6 | Expanded: ~ 7 | Splitter Ratio: 0.5 8 | Tree Height: 802 9 | - Class: rviz_common/Selection 10 | Name: Selection 11 | - Class: rviz_common/Tool Properties 12 | Expanded: 13 | - /2D Goal Pose1 14 | - /Publish Point1 15 | Name: Tool Properties 16 | Splitter Ratio: 0.5886790156364441 17 | - Class: rviz_common/Views 18 | Expanded: 19 | - /Current View1 20 | Name: Views 21 | Splitter Ratio: 0.5 22 | Visualization Manager: 23 | Class: "" 24 | Displays: 25 | - Alpha: 0.5 26 | Cell Size: 1 27 | Class: rviz_default_plugins/Grid 28 | Color: 160; 160; 164 29 | Enabled: true 30 | Line Style: 31 | Line Width: 0.029999999329447746 32 | Value: Lines 33 | Name: Grid 34 | Normal Cell Count: 0 35 | Offset: 36 | X: 0 37 | Y: 0 38 | Z: 0 39 | Plane: XY 40 | Plane Cell Count: 10 41 | Reference Frame: 42 | Value: true 43 | - Class: rviz_default_plugins/MarkerArray 44 | Enabled: true 45 | Name: MarkerArray 46 | Namespaces: 47 | {} 48 | Topic: 49 | Depth: 100 50 | Durability Policy: Volatile 51 | History Policy: Keep Last 52 | Reliability Policy: Reliable 53 | Value: /rviz_visual_tools 54 | Value: true 55 | Enabled: true 56 | Global Options: 57 | Background Color: 48; 48; 48 58 | Fixed Frame: panda_link0 59 | Frame Rate: 30 60 | Name: root 61 | Tools: 62 | - Class: rviz_default_plugins/Interact 63 | Hide Inactive Objects: true 64 | - Class: rviz_default_plugins/MoveCamera 65 | - Class: rviz_default_plugins/Select 66 | - Class: rviz_default_plugins/FocusCamera 67 | - Class: rviz_default_plugins/Measure 68 | Line color: 128; 128; 0 69 | - Class: rviz_default_plugins/SetInitialPose 70 | Topic: 71 | Depth: 5 72 | Durability Policy: Volatile 73 | History Policy: Keep Last 74 | Reliability Policy: Reliable 75 | Value: /initialpose 76 | - Class: rviz_default_plugins/SetGoal 77 | Topic: 78 | Depth: 5 79 | Durability Policy: Volatile 80 | History Policy: Keep Last 81 | Reliability Policy: Reliable 82 | Value: /goal_pose 83 | - Class: rviz_default_plugins/PublishPoint 84 | Single click: true 85 | Topic: 86 | Depth: 5 87 | Durability Policy: Volatile 88 | History Policy: Keep Last 89 | Reliability Policy: Reliable 90 | Value: /clicked_point 91 | Transformation: 92 | Current: 93 | Class: rviz_default_plugins/TF 94 | Value: true 95 | Views: 96 | Current: 97 | Class: rviz_default_plugins/Orbit 98 | Distance: 3.119211196899414 99 | Enable Stereo Rendering: 100 | Stereo Eye Separation: 0.05999999865889549 101 | Stereo Focal Distance: 1 102 | Swap Stereo Eyes: false 103 | Value: false 104 | Focal Point: 105 | X: 0.02386285550892353 106 | Y: 0.15478567779064178 107 | Z: 0.039489321410655975 108 | Focal Shape Fixed Size: true 109 | Focal Shape Size: 0.05000000074505806 110 | Invert Z Axis: false 111 | Name: Current View 112 | Near Clip Distance: 0.009999999776482582 113 | Pitch: 0.5953981876373291 114 | Target Frame: 115 | Value: Orbit (rviz) 116 | Yaw: 5.958578109741211 117 | Saved: ~ 118 | Window Geometry: 119 | Displays: 120 | collapsed: false 121 | Height: 1025 122 | Hide Left Dock: false 123 | Hide Right Dock: true 124 | QMainWindow State: 000000ff00000000fd000000040000000000000156000003abfc020000000afb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003b000003ab000000c700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb000000280020002d0020005400720061006a006500630074006f0072007900200053006c00690064006500720000000000ffffffff0000000000000000fb0000003c005400720061006a006500630074006f007200790020002d0020005400720061006a006500630074006f0072007900200053006c00690064006500720000000000ffffffff0000000000000000000000010000010f000003abfc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003b000003ab000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004420000003efc0100000002fb0000000800540069006d00650100000000000004420000000000000000fb0000000800540069006d00650100000000000004500000000000000000000005e1000003ab00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 125 | Selection: 126 | collapsed: false 127 | Tool Properties: 128 | collapsed: false 129 | Views: 130 | collapsed: true 131 | Width: 1853 132 | X: 67 133 | Y: 27 134 | -------------------------------------------------------------------------------- /panda_resources/panda_moveit_config/launch/moveit_rviz.launch.py: -------------------------------------------------------------------------------- 1 | import os 2 | from sys import prefix 3 | import yaml 4 | from launch import LaunchDescription 5 | from launch.actions import DeclareLaunchArgument 6 | from launch.substitutions import LaunchConfiguration 7 | from launch.conditions import IfCondition, UnlessCondition 8 | from launch_ros.actions import Node 9 | from launch.actions import ExecuteProcess 10 | from ament_index_python.packages import get_package_share_directory 11 | 12 | 13 | def load_file(package_name, file_path): 14 | package_path = get_package_share_directory(package_name) 15 | absolute_file_path = os.path.join(package_path, file_path) 16 | 17 | try: 18 | with open(absolute_file_path, "r") as file: 19 | return file.read() 20 | except EnvironmentError: # parent of IOError, OSError *and* WindowsError where available 21 | return None 22 | 23 | 24 | def load_yaml(package_name, file_path): 25 | package_path = get_package_share_directory(package_name) 26 | absolute_file_path = os.path.join(package_path, file_path) 27 | 28 | try: 29 | with open(absolute_file_path, "r") as file: 30 | return yaml.safe_load(file) 31 | except EnvironmentError: # parent of IOError, OSError *and* WindowsError where available 32 | return None 33 | 34 | 35 | def generate_launch_description(): 36 | 37 | # Command-line arguments 38 | tutorial_arg = DeclareLaunchArgument( 39 | "rviz_tutorial", default_value="False", description="Tutorial flag" 40 | ) 41 | 42 | kinematics_yaml = load_yaml( 43 | "moveit_resources_panda_moveit_config", "config/kinematics.yaml" 44 | ) 45 | 46 | # RViz 47 | tutorial_mode = LaunchConfiguration("rviz_tutorial") 48 | rviz_base = os.path.join(get_package_share_directory("moveit2_tutorials"), "launch") 49 | rviz_full_config = os.path.join(rviz_base, "panda_moveit_config_demo.rviz") 50 | rviz_empty_config = os.path.join(rviz_base, "panda_moveit_config_demo_empty.rviz") 51 | rviz_node_tutorial = Node( 52 | package="rviz2", 53 | executable="rviz2", 54 | name="rviz2", 55 | output="log", 56 | arguments=["-d", rviz_empty_config], 57 | parameters=[kinematics_yaml], 58 | condition=IfCondition(tutorial_mode), 59 | ) 60 | rviz_node = Node( 61 | package="rviz2", 62 | executable="rviz2", 63 | name="rviz2", 64 | output="log", 65 | arguments=["-d", rviz_full_config], 66 | parameters=[kinematics_yaml], 67 | condition=UnlessCondition(tutorial_mode), 68 | ) 69 | 70 | return LaunchDescription( 71 | [ 72 | tutorial_arg, 73 | rviz_node, 74 | rviz_node_tutorial, 75 | ] 76 | ) 77 | -------------------------------------------------------------------------------- /panda_resources/panda_moveit_config/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | moveit_resources_panda_moveit_config 4 | 2.0.7 5 | 6 |

7 | MoveIt Resources for testing: Franka Emika Panda 8 |

9 |

10 | A project-internal configuration for testing in MoveIt. 11 |

12 |
13 | Mike Lautman 14 | Mike Lautman 15 | 16 | BSD 17 | 18 | http://moveit.ros.org/ 19 | https://github.com/ros-planning/moveit_resources/issues 20 | https://github.com/ros-planning/moveit_resources 21 | 22 | ament_cmake 23 | 24 | moveit_resources_panda_description 25 | 32 | joint_state_publisher 33 | joint_state_publisher_gui 34 | robot_state_publisher 35 | xacro 36 | 39 | 41 | 42 | 43 | 44 | ament_cmake 45 | 46 |
47 | -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.10.2) 2 | project(panda_mujoco) 3 | find_package(ament_cmake REQUIRED) 4 | 5 | ament_package() 6 | 7 | install(DIRECTORY franka_emika_panda DESTINATION share/${PROJECT_NAME}) 8 | -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/LICENSE: -------------------------------------------------------------------------------- 1 | Apache License 2 | Version 2.0, January 2004 3 | http://www.apache.org/licenses/ 4 | 5 | TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION 6 | 7 | 1. Definitions. 8 | 9 | "License" shall mean the terms and conditions for use, reproduction, 10 | and distribution as defined by Sections 1 through 9 of this document. 11 | 12 | "Licensor" shall mean the copyright owner or entity authorized by 13 | the copyright owner that is granting the License. 14 | 15 | "Legal Entity" shall mean the union of the acting entity and all 16 | other entities that control, are controlled by, or are under common 17 | control with that entity. For the purposes of this definition, 18 | "control" means (i) the power, direct or indirect, to cause the 19 | direction or management of such entity, whether by contract or 20 | otherwise, or (ii) ownership of fifty percent (50%) or more of the 21 | outstanding shares, or (iii) beneficial ownership of such entity. 22 | 23 | "You" (or "Your") shall mean an individual or Legal Entity 24 | exercising permissions granted by this License. 25 | 26 | "Source" form shall mean the preferred form for making modifications, 27 | including but not limited to software source code, documentation 28 | source, and configuration files. 29 | 30 | "Object" form shall mean any form resulting from mechanical 31 | transformation or translation of a Source form, including but 32 | not limited to compiled object code, generated documentation, 33 | and conversions to other media types. 34 | 35 | "Work" shall mean the work of authorship, whether in Source or 36 | Object form, made available under the License, as indicated by a 37 | copyright notice that is included in or attached to the work 38 | (an example is provided in the Appendix below). 39 | 40 | "Derivative Works" shall mean any work, whether in Source or Object 41 | form, that is based on (or derived from) the Work and for which the 42 | editorial revisions, annotations, elaborations, or other modifications 43 | represent, as a whole, an original work of authorship. For the purposes 44 | of this License, Derivative Works shall not include works that remain 45 | separable from, or merely link (or bind by name) to the interfaces of, 46 | the Work and Derivative Works thereof. 47 | 48 | "Contribution" shall mean any work of authorship, including 49 | the original version of the Work and any modifications or additions 50 | to that Work or Derivative Works thereof, that is intentionally 51 | submitted to Licensor for inclusion in the Work by the copyright owner 52 | or by an individual or Legal Entity authorized to submit on behalf of 53 | the copyright owner. For the purposes of this definition, "submitted" 54 | means any form of electronic, verbal, or written communication sent 55 | to the Licensor or its representatives, including but not limited to 56 | communication on electronic mailing lists, source code control systems, 57 | and issue tracking systems that are managed by, or on behalf of, the 58 | Licensor for the purpose of discussing and improving the Work, but 59 | excluding communication that is conspicuously marked or otherwise 60 | designated in writing by the copyright owner as "Not a Contribution." 61 | 62 | "Contributor" shall mean Licensor and any individual or Legal Entity 63 | on behalf of whom a Contribution has been received by Licensor and 64 | subsequently incorporated within the Work. 65 | 66 | 2. Grant of Copyright License. Subject to the terms and conditions of 67 | this License, each Contributor hereby grants to You a perpetual, 68 | worldwide, non-exclusive, no-charge, royalty-free, irrevocable 69 | copyright license to reproduce, prepare Derivative Works of, 70 | publicly display, publicly perform, sublicense, and distribute the 71 | Work and such Derivative Works in Source or Object form. 72 | 73 | 3. Grant of Patent License. Subject to the terms and conditions of 74 | this License, each Contributor hereby grants to You a perpetual, 75 | worldwide, non-exclusive, no-charge, royalty-free, irrevocable 76 | (except as stated in this section) patent license to make, have made, 77 | use, offer to sell, sell, import, and otherwise transfer the Work, 78 | where such license applies only to those patent claims licensable 79 | by such Contributor that are necessarily infringed by their 80 | Contribution(s) alone or by combination of their Contribution(s) 81 | with the Work to which such Contribution(s) was submitted. If You 82 | institute patent litigation against any entity (including a 83 | cross-claim or counterclaim in a lawsuit) alleging that the Work 84 | or a Contribution incorporated within the Work constitutes direct 85 | or contributory patent infringement, then any patent licenses 86 | granted to You under this License for that Work shall terminate 87 | as of the date such litigation is filed. 88 | 89 | 4. Redistribution. You may reproduce and distribute copies of the 90 | Work or Derivative Works thereof in any medium, with or without 91 | modifications, and in Source or Object form, provided that You 92 | meet the following conditions: 93 | 94 | (a) You must give any other recipients of the Work or 95 | Derivative Works a copy of this License; and 96 | 97 | (b) You must cause any modified files to carry prominent notices 98 | stating that You changed the files; and 99 | 100 | (c) You must retain, in the Source form of any Derivative Works 101 | that You distribute, all copyright, patent, trademark, and 102 | attribution notices from the Source form of the Work, 103 | excluding those notices that do not pertain to any part of 104 | the Derivative Works; and 105 | 106 | (d) If the Work includes a "NOTICE" text file as part of its 107 | distribution, then any Derivative Works that You distribute must 108 | include a readable copy of the attribution notices contained 109 | within such NOTICE file, excluding those notices that do not 110 | pertain to any part of the Derivative Works, in at least one 111 | of the following places: within a NOTICE text file distributed 112 | as part of the Derivative Works; within the Source form or 113 | documentation, if provided along with the Derivative Works; or, 114 | within a display generated by the Derivative Works, if and 115 | wherever such third-party notices normally appear. The contents 116 | of the NOTICE file are for informational purposes only and 117 | do not modify the License. You may add Your own attribution 118 | notices within Derivative Works that You distribute, alongside 119 | or as an addendum to the NOTICE text from the Work, provided 120 | that such additional attribution notices cannot be construed 121 | as modifying the License. 122 | 123 | You may add Your own copyright statement to Your modifications and 124 | may provide additional or different license terms and conditions 125 | for use, reproduction, or distribution of Your modifications, or 126 | for any such Derivative Works as a whole, provided Your use, 127 | reproduction, and distribution of the Work otherwise complies with 128 | the conditions stated in this License. 129 | 130 | 5. Submission of Contributions. Unless You explicitly state otherwise, 131 | any Contribution intentionally submitted for inclusion in the Work 132 | by You to the Licensor shall be under the terms and conditions of 133 | this License, without any additional terms or conditions. 134 | Notwithstanding the above, nothing herein shall supersede or modify 135 | the terms of any separate license agreement you may have executed 136 | with Licensor regarding such Contributions. 137 | 138 | 6. Trademarks. This License does not grant permission to use the trade 139 | names, trademarks, service marks, or product names of the Licensor, 140 | except as required for reasonable and customary use in describing the 141 | origin of the Work and reproducing the content of the NOTICE file. 142 | 143 | 7. Disclaimer of Warranty. Unless required by applicable law or 144 | agreed to in writing, Licensor provides the Work (and each 145 | Contributor provides its Contributions) on an "AS IS" BASIS, 146 | WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or 147 | implied, including, without limitation, any warranties or conditions 148 | of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A 149 | PARTICULAR PURPOSE. You are solely responsible for determining the 150 | appropriateness of using or redistributing the Work and assume any 151 | risks associated with Your exercise of permissions under this License. 152 | 153 | 8. Limitation of Liability. In no event and under no legal theory, 154 | whether in tort (including negligence), contract, or otherwise, 155 | unless required by applicable law (such as deliberate and grossly 156 | negligent acts) or agreed to in writing, shall any Contributor be 157 | liable to You for damages, including any direct, indirect, special, 158 | incidental, or consequential damages of any character arising as a 159 | result of this License or out of the use or inability to use the 160 | Work (including but not limited to damages for loss of goodwill, 161 | work stoppage, computer failure or malfunction, or any and all 162 | other commercial damages or losses), even if such Contributor 163 | has been advised of the possibility of such damages. 164 | 165 | 9. Accepting Warranty or Additional Liability. While redistributing 166 | the Work or Derivative Works thereof, You may choose to offer, 167 | and charge a fee for, acceptance of support, warranty, indemnity, 168 | or other liability obligations and/or rights consistent with this 169 | License. However, in accepting such obligations, You may act only 170 | on Your own behalf and on Your sole responsibility, not on behalf 171 | of any other Contributor, and only if You agree to indemnify, 172 | defend, and hold each Contributor harmless for any liability 173 | incurred by, or claims asserted against, such Contributor by reason 174 | of your accepting any such warranty or additional liability. 175 | 176 | END OF TERMS AND CONDITIONS 177 | -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/README.md: -------------------------------------------------------------------------------- 1 | # Franka Emika Panda Description (MJCF) 2 | 3 | Requires MuJoCo 2.3.3 or later. 4 | 5 | ## Overview 6 | 7 | This package contains a simplified robot description (MJCF) of the [Franka Emika 8 | Panda](https://www.franka.de/) developed by [Franka 9 | Emika](https://www.franka.de/company). It is derived from the [publicly 10 | available URDF 11 | description](https://github.com/frankaemika/franka_ros/tree/develop/franka_description). 12 | 13 |

14 | 15 |

16 | 17 | ## URDF → MJCF derivation steps 18 | 19 | 1. Converted the DAE [mesh 20 | files](https://github.com/frankaemika/franka_ros/tree/develop/franka_description/meshes/visual) 21 | to OBJ format using [Blender](https://www.blender.org/). 22 | 2. Processed `.obj` files with [`obj2mjcf`](https://github.com/kevinzakka/obj2mjcf). 23 | 3. Eliminated the perfectly flat `link0_6` from the resulting submeshes created for `link0`. 24 | 4. Created a convex decomposition of the STL collision [mesh 25 | file](https://github.com/frankaemika/franka_ros/tree/develop/franka_description/meshes/collision) 26 | for `link5` using [V-HACD](https://github.com/kmammou/v-hacd). 27 | 5. Added ` ` to the 28 | [URDF](https://github.com/frankaemika/franka_ros/tree/develop/franka_description/robots)'s 29 | `` clause in order to preserve visual geometries. 30 | 6. Loaded the URDF into MuJoCo and saved a corresponding MJCF. 31 | 7. Matched inertial parameters with [inertial.yaml]( 32 | https://github.com/frankaemika/franka_ros/blob/develop/franka_description/robots/common/inertial.yaml). 33 | 8. Added a tracking light to the base. 34 | 9. Manually edited the MJCF to extract common properties into the `` section. 35 | 10. Added `` clauses to prevent collisions between `link7` and `link8`. 36 | 11. Manually designed collision geoms for the fingertips. 37 | 12. Added position-controlled actuators for the arm. 38 | 13. Added an equality constraint so that the left finger mimics the position of the right finger. 39 | 14. Added a tendon to split the force equally between both fingers and a 40 | position actuator acting on this tendon. 41 | 15. Added `scene.xml` which includes the robot, with a textured groundplane, skybox, and haze. 42 | 43 | ## License 44 | 45 | This model is released under an [Apache-2.0 License](LICENSE). 46 | -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/bevel_peg.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/bevel_peg.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_0.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_0.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_1.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_1.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_10.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_10.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_11.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_11.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_12.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_12.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_13.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_13.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_14.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_14.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_15.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_15.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_16.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_16.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_17.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_17.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_18.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_18.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_19.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_19.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_2.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_2.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_20.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_20.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_21.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_21.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_22.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_22.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_23.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_23.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_24.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_24.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_25.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_25.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_26.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_26.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_27.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_27.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_28.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_28.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_29.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_29.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_3.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_3.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_30.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_30.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_31.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_31.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_32.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_32.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_33.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_33.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_34.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_34.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_35.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_35.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_36.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_36.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_37.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_37.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_38.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_38.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_39.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_39.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_4.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_4.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_40.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_40.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_41.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_41.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_42.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_42.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_43.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_43.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_44.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_44.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_45.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_45.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_46.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_46.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_47.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_47.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_48.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_48.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_49.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_49.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_5.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_5.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_50.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_50.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_51.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_51.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_52.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_52.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_53.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_53.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_54.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_54.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_55.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_55.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_56.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_56.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_57.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_57.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_58.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_58.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_59.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_59.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_6.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_6.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_60.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_60.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_61.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_61.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_62.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_62.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_63.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_63.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_64.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_64.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_65.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_65.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_66.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_66.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_67.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_67.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_68.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_68.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_69.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_69.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_7.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_7.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_70.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_70.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_71.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_71.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_72.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_72.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_73.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_73.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_74.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_74.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_75.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_75.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_76.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_76.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_77.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_77.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_78.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_78.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_79.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_79.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_8.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_8.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_9.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/geometry_9.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/hand.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/hand.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/hand_0.obj: -------------------------------------------------------------------------------- 1 | mtllib material_0.mtl 2 | usemtl material_0 3 | v 0.01525500 -0.06846300 0.02643800 4 | v 0.01525500 -0.06846300 0.02643800 5 | v 0.01525500 -0.06846300 0.02643800 6 | v 0.01525500 -0.06962700 0.02613600 7 | v 0.01525600 0.06845600 0.02644100 8 | v 0.01525600 0.06845600 0.02644100 9 | v 0.01525600 0.06845600 0.02644100 10 | v 0.01525600 0.06845600 0.02644100 11 | v 0.01525400 0.06938500 0.01339000 12 | v 0.01525400 0.06938500 0.01339000 13 | v 0.01525400 0.06938500 0.01339000 14 | v 0.01525400 0.07093400 0.01820800 15 | v 0.01525400 0.07093400 0.01820800 16 | v 0.01525500 0.07196200 0.02213600 17 | v 0.01525500 0.07196200 0.02213600 18 | v 0.01525500 0.07196200 0.02213600 19 | v 0.01525500 0.07189200 0.02323400 20 | v 0.01525500 0.07189200 0.02323400 21 | v 0.01525500 0.07189200 0.02323400 22 | v 0.01525500 0.07155200 0.02429100 23 | v 0.01525500 0.07087700 0.02522400 24 | v 0.01525500 0.07087700 0.02522400 25 | v 0.01525500 0.07016000 0.02582700 26 | v 0.01525500 -0.07078900 0.02532300 27 | v 0.01525500 -0.07078900 0.02532300 28 | v 0.01525500 -0.07078900 0.02532300 29 | v 0.01525500 -0.07078900 0.02532300 30 | v 0.01525500 -0.07159000 0.02423400 31 | v 0.01525500 0.06931900 0.02623500 32 | v 0.01525500 0.06931900 0.02623500 33 | v 0.01525500 0.06931900 0.02623500 34 | v 0.01525500 -0.06638600 0.01107000 35 | v 0.01525500 -0.06638600 0.01107000 36 | v 0.01525500 -0.06638600 0.01107000 37 | v 0.01525500 -0.06638600 0.01107000 38 | v 0.01525500 0.06630700 0.01106100 39 | v 0.01525500 0.06630700 0.01106100 40 | v 0.01525500 0.06630700 0.01106100 41 | v 0.01525500 -0.07197300 0.02268900 42 | v 0.01525500 -0.07197300 0.02268900 43 | v 0.01525500 -0.07185600 0.02158600 44 | v 0.01525500 -0.07185600 0.02158600 45 | v 0.01525500 -0.07185600 0.02158600 46 | v 0.01525400 0.06754800 0.01146300 47 | v 0.01525400 0.06754800 0.01146300 48 | v 0.01525500 0.06862300 0.01224500 49 | v 0.01525500 -0.06930700 0.01320600 50 | v 0.01525500 -0.06930700 0.01320600 51 | v 0.01525500 -0.06930700 0.01320600 52 | v 0.01525500 -0.06847200 0.01210900 53 | v 0.01525500 -0.06758700 0.01148800 54 | v 0.01525500 -0.06758700 0.01148800 55 | v 0.01525500 -0.07075300 0.01761800 56 | v 0.01525500 -0.07075300 0.01761800 57 | v 0.01525500 -0.07075300 0.01761800 58 | v -0.01525500 -0.06846300 0.02643800 59 | v -0.01525500 -0.06846300 0.02643800 60 | v -0.01525500 -0.06846300 0.02643800 61 | v -0.01525500 -0.06962700 0.02613600 62 | v -0.01525600 0.06845600 0.02644100 63 | v -0.01525600 0.06845600 0.02644100 64 | v -0.01525600 0.06845600 0.02644100 65 | v -0.01525600 0.06845600 0.02644100 66 | v -0.01525600 0.06845600 0.02644100 67 | v -0.01525400 0.06938500 0.01339000 68 | v -0.01525400 0.06938500 0.01339000 69 | v -0.01525400 0.06938500 0.01339000 70 | v -0.01525400 0.07093400 0.01820800 71 | v -0.01525400 0.07093400 0.01820800 72 | v -0.01525500 0.07196200 0.02213600 73 | v -0.01525500 0.07196200 0.02213600 74 | v -0.01525500 0.07189200 0.02323400 75 | v -0.01525500 0.07189200 0.02323400 76 | v -0.01525500 0.07189200 0.02323400 77 | v -0.01525500 0.07189200 0.02323400 78 | v -0.01525500 0.07155200 0.02429100 79 | v -0.01525500 0.07087700 0.02522400 80 | v -0.01525500 0.07087700 0.02522400 81 | v -0.01525500 0.07016000 0.02582700 82 | v -0.01525500 -0.07078900 0.02532300 83 | v -0.01525500 -0.07078900 0.02532300 84 | v -0.01525500 -0.07078900 0.02532300 85 | v -0.01525500 -0.07078900 0.02532300 86 | v -0.01525500 -0.07159000 0.02423400 87 | v -0.01525500 0.06931900 0.02623500 88 | v -0.01525500 0.06931900 0.02623500 89 | v -0.01525500 -0.06638600 0.01107000 90 | v -0.01525500 -0.06638600 0.01107000 91 | v -0.01525500 -0.06638600 0.01107000 92 | v -0.01525500 -0.06638600 0.01107000 93 | v -0.01525500 0.06630700 0.01106100 94 | v -0.01525500 0.06630700 0.01106100 95 | v -0.01525500 0.06630700 0.01106100 96 | v -0.01525500 -0.07197300 0.02268900 97 | v -0.01525500 -0.07197300 0.02268900 98 | v -0.01525500 -0.07185600 0.02158600 99 | v -0.01525500 -0.07185600 0.02158600 100 | v -0.01525500 -0.07185600 0.02158600 101 | v -0.01525400 0.06754800 0.01146300 102 | v -0.01525400 0.06754800 0.01146300 103 | v -0.01525500 0.06862300 0.01224500 104 | v -0.01525500 -0.06930700 0.01320600 105 | v -0.01525500 -0.06930700 0.01320600 106 | v -0.01525500 -0.06930700 0.01320600 107 | v -0.01525500 -0.06847200 0.01210900 108 | v -0.01525500 -0.06758700 0.01148800 109 | v -0.01525500 -0.06758700 0.01148800 110 | v -0.01525500 -0.07075300 0.01761800 111 | v -0.01525500 -0.07075300 0.01761800 112 | v -0.01525500 -0.07075300 0.01761800 113 | vn 1.00000000 -0.00000000 -0.00000000 114 | vn 1.00000000 0.00010000 0.00000000 115 | vn 1.00000000 -0.00010000 0.00010000 116 | vn 1.00000000 -0.00000000 -0.00000000 117 | vn 1.00000000 0.00020000 0.00010000 118 | vn 1.00000000 -0.00020000 -0.00020000 119 | vn 1.00000000 0.00030000 -0.00010000 120 | vn 1.00000000 -0.00000000 -0.00000000 121 | vn 1.00000000 0.00070000 -0.00060000 122 | vn 1.00000000 -0.00200000 0.00190000 123 | vn 1.00000000 0.00030000 -0.00010000 124 | vn 1.00000000 -0.00020000 -0.00020000 125 | vn 1.00000000 0.00030000 -0.00010000 126 | vn 1.00000000 0.00020000 0.00010000 127 | vn 1.00000000 -0.00000000 -0.00010000 128 | vn 1.00000000 -0.00020000 -0.00020000 129 | vn 1.00000000 -0.00000000 -0.00000000 130 | vn 1.00000000 0.00020000 0.00010000 131 | vn 1.00000000 -0.00000000 -0.00010000 132 | vn 1.00000000 0.00020000 0.00010000 133 | vn 1.00000000 -0.00000000 -0.00000000 134 | vn 1.00000000 0.00020000 0.00010000 135 | vn 1.00000000 -0.00000000 -0.00000000 136 | vn 1.00000000 -0.00010000 0.00010000 137 | vn 1.00000000 0.00010000 0.00000000 138 | vn 1.00000000 -0.00040000 0.00030000 139 | vn 1.00000000 -0.00000000 -0.00000000 140 | vn 1.00000000 -0.00040000 0.00030000 141 | vn 1.00000000 0.00020000 0.00010000 142 | vn 1.00000000 -0.00000000 -0.00010000 143 | vn 1.00000000 -0.00000000 -0.00000000 144 | vn 1.00000000 0.00070000 0.00060000 145 | vn 1.00000000 -0.00000000 -0.00000000 146 | vn 1.00000000 0.00010000 0.00000000 147 | vn 1.00000000 0.00040000 0.00020000 148 | vn 1.00000000 0.00070000 -0.00060000 149 | vn 1.00000000 -0.00000000 -0.00000000 150 | vn 1.00000000 0.00030000 -0.00010000 151 | vn 1.00000000 -0.00040000 0.00030000 152 | vn 1.00000000 0.00010000 0.00000000 153 | vn 1.00000000 -0.00010000 0.00010000 154 | vn 1.00000000 -0.00000000 -0.00000000 155 | vn 1.00000000 0.00010000 0.00000000 156 | vn 1.00000000 0.00070000 -0.00060000 157 | vn 1.00000000 -0.00200000 0.00190000 158 | vn 1.00000000 -0.00200000 0.00190000 159 | vn 1.00000000 0.00040000 0.00020000 160 | vn 1.00000000 0.00070000 0.00060000 161 | vn 1.00000000 -0.00060000 -0.00070000 162 | vn 1.00000000 -0.00060000 -0.00070000 163 | vn 1.00000000 -0.00060000 -0.00070000 164 | vn 1.00000000 0.00070000 0.00060000 165 | vn 1.00000000 -0.00000000 -0.00000000 166 | vn 1.00000000 0.00010000 0.00000000 167 | vn 1.00000000 0.00040000 0.00020000 168 | vn -1.00000000 0.00010000 0.00000000 169 | vn -1.00000000 -0.00010000 0.00010000 170 | vn -1.00000000 -0.00000000 -0.00000000 171 | vn -1.00000000 -0.00000000 -0.00000000 172 | vn -1.00000000 -0.00000000 -0.00000000 173 | vn -1.00000000 0.00030000 0.00020000 174 | vn -1.00000000 -0.00020000 -0.00020000 175 | vn -1.00000000 0.00000000 -0.00010000 176 | vn -1.00000000 0.00030000 -0.00010000 177 | vn -1.00000000 -0.00200000 0.00190000 178 | vn -1.00000000 0.00070000 -0.00060000 179 | vn -1.00000000 0.00030000 -0.00010000 180 | vn -1.00000000 0.00030000 -0.00010000 181 | vn -1.00000000 -0.00020000 -0.00020000 182 | vn -1.00000000 -0.00020000 -0.00020000 183 | vn -1.00000000 0.00000000 -0.00010000 184 | vn -1.00000000 0.00030000 0.00020000 185 | vn -1.00000000 -0.00000000 -0.00000000 186 | vn -1.00000000 0.00020000 0.00010000 187 | vn -1.00000000 0.00000000 -0.00010000 188 | vn -1.00000000 0.00020000 0.00010000 189 | vn -1.00000000 0.00020000 0.00010000 190 | vn -1.00000000 -0.00000000 -0.00000000 191 | vn -1.00000000 -0.00000000 -0.00000000 192 | vn -1.00000000 -0.00010000 0.00010000 193 | vn -1.00000000 -0.00040000 0.00030000 194 | vn -1.00000000 0.00010000 0.00000000 195 | vn -1.00000000 -0.00000000 -0.00000000 196 | vn -1.00000000 -0.00040000 0.00030000 197 | vn -1.00000000 -0.00000000 -0.00000000 198 | vn -1.00000000 0.00030000 0.00020000 199 | vn -1.00000000 0.00070000 0.00060000 200 | vn -1.00000000 0.00010000 0.00000000 201 | vn -1.00000000 0.00040000 0.00020000 202 | vn -1.00000000 -0.00000000 -0.00000000 203 | vn -1.00000000 0.00030000 -0.00010000 204 | vn -1.00000000 -0.00000000 -0.00000000 205 | vn -1.00000000 0.00070000 -0.00060000 206 | vn -1.00000000 0.00010000 0.00000000 207 | vn -1.00000000 -0.00040000 0.00030000 208 | vn -1.00000000 0.00010000 0.00000000 209 | vn -1.00000000 -0.00000000 -0.00000000 210 | vn -1.00000000 -0.00010000 0.00010000 211 | vn -1.00000000 -0.00200000 0.00190000 212 | vn -1.00000000 0.00070000 -0.00060000 213 | vn -1.00000000 -0.00200000 0.00190000 214 | vn -1.00000000 -0.00060000 -0.00070000 215 | vn -1.00000000 0.00070000 0.00060000 216 | vn -1.00000000 0.00040000 0.00020000 217 | vn -1.00000000 -0.00060000 -0.00070000 218 | vn -1.00000000 -0.00060000 -0.00070000 219 | vn -1.00000000 0.00070000 0.00060000 220 | vn -1.00000000 0.00040000 0.00020000 221 | vn -1.00000000 -0.00000000 -0.00000000 222 | vn -1.00000000 0.00010000 0.00000000 223 | f 37//37 8//8 1//1 224 | f 60//60 92//92 58//58 225 | f 29//29 5//5 14//14 226 | f 1//1 4//4 27//27 227 | f 26//26 28//28 39//39 228 | f 40//40 43//43 25//25 229 | f 55//55 47//47 35//35 230 | f 50//50 51//51 49//49 231 | f 33//33 37//37 1//1 232 | f 45//45 46//46 10//10 233 | f 9//9 36//36 44//44 234 | f 15//15 19//19 30//30 235 | f 20//20 22//22 18//18 236 | f 23//23 31//31 21//21 237 | f 3//3 24//24 41//41 238 | f 42//42 53//53 1//1 239 | f 52//52 32//32 48//48 240 | f 11//11 13//13 38//38 241 | f 17//17 21//21 31//31 242 | f 7//7 38//38 13//13 243 | f 54//54 34//34 2//2 244 | f 12//12 16//16 6//6 245 | f 106//106 105//105 102//102 246 | f 104//104 108//108 89//89 247 | f 96//96 94//94 82//82 248 | f 84//84 81//81 95//95 249 | f 59//59 58//58 83//83 250 | f 61//61 86//86 72//72 251 | f 79//79 78//78 85//85 252 | f 76//76 74//74 77//77 253 | f 71//71 63//63 75//75 254 | f 65//65 101//101 99//99 255 | f 100//100 93//93 66//66 256 | f 87//87 107//107 103//103 257 | f 109//109 97//97 58//58 258 | f 80//80 57//57 98//98 259 | f 85//85 78//78 73//73 260 | f 70//70 69//69 62//62 261 | f 67//67 91//91 68//68 262 | f 88//88 110//110 56//56 263 | f 58//58 92//92 90//90 264 | f 68//68 91//91 64//64 265 | -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/link0.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/link0.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/link1.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/link1.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/link2.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/link2.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/link3.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/link3.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/link4.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/link4.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/link5_collision_0.obj: -------------------------------------------------------------------------------- 1 | v 0.029063642 0.095448048 -0.133538792 2 | v 0.049877137 -0.013343874 -0.215408068 3 | v 0.046604998 0.029219000 -0.259000003 4 | v -0.043494001 0.033698998 -0.259000003 5 | v -0.030187000 -0.020500001 -0.186547995 6 | v -0.017736474 -0.052050648 -0.258999242 7 | v 0.012548444 0.082957777 -0.202027869 8 | v 0.050364564 0.017247290 -0.214926371 9 | v 0.020709741 -0.020753554 -0.182012846 10 | v -0.038214683 0.050463360 -0.167851336 11 | v 0.045944492 -0.030214707 -0.258999161 12 | v -0.051997126 -0.017851673 -0.259000003 13 | v 0.026338819 0.085091480 -0.183646959 14 | v 0.020922000 0.050882000 -0.259000003 15 | v 0.045491802 0.013339541 -0.187636452 16 | v 0.050951000 0.020726001 -0.259000003 17 | v 0.023551804 0.063747043 -0.133252288 18 | v -0.013548823 -0.047308172 -0.207602441 19 | v -0.023108632 0.089348183 -0.175470195 20 | v 0.028642003 -0.042568484 -0.211525585 21 | v -0.051912808 0.016682228 -0.233346078 22 | v 0.021637405 0.093787480 -0.156753967 23 | v 0.028892799 0.093108394 -0.147202451 24 | v -0.021765672 0.050517374 -0.259000003 25 | v 0.029191773 0.046614188 -0.259000003 26 | v 0.020095230 0.083558674 -0.197022477 27 | v 0.050294057 0.012853477 -0.210481151 28 | v 0.041400984 -0.012110881 -0.190499104 29 | v 0.050274495 0.021321905 -0.223857806 30 | v 0.050395896 -0.021963709 -0.259000003 31 | v -0.014053484 -0.016454442 -0.177588961 32 | v -0.023077204 0.053522191 -0.146035077 33 | v 0.028830698 0.067305577 -0.135375573 34 | v -0.038313158 -0.038208997 -0.224413296 35 | v 0.045422879 -0.030121078 -0.229083894 36 | v 0.011903144 -0.042590730 -0.199122301 37 | v 0.012319026 -0.051745998 -0.224350901 38 | v -0.052457958 0.016511494 -0.258999590 39 | v -0.046985660 -0.009035359 -0.196875560 40 | v 0.022625311 0.097598446 -0.133939149 41 | v 0.012620136 0.087869933 -0.188952639 42 | v 0.025225283 0.087563533 -0.179602397 43 | v -0.009634502 0.083175007 -0.202322834 44 | v -0.024273001 0.085358001 -0.188354000 45 | v 0.022706000 0.084515996 -0.192412004 46 | v 0.031834746 0.074158814 -0.139114503 47 | v 0.050391338 -0.004898283 -0.210560332 48 | v 0.036850054 -0.028951537 -0.199617216 49 | v 0.028814057 -0.007357717 -0.177964311 50 | v 0.007988000 -0.025363000 -0.182107002 51 | v -0.017462573 -0.033546585 -0.190912689 52 | v -0.022334082 -0.002848132 -0.172981292 53 | v -0.030079996 0.053249859 -0.151432391 54 | v 0.045789921 -0.008346553 -0.194042762 55 | v 0.037322809 -0.011895567 -0.186316195 56 | v -0.034569787 -0.042770809 -0.259000003 57 | v -0.026268487 -0.046990059 -0.224191914 58 | v 0.033556075 -0.043548766 -0.258998990 59 | v 0.049874237 -0.022123435 -0.233471659 60 | v -0.005066666 -0.052041921 -0.219576018 61 | v 0.016204123 -0.046663484 -0.207808223 62 | v -0.051942493 -0.005029111 -0.219727096 63 | v -0.029441908 0.082404274 -0.175896559 64 | v -0.042174398 -0.025291337 -0.202643498 65 | f 12 4 3 66 | f 14 3 4 67 | f 16 12 3 68 | f 23 3 13 69 | f 23 16 3 70 | f 23 1 16 71 | f 24 14 4 72 | f 25 13 3 73 | f 25 3 14 74 | f 26 14 7 75 | f 26 25 14 76 | f 27 8 1 77 | f 29 16 1 78 | f 29 1 8 79 | f 29 8 16 80 | f 30 12 16 81 | f 32 31 17 82 | f 33 1 17 83 | f 38 4 12 84 | f 40 22 19 85 | f 40 23 22 86 | f 40 1 23 87 | f 40 32 17 88 | f 40 17 1 89 | f 41 19 22 90 | f 41 26 7 91 | f 42 23 13 92 | f 42 22 23 93 | f 42 41 22 94 | f 43 7 14 95 | f 43 14 24 96 | f 43 41 7 97 | f 43 19 41 98 | f 44 24 4 99 | f 44 43 24 100 | f 44 19 43 101 | f 45 13 25 102 | f 45 25 26 103 | f 45 42 13 104 | f 45 26 41 105 | f 45 41 42 106 | f 46 27 1 107 | f 46 15 27 108 | f 46 1 33 109 | f 47 27 15 110 | f 47 30 16 111 | f 47 16 8 112 | f 47 8 27 113 | f 48 20 35 114 | f 48 35 2 115 | f 48 36 20 116 | f 48 9 36 117 | f 49 17 9 118 | f 50 9 17 119 | f 50 17 31 120 | f 50 36 9 121 | f 51 31 5 122 | f 51 50 31 123 | f 51 18 36 124 | f 51 36 50 125 | f 52 32 5 126 | f 52 5 31 127 | f 52 31 32 128 | f 53 10 39 129 | f 53 39 5 130 | f 53 5 32 131 | f 53 32 40 132 | f 54 33 28 133 | f 54 46 33 134 | f 54 15 46 135 | f 54 47 15 136 | f 54 2 47 137 | f 54 48 2 138 | f 54 28 48 139 | f 55 33 17 140 | f 55 28 33 141 | f 55 17 49 142 | f 55 48 28 143 | f 55 49 9 144 | f 55 9 48 145 | f 56 34 12 146 | f 56 30 6 147 | f 56 12 30 148 | f 57 56 6 149 | f 57 34 56 150 | f 58 35 20 151 | f 58 11 35 152 | f 58 20 37 153 | f 58 37 6 154 | f 58 30 11 155 | f 58 6 30 156 | f 59 2 35 157 | f 59 47 2 158 | f 59 30 47 159 | f 59 35 11 160 | f 59 11 30 161 | f 60 6 37 162 | f 60 57 6 163 | f 60 18 57 164 | f 61 37 20 165 | f 61 20 36 166 | f 61 60 37 167 | f 61 36 18 168 | f 61 18 60 169 | f 62 38 12 170 | f 62 21 38 171 | f 62 39 10 172 | f 62 10 21 173 | f 63 38 21 174 | f 63 21 10 175 | f 63 19 44 176 | f 63 44 4 177 | f 63 4 38 178 | f 63 10 53 179 | f 63 53 40 180 | f 63 40 19 181 | f 64 5 39 182 | f 64 51 5 183 | f 64 18 51 184 | f 64 57 18 185 | f 64 34 57 186 | f 64 12 34 187 | f 64 62 12 188 | f 64 39 62 189 | -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/link5_collision_1.obj: -------------------------------------------------------------------------------- 1 | v 0.029605924 0.107695894 -0.057770639 2 | v 0.028114332 0.082823920 -0.058553905 3 | v 0.038816102 0.053402838 -0.175505396 4 | v -0.026856016 0.088084521 -0.175136227 5 | v -0.030626847 0.107119812 -0.057687294 6 | v 0.025670733 0.088513946 -0.175229901 7 | v -0.004989269 0.102164150 -0.123603135 8 | v -0.038214683 0.050463360 -0.167851336 9 | v 0.029153411 0.097073936 -0.123627471 10 | v -0.039514421 0.050433927 -0.176900026 11 | v -0.009555079 0.106683172 -0.095345165 12 | v -0.018650687 0.092581494 -0.165880068 13 | v 0.028410194 0.050382871 -0.151882879 14 | v -0.025116868 0.079917612 -0.059207257 15 | v 0.027728461 0.088850155 -0.170468824 16 | v 0.012301352 0.106583136 -0.090584029 17 | v -0.033031356 0.072019963 -0.176122603 18 | v -0.028518812 0.083365915 -0.058497467 19 | v 0.017236843 0.092763911 -0.165977938 20 | v -0.013955552 0.101873439 -0.118898329 21 | v -0.028958102 0.093907525 -0.142630397 22 | v 0.017254189 0.075705868 -0.064336333 23 | v -0.014409871 0.075430847 -0.064290830 24 | v 0.028214046 0.087293870 -0.171111784 25 | v 0.025659250 0.106544369 -0.076459959 26 | v 0.003562050 0.106723586 -0.095327997 27 | v -0.038642138 0.054804181 -0.176806387 28 | v 0.024373464 0.079432104 -0.059087522 29 | v 0.021627842 0.092908946 -0.161300197 30 | v -0.022714762 0.106727072 -0.081193925 31 | v -0.026651997 0.092292062 -0.156493182 32 | v -0.028411485 0.090537503 -0.161463618 33 | v -0.033238728 0.052765384 -0.155973185 34 | v 0.028928091 0.106502887 -0.067219353 35 | v 0.003488032 0.101747359 -0.123570031 36 | v 0.025518961 0.096898989 -0.133035213 37 | v 0.021620985 0.097180492 -0.137775852 38 | v -0.029182131 0.097825064 -0.119030284 39 | v -0.022783418 0.101743257 -0.109443270 40 | v -0.027976784 0.086163124 -0.175228428 41 | v -0.029871457 0.106777512 -0.062281333 42 | f 1 2 3 43 | f 5 2 1 44 | f 9 1 3 45 | f 10 6 3 46 | f 11 5 1 47 | f 12 6 4 48 | f 13 3 2 49 | f 13 10 3 50 | f 13 8 10 51 | f 17 4 6 52 | f 18 10 8 53 | f 18 5 10 54 | f 18 8 14 55 | f 18 2 5 56 | f 19 12 7 57 | f 19 6 12 58 | f 20 11 7 59 | f 20 7 12 60 | f 23 14 8 61 | f 23 13 22 62 | f 24 15 9 63 | f 24 9 3 64 | f 24 3 6 65 | f 24 6 15 66 | f 25 16 1 67 | f 26 11 1 68 | f 26 1 16 69 | f 26 7 11 70 | f 26 16 19 71 | f 27 17 6 72 | f 27 6 10 73 | f 27 10 5 74 | f 27 5 21 75 | f 28 18 14 76 | f 28 2 18 77 | f 28 23 22 78 | f 28 14 23 79 | f 28 22 13 80 | f 28 13 2 81 | f 29 15 6 82 | f 29 6 19 83 | f 30 5 11 84 | f 30 11 20 85 | f 31 12 4 86 | f 31 21 30 87 | f 32 27 21 88 | f 32 17 27 89 | f 32 31 4 90 | f 32 21 31 91 | f 33 23 8 92 | f 33 8 13 93 | f 33 13 23 94 | f 34 25 1 95 | f 34 1 9 96 | f 34 9 25 97 | f 35 26 19 98 | f 35 19 7 99 | f 35 7 26 100 | f 36 9 15 101 | f 36 15 29 102 | f 36 25 9 103 | f 37 29 19 104 | f 37 19 16 105 | f 37 16 25 106 | f 37 36 29 107 | f 37 25 36 108 | f 38 30 21 109 | f 38 21 5 110 | f 39 30 20 111 | f 39 20 12 112 | f 39 31 30 113 | f 39 12 31 114 | f 40 32 4 115 | f 40 4 17 116 | f 40 17 32 117 | f 41 38 5 118 | f 41 5 30 119 | f 41 30 38 120 | -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/link5_collision_2.obj: -------------------------------------------------------------------------------- 1 | v 0.016219155 0.099363113 0.048750773 2 | v 0.046550363 0.015799999 0.011058674 3 | v 0.046166659 0.105324245 -0.019041548 4 | v -0.005436418 0.111465780 -0.067873175 5 | v -0.043746749 0.015799999 0.019475930 6 | v 0.032618475 0.015799999 -0.035021468 7 | v 0.012971462 0.125447286 0.026076443 8 | v 0.045556378 0.100993129 0.023528159 9 | v 0.016534659 0.015799999 0.044952921 10 | v 0.045622136 0.015799999 -0.014505461 11 | v 0.031590266 0.097675904 -0.057701935 12 | v -0.026144502 0.015799999 -0.040104519 13 | v 0.020916727 0.125582876 -0.010159381 14 | v -0.043170314 0.100482302 0.027956662 15 | v 0.046145375 0.108191241 0.006346428 16 | v 0.028387091 0.112218342 0.031375415 17 | v 0.033002187 0.099171431 0.039965413 18 | v 0.016412747 0.015799999 -0.044989475 19 | v 0.036705779 0.015799999 -0.030707024 20 | v -0.022295018 0.125131249 -0.010109805 21 | v 0.029605924 0.107695894 -0.057770639 22 | v -0.013213095 0.112592014 0.039924672 23 | v -0.017325918 0.015799999 0.044664757 24 | v -0.047688079 0.104963029 -0.014858533 25 | v 0.045808408 0.103510400 0.019105049 26 | v 0.032957420 0.121769349 -0.001719666 27 | v 0.011885780 0.108060682 0.044095325 28 | v 0.016109216 0.089384114 0.048719259 29 | v 0.041214473 0.103236411 0.027403040 30 | v 0.041650999 0.015799999 0.023706000 31 | v 0.028114332 0.082823920 -0.058553905 32 | v -0.017699993 0.015799999 -0.044454039 33 | v 0.030954458 0.092818151 -0.058089685 34 | v -0.013656957 0.125189726 -0.019080479 35 | v 0.020627846 0.125801899 0.015541304 36 | v 0.008510412 0.111150243 -0.067818128 37 | v -0.029781181 0.121768239 0.014799138 38 | v -0.038794729 0.015799999 0.028113908 39 | v -0.017496539 0.098143056 0.049083962 40 | v -0.044002704 0.015799999 -0.018961373 41 | v -0.047333769 0.101445201 0.019313718 42 | v -0.030626847 0.107119812 -0.057687294 43 | v 0.046107670 0.108070694 -0.010345774 44 | v 0.028871230 0.120837663 -0.014381368 45 | v 0.011692637 0.121507793 0.031446733 46 | v 0.020178268 0.103656248 0.044326107 47 | v 0.024954524 0.015799999 0.040826797 48 | v 0.037099553 0.099607308 0.036020114 49 | v 0.028145238 0.121197152 0.018754182 50 | v -0.021927781 0.125344027 0.015252414 51 | v 0.020917077 0.111451583 -0.057406886 52 | v 0.012405067 0.125386135 -0.019235931 53 | v 0.024373464 0.079432104 -0.059087522 54 | v -0.033976639 0.107508587 0.031219781 55 | v -0.032505696 0.120513471 -0.010314825 56 | v -0.026112117 0.015799999 0.040139331 57 | v -0.008981987 0.108489258 0.044495871 58 | v -0.005033433 0.070411983 0.049486264 59 | v -0.047363327 0.103674321 0.015035708 60 | v -0.033832737 0.116474922 0.018745562 61 | v -0.047827588 0.074670758 0.002492660 62 | v -0.028518812 0.083365915 -0.058497467 63 | v -0.022142435 0.111037086 -0.057352830 64 | v 0.041463828 0.111761132 -0.014586542 65 | f 6 2 5 66 | f 9 5 2 67 | f 10 3 2 68 | f 10 2 6 69 | f 11 3 10 70 | f 12 6 5 71 | f 15 2 3 72 | f 18 6 12 73 | f 19 10 6 74 | f 21 3 11 75 | f 23 5 9 76 | f 25 8 2 77 | f 25 2 15 78 | f 28 17 1 79 | f 29 8 25 80 | f 30 9 2 81 | f 30 2 8 82 | f 31 6 18 83 | f 31 19 6 84 | f 32 18 12 85 | f 32 4 18 86 | f 33 11 10 87 | f 33 10 19 88 | f 33 19 31 89 | f 35 13 34 90 | f 35 26 13 91 | f 36 21 11 92 | f 36 11 33 93 | f 36 33 31 94 | f 36 18 4 95 | f 38 14 5 96 | f 38 5 23 97 | f 40 12 5 98 | f 41 5 14 99 | f 42 40 24 100 | f 43 26 15 101 | f 43 15 3 102 | f 44 26 21 103 | f 44 21 13 104 | f 44 13 26 105 | f 45 16 7 106 | f 45 7 22 107 | f 46 17 16 108 | f 46 45 27 109 | f 46 16 45 110 | f 46 27 1 111 | f 46 1 17 112 | f 47 28 9 113 | f 47 17 28 114 | f 47 9 30 115 | f 48 8 29 116 | f 48 30 8 117 | f 48 47 30 118 | f 48 17 47 119 | f 48 29 16 120 | f 48 16 17 121 | f 49 29 25 122 | f 49 16 29 123 | f 49 25 15 124 | f 49 15 26 125 | f 49 26 35 126 | f 49 35 7 127 | f 49 7 16 128 | f 50 7 35 129 | f 50 37 22 130 | f 50 22 7 131 | f 50 35 34 132 | f 50 34 20 133 | f 51 13 21 134 | f 51 21 36 135 | f 52 34 13 136 | f 52 51 36 137 | f 52 13 51 138 | f 52 36 4 139 | f 52 4 34 140 | f 53 36 31 141 | f 53 31 18 142 | f 53 18 36 143 | f 54 22 37 144 | f 54 39 22 145 | f 54 14 39 146 | f 55 42 24 147 | f 55 50 20 148 | f 55 37 50 149 | f 56 38 23 150 | f 56 23 39 151 | f 56 39 14 152 | f 56 14 38 153 | f 57 22 39 154 | f 57 45 22 155 | f 57 27 45 156 | f 57 39 1 157 | f 57 1 27 158 | f 58 28 1 159 | f 58 1 39 160 | f 58 9 28 161 | f 58 39 23 162 | f 58 23 9 163 | f 59 55 24 164 | f 59 37 55 165 | f 60 41 14 166 | f 60 59 41 167 | f 60 37 59 168 | f 60 54 37 169 | f 60 14 54 170 | f 61 40 5 171 | f 61 5 41 172 | f 61 24 40 173 | f 61 59 24 174 | f 61 41 59 175 | f 62 12 40 176 | f 62 40 42 177 | f 62 32 12 178 | f 62 42 4 179 | f 62 4 32 180 | f 63 34 4 181 | f 63 4 42 182 | f 63 20 34 183 | f 63 55 20 184 | f 63 42 55 185 | f 64 43 3 186 | f 64 3 21 187 | f 64 21 26 188 | f 64 26 43 189 | -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/link6.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/link6.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/link6_12.obj: -------------------------------------------------------------------------------- 1 | mtllib material_0.mtl 2 | usemtl material_0 3 | v 0.08738500 0.07734600 -0.02619700 4 | v 0.08738500 0.07734600 -0.02619700 5 | v 0.08738500 0.07734600 -0.02619700 6 | v 0.08815600 0.07722600 -0.02612400 7 | v 0.08815600 0.07722600 -0.02612400 8 | v 0.08815600 0.07722600 -0.02612400 9 | v 0.08815600 0.07722600 -0.02612400 10 | v 0.08771600 0.07718900 -0.02655000 11 | v 0.08941600 0.07743300 -0.02422300 12 | v 0.08941600 0.07743300 -0.02422300 13 | v 0.08941600 0.07743300 -0.02422300 14 | v 0.08974500 0.07729600 -0.02457100 15 | v 0.08916900 0.07728200 -0.02513600 16 | v 0.08916900 0.07728200 -0.02513600 17 | v 0.08916900 0.07728200 -0.02513600 18 | v 0.08916900 0.07728200 -0.02513600 19 | v 0.08739100 0.07752100 -0.02551400 20 | v 0.08739100 0.07752100 -0.02551400 21 | v 0.08739100 0.07752100 -0.02551400 22 | v 0.08705300 0.07749700 -0.02584300 23 | v 0.08773300 0.07754000 -0.02518000 24 | v 0.08773300 0.07754000 -0.02518000 25 | v 0.08773300 0.07754000 -0.02518000 26 | v 0.08860200 0.07725500 -0.02568900 27 | v 0.08860200 0.07725500 -0.02568900 28 | v 0.08860200 0.07725500 -0.02568900 29 | v 0.08807900 0.07755400 -0.02484200 30 | v 0.08807900 0.07755400 -0.02484200 31 | v 0.08807900 0.07755400 -0.02484200 32 | v 0.08842800 0.07756300 -0.02450000 33 | v 0.08842800 0.07756300 -0.02450000 34 | v 0.08842800 0.07756300 -0.02450000 35 | v 0.08842800 0.07756300 -0.02450000 36 | v 0.08842800 0.07756300 -0.02450000 37 | v 0.08908300 0.07756600 -0.02387100 38 | v 0.08908300 0.07756600 -0.02387100 39 | v 0.08874400 0.07769400 -0.02351600 40 | v 0.08874400 0.07769400 -0.02351600 41 | v 0.08874400 0.07769400 -0.02351600 42 | v 0.08874400 0.07769400 -0.02351600 43 | v 0.08809300 0.07769700 -0.02414700 44 | v 0.08809300 0.07769700 -0.02414700 45 | v 0.08809300 0.07769700 -0.02414700 46 | v 0.08807600 0.07782400 -0.02347800 47 | v 0.08807600 0.07782400 -0.02347800 48 | v 0.08807600 0.07782400 -0.02347800 49 | v 0.08840200 0.07781800 -0.02315600 50 | v 0.08775700 0.07782500 -0.02379300 51 | vn 0.17290000 0.94970000 -0.26090000 52 | vn 0.17250000 0.95380000 -0.24590000 53 | vn 0.17210000 0.95390000 -0.24590000 54 | vn 0.17290000 0.94970000 -0.26090000 55 | vn 0.17910000 0.95470000 -0.23760000 56 | vn 0.17160000 0.95520000 -0.24110000 57 | vn 0.17210000 0.95390000 -0.24590000 58 | vn 0.17290000 0.94970000 -0.26090000 59 | vn 0.18140000 0.96450000 -0.19210000 60 | vn 0.18570000 0.96000000 -0.20940000 61 | vn 0.18050000 0.96130000 -0.20820000 62 | vn 0.18050000 0.96130000 -0.20820000 63 | vn 0.17810000 0.95730000 -0.22760000 64 | vn 0.18050000 0.96130000 -0.20820000 65 | vn 0.18570000 0.96000000 -0.20940000 66 | vn 0.18270000 0.95990000 -0.21270000 67 | vn 0.17250000 0.95380000 -0.24590000 68 | vn 0.17210000 0.95390000 -0.24590000 69 | vn 0.17910000 0.95470000 -0.23760000 70 | vn 0.17250000 0.95380000 -0.24590000 71 | vn 0.17910000 0.95470000 -0.23760000 72 | vn 0.18130000 0.95720000 -0.22550000 73 | vn 0.17160000 0.95520000 -0.24110000 74 | vn 0.17810000 0.95730000 -0.22760000 75 | vn 0.18130000 0.95720000 -0.22550000 76 | vn 0.17160000 0.95520000 -0.24110000 77 | vn 0.18270000 0.95990000 -0.21270000 78 | vn 0.18130000 0.95720000 -0.22550000 79 | vn 0.17810000 0.95730000 -0.22760000 80 | vn 0.18140000 0.96450000 -0.19210000 81 | vn 0.18570000 0.96000000 -0.20940000 82 | vn 0.18270000 0.95990000 -0.21270000 83 | vn 0.17380000 0.96740000 -0.18420000 84 | vn 0.18650000 0.96430000 -0.18780000 85 | vn 0.17380000 0.96740000 -0.18420000 86 | vn 0.18140000 0.96450000 -0.19210000 87 | vn 0.17770000 0.96770000 -0.17880000 88 | vn 0.17900000 0.97000000 -0.16440000 89 | vn 0.18650000 0.96430000 -0.18780000 90 | vn 0.17380000 0.96740000 -0.18420000 91 | vn 0.17770000 0.96770000 -0.17880000 92 | vn 0.18020000 0.96730000 -0.17860000 93 | vn 0.18650000 0.96430000 -0.18780000 94 | vn 0.17900000 0.97000000 -0.16440000 95 | vn 0.18020000 0.96730000 -0.17860000 96 | vn 0.17770000 0.96770000 -0.17880000 97 | vn 0.17900000 0.97000000 -0.16440000 98 | vn 0.18020000 0.96730000 -0.17860000 99 | f 1//1 4//4 8//8 100 | f 11//11 12//12 14//14 101 | f 17//17 2//2 20//20 102 | f 18//18 7//7 3//3 103 | f 23//23 26//26 6//6 104 | f 21//21 5//5 19//19 105 | f 29//29 13//13 24//24 106 | f 28//28 25//25 22//22 107 | f 30//30 36//36 9//9 108 | f 31//31 10//10 15//15 109 | f 32//32 16//16 27//27 110 | f 40//40 35//35 33//33 111 | f 43//43 39//39 34//34 112 | f 44//44 47//47 38//38 113 | f 46//46 37//37 41//41 114 | f 48//48 45//45 42//42 115 | -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/link6_13.obj: -------------------------------------------------------------------------------- 1 | mtllib material_0.mtl 2 | usemtl material_0 3 | v 0.08937000 0.07712300 0.02554700 4 | v 0.08937000 0.07712300 0.02554700 5 | v 0.08937000 0.07712300 0.02554700 6 | v 0.08885500 0.07735300 0.02500000 7 | v 0.08885500 0.07735300 0.02500000 8 | v 0.08885500 0.07735300 0.02500000 9 | v 0.08722100 0.07724700 0.02659100 10 | v 0.08813200 0.07732100 0.02570800 11 | v 0.08813200 0.07732100 0.02570800 12 | v 0.08813200 0.07732100 0.02570800 13 | v 0.08813200 0.07732100 0.02570800 14 | v 0.08813200 0.07732100 0.02570800 15 | v 0.08813200 0.07732100 0.02570800 16 | v 0.08746500 0.07761000 0.02500000 17 | v 0.08746500 0.07761000 0.02500000 18 | v 0.08746500 0.07761000 0.02500000 19 | v 0.08746500 0.07761000 0.02500000 20 | v 0.08746500 0.07761000 0.02500000 21 | v 0.08696300 0.07758100 0.02548900 22 | v 0.08696300 0.07758100 0.02548900 23 | v 0.08818700 0.07763200 0.02429300 24 | v 0.08818700 0.07763200 0.02429300 25 | v 0.08818700 0.07763200 0.02429300 26 | v 0.08818700 0.07763200 0.02429300 27 | v 0.08818700 0.07763200 0.02429300 28 | v 0.08818700 0.07763200 0.02429300 29 | v 0.08734500 0.07794800 0.02340900 30 | v 0.08968600 0.07697400 0.02588400 31 | v 0.08968600 0.07697400 0.02588400 32 | v 0.08704800 0.07777700 0.02456100 33 | v 0.08704800 0.07777700 0.02456100 34 | v 0.08662600 0.07794100 0.02411600 35 | v 0.08662600 0.07794100 0.02411600 36 | v 0.08857000 0.07711300 0.02617400 37 | v 0.08857000 0.07711300 0.02617400 38 | v 0.08857000 0.07711300 0.02617400 39 | v 0.08895900 0.07692100 0.02659100 40 | v 0.08926000 0.07736400 0.02460300 41 | v 0.08926000 0.07736400 0.02460300 42 | v 0.08926000 0.07736400 0.02460300 43 | v 0.08975600 0.07736900 0.02411600 44 | v 0.08975600 0.07736900 0.02411600 45 | v 0.08975600 0.07736900 0.02411600 46 | v 0.08864800 0.07763300 0.02383900 47 | v 0.08864800 0.07763300 0.02383900 48 | v 0.08908400 0.07763100 0.02340900 49 | v 0.08655700 0.07755200 0.02588400 50 | v 0.08655700 0.07755200 0.02588400 51 | vn 0.18430000 0.95040000 0.25040000 52 | vn 0.18200000 0.95620000 0.22910000 53 | vn 0.18380000 0.95070000 0.24960000 54 | vn 0.17770000 0.96180000 0.20800000 55 | vn 0.18200000 0.95620000 0.22910000 56 | vn 0.17710000 0.95830000 0.22420000 57 | vn 0.16800000 0.95290000 0.25240000 58 | vn 0.17060000 0.95810000 0.23030000 59 | vn 0.16740000 0.95520000 0.24390000 60 | vn 0.18380000 0.95070000 0.24960000 61 | vn 0.17710000 0.95830000 0.22420000 62 | vn 0.18200000 0.95620000 0.22910000 63 | vn 0.16800000 0.95290000 0.25240000 64 | vn 0.17710000 0.95830000 0.22420000 65 | vn 0.17770000 0.96180000 0.20800000 66 | vn 0.17180000 0.96350000 0.20550000 67 | vn 0.17850000 0.96080000 0.21230000 68 | vn 0.17060000 0.95810000 0.23030000 69 | vn 0.17060000 0.95810000 0.23030000 70 | vn 0.16740000 0.95520000 0.24390000 71 | vn 0.17180000 0.96350000 0.20550000 72 | vn 0.18280000 0.96480000 0.18910000 73 | vn 0.17850000 0.96080000 0.21230000 74 | vn 0.18340000 0.96300000 0.19740000 75 | vn 0.17100000 0.96790000 0.18410000 76 | vn 0.16950000 0.96620000 0.19440000 77 | vn 0.17100000 0.96790000 0.18410000 78 | vn 0.18690000 0.94670000 0.26230000 79 | vn 0.18430000 0.95040000 0.25040000 80 | vn 0.17180000 0.96350000 0.20550000 81 | vn 0.16950000 0.96620000 0.19440000 82 | vn 0.17100000 0.96790000 0.18410000 83 | vn 0.16950000 0.96620000 0.19440000 84 | vn 0.18430000 0.95040000 0.25040000 85 | vn 0.18380000 0.95070000 0.24960000 86 | vn 0.18690000 0.94670000 0.26230000 87 | vn 0.18690000 0.94670000 0.26230000 88 | vn 0.17770000 0.96180000 0.20800000 89 | vn 0.18340000 0.96300000 0.19740000 90 | vn 0.17850000 0.96080000 0.21230000 91 | vn 0.18340000 0.96300000 0.19740000 92 | vn 0.18460000 0.96570000 0.18270000 93 | vn 0.18280000 0.96480000 0.18910000 94 | vn 0.18460000 0.96570000 0.18270000 95 | vn 0.18280000 0.96480000 0.18910000 96 | vn 0.18460000 0.96570000 0.18270000 97 | vn 0.16800000 0.95290000 0.25240000 98 | vn 0.16740000 0.95520000 0.24390000 99 | f 8//8 18//18 19//19 100 | f 25//25 27//27 32//32 101 | f 5//5 12//12 2//2 102 | f 6//6 14//14 11//11 103 | f 3//3 10//10 35//35 104 | f 38//38 15//15 4//4 105 | f 40//40 23//23 17//17 106 | f 41//41 24//24 39//39 107 | f 45//45 22//22 43//43 108 | f 21//21 30//30 16//16 109 | f 28//28 36//36 37//37 110 | f 46//46 44//44 42//42 111 | f 13//13 47//47 7//7 112 | f 33//33 31//31 26//26 113 | f 1//1 34//34 29//29 114 | f 20//20 48//48 9//9 115 | -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/link6_7.obj: -------------------------------------------------------------------------------- 1 | mtllib material_0.mtl 2 | usemtl material_0 3 | v 0.06278800 0.08158900 -0.00050000 4 | v 0.06278800 0.08158900 -0.00050000 5 | v 0.06278800 0.08158900 -0.00050000 6 | v 0.06278800 0.08158900 -0.00050000 7 | v 0.06196700 0.08154300 -0.00050000 8 | v 0.06196800 0.08154400 -0.00000000 9 | v 0.06196800 0.08154400 -0.00000000 10 | v 0.06196800 0.08154400 -0.00000000 11 | v 0.06196800 0.08154400 -0.00000000 12 | v 0.06382300 0.08162700 -0.00073800 13 | v 0.06382300 0.08162700 -0.00073800 14 | v 0.06382300 0.08162700 -0.00073800 15 | v 0.06382300 0.08162700 -0.00073800 16 | v 0.06365600 0.08161700 -0.00135000 17 | v 0.06365600 0.08161700 -0.00135000 18 | v 0.06322500 0.08160600 -0.00092700 19 | v 0.06322500 0.08160600 -0.00092700 20 | v 0.06322500 0.08160600 -0.00092700 21 | v 0.06319700 0.08160800 -0.00012500 22 | v 0.06319700 0.08160800 -0.00012500 23 | v 0.06319700 0.08160800 -0.00012500 24 | v 0.06319700 0.08160800 -0.00000000 25 | v 0.06319700 0.08160800 -0.00000000 26 | v 0.06319700 0.08160800 -0.00000000 27 | v 0.06319700 0.08160800 -0.00000000 28 | v 0.06422200 0.08163600 -0.00079600 29 | v 0.06422200 0.08163600 -0.00079600 30 | v 0.06422200 0.08163600 -0.00079600 31 | v 0.06432000 0.08164000 -0.00025000 32 | v 0.06432000 0.08164000 -0.00025000 33 | v 0.06477800 0.08164500 -0.00025000 34 | v 0.06278800 0.08158900 0.00050000 35 | v 0.06278800 0.08158900 0.00050000 36 | v 0.06278800 0.08158900 0.00050000 37 | v 0.06278800 0.08158900 0.00050000 38 | v 0.06196700 0.08154300 0.00050000 39 | v 0.06319700 0.08160800 0.00012500 40 | v 0.06319700 0.08160800 0.00012500 41 | v 0.06319700 0.08160800 0.00012500 42 | v 0.06322500 0.08160600 0.00092700 43 | v 0.06322500 0.08160600 0.00092700 44 | v 0.06322500 0.08160600 0.00092700 45 | v 0.06382300 0.08162700 0.00073800 46 | v 0.06382300 0.08162700 0.00073800 47 | v 0.06382300 0.08162700 0.00073800 48 | v 0.06382300 0.08162700 0.00073800 49 | v 0.06365600 0.08161700 0.00135000 50 | v 0.06365600 0.08161700 0.00135000 51 | v 0.06422200 0.08163600 0.00079500 52 | v 0.06422200 0.08163600 0.00079500 53 | v 0.06422200 0.08163600 0.00079500 54 | v 0.06432000 0.08164000 0.00025000 55 | v 0.06432000 0.08164000 0.00025000 56 | v 0.06477800 0.08164500 0.00025000 57 | vn -0.05590000 0.99840000 -0.00200000 58 | vn -0.04540000 0.99900000 -0.00040000 59 | vn -0.05180000 0.99860000 0.00480000 60 | vn -0.04210000 0.99910000 -0.00400000 61 | vn -0.05590000 0.99840000 -0.00200000 62 | vn -0.05180000 0.99860000 -0.00480000 63 | vn -0.05180000 0.99860000 0.00480000 64 | vn -0.05590000 0.99840000 0.00200000 65 | vn -0.05590000 0.99840000 -0.00200000 66 | vn -0.02370000 0.99970000 -0.00890000 67 | vn -0.03390000 0.99940000 -0.00370000 68 | vn -0.02280000 0.99970000 -0.00280000 69 | vn -0.03300000 0.99940000 -0.00640000 70 | vn -0.03300000 0.99940000 -0.00640000 71 | vn -0.02370000 0.99970000 -0.00890000 72 | vn -0.03390000 0.99940000 -0.00370000 73 | vn -0.03300000 0.99940000 -0.00640000 74 | vn -0.04210000 0.99910000 -0.00400000 75 | vn -0.04210000 0.99910000 -0.00400000 76 | vn -0.04540000 0.99900000 -0.00040000 77 | vn -0.03390000 0.99940000 -0.00370000 78 | vn -0.05180000 0.99860000 -0.00480000 79 | vn -0.04540000 0.99900000 0.00040000 80 | vn -0.04540000 0.99900000 -0.00040000 81 | vn -0.05180000 0.99860000 0.00480000 82 | vn -0.02370000 0.99970000 -0.00890000 83 | vn -0.02280000 0.99970000 -0.00280000 84 | vn -0.01250000 0.99990000 -0.00460000 85 | vn -0.02280000 0.99970000 -0.00280000 86 | vn -0.01250000 0.99990000 -0.00460000 87 | vn -0.01250000 0.99990000 -0.00460000 88 | vn -0.05590000 0.99840000 0.00200000 89 | vn -0.05180000 0.99860000 -0.00480000 90 | vn -0.04540000 0.99900000 0.00040000 91 | vn -0.04210000 0.99910000 0.00400000 92 | vn -0.05590000 0.99840000 0.00200000 93 | vn -0.04540000 0.99900000 0.00040000 94 | vn -0.04210000 0.99910000 0.00400000 95 | vn -0.03390000 0.99940000 0.00370000 96 | vn -0.03390000 0.99940000 0.00370000 97 | vn -0.03300000 0.99940000 0.00640000 98 | vn -0.04210000 0.99910000 0.00400000 99 | vn -0.03390000 0.99940000 0.00370000 100 | vn -0.03300000 0.99940000 0.00640000 101 | vn -0.02280000 0.99970000 0.00280000 102 | vn -0.02360000 0.99970000 0.00890000 103 | vn -0.03300000 0.99940000 0.00640000 104 | vn -0.02360000 0.99970000 0.00890000 105 | vn -0.02280000 0.99970000 0.00280000 106 | vn -0.02360000 0.99970000 0.00890000 107 | vn -0.01250000 0.99990000 0.00460000 108 | vn -0.01250000 0.99990000 0.00460000 109 | vn -0.02280000 0.99970000 0.00280000 110 | vn -0.01250000 0.99990000 0.00460000 111 | f 1//1 5//5 9//9 112 | f 13//13 14//14 17//17 113 | f 19//19 18//18 4//4 114 | f 21//21 11//11 16//16 115 | f 25//25 3//3 7//7 116 | f 24//24 20//20 2//2 117 | f 26//26 15//15 10//10 118 | f 29//29 27//27 12//12 119 | f 31//31 28//28 30//30 120 | f 33//33 22//22 6//6 121 | f 32//32 8//8 36//36 122 | f 37//37 23//23 34//34 123 | f 42//42 38//38 35//35 124 | f 43//43 39//39 40//40 125 | f 47//47 44//44 41//41 126 | f 49//49 53//53 45//45 127 | f 50//50 46//46 48//48 128 | f 54//54 52//52 51//51 129 | -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/link6_8.obj: -------------------------------------------------------------------------------- 1 | mtllib material_0.mtl 2 | usemtl material_0 3 | v 0.11308100 0.07180500 -0.00075400 4 | v 0.11308100 0.07180500 -0.00075400 5 | v 0.11373800 0.07140400 -0.00040000 6 | v 0.11373800 0.07140400 -0.00040000 7 | v 0.11373800 0.07140400 -0.00040000 8 | v 0.11373800 0.07140400 -0.00040000 9 | v 0.11331900 0.07165700 -0.00112600 10 | v 0.11331900 0.07165700 -0.00112600 11 | v 0.11331900 0.07165700 -0.00112600 12 | v 0.11388500 0.07131000 -0.00060800 13 | v 0.11388500 0.07131000 -0.00060800 14 | v 0.11388500 0.07131000 -0.00060800 15 | v 0.11519800 0.07044600 0.00008600 16 | v 0.11519800 0.07044600 0.00008600 17 | v 0.11519800 0.07044600 0.00008600 18 | v 0.11519800 0.07044600 0.00008600 19 | v 0.11591500 0.06994200 -0.00024100 20 | v 0.11591500 0.06994200 -0.00024100 21 | v 0.11591500 0.06994200 -0.00024100 22 | v 0.11518000 0.07045900 -0.00020300 23 | v 0.11518000 0.07045900 -0.00020300 24 | v 0.11518000 0.07045900 -0.00020300 25 | v 0.11575300 0.07005400 -0.00077100 26 | v 0.11575300 0.07005400 -0.00077100 27 | v 0.11575300 0.07005400 -0.00077100 28 | v 0.11506800 0.07053400 -0.00048200 29 | v 0.11506800 0.07053400 -0.00048200 30 | v 0.11506800 0.07053400 -0.00048200 31 | v 0.11549700 0.07023200 -0.00115900 32 | v 0.11549700 0.07023200 -0.00115900 33 | v 0.11549700 0.07023200 -0.00115900 34 | v 0.11485400 0.07067800 -0.00071400 35 | v 0.11485400 0.07067800 -0.00071400 36 | v 0.11485400 0.07067800 -0.00071400 37 | v 0.11485400 0.07067800 -0.00071400 38 | v 0.11522800 0.07041600 -0.00139400 39 | v 0.11522800 0.07041600 -0.00139400 40 | v 0.11482900 0.07068500 -0.00160100 41 | v 0.11482900 0.07068500 -0.00160100 42 | v 0.11482900 0.07068500 -0.00160100 43 | v 0.11456100 0.07087200 -0.00084200 44 | v 0.11456100 0.07087200 -0.00084200 45 | v 0.11456100 0.07087200 -0.00084200 46 | v 0.11428000 0.07104700 -0.00164700 47 | v 0.11428000 0.07104700 -0.00164700 48 | v 0.11428000 0.07104700 -0.00164700 49 | v 0.11428000 0.07104700 -0.00164700 50 | v 0.11431700 0.07103200 -0.00084100 51 | v 0.11431700 0.07103200 -0.00084100 52 | v 0.11407900 0.07118600 -0.00076500 53 | v 0.11407900 0.07118600 -0.00076500 54 | v 0.11407900 0.07118600 -0.00076500 55 | v 0.11292200 0.07190200 -0.00022300 56 | v 0.11292200 0.07190200 -0.00022300 57 | v 0.11292200 0.07190200 -0.00022300 58 | v 0.11365200 0.07145800 -0.00008800 59 | v 0.11365200 0.07145800 -0.00008800 60 | v 0.11365200 0.07145800 -0.00008800 61 | v 0.11375000 0.07138600 -0.00148800 62 | v 0.11375000 0.07138600 -0.00148800 63 | v 0.11375000 0.07138600 -0.00148800 64 | v 0.11414600 0.07114300 0.00079700 65 | v 0.11414600 0.07114300 0.00079700 66 | v 0.11414600 0.07114300 0.00079700 67 | v 0.11352000 0.07153200 0.00132400 68 | v 0.11352000 0.07153200 0.00132400 69 | v 0.11352000 0.07153200 0.00132400 70 | v 0.11400800 0.07122200 0.00159700 71 | v 0.11400800 0.07122200 0.00159700 72 | v 0.11400800 0.07122200 0.00159700 73 | v 0.11382600 0.07134700 0.00055400 74 | v 0.11382600 0.07134700 0.00055400 75 | v 0.11382600 0.07134700 0.00055400 76 | v 0.11382600 0.07134700 0.00055400 77 | v 0.11328300 0.07168000 0.00107600 78 | v 0.11328300 0.07168000 0.00107600 79 | v 0.11309400 0.07179600 0.00078300 80 | v 0.11309400 0.07179600 0.00078300 81 | v 0.11309400 0.07179600 0.00078300 82 | v 0.11367100 0.07144600 0.00020300 83 | v 0.11367100 0.07144600 0.00020300 84 | v 0.11367100 0.07144600 0.00020300 85 | v 0.11294600 0.07188700 0.00034000 86 | v 0.11294600 0.07188700 0.00034000 87 | v 0.11294600 0.07188700 0.00034000 88 | v 0.11491300 0.07063900 0.00066700 89 | v 0.11491300 0.07063900 0.00066700 90 | v 0.11491300 0.07063900 0.00066700 91 | v 0.11491300 0.07063900 0.00066700 92 | v 0.11531900 0.07035500 0.00133000 93 | v 0.11531900 0.07035500 0.00133000 94 | v 0.11561600 0.07015000 0.00100700 95 | v 0.11561600 0.07015000 0.00100700 96 | v 0.11561600 0.07015000 0.00100700 97 | v 0.11511500 0.07050300 0.00039600 98 | v 0.11511500 0.07050300 0.00039600 99 | v 0.11511500 0.07050300 0.00039600 100 | v 0.11496000 0.07059700 0.00154500 101 | v 0.11496000 0.07059700 0.00154500 102 | v 0.11496000 0.07059700 0.00154500 103 | v 0.11581700 0.07000900 0.00061700 104 | v 0.11581700 0.07000900 0.00061700 105 | v 0.11581700 0.07000900 0.00061700 106 | v 0.11462500 0.07083000 0.00082600 107 | v 0.11462500 0.07083000 0.00082600 108 | v 0.11462500 0.07083000 0.00082600 109 | v 0.11455800 0.07086500 0.00164800 110 | v 0.11455800 0.07086500 0.00164800 111 | v 0.11455800 0.07086500 0.00164800 112 | v 0.11590900 0.06994600 0.00023300 113 | v 0.11590900 0.06994600 0.00023300 114 | v 0.11438400 0.07098900 0.00084900 115 | v 0.11438400 0.07098900 0.00084900 116 | v 0.11438400 0.07098900 0.00084900 117 | vn 0.52110000 0.85350000 -0.00020000 118 | vn 0.52280000 0.85240000 -0.00470000 119 | vn 0.52020000 0.85400000 -0.00590000 120 | vn 0.52110000 0.85350000 -0.00020000 121 | vn 0.52280000 0.85240000 -0.00470000 122 | vn 0.52720000 0.84970000 -0.00820000 123 | vn 0.52720000 0.84970000 -0.00820000 124 | vn 0.52690000 0.84990000 -0.00770000 125 | vn 0.52280000 0.85240000 -0.00470000 126 | vn 0.52720000 0.84970000 -0.00820000 127 | vn 0.53400000 0.84550000 -0.00920000 128 | vn 0.52690000 0.84990000 -0.00770000 129 | vn 0.57590000 0.81750000 0.00060000 130 | vn 0.57590000 0.81760000 0.00110000 131 | vn 0.57330000 0.81940000 0.00560000 132 | vn 0.57530000 0.81800000 -0.00150000 133 | vn 0.57530000 0.81800000 -0.00190000 134 | vn 0.57530000 0.81800000 -0.00150000 135 | vn 0.57590000 0.81750000 0.00060000 136 | vn 0.57180000 0.82040000 -0.00710000 137 | vn 0.57530000 0.81800000 -0.00190000 138 | vn 0.57530000 0.81800000 -0.00150000 139 | vn 0.57320000 0.81940000 -0.00210000 140 | vn 0.57530000 0.81800000 -0.00190000 141 | vn 0.57180000 0.82040000 -0.00710000 142 | vn 0.57320000 0.81940000 -0.00210000 143 | vn 0.56510000 0.82500000 -0.00980000 144 | vn 0.57180000 0.82040000 -0.00710000 145 | vn 0.56750000 0.82330000 -0.00460000 146 | vn 0.56510000 0.82500000 -0.00980000 147 | vn 0.57320000 0.81940000 -0.00210000 148 | vn 0.56200000 0.82710000 -0.00910000 149 | vn 0.55500000 0.83180000 -0.00880000 150 | vn 0.56750000 0.82330000 -0.00460000 151 | vn 0.56510000 0.82500000 -0.00980000 152 | vn 0.56750000 0.82330000 -0.00460000 153 | vn 0.56200000 0.82710000 -0.00910000 154 | vn 0.56200000 0.82710000 -0.00910000 155 | vn 0.55500000 0.83180000 -0.00880000 156 | vn 0.55070000 0.83460000 -0.01100000 157 | vn 0.54830000 0.83620000 -0.00990000 158 | vn 0.55500000 0.83180000 -0.00880000 159 | vn 0.55070000 0.83460000 -0.01100000 160 | vn 0.53690000 0.84360000 -0.01100000 161 | vn 0.54140000 0.84070000 -0.00950000 162 | vn 0.55070000 0.83460000 -0.01100000 163 | vn 0.54830000 0.83620000 -0.00990000 164 | vn 0.54830000 0.83620000 -0.00990000 165 | vn 0.54140000 0.84070000 -0.00950000 166 | vn 0.54140000 0.84070000 -0.00950000 167 | vn 0.53690000 0.84360000 -0.01100000 168 | vn 0.53400000 0.84550000 -0.00920000 169 | vn 0.52020000 0.85400000 -0.00590000 170 | vn 0.52110000 0.85350000 -0.00020000 171 | vn 0.51930000 0.85460000 0.00050000 172 | vn 0.51930000 0.85460000 0.00050000 173 | vn 0.51970000 0.85440000 0.00120000 174 | vn 0.52020000 0.85400000 -0.00590000 175 | vn 0.53400000 0.84550000 -0.00920000 176 | vn 0.52690000 0.84990000 -0.00770000 177 | vn 0.53690000 0.84360000 -0.01100000 178 | vn 0.53360000 0.84570000 0.00970000 179 | vn 0.54330000 0.83950000 0.01080000 180 | vn 0.53280000 0.84620000 0.00830000 181 | vn 0.53360000 0.84570000 0.00970000 182 | vn 0.52510000 0.85100000 0.00490000 183 | vn 0.53280000 0.84620000 0.00830000 184 | vn 0.54380000 0.83910000 0.01110000 185 | vn 0.53280000 0.84620000 0.00830000 186 | vn 0.54330000 0.83950000 0.01080000 187 | vn 0.52510000 0.85100000 0.00490000 188 | vn 0.52310000 0.85230000 0.00200000 189 | vn 0.53360000 0.84570000 0.00970000 190 | vn 0.52430000 0.85150000 0.00740000 191 | vn 0.52310000 0.85230000 0.00200000 192 | vn 0.52510000 0.85100000 0.00490000 193 | vn 0.51960000 0.85440000 0.00100000 194 | vn 0.52430000 0.85150000 0.00740000 195 | vn 0.52310000 0.85230000 0.00200000 196 | vn 0.51960000 0.85440000 0.00100000 197 | vn 0.51970000 0.85440000 0.00120000 198 | vn 0.52430000 0.85150000 0.00740000 199 | vn 0.51960000 0.85440000 0.00100000 200 | vn 0.51930000 0.85460000 0.00050000 201 | vn 0.51970000 0.85440000 0.00120000 202 | vn 0.56320000 0.82630000 0.00830000 203 | vn 0.56720000 0.82350000 0.00970000 204 | vn 0.55750000 0.83010000 0.00890000 205 | vn 0.56960000 0.82190000 0.00250000 206 | vn 0.56320000 0.82630000 0.00830000 207 | vn 0.56960000 0.82190000 0.00250000 208 | vn 0.56720000 0.82350000 0.00970000 209 | vn 0.57420000 0.81870000 0.00130000 210 | vn 0.56960000 0.82190000 0.00250000 211 | vn 0.57420000 0.81870000 0.00130000 212 | vn 0.57330000 0.81940000 0.00560000 213 | vn 0.56720000 0.82350000 0.00970000 214 | vn 0.55600000 0.83110000 0.00980000 215 | vn 0.55750000 0.83010000 0.00890000 216 | vn 0.56320000 0.82630000 0.00830000 217 | vn 0.57420000 0.81870000 0.00130000 218 | vn 0.57330000 0.81940000 0.00560000 219 | vn 0.57590000 0.81760000 0.00110000 220 | vn 0.54990000 0.83520000 0.00920000 221 | vn 0.55600000 0.83110000 0.00980000 222 | vn 0.55750000 0.83010000 0.00890000 223 | vn 0.54380000 0.83910000 0.01110000 224 | vn 0.54990000 0.83520000 0.00920000 225 | vn 0.55600000 0.83110000 0.00980000 226 | vn 0.57590000 0.81760000 0.00110000 227 | vn 0.57590000 0.81750000 0.00060000 228 | vn 0.54380000 0.83910000 0.01110000 229 | vn 0.54990000 0.83520000 0.00920000 230 | vn 0.54330000 0.83950000 0.01080000 231 | f 8//8 12//12 60//60 232 | f 9//9 2//2 5//5 233 | f 7//7 6//6 10//10 234 | f 22//22 16//16 18//18 235 | f 21//21 17//17 24//24 236 | f 28//28 20//20 25//25 237 | f 31//31 26//26 23//23 238 | f 35//35 27//27 30//30 239 | f 36//36 34//34 29//29 240 | f 38//38 32//32 37//37 241 | f 39//39 42//42 33//33 242 | f 47//47 48//48 41//41 243 | f 46//46 43//43 40//40 244 | f 45//45 50//50 49//49 245 | f 61//61 51//51 44//44 246 | f 53//53 58//58 3//3 247 | f 1//1 54//54 4//4 248 | f 59//59 11//11 52//52 249 | f 64//64 67//67 69//69 250 | f 73//73 65//65 62//62 251 | f 76//76 66//66 71//71 252 | f 79//79 75//75 72//72 253 | f 78//78 74//74 82//82 254 | f 83//83 77//77 80//80 255 | f 85//85 81//81 57//57 256 | f 55//55 84//84 56//56 257 | f 89//89 91//91 94//94 258 | f 97//97 87//87 92//92 259 | f 86//86 100//100 90//90 260 | f 95//95 93//93 101//101 261 | f 105//105 109//109 98//98 262 | f 106//106 99//99 88//88 263 | f 14//14 103//103 110//110 264 | f 15//15 96//96 102//102 265 | f 13//13 111//111 19//19 266 | f 112//112 68//68 107//107 267 | f 113//113 108//108 104//104 268 | f 63//63 70//70 114//114 269 | -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/assets/link7.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/moveit/mujoco_ros2_control_examples/84021923d075dd9598cc2c0c0a5586d6721705a1/panda_resources/panda_mujoco/franka_emika_panda/assets/link7.stl -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/hand.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 115 | -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/franka_emika_panda/scene.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | -------------------------------------------------------------------------------- /panda_resources/panda_mujoco/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | panda_mujoco 4 | 0.1.0 5 | panda mjcf model 6 | 7 | TODO 8 | TODO 9 | 10 | ament_cmake 11 | 12 | 13 | ament_cmake 14 | 15 | 16 | -------------------------------------------------------------------------------- /peg_in_hole/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.5) 2 | project(peg_in_hole) 3 | 4 | # Default to C++14 5 | if(NOT CMAKE_CXX_STANDARD) 6 | set(CMAKE_CXX_STANDARD 14) 7 | set(CMAKE_CXX_STANDARD_REQUIRED ON) 8 | endif() 9 | 10 | if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") 11 | add_compile_options(-Wall -Wextra -Wpedantic) 12 | endif() 13 | 14 | # find dependencies 15 | find_package(ament_cmake REQUIRED) 16 | find_package(rclcpp REQUIRED) 17 | find_package(moveit REQUIRED) 18 | find_package(moveit_ros_planning_interface REQUIRED) 19 | find_package(control_msgs REQUIRED) 20 | 21 | set(THIS_PACKAGE_DEPENDS 22 | ament_cmake 23 | rclcpp 24 | moveit 25 | moveit_ros_planning_interface 26 | control_msgs 27 | ) 28 | 29 | add_executable(controller src/controller.cpp) 30 | ament_target_dependencies(controller ${THIS_PACKAGE_DEPENDS}) 31 | 32 | install(TARGETS 33 | controller 34 | DESTINATION lib/${PROJECT_NAME} 35 | ) 36 | 37 | install(DIRECTORY 38 | launch 39 | DESTINATION share/${PROJECT_NAME}/ 40 | ) 41 | 42 | if(BUILD_TESTING) 43 | find_package(ament_lint_auto REQUIRED) 44 | set(ament_cmake_copyright_FOUND TRUE) 45 | set(ament_cmake_cpplint_FOUND TRUE) 46 | ament_lint_auto_find_test_dependencies() 47 | endif() 48 | 49 | ament_package() -------------------------------------------------------------------------------- /peg_in_hole/launch/peg_in_hole.launch.py: -------------------------------------------------------------------------------- 1 | import os 2 | from launch import LaunchDescription 3 | from launch_ros.actions import Node 4 | from launch.actions import RegisterEventHandler 5 | from launch.event_handlers import OnProcessStart, OnProcessExit 6 | from ament_index_python.packages import get_package_share_directory 7 | from moveit_configs_utils import MoveItConfigsBuilder 8 | 9 | def generate_launch_description(): 10 | 11 | moveit_config = ( 12 | MoveItConfigsBuilder("moveit_resources_panda") 13 | .robot_description( 14 | file_path="config/panda.urdf.xacro", 15 | mappings={ 16 | "ros2_control_hardware_type": "mujoco" 17 | }, 18 | ) 19 | .robot_description_semantic(file_path="config/panda.srdf") 20 | .trajectory_execution(file_path="config/gripper_moveit_controllers.yaml") 21 | .planning_pipelines(pipelines=["pilz_industrial_motion_planner"]) 22 | .to_moveit_configs() 23 | ) 24 | 25 | move_group_capabilities = { 26 | "capabilities": "pilz_industrial_motion_planner/MoveGroupSequenceAction pilz_industrial_motion_planner/MoveGroupSequenceService" 27 | } 28 | controller_node = Node( 29 | package="peg_in_hole", 30 | executable="controller", 31 | output="screen", 32 | parameters=[ 33 | moveit_config.robot_description, 34 | moveit_config.robot_description_semantic, 35 | moveit_config.robot_description_kinematics, 36 | moveit_config.joint_limits, 37 | {"use_sim_time": True} 38 | ], 39 | ) 40 | 41 | # Start the actual move_group node/action server 42 | move_group_node = Node( 43 | package="moveit_ros_move_group", 44 | executable="move_group", 45 | output="screen", 46 | parameters=[moveit_config.to_dict(), {"use_sim_time": True}, move_group_capabilities] 47 | ) 48 | 49 | # Static TF 50 | world2robot_tf_node = Node( 51 | package="tf2_ros", 52 | executable="static_transform_publisher", 53 | name="static_transform_publisher", 54 | output="log", 55 | arguments=["--frame-id", "world", "--child-frame-id", "panda_link0"], 56 | parameters=[{"use_sim_time": True}] 57 | ) 58 | 59 | # Publish TF 60 | robot_state_publisher = Node( 61 | package="robot_state_publisher", 62 | executable="robot_state_publisher", 63 | name="robot_state_publisher", 64 | output="both", 65 | parameters=[moveit_config.robot_description, {"use_sim_time": True}], 66 | ) 67 | 68 | # ros2_control config 69 | ros2_controllers_path = os.path.join( 70 | get_package_share_directory("moveit_resources_panda_moveit_config"), 71 | "config", 72 | "ros2_controllers.yaml", 73 | ) 74 | 75 | node_mujoco_ros2_control = Node( 76 | package='mujoco_ros2_control', 77 | executable='mujoco_ros2_control', 78 | output='screen', 79 | parameters=[ 80 | moveit_config.robot_description, 81 | ros2_controllers_path, 82 | {'mujoco_model_path':os.path.join(get_package_share_directory('panda_mujoco'), 'franka_emika_panda', 'scene.xml')}, 83 | {"use_sim_time": True} 84 | ] 85 | ) 86 | 87 | joint_state_broadcaster_spawner = Node( 88 | package="controller_manager", 89 | executable="spawner", 90 | arguments=[ 91 | "joint_state_broadcaster", 92 | "--controller-manager", 93 | "/controller_manager", 94 | ], 95 | ) 96 | 97 | panda_arm_controller_spawner = Node( 98 | package="controller_manager", 99 | executable="spawner", 100 | arguments=["panda_arm_controller", "-c", "/controller_manager"], 101 | ) 102 | 103 | panda_hand_controller_spawner = Node( 104 | package="controller_manager", 105 | executable="spawner", 106 | arguments=["panda_hand_controller", "-c", "/controller_manager"], 107 | ) 108 | 109 | ft_sensor_broadcaster_spawner = Node( 110 | package="controller_manager", 111 | executable="spawner", 112 | arguments=["force_torque_broadcaster", "-c", "/controller_manager"], 113 | ) 114 | 115 | admittance_controller_spawner = Node( 116 | package="controller_manager", 117 | executable="spawner", 118 | arguments=["admittance_controller", "-c", "/controller_manager"], 119 | ) 120 | 121 | return LaunchDescription( 122 | [ 123 | RegisterEventHandler( 124 | event_handler=OnProcessStart( 125 | target_action=node_mujoco_ros2_control, 126 | on_start=[joint_state_broadcaster_spawner], 127 | ) 128 | ), 129 | RegisterEventHandler( 130 | event_handler=OnProcessExit( 131 | target_action=joint_state_broadcaster_spawner, 132 | on_exit=[admittance_controller_spawner, panda_hand_controller_spawner,ft_sensor_broadcaster_spawner], 133 | ) 134 | ), 135 | RegisterEventHandler( 136 | event_handler=OnProcessExit( 137 | target_action=admittance_controller_spawner, 138 | on_exit=[panda_arm_controller_spawner], 139 | ) 140 | ), 141 | world2robot_tf_node, 142 | robot_state_publisher, 143 | move_group_node, 144 | node_mujoco_ros2_control, 145 | controller_node 146 | ] 147 | ) -------------------------------------------------------------------------------- /peg_in_hole/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 5 | 6 | peg_in_hole 7 | 0.1.0 8 | peg_in_hole 9 | 10 | Sangtaek Lee 11 | 12 | MIT 13 | 14 | Sangtaek Lee 15 | 16 | ament_cmake 17 | 18 | control_msgs 19 | controller_manager 20 | moveit 21 | moveit_ros_move_group 22 | moveit_configs_utils 23 | moveit_resources_panda_description 24 | moveit_resources_panda_moveit_config 25 | moveit_simple_controller_manager 26 | kinematics_interface_kdl 27 | position_controllers 28 | gripper_controllers 29 | admittance_controller 30 | moveit_planners_ompl 31 | pilz_industrial_motion_planner 32 | rviz2 33 | 34 | ament_lint_auto 35 | ament_lint_common 36 | 37 | 38 | ament_cmake 39 | 40 | -------------------------------------------------------------------------------- /peg_in_hole/src/controller.cpp: -------------------------------------------------------------------------------- 1 | 2 | #include 3 | #include 4 | #include 5 | #include 6 | #include 7 | 8 | using namespace std::chrono_literals; 9 | 10 | static const rclcpp::Logger LOGGER = rclcpp::get_logger("move_group_demo"); 11 | 12 | int main(int argc, char** argv) 13 | { 14 | rclcpp::init(argc, argv); 15 | rclcpp::NodeOptions node_options; 16 | node_options.automatically_declare_parameters_from_overrides(true); 17 | auto move_group_node = rclcpp::Node::make_shared("move_group_interface_tutorial", node_options); 18 | 19 | rclcpp::executors::MultiThreadedExecutor executor; 20 | executor.add_node(move_group_node); 21 | std::thread([&executor]() { executor.spin(); }).detach(); 22 | 23 | auto gripper_action_client = rclcpp_action::create_client( 24 | move_group_node, 25 | "/panda_hand_controller/gripper_cmd"); 26 | auto admittance_param_client = move_group_node->create_client("/admittance_controller/set_parameters"); 27 | 28 | auto service_client = move_group_node->create_client("/plan_sequence_path"); 29 | 30 | static const std::string PLANNING_GROUP = "panda_arm"; 31 | moveit::planning_interface::MoveGroupInterface move_group(move_group_node, PLANNING_GROUP); 32 | 33 | move_group.setPlanningPipelineId("pilz_industrial_motion_planner"); 34 | move_group.setPlannerId("PTP"); 35 | 36 | RCLCPP_INFO(LOGGER, "Planning pipeline: %s", move_group.getPlanningPipelineId().c_str()); 37 | RCLCPP_INFO(LOGGER, "Planner ID: %s", move_group.getPlannerId().c_str()); 38 | RCLCPP_INFO(LOGGER, "Planning frame: %s", move_group.getPlanningFrame().c_str()); 39 | RCLCPP_INFO(LOGGER, "End effector link: %s", move_group.getEndEffectorLink().c_str()); 40 | 41 | rclcpp::Rate(0.25).sleep(); 42 | 43 | if (!gripper_action_client->wait_for_action_server(std::chrono::seconds(10))) 44 | { 45 | RCLCPP_ERROR(LOGGER, "Action server not available after waiting"); 46 | rclcpp::shutdown(); 47 | } 48 | 49 | if (!admittance_param_client->wait_for_service(std::chrono::seconds(10))) 50 | { 51 | RCLCPP_ERROR(LOGGER, "Param server not available after waiting"); 52 | rclcpp::shutdown(); 53 | } 54 | 55 | if (!service_client->wait_for_service(std::chrono::seconds(10))) 56 | { 57 | RCLCPP_ERROR(LOGGER, "/plan_sequence_path server not available after waiting"); 58 | rclcpp::shutdown(); 59 | } 60 | 61 | auto gripper_goal_msg = control_msgs::action::GripperCommand::Goal(); 62 | auto send_goal_options = rclcpp_action::Client::SendGoalOptions(); 63 | 64 | gripper_goal_msg.command.position = 0.02; 65 | gripper_action_client->async_send_goal(gripper_goal_msg, send_goal_options); 66 | 67 | rclcpp::Rate(1).sleep(); 68 | 69 | geometry_msgs::msg::Pose target_pose; 70 | target_pose.orientation.w = 0; 71 | target_pose.orientation.x = -0.924; 72 | target_pose.orientation.y = 0.383; 73 | target_pose.orientation.z = 0; 74 | target_pose.position.x = 0.5; 75 | target_pose.position.y = 0.0; 76 | target_pose.position.z = 0.35; 77 | move_group.setPoseTarget(target_pose); 78 | move_group.move(); 79 | 80 | auto param_request = std::make_shared(); 81 | auto param = rcl_interfaces::msg::Parameter(); 82 | param.name = "admittance.selected_axes"; 83 | param.value.type = 6; 84 | param.value.bool_array_value = std::vector(6, false); 85 | param.value.bool_array_value.at(0) = true; 86 | param.value.bool_array_value.at(1) = true; 87 | param.value.bool_array_value.at(2) = true; 88 | param_request->parameters.push_back(param); 89 | admittance_param_client->async_send_request(param_request); 90 | 91 | rclcpp::Rate(1).sleep(); 92 | 93 | moveit_msgs::msg::MotionSequenceItem item1; 94 | item1.blend_radius = 0.0; 95 | 96 | item1.req.group_name = PLANNING_GROUP; 97 | item1.req.planner_id = "PTP"; 98 | item1.req.allowed_planning_time = 5.0; 99 | item1.req.max_velocity_scaling_factor = 0.05; 100 | item1.req.max_acceleration_scaling_factor = 0.05; 101 | 102 | moveit_msgs::msg::Constraints constraints_item1; 103 | moveit_msgs::msg::PositionConstraint pos_constraint_item1; 104 | pos_constraint_item1.header.frame_id = "panda_link0"; 105 | pos_constraint_item1.link_name = "panda_hand"; 106 | 107 | geometry_msgs::msg::PoseStamped pose_stamped; 108 | pose_stamped.header.frame_id = "panda_link0"; 109 | pose_stamped.pose = target_pose; 110 | pose_stamped.pose.position.z = 0.2; 111 | 112 | item1.req.goal_constraints.push_back(kinematic_constraints::constructGoalConstraints(std::string("panda_link7"), pose_stamped)); 113 | 114 | auto item2 = item1; 115 | item2.req.goal_constraints.clear(); 116 | pose_stamped.pose.position.x = 0.49; 117 | pose_stamped.pose.position.y = -0.005; 118 | item2.req.goal_constraints.push_back(kinematic_constraints::constructGoalConstraints(std::string("panda_link7"), pose_stamped)); 119 | 120 | auto item3 = item1; 121 | item3.req.goal_constraints.clear(); 122 | pose_stamped.pose.position.x = 0.475; 123 | pose_stamped.pose.position.y = -0.0075; 124 | item3.req.goal_constraints.push_back(kinematic_constraints::constructGoalConstraints(std::string("panda_link7"), pose_stamped)); 125 | 126 | auto service_request = std::make_shared(); 127 | service_request->request.items.push_back(item1); 128 | service_request->request.items.push_back(item2); 129 | service_request->request.items.push_back(item3); 130 | 131 | auto service_future = service_client->async_send_request(service_request); 132 | auto service_response = service_future.get(); 133 | 134 | moveit::planning_interface::MoveGroupInterface::Plan plan; 135 | 136 | if (service_response->response.error_code.val == moveit::planning_interface::MoveItErrorCode::SUCCESS) 137 | { 138 | plan.trajectory_ = service_response.get()->response.planned_trajectories[0]; 139 | } 140 | 141 | move_group.execute(plan); 142 | 143 | rclcpp::shutdown(); 144 | return 0; 145 | } --------------------------------------------------------------------------------