Skip to content
Open
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
2 changes: 2 additions & 0 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -2,3 +2,5 @@
.DS_Store
.vscode/
__pycache__/
.github/
openarm_description/
59 changes: 59 additions & 0 deletions dev/修改記錄.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,59 @@
# 註冊新硬件接口
openarm_hardware.xml
```
class name="openarm_hardware/OpenArm_OYHW"
```


## Markdown 內容樣式範例

### 標題
```markdown
# 一級標題
## 二級標題
### 三級標題
```

### 列表
```markdown
- 無序列表項目 1
- 無序列表項目 2

1. 有序列表項目 1
2. 有序列表項目 2
```

### 程式碼區塊
```markdown
`行內程式碼`

​```python
def hello():
print("Hello World")
​```
```

### 連結與圖片
```markdown
[連結文字](https://example.com)
![圖片描述](image.png)
```

### 表格
```markdown
| 欄位1 | 欄位2 | 欄位3 |
|-------|-------|-------|
| 內容1 | 內容2 | 內容3 |
```

### 引用
```markdown
> 這是一段引用文字
```

### 強調
```markdown
**粗體文字**
*斜體文字*
~~刪除線~~
```
4 changes: 2 additions & 2 deletions openarm.repos
Original file line number Diff line number Diff line change
Expand Up @@ -15,5 +15,5 @@
repositories:
openarm_can:
type: git
url: https://github.com/enactic/openarm_can.git
version: main
url: git@github.com:openvmi/openarm_can.git
Copy link

Copilot AI Mar 12, 2026

Choose a reason for hiding this comment

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

Switching the .repos entry to an SSH URL (git@github.com:...) makes vcs import fail for users/CI without GitHub SSH keys configured. Prefer an HTTPS URL, and consider pinning to a tag/commit SHA instead of a moving branch to keep builds reproducible.

Suggested change
url: git@github.com:openvmi/openarm_can.git
url: https://github.com/openvmi/openarm_can.git

Copilot uses AI. Check for mistakes.
version: oy_openarm_can
4 changes: 2 additions & 2 deletions openarm_bimanual_moveit_config/config/openarm_bimanual.srdf
Original file line number Diff line number Diff line change
Expand Up @@ -104,8 +104,8 @@
<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"/>
<end_effector name="left_ee" parent_link="openarm_left_link7" group="left_gripper" parent_group="left_arm"/>
<end_effector name="right_ee" parent_link="openarm_right_link7" group="right_gripper" parent_group="right_arm"/>
<!--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"/>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,8 +19,7 @@
<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/oy.urdf.xacro" />
<link name="base_link"/>
<joint name="world_to_pedestal" type="fixed">
<parent link="world"/>
Expand Down
2 changes: 2 additions & 0 deletions openarm_bimanual_moveit_config/config/ros2_controllers.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,7 @@ left_arm_controller:
- openarm_left_joint7
command_interfaces:
- position
- velocity
state_interfaces:
- position
- velocity
Expand All @@ -61,6 +62,7 @@ right_arm_controller:
- openarm_right_joint7
command_interfaces:
- position
- velocity
state_interfaces:
- position
- velocity
Expand Down
43 changes: 39 additions & 4 deletions openarm_bimanual_moveit_config/launch/demo.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -139,16 +139,51 @@ def controller_spawner(context: LaunchContext, robot_controller):


def generate_launch_description():
"""Generate launch description for OpenARM bimanual robot with MoveIt2 configuration.

This function creates a complete launch description that sets up a dual-arm (bimanual)
OpenARM robot system with MoveIt2 motion planning capabilities.

The launch description includes:
- Robot description and state publisher nodes via OpaqueFunction
- Joint state broadcaster for publishing joint states
- Arm trajectory controllers (forward position or joint trajectory)
- Gripper controllers for both left and right grippers
- MoveIt2 move_group node for motion planning
- RViz2 visualization with MoveIt configuration

Launch Arguments:
description_package (str): Package containing robot description. Default: "openarm_description"
description_file (str): URDF/xacro file name. Default: "oy.urdf.xacro"
arm_type (str): Type of arm configuration. Default: "oy"
use_fake_hardware (str): Whether to use simulated hardware. Default: "false"
robot_controller (str): Controller type to use. Default: "joint_trajectory_controller"
Choices: "forward_position_controller", "joint_trajectory_controller"
runtime_config_package (str): Package with runtime configs. Default: "openarm_bringup"
arm_prefix (str): Prefix for arm links/joints. Default: ""
right_can_interface (str): CAN interface for right arm. Default: "can0"
left_can_interface (str): CAN interface for left arm. Default: "can1"
controllers_file (str): Controllers YAML config file. Default: "openarm_oy_bimanual_controllers.yaml"

Note:
OpaqueFunction is used to defer node creation until launch time, allowing
dynamic configuration based on launch arguments that are only resolved
at runtime. This is necessary when node parameters depend on substitutions
that cannot be evaluated during launch file parsing.

Returns:
LaunchDescription: Complete launch description for the bimanual robot system.
"""
declared_arguments = [
DeclareLaunchArgument(
"description_package",
default_value="openarm_description",
),
DeclareLaunchArgument(
"description_file",
default_value="v10.urdf.xacro",
default_value="oy.urdf.xacro",
),
DeclareLaunchArgument("arm_type", default_value="v10"),
DeclareLaunchArgument("arm_type", default_value="oy"),
DeclareLaunchArgument("use_fake_hardware", default_value="false"),
DeclareLaunchArgument(
"robot_controller",
Expand All @@ -164,7 +199,7 @@ def generate_launch_description():
DeclareLaunchArgument("left_can_interface", default_value="can1"),
DeclareLaunchArgument(
"controllers_file",
default_value="openarm_v10_bimanual_controllers.yaml",
default_value="openarm_oy_bimanual_controllers.yaml",
),
]

Expand All @@ -181,7 +216,7 @@ def generate_launch_description():

controllers_file = PathJoinSubstitution(
[FindPackageShare(runtime_config_package), "config",
"v10_controllers", controllers_file]
"oy_controllers", controllers_file]
)

robot_nodes_spawner_func = OpaqueFunction(
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,179 @@
# Copyright 2025 Enactic, Inc.
# Copyright 2024 Stogl Robotics Consulting UG (haftungsbeschränkt)
#
# 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.

controller_manager:
ros__parameters:
update_rate: 100 # Hz

joint_state_broadcaster:
type: joint_state_broadcaster/JointStateBroadcaster

left_forward_position_controller:
type: forward_command_controller/ForwardCommandController

left_forward_velocity_controller:
type: forward_command_controller/ForwardCommandController

left_joint_trajectory_controller:
type: joint_trajectory_controller/JointTrajectoryController

left_gripper_controller:
type: position_controllers/GripperActionController

right_forward_position_controller:
type: forward_command_controller/ForwardCommandController

right_forward_velocity_controller:
type: forward_command_controller/ForwardCommandController

right_joint_trajectory_controller:
type: joint_trajectory_controller/JointTrajectoryController

right_gripper_controller:
type: position_controllers/GripperActionController


left_forward_position_controller:
ros__parameters:
joints:
- openarm_left_joint1
- openarm_left_joint2
- openarm_left_joint3
- openarm_left_joint4
- openarm_left_joint5
- openarm_left_joint6
- openarm_left_joint7
interface_name: position
command_interfaces:
- position
state_interfaces:
- position

left_forward_velocity_controller:
ros__parameters:
joints:
- openarm_left_joint1
- openarm_left_joint2
- openarm_left_joint3
- openarm_left_joint4
- openarm_left_joint5
- openarm_left_joint6
- openarm_left_joint7
interface_name: velocity
command_interfaces:
- velocity
state_interfaces:
- velocity

left_joint_trajectory_controller:
ros__parameters:
joints:
- openarm_left_joint1
- openarm_left_joint2
- openarm_left_joint3
- openarm_left_joint4
- openarm_left_joint5
- openarm_left_joint6
- openarm_left_joint7
interface_name: position
command_interfaces:
- position
- velocity
state_interfaces:
- position
- velocity

state_publish_rate: 50.0 # Defaults to 50
action_monitor_rate: 50.0 # Defaults to 20

allow_partial_joints_goal: false # Defaults to false
constraints:
stopped_velocity_tolerance: 0.05 # Relaxed for real motor velocity jitter
goal_time: 0.0 # Defaults to 0.0 (start immediately)

left_gripper_controller:
ros__parameters:
joint: openarm_left_finger_joint1
command_interfaces:
- position
state_interfaces:
- position


right_forward_position_controller:
ros__parameters:
joints:
- openarm_right_joint1
- openarm_right_joint2
- openarm_right_joint3
- openarm_right_joint4
- openarm_right_joint5
- openarm_right_joint6
- openarm_right_joint7
interface_name: position
command_interfaces:
- position
state_interfaces:
- position

right_forward_velocity_controller:
ros__parameters:
joints:
- openarm_right_joint1
- openarm_right_joint2
- openarm_right_joint3
- openarm_right_joint4
- openarm_right_joint5
- openarm_right_joint6
- openarm_right_joint7
interface_name: velocity
command_interfaces:
- velocity
state_interfaces:
- velocity

right_joint_trajectory_controller:
ros__parameters:
joints:
- openarm_right_joint1
- openarm_right_joint2
- openarm_right_joint3
- openarm_right_joint4
- openarm_right_joint5
- openarm_right_joint6
- openarm_right_joint7
interface_name: position
command_interfaces:
- position
- velocity
state_interfaces:
- position
- velocity

state_publish_rate: 50.0 # Defaults to 50
action_monitor_rate: 50.0 # Defaults to 20

allow_partial_joints_goal: false # Defaults to false
constraints:
stopped_velocity_tolerance: 0.05 # Relaxed for real motor velocity jitter
goal_time: 0.0 # Defaults to 0.0 (start immediately)

right_gripper_controller:
ros__parameters:
joint: openarm_right_finger_joint1
command_interfaces:
- position
state_interfaces:
- position
Loading
Loading