Skip to content
Draft
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 3 additions & 0 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -2,3 +2,6 @@
.DS_Store
.vscode/
__pycache__/
**/out/
.venv/
venv/
1 change: 1 addition & 0 deletions openarm/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,7 @@
<exec_depend>openarm_bringup</exec_depend>
<exec_depend>openarm_description</exec_depend>
<exec_depend>openarm_hardware</exec_depend>
<exec_depend>openarm_bimanual_moveit_config</exec_depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>

Expand Down
252 changes: 0 additions & 252 deletions openarm_bimanual_moveit_config/config/openarm_bimanual.srdf

This file was deleted.

Original file line number Diff line number Diff line change
@@ -0,0 +1,143 @@
<?xml version="1.0" encoding="UTF-8"?>
<!--
 Copyright 2025 Enactic, Inc.

 Licensed under the Apache License, Version 2.0 (the "License");
 you may not use this file except in compliance with the License.
 You may obtain a copy of the License at

  http://www.apache.org/licenses/LICENSE-2.0

 Unless required by applicable law or agreed to in writing, software
 distributed under the License is distributed on an "AS IS" BASIS,
 WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
 See the License for the specific language governing permissions and
 limitations under the License.
-->

<!--This does not replace URDF, and is not an extension of URDF.
This is a format for representing semantic information about the robot structure.
A URDF file must exist for this robot as well, where the joints and the links that are referenced are defined
-->
<robot name="openarm">
<!--GROUPS: Representation of a set of joints and links. This can be useful for specifying DOF to plan for, defining arms, end effectors, etc-->
<!--LINKS: When a link is specified, the parent joint of that link (if it exists) is automatically included-->
<!--JOINTS: When a joint is specified, the child link of that joint (which will always exist) is automatically included-->
<!--CHAINS: When a chain is specified, all the links along the chain (including endpoints) are included in the group. Additionally, all the joints that are parents to included links are also included. This means that joints along the chain and the parent joint of the base link are included in the group-->
<!--SUBGROUPS: Groups can also be formed by referencing to already defined group names-->
<group name="left_arm">
<joint name="openarm_left_joint1"/>
<joint name="openarm_left_joint2"/>
<joint name="openarm_left_joint3"/>
<joint name="openarm_left_joint4"/>
<joint name="openarm_left_joint5"/>
<joint name="openarm_left_joint6"/>
<joint name="openarm_left_joint7"/>
</group>
<group name="right_arm">
<joint name="openarm_right_joint1"/>
<joint name="openarm_right_joint2"/>
<joint name="openarm_right_joint3"/>
<joint name="openarm_right_joint4"/>
<joint name="openarm_right_joint5"/>
<joint name="openarm_right_joint6"/>
<joint name="openarm_right_joint7"/>
</group> <!--GROUP STATES: Purpose: Define a named state for a particular group, in terms of joint values. This is useful to define states like 'folded arms'-->
<group name="left_gripper">
<joint name="openarm_left_finger_joint1"/>
</group>
<group name="right_gripper">
<joint name="openarm_right_finger_joint1"/>
</group>
<group_state name="home" group="left_arm">
<joint name="openarm_left_joint1" value="0"/>
<joint name="openarm_left_joint2" value="0"/>
<joint name="openarm_left_joint3" value="0"/>
<joint name="openarm_left_joint4" value="0"/>
<joint name="openarm_left_joint5" value="0"/>
<joint name="openarm_left_joint6" value="0"/>
<joint name="openarm_left_joint7" value="0"/>
</group_state>
<group_state name="home" group="right_arm">
<joint name="openarm_right_joint1" value="0"/>
<joint name="openarm_right_joint2" value="0"/>
<joint name="openarm_right_joint3" value="0"/>
<joint name="openarm_right_joint4" value="0"/>
<joint name="openarm_right_joint5" value="0"/>
<joint name="openarm_right_joint6" value="0"/>
<joint name="openarm_right_joint7" value="0"/>
</group_state>
<group_state name="hands_up" group="left_arm">
<joint name="openarm_left_joint1" value="0"/>
<joint name="openarm_left_joint2" value="0"/>
<joint name="openarm_left_joint3" value="0"/>
<joint name="openarm_left_joint4" value="2"/>
<joint name="openarm_left_joint5" value="0"/>
<joint name="openarm_left_joint6" value="0"/>
<joint name="openarm_left_joint7" value="0"/>
</group_state>
<group_state name="hands_up" group="right_arm">
<joint name="openarm_right_joint1" value="0"/>
<joint name="openarm_right_joint2" value="0"/>
<joint name="openarm_right_joint3" value="0"/>
<joint name="openarm_right_joint4" value="2"/>
<joint name="openarm_right_joint5" value="0"/>
<joint name="openarm_right_joint6" value="0"/>
<joint name="openarm_right_joint7" value="0"/>
</group_state>
<group_state name="closed" group="left_gripper">
<joint name="openarm_left_finger_joint1" value="0"/>
</group_state>
<group_state name="closed" group="right_gripper">
<joint name="openarm_right_finger_joint1" value="0"/>
</group_state>
<group_state name="half closed" group="left_gripper">
<joint name="openarm_left_finger_joint1" value="0.022"/>
</group_state>
<group_state name="half_closed" group="right_gripper">
<joint name="openarm_right_finger_joint1" value="0.022"/>
</group_state>
<group_state name="open" group="left_gripper">
<joint name="openarm_left_finger_joint1" value="0.044"/>
</group_state>
<group_state name="open" group="right_gripper">
<joint name="openarm_right_finger_joint1" value="0.044"/>
</group_state>
<!--END EFFECTOR: Purpose: Represent information about an end effector.-->
<end_effector name="left_ee" parent_link="openarm_left_hand" group="left_gripper"/>
<end_effector name="right_ee" parent_link="openarm_right_hand" group="right_gripper"/>
<!--PASSIVE JOINT: Purpose: this element is used to mark joints that are not actuated-->
<passive_joint name="openarm_left_finger_joint2"/>
<passive_joint name="openarm_right_finger_joint2"/>

<!--DISABLE COLLISIONS: By default it is assumed that any link of the robot could potentially come into collision with any other link in the robot. This tag disables collision checking between a specified pair of links. -->
<disable_collisions link1="openarm_body_link0" link2="openarm_left_link0" reason="Adjacent"/>
<disable_collisions link1="openarm_body_link0" link2="openarm_right_link0" reason="Adjacent"/>
<disable_collisions link1="openarm_left_hand" link2="openarm_left_left_finger" reason="Adjacent"/>
<disable_collisions link1="openarm_left_hand" link2="openarm_left_link7" reason="Adjacent"/>
<disable_collisions link1="openarm_left_hand" link2="openarm_left_right_finger" reason="Adjacent"/>
<disable_collisions link1="openarm_left_left_finger" link2="openarm_left_right_finger" reason="Adjacent"/>
<disable_collisions link1="openarm_left_link0" link2="openarm_left_link1" reason="Adjacent"/>
<disable_collisions link1="openarm_left_link1" link2="openarm_left_link2" reason="Adjacent"/>
<disable_collisions link1="openarm_left_link2" link2="openarm_left_link3" reason="Adjacent"/>
<disable_collisions link1="openarm_left_link3" link2="openarm_left_link4" reason="Adjacent"/>
<disable_collisions link1="openarm_left_link4" link2="openarm_left_link5" reason="Adjacent"/>
<disable_collisions link1="openarm_left_link5" link2="openarm_left_link6" reason="Adjacent"/>
<disable_collisions link1="openarm_left_link6" link2="openarm_left_link7" reason="Adjacent"/>
<disable_collisions link1="openarm_right_hand" link2="openarm_right_left_finger" reason="Adjacent"/>
<disable_collisions link1="openarm_right_hand" link2="openarm_right_link7" reason="Adjacent"/>
<disable_collisions link1="openarm_right_hand" link2="openarm_right_right_finger" reason="Adjacent"/>
<disable_collisions link1="openarm_right_left_finger" link2="openarm_right_right_finger" reason="Adjacent"/>
<disable_collisions link1="openarm_right_link0" link2="openarm_right_link1" reason="Adjacent"/>
<disable_collisions link1="openarm_right_link1" link2="openarm_right_link2" reason="Adjacent"/>
<disable_collisions link1="openarm_right_link2" link2="openarm_right_link3" reason="Adjacent"/>
<disable_collisions link1="openarm_right_link3" link2="openarm_right_link4" reason="Adjacent"/>
<disable_collisions link1="openarm_right_link4" link2="openarm_right_link5" reason="Adjacent"/>
<disable_collisions link1="openarm_right_link5" link2="openarm_right_link6" reason="Adjacent"/>
<disable_collisions link1="openarm_right_link6" link2="openarm_right_link7" reason="Adjacent"/>
<disable_collisions link1="openarm_left_link7" link2="openarm_left_left_finger" reason="Adjacent"/>
<disable_collisions link1="openarm_left_link7" link2="openarm_left_right_finger" reason="Adjacent"/>
<disable_collisions link1="openarm_right_link7" link2="openarm_right_left_finger" reason="Adjacent"/>
<disable_collisions link1="openarm_right_link7" link2="openarm_right_right_finger" reason="Adjacent"/>

</robot>
Original file line number Diff line number Diff line change
Expand Up @@ -17,15 +17,11 @@
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="openarm_bimanual">
<xacro:arg name="initial_positions_file" default="initial_positions.yaml" />
<xacro:arg name="hardware_type" default="real" />

<!-- Import openarm_bimanual urdf file -->
<xacro:include filename="$(find openarm_description)/urdf/robot/v10.urdf.xacro" />

<xacro:include filename="$(find openarm_description)/urdf/robot/v10/v10.urdf.xacro" />
<link name="base_link"/>
<joint name="world_to_pedestal" type="fixed">
<parent link="world"/>
<child link="base_link"/>
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/>
</joint>

</robot>
</robot>
104 changes: 104 additions & 0 deletions openarm_bimanual_moveit_config/config/openarm_v2.0/joint_limits.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,104 @@
# Copyright 2025 Enactic, Inc.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.

# joint_limits.yaml allows the dynamics properties specified in the URDF to be overwritten or augmented as needed

# For beginners, we downscale velocity and acceleration limits.
# You can always specify higher scaling factors (<= 1.0) in your motion requests. # Increase the values below to 1.0 to always move at maximum speed.
default_velocity_scaling_factor: 0.1
default_acceleration_scaling_factor: 0.1

# Specific joint properties can be changed with the keys [max_position, min_position, max_velocity, max_acceleration]
# Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits]
joint_limits:
openarm_left_finger_joint1:
has_velocity_limits: true
max_velocity: 10.0
has_acceleration_limits: false
max_acceleration: 0.0
openarm_left_joint1:
has_velocity_limits: true
max_velocity: 16.754666
has_acceleration_limits: false
max_acceleration: 0.0
openarm_left_joint2:
has_velocity_limits: true
max_velocity: 16.754666
has_acceleration_limits: false
max_acceleration: 0.0
openarm_left_joint3:
has_velocity_limits: true
max_velocity: 5.445426
has_acceleration_limits: false
max_acceleration: 0.0
openarm_left_joint4:
has_velocity_limits: true
max_velocity: 5.445426
has_acceleration_limits: false
max_acceleration: 0.0
openarm_left_joint5:
has_velocity_limits: true
max_velocity: 20.943946
has_acceleration_limits: false
max_acceleration: 0.0
openarm_left_joint6:
has_velocity_limits: true
max_velocity: 20.943946
has_acceleration_limits: false
max_acceleration: 0.0
openarm_left_joint7:
has_velocity_limits: true
max_velocity: 20.943946
has_acceleration_limits: false
max_acceleration: 0.0
openarm_right_finger_joint1:
has_velocity_limits: true
max_velocity: 10.0
has_acceleration_limits: false
max_acceleration: 0.0
openarm_right_joint1:
has_velocity_limits: true
max_velocity: 16.754666
has_acceleration_limits: false
max_acceleration: 0.0
openarm_right_joint2:
has_velocity_limits: true
max_velocity: 16.754666
has_acceleration_limits: false
max_acceleration: 0.0
openarm_right_joint3:
has_velocity_limits: true
max_velocity: 5.445426
has_acceleration_limits: false
max_acceleration: 0.0
openarm_right_joint4:
has_velocity_limits: true
max_velocity: 5.445426
has_acceleration_limits: false
max_acceleration: 0.0
openarm_right_joint5:
has_velocity_limits: true
max_velocity: 20.943946
has_acceleration_limits: false
max_acceleration: 0.0
openarm_right_joint6:
has_velocity_limits: true
max_velocity: 20.943946
has_acceleration_limits: false
max_acceleration: 0.0
openarm_right_joint7:
has_velocity_limits: true
max_velocity: 20.943946
has_acceleration_limits: false
max_acceleration: 0.0
Original file line number Diff line number Diff line change
Expand Up @@ -12,21 +12,13 @@
# See the License for the specific language governing permissions and
# limitations under the License.

# Default initial positions for openarm's ros2_control fake system
initial_positions:
openarm_left_finger_joint1: 0
openarm_left_joint1: 0
openarm_left_joint2: 0
openarm_left_joint3: 0
openarm_left_joint4: 0
openarm_left_joint5: 0
openarm_left_joint6: 0
openarm_left_joint7: 0
openarm_right_finger_joint1: 0
openarm_right_joint1: 0
openarm_right_joint2: 0
openarm_right_joint3: 0
openarm_right_joint4: 0
openarm_right_joint5: 0
openarm_right_joint6: 0
openarm_right_joint7: 0

left_arm:
kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin
kinematics_solver_search_resolution: 0.0050000000000000001
kinematics_solver_timeout: 0.0050000000000000001

right_arm:
kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin
kinematics_solver_search_resolution: 0.0050000000000000001
kinematics_solver_timeout: 0.0050000000000000001
Loading