Reconfigured controllers with new URDF for v1.0 (#34)
This PR is made for new release and do not work with current v0.3 robot descriptions. Use for the ros2 control for quick arm control. Launch files spawn: - Robot state publisher - Controller manager with ros2_control - Joint state broadcaster - Robot controller (joint trajectory or forward position) - Gripper controller - RViz2 visualization --------- Co-authored-by: Thomason Zhou <t95zhou@uwaterloo.ca>
This commit is contained in:
parent
0e136a2b8b
commit
67a60a23ba
@ -17,7 +17,7 @@
|
||||
-->
|
||||
<package format="3">
|
||||
<name>openarm</name>
|
||||
<version>0.3.0</version>
|
||||
<version>1.0.0</version>
|
||||
<description>Metapackage for OpenArm</description>
|
||||
<maintainer email="t95zhou@uwaterloo.ca">Thomason Zhou</maintainer>
|
||||
<license>Apache-2.0</license>
|
||||
@ -28,7 +28,6 @@
|
||||
<exec_depend>openarm_bringup</exec_depend>
|
||||
<exec_depend>openarm_description</exec_depend>
|
||||
<exec_depend>openarm_hardware</exec_depend>
|
||||
|
||||
<test_depend>ament_lint_auto</test_depend>
|
||||
<test_depend>ament_lint_common</test_depend>
|
||||
|
||||
|
||||
@ -17,7 +17,7 @@
|
||||
-->
|
||||
<package format="3">
|
||||
<name>openarm_bimanual_moveit_config</name>
|
||||
<version>0.3.0</version>
|
||||
<version>1.0.0</version>
|
||||
<description>
|
||||
An automatically generated package with all the configuration and launch files for using the openarm_bimanual with the MoveIt Motion Planning Framework
|
||||
</description>
|
||||
|
||||
@ -1,4 +1,4 @@
|
||||
# Copyright 2025 Reazon Holdings, Inc.
|
||||
# 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.
|
||||
|
||||
@ -1,9 +1,32 @@
|
||||
## utils
|
||||
# OpenArm Bringup
|
||||
|
||||
init_can.sh \<device\> \<can interface\>
|
||||
This package provides launch files to bring up the OpenArm robot system.
|
||||
|
||||
e.g.
|
||||
```sh
|
||||
./init_can.sh/dev/ACM0 can0
|
||||
./init_can.sh/dev/ACM1 can1
|
||||
## Quick Start
|
||||
|
||||
Launch the OpenArm with v1.0 configuration and fake hardware:
|
||||
|
||||
```bash
|
||||
ros2 launch openarm_bringup openarm.launch.py arm_type:=v10 use_fake_hardware:=true
|
||||
```
|
||||
|
||||
## Launch Files
|
||||
|
||||
- `openarm.launch.py` - Single arm configuration
|
||||
- `openarm.bimanual.launch.py` - Dual arm configuration
|
||||
|
||||
## Key Parameters
|
||||
|
||||
- `arm_type` - Arm type (default: v10)
|
||||
- `use_fake_hardware` - Use fake hardware instead of real hardware (default: false)
|
||||
- `can_interface` - CAN interface to use (default: can0)
|
||||
- `robot_controller` - Controller type: `joint_trajectory_controller` or `forward_position_controller`
|
||||
|
||||
## What Gets Launched
|
||||
|
||||
- Robot state publisher
|
||||
- Controller manager with ros2_control
|
||||
- Joint state broadcaster
|
||||
- Robot controller (joint trajectory or forward position)
|
||||
- Gripper controller
|
||||
- RViz2 visualization
|
||||
|
||||
@ -1,58 +0,0 @@
|
||||
# Copyright (c) 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.
|
||||
|
||||
#
|
||||
# Source of this file are templates in
|
||||
# [RosTeamWorkspace](https://github.com/StoglRobotics/ros_team_workspace) repository.
|
||||
#
|
||||
|
||||
publisher_forward_position_controller:
|
||||
ros__parameters:
|
||||
|
||||
controller_name: "forward_position_controller"
|
||||
wait_sec_between_publish: 5
|
||||
|
||||
goal_names: ["pos1", "pos2", "pos3", "pos4"]
|
||||
pos1: [0.185, 0.185, 0.185, 0.185, 0.185, 0.185, 0.185]
|
||||
pos2: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
|
||||
pos3: [-0.185, -0.185, -0.185, -0.185, -0.185, -0.185, -0.185]
|
||||
pos4: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
|
||||
|
||||
|
||||
publisher_joint_trajectory_controller:
|
||||
ros__parameters:
|
||||
|
||||
controller_name: "joint_trajectory_controller"
|
||||
wait_sec_between_publish: 6
|
||||
repeat_the_same_goal: 1 # useful to simulate continuous inputs
|
||||
|
||||
goal_time_from_start: 3.0
|
||||
goal_names: ["pos1", "pos2", "pos3", "pos4"]
|
||||
pos1:
|
||||
positions: [0.185, 0.185, 0.185, 0.185, 0.185, 0.185, 0.185]
|
||||
pos2:
|
||||
positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
|
||||
pos3:
|
||||
positions: [-0.185, -0.185, -0.185, -0.185, -0.185, -0.185, -0.185]
|
||||
pos4:
|
||||
positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
|
||||
|
||||
joints:
|
||||
- rev1
|
||||
- rev2
|
||||
- rev3
|
||||
- rev4
|
||||
- rev5
|
||||
- rev6
|
||||
- rev7
|
||||
@ -0,0 +1,175 @@
|
||||
# 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
|
||||
state_interfaces:
|
||||
- position
|
||||
|
||||
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.01 # Defaults to 0.01
|
||||
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
|
||||
state_interfaces:
|
||||
- position
|
||||
|
||||
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.01 # Defaults to 0.01
|
||||
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
|
||||
@ -0,0 +1,124 @@
|
||||
/**:
|
||||
ros__parameters:
|
||||
update_rate: 100 # Hz
|
||||
|
||||
joint_state_broadcaster:
|
||||
type: joint_state_broadcaster/JointStateBroadcaster
|
||||
|
||||
left_joint_trajectory_controller:
|
||||
type: joint_trajectory_controller/JointTrajectoryController
|
||||
|
||||
right_joint_trajectory_controller:
|
||||
type: joint_trajectory_controller/JointTrajectoryController
|
||||
|
||||
left_forward_position_controller:
|
||||
type: forward_command_controller/ForwardCommandController
|
||||
|
||||
right_forward_position_controller:
|
||||
type: forward_command_controller/ForwardCommandController
|
||||
|
||||
left_gripper_controller:
|
||||
type: forward_command_controller/ForwardCommandController
|
||||
|
||||
right_gripper_controller:
|
||||
type: forward_command_controller/ForwardCommandController
|
||||
|
||||
/**/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
|
||||
state_interfaces:
|
||||
- position
|
||||
- velocity
|
||||
state_publish_rate: 100.0
|
||||
action_monitor_rate: 20.0
|
||||
allow_partial_joints_goal: false
|
||||
open_loop_control: false
|
||||
allow_integration_in_goal_trajectories: true
|
||||
constraints:
|
||||
stopped_velocity_tolerance: 0.01
|
||||
goal_time: 0.6
|
||||
openarm_left_joint1: {trajectory: 0.1, goal: 0.1}
|
||||
openarm_left_joint2: {trajectory: 0.1, goal: 0.1}
|
||||
openarm_left_joint3: {trajectory: 0.1, goal: 0.1}
|
||||
openarm_left_joint4: {trajectory: 0.1, goal: 0.1}
|
||||
openarm_left_joint5: {trajectory: 0.1, goal: 0.1}
|
||||
openarm_left_joint6: {trajectory: 0.1, goal: 0.1}
|
||||
openarm_left_joint7: {trajectory: 0.1, goal: 0.1}
|
||||
|
||||
/**/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
|
||||
state_interfaces:
|
||||
- position
|
||||
- velocity
|
||||
state_publish_rate: 100.0
|
||||
action_monitor_rate: 20.0
|
||||
allow_partial_joints_goal: false
|
||||
open_loop_control: false
|
||||
allow_integration_in_goal_trajectories: true
|
||||
constraints:
|
||||
stopped_velocity_tolerance: 0.01
|
||||
goal_time: 0.6
|
||||
openarm_right_joint1: {trajectory: 0.1, goal: 0.1}
|
||||
openarm_right_joint2: {trajectory: 0.1, goal: 0.1}
|
||||
openarm_right_joint3: {trajectory: 0.1, goal: 0.1}
|
||||
openarm_right_joint4: {trajectory: 0.1, goal: 0.1}
|
||||
openarm_right_joint5: {trajectory: 0.1, goal: 0.1}
|
||||
openarm_right_joint6: {trajectory: 0.1, goal: 0.1}
|
||||
openarm_right_joint7: {trajectory: 0.1, goal: 0.1}
|
||||
|
||||
/**/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
|
||||
|
||||
/**/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
|
||||
|
||||
/**/left_gripper_controller:
|
||||
ros__parameters:
|
||||
joints:
|
||||
- openarm_left_finger_joint1
|
||||
interface_name: position
|
||||
|
||||
/**/right_gripper_controller:
|
||||
ros__parameters:
|
||||
joints:
|
||||
- openarm_right_finger_joint1
|
||||
interface_name: position
|
||||
@ -1,4 +1,5 @@
|
||||
# Copyright (c) 2024 Stogl Robotics Consulting UG (haftungsbeschränkt)
|
||||
# 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.
|
||||
@ -12,13 +13,6 @@
|
||||
# See the License for the specific language governing permissions and
|
||||
# limitations under the License.
|
||||
|
||||
#
|
||||
# Source of this file are templates in
|
||||
# [RosTeamWorkspace](https://github.com/StoglRobotics/ros_team_workspace) repository.
|
||||
#
|
||||
# Author: Dr. Denis
|
||||
#
|
||||
|
||||
controller_manager:
|
||||
ros__parameters:
|
||||
update_rate: 100 # Hz
|
||||
@ -35,40 +29,52 @@ controller_manager:
|
||||
joint_trajectory_controller:
|
||||
type: joint_trajectory_controller/JointTrajectoryController
|
||||
|
||||
gripper_controller:
|
||||
type: position_controllers/GripperActionController
|
||||
|
||||
forward_position_controller:
|
||||
ros__parameters:
|
||||
joints:
|
||||
- rev1
|
||||
- rev2
|
||||
- rev3
|
||||
- rev4
|
||||
- rev5
|
||||
- rev6
|
||||
- rev7
|
||||
- openarm_joint1
|
||||
- openarm_joint2
|
||||
- openarm_joint3
|
||||
- openarm_joint4
|
||||
- openarm_joint5
|
||||
- openarm_joint6
|
||||
- openarm_joint7
|
||||
interface_name: position
|
||||
command_interfaces:
|
||||
- position
|
||||
state_interfaces:
|
||||
- position
|
||||
|
||||
|
||||
forward_velocity_controller:
|
||||
ros__parameters:
|
||||
joints:
|
||||
- rev1
|
||||
- rev2
|
||||
- rev3
|
||||
- rev4
|
||||
- rev5
|
||||
- rev6
|
||||
- rev7
|
||||
- openarm_joint1
|
||||
- openarm_joint2
|
||||
- openarm_joint3
|
||||
- openarm_joint4
|
||||
- openarm_joint5
|
||||
- openarm_joint6
|
||||
- openarm_joint7
|
||||
interface_name: velocity
|
||||
command_interfaces:
|
||||
- velocity
|
||||
state_interfaces:
|
||||
- velocity
|
||||
|
||||
joint_trajectory_controller:
|
||||
ros__parameters:
|
||||
joints:
|
||||
- rev1
|
||||
- rev2
|
||||
- rev3
|
||||
- rev4
|
||||
- rev5
|
||||
- rev6
|
||||
- rev7
|
||||
- openarm_joint1
|
||||
- openarm_joint2
|
||||
- openarm_joint3
|
||||
- openarm_joint4
|
||||
- openarm_joint5
|
||||
- openarm_joint6
|
||||
- openarm_joint7
|
||||
|
||||
command_interfaces:
|
||||
- position
|
||||
@ -82,3 +88,12 @@ joint_trajectory_controller:
|
||||
constraints:
|
||||
stopped_velocity_tolerance: 0.01 # Defaults to 0.01
|
||||
goal_time: 0.0 # Defaults to 0.0 (start immediately)
|
||||
|
||||
|
||||
gripper_controller:
|
||||
ros__parameters:
|
||||
joint: openarm_finger_joint1
|
||||
command_interfaces:
|
||||
- position
|
||||
state_interfaces:
|
||||
- position
|
||||
285
openarm_bringup/launch/openarm.bimanual.launch.py
Normal file
285
openarm_bringup/launch/openarm.bimanual.launch.py
Normal file
@ -0,0 +1,285 @@
|
||||
# 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.
|
||||
|
||||
import os
|
||||
import xacro
|
||||
|
||||
from ament_index_python.packages import get_package_share_directory
|
||||
|
||||
from launch import LaunchDescription, LaunchContext
|
||||
from launch.actions import DeclareLaunchArgument, RegisterEventHandler, TimerAction, OpaqueFunction
|
||||
from launch.event_handlers import OnProcessExit
|
||||
from launch.substitutions import (
|
||||
LaunchConfiguration,
|
||||
PathJoinSubstitution,
|
||||
)
|
||||
from launch_ros.actions import Node
|
||||
from launch_ros.substitutions import FindPackageShare
|
||||
|
||||
|
||||
def namespace_from_context(context, arm_prefix):
|
||||
arm_prefix_str = context.perform_substitution(arm_prefix)
|
||||
if arm_prefix_str:
|
||||
return arm_prefix_str.strip('/')
|
||||
return None
|
||||
|
||||
|
||||
def generate_robot_description(context: LaunchContext, description_package, description_file,
|
||||
arm_type, use_fake_hardware, right_can_interface, left_can_interface):
|
||||
"""Generate robot description using xacro processing."""
|
||||
|
||||
description_package_str = context.perform_substitution(description_package)
|
||||
description_file_str = context.perform_substitution(description_file)
|
||||
arm_type_str = context.perform_substitution(arm_type)
|
||||
use_fake_hardware_str = context.perform_substitution(use_fake_hardware)
|
||||
right_can_interface_str = context.perform_substitution(right_can_interface)
|
||||
left_can_interface_str = context.perform_substitution(left_can_interface)
|
||||
|
||||
xacro_path = os.path.join(
|
||||
get_package_share_directory(description_package_str),
|
||||
"urdf", "robot", description_file_str
|
||||
)
|
||||
|
||||
# Process xacro with required arguments
|
||||
robot_description = xacro.process_file(
|
||||
xacro_path,
|
||||
mappings={
|
||||
"arm_type": arm_type_str,
|
||||
"bimanual": "true",
|
||||
"use_fake_hardware": use_fake_hardware_str,
|
||||
"ros2_control": "true",
|
||||
"right_can_interface": right_can_interface_str,
|
||||
"left_can_interface": left_can_interface_str,
|
||||
}
|
||||
).toprettyxml(indent=" ")
|
||||
|
||||
return robot_description
|
||||
|
||||
|
||||
def robot_nodes_spawner(context: LaunchContext, description_package, description_file,
|
||||
arm_type, use_fake_hardware, controllers_file, right_can_interface, left_can_interface, arm_prefix):
|
||||
"""Spawn both robot state publisher and control nodes with shared robot description."""
|
||||
namespace = namespace_from_context(context, arm_prefix)
|
||||
|
||||
robot_description = generate_robot_description(
|
||||
context, description_package, description_file, arm_type, use_fake_hardware, right_can_interface, left_can_interface,
|
||||
)
|
||||
|
||||
controllers_file_str = context.perform_substitution(controllers_file)
|
||||
robot_description_param = {"robot_description": robot_description}
|
||||
|
||||
if namespace:
|
||||
controllers_file_str = controllers_file_str.replace(
|
||||
"openarm_v10_bimanual_controllers.yaml", "openarm_v10_bimanual_controllers_namespaced.yaml"
|
||||
)
|
||||
robot_state_pub_node = Node(
|
||||
package="robot_state_publisher",
|
||||
executable="robot_state_publisher",
|
||||
name="robot_state_publisher",
|
||||
output="screen",
|
||||
namespace=namespace,
|
||||
parameters=[robot_description_param],
|
||||
)
|
||||
|
||||
control_node = Node(
|
||||
package="controller_manager",
|
||||
executable="ros2_control_node",
|
||||
output="both",
|
||||
namespace=namespace,
|
||||
parameters=[robot_description_param, controllers_file_str],
|
||||
)
|
||||
|
||||
return [robot_state_pub_node, control_node]
|
||||
|
||||
|
||||
def controller_spawner(context: LaunchContext, robot_controller, arm_prefix):
|
||||
"""Spawn controller based on robot_controller argument."""
|
||||
namespace = namespace_from_context(context, arm_prefix)
|
||||
|
||||
controller_manager_ref = f"/{namespace}/controller_manager" if namespace else "/controller_manager"
|
||||
|
||||
robot_controller_str = context.perform_substitution(robot_controller)
|
||||
|
||||
if robot_controller_str == "forward_position_controller":
|
||||
robot_controller_left = "left_forward_position_controller"
|
||||
robot_controller_right = "right_forward_position_controller"
|
||||
elif robot_controller_str == "joint_trajectory_controller":
|
||||
robot_controller_left = "left_joint_trajectory_controller"
|
||||
robot_controller_right = "right_joint_trajectory_controller"
|
||||
else:
|
||||
raise ValueError(f"Unknown robot_controller: {robot_controller_str}")
|
||||
|
||||
robot_controller_spawner = Node(
|
||||
package="controller_manager",
|
||||
executable="spawner",
|
||||
namespace=namespace,
|
||||
arguments=[robot_controller_left,
|
||||
robot_controller_right, "-c", controller_manager_ref],
|
||||
)
|
||||
|
||||
return [robot_controller_spawner]
|
||||
|
||||
|
||||
def generate_launch_description():
|
||||
"""Generate launch description for OpenArm bimanual configuration."""
|
||||
|
||||
# Declare launch arguments
|
||||
declared_arguments = [
|
||||
DeclareLaunchArgument(
|
||||
"description_package",
|
||||
default_value="openarm_description",
|
||||
description="Description package with robot URDF/xacro files.",
|
||||
),
|
||||
DeclareLaunchArgument(
|
||||
"description_file",
|
||||
default_value="v10.urdf.xacro",
|
||||
description="URDF/XACRO description file with the robot.",
|
||||
),
|
||||
DeclareLaunchArgument(
|
||||
"arm_type",
|
||||
default_value="v10",
|
||||
description="Type of arm (e.g., v10).",
|
||||
),
|
||||
DeclareLaunchArgument(
|
||||
"use_fake_hardware",
|
||||
default_value="false",
|
||||
description="Use fake hardware instead of real hardware.",
|
||||
),
|
||||
DeclareLaunchArgument(
|
||||
"robot_controller",
|
||||
default_value="joint_trajectory_controller",
|
||||
choices=["forward_position_controller",
|
||||
"joint_trajectory_controller"],
|
||||
description="Robot controller to start.",
|
||||
),
|
||||
DeclareLaunchArgument(
|
||||
"runtime_config_package",
|
||||
default_value="openarm_bringup",
|
||||
description="Package with the controller's configuration in config folder.",
|
||||
),
|
||||
DeclareLaunchArgument(
|
||||
"arm_prefix",
|
||||
default_value="",
|
||||
description="Prefix for the arm for topic namespacing.",
|
||||
),
|
||||
DeclareLaunchArgument(
|
||||
"right_can_interface",
|
||||
default_value="can0",
|
||||
description="CAN interface to use for the right arm.",
|
||||
),
|
||||
DeclareLaunchArgument(
|
||||
"left_can_interface",
|
||||
default_value="can1",
|
||||
description="CAN interface to use for the left arm.",
|
||||
),
|
||||
DeclareLaunchArgument(
|
||||
"controllers_file",
|
||||
default_value="openarm_v10_bimanual_controllers.yaml",
|
||||
description="Controllers file(s) to use. Can be a single file or comma-separated list of files.",
|
||||
),
|
||||
]
|
||||
|
||||
# Initialize launch configurations
|
||||
description_package = LaunchConfiguration("description_package")
|
||||
description_file = LaunchConfiguration("description_file")
|
||||
arm_type = LaunchConfiguration("arm_type")
|
||||
use_fake_hardware = LaunchConfiguration("use_fake_hardware")
|
||||
robot_controller = LaunchConfiguration("robot_controller")
|
||||
runtime_config_package = LaunchConfiguration("runtime_config_package")
|
||||
controllers_file = LaunchConfiguration("controllers_file")
|
||||
rightcan_interface = LaunchConfiguration("right_can_interface")
|
||||
left_can_interface = LaunchConfiguration("left_can_interface")
|
||||
arm_prefix = LaunchConfiguration("arm_prefix")
|
||||
|
||||
controllers_file = PathJoinSubstitution(
|
||||
[FindPackageShare(runtime_config_package), "config",
|
||||
"v10_controllers", controllers_file]
|
||||
)
|
||||
|
||||
robot_nodes_spawner_func = OpaqueFunction(
|
||||
function=robot_nodes_spawner,
|
||||
args=[description_package, description_file, arm_type,
|
||||
use_fake_hardware, controllers_file, rightcan_interface, left_can_interface, arm_prefix]
|
||||
)
|
||||
|
||||
rviz_config_file = PathJoinSubstitution(
|
||||
[FindPackageShare(description_package), "rviz",
|
||||
"bimanual.rviz"]
|
||||
)
|
||||
|
||||
rviz_node = Node(
|
||||
package="rviz2",
|
||||
executable="rviz2",
|
||||
name="rviz2",
|
||||
output="log",
|
||||
arguments=["-d", rviz_config_file],
|
||||
)
|
||||
|
||||
# Joint state broadcaster spawner
|
||||
joint_state_broadcaster_spawner = OpaqueFunction(
|
||||
function=lambda context: [Node(
|
||||
package="controller_manager",
|
||||
executable="spawner",
|
||||
namespace=namespace_from_context(context, arm_prefix),
|
||||
arguments=["joint_state_broadcaster",
|
||||
"--controller-manager",
|
||||
f"/{namespace_from_context(context, arm_prefix)}/controller_manager" if namespace_from_context(context, arm_prefix) else "/controller_manager"],
|
||||
)]
|
||||
)
|
||||
|
||||
# Controller spawners
|
||||
controller_spawner_func = OpaqueFunction(
|
||||
function=controller_spawner,
|
||||
args=[robot_controller, arm_prefix]
|
||||
)
|
||||
|
||||
gripper_controller_spawner = OpaqueFunction(
|
||||
function=lambda context: [Node(
|
||||
package="controller_manager",
|
||||
executable="spawner",
|
||||
namespace=namespace_from_context(context, arm_prefix),
|
||||
arguments=["left_gripper_controller",
|
||||
"right_gripper_controller", "-c",
|
||||
f"/{namespace_from_context(context, arm_prefix)}/controller_manager" if namespace_from_context(context, arm_prefix) else "/controller_manager"],
|
||||
)]
|
||||
)
|
||||
|
||||
# Timing and sequencing
|
||||
LAUNCH_DELAY_SECONDS = 1.0
|
||||
delayed_joint_state_broadcaster = TimerAction(
|
||||
period=LAUNCH_DELAY_SECONDS,
|
||||
actions=[joint_state_broadcaster_spawner],
|
||||
)
|
||||
|
||||
delayed_robot_controller = TimerAction(
|
||||
period=LAUNCH_DELAY_SECONDS,
|
||||
actions=[controller_spawner_func],
|
||||
)
|
||||
delayed_gripper_controller = TimerAction(
|
||||
period=LAUNCH_DELAY_SECONDS,
|
||||
actions=[gripper_controller_spawner],
|
||||
)
|
||||
|
||||
return LaunchDescription(
|
||||
declared_arguments + [
|
||||
robot_nodes_spawner_func,
|
||||
rviz_node,
|
||||
] +
|
||||
[
|
||||
delayed_joint_state_broadcaster,
|
||||
delayed_robot_controller,
|
||||
delayed_gripper_controller,
|
||||
]
|
||||
)
|
||||
@ -1,4 +1,4 @@
|
||||
# Copyright 2025 Reazon Holdings, Inc.
|
||||
# Copyright 2025 Enactic, Inc.
|
||||
# Copyright 2024 Stogl Robotics Consulting UG (haftungsbeschränkt)
|
||||
#
|
||||
# Licensed under the Apache License, Version 2.0 (the "License");
|
||||
@ -13,19 +13,15 @@
|
||||
# See the License for the specific language governing permissions and
|
||||
# limitations under the License.
|
||||
|
||||
#
|
||||
# Source of this file are templates in
|
||||
# [RosTeamWorkspace](https://github.com/StoglRobotics/ros_team_workspace) repository.
|
||||
#
|
||||
# Author: Dr. Denis
|
||||
#
|
||||
import os
|
||||
import xacro
|
||||
|
||||
from launch import LaunchDescription
|
||||
from launch.actions import DeclareLaunchArgument, RegisterEventHandler, TimerAction
|
||||
from launch.event_handlers import OnProcessExit, OnProcessStart
|
||||
from ament_index_python.packages import get_package_share_directory
|
||||
|
||||
from launch import LaunchDescription, LaunchContext
|
||||
from launch.actions import DeclareLaunchArgument, RegisterEventHandler, TimerAction, OpaqueFunction
|
||||
from launch.event_handlers import OnProcessExit
|
||||
from launch.substitutions import (
|
||||
Command,
|
||||
FindExecutable,
|
||||
LaunchConfiguration,
|
||||
PathJoinSubstitution,
|
||||
)
|
||||
@ -33,126 +29,155 @@ from launch_ros.actions import Node
|
||||
from launch_ros.substitutions import FindPackageShare
|
||||
|
||||
|
||||
def generate_robot_description(context: LaunchContext, description_package, description_file,
|
||||
arm_type, use_fake_hardware, can_interface, arm_prefix):
|
||||
"""Generate robot description using xacro processing."""
|
||||
|
||||
# Substitute launch configuration values
|
||||
description_package_str = context.perform_substitution(description_package)
|
||||
description_file_str = context.perform_substitution(description_file)
|
||||
arm_type_str = context.perform_substitution(arm_type)
|
||||
use_fake_hardware_str = context.perform_substitution(use_fake_hardware)
|
||||
can_interface_str = context.perform_substitution(can_interface)
|
||||
arm_prefix_str = context.perform_substitution(arm_prefix)
|
||||
|
||||
# Build xacro file path
|
||||
xacro_path = os.path.join(
|
||||
get_package_share_directory(description_package_str),
|
||||
"urdf", "robot", description_file_str
|
||||
)
|
||||
|
||||
# Process xacro with required arguments
|
||||
robot_description = xacro.process_file(
|
||||
xacro_path,
|
||||
mappings={
|
||||
"arm_type": arm_type_str,
|
||||
"bimanual": "false",
|
||||
"use_fake_hardware": use_fake_hardware_str,
|
||||
"ros2_control": "true",
|
||||
"can_interface": can_interface_str,
|
||||
"arm_prefix": arm_prefix_str,
|
||||
}
|
||||
).toprettyxml(indent=" ")
|
||||
|
||||
return robot_description
|
||||
|
||||
|
||||
def robot_nodes_spawner(context: LaunchContext, description_package, description_file,
|
||||
arm_type, use_fake_hardware, controllers_file, can_interface, arm_prefix):
|
||||
"""Spawn both robot state publisher and control nodes with shared robot description."""
|
||||
|
||||
# Generate robot description once
|
||||
robot_description = generate_robot_description(
|
||||
context, description_package, description_file, arm_type, use_fake_hardware, can_interface, arm_prefix
|
||||
)
|
||||
|
||||
# Get controllers file path
|
||||
controllers_file_str = context.perform_substitution(controllers_file)
|
||||
robot_description_param = {"robot_description": robot_description}
|
||||
|
||||
# Robot state publisher node
|
||||
robot_state_pub_node = Node(
|
||||
package="robot_state_publisher",
|
||||
executable="robot_state_publisher",
|
||||
name="robot_state_publisher",
|
||||
output="screen",
|
||||
parameters=[robot_description_param],
|
||||
)
|
||||
|
||||
# Control node
|
||||
control_node = Node(
|
||||
package="controller_manager",
|
||||
executable="ros2_control_node",
|
||||
output="both",
|
||||
parameters=[robot_description_param, controllers_file_str],
|
||||
)
|
||||
|
||||
return [robot_state_pub_node, control_node]
|
||||
|
||||
|
||||
def generate_launch_description():
|
||||
# Declare arguments
|
||||
declared_arguments = []
|
||||
declared_arguments.append(
|
||||
DeclareLaunchArgument(
|
||||
"runtime_config_package",
|
||||
default_value="openarm_bringup",
|
||||
description='Package with the controller\'s configuration in "config" folder. \
|
||||
Usually the argument is not set, it enables use of a custom setup.',
|
||||
)
|
||||
)
|
||||
declared_arguments.append(
|
||||
DeclareLaunchArgument(
|
||||
"controllers_file",
|
||||
default_value="openarm_controllers.yaml",
|
||||
description="YAML file with the controllers configuration.",
|
||||
)
|
||||
)
|
||||
declared_arguments.append(
|
||||
"""Generate launch description for OpenArm unimanual configuration."""
|
||||
|
||||
# Declare launch arguments
|
||||
declared_arguments = [
|
||||
DeclareLaunchArgument(
|
||||
"description_package",
|
||||
default_value="openarm_description",
|
||||
description="Description package with robot URDF/xacro files. Usually the argument \
|
||||
is not set, it enables use of a custom description.",
|
||||
)
|
||||
)
|
||||
declared_arguments.append(
|
||||
description="Description package with robot URDF/xacro files.",
|
||||
),
|
||||
DeclareLaunchArgument(
|
||||
"description_file",
|
||||
default_value="openarm.urdf.xacro",
|
||||
default_value="v10.urdf.xacro",
|
||||
description="URDF/XACRO description file with the robot.",
|
||||
)
|
||||
)
|
||||
declared_arguments.append(
|
||||
),
|
||||
DeclareLaunchArgument(
|
||||
"prefix",
|
||||
default_value='""',
|
||||
description="Prefix of the joint names, useful for \
|
||||
multi-robot setup. If changed than also joint names in the controllers' configuration \
|
||||
have to be updated.",
|
||||
)
|
||||
)
|
||||
declared_arguments.append(
|
||||
"arm_type",
|
||||
default_value="v10",
|
||||
description="Type of arm (e.g., v10).",
|
||||
),
|
||||
DeclareLaunchArgument(
|
||||
"hardware_type",
|
||||
default_value="real",
|
||||
description="Hardware interface type: 'real', 'sim' (MuJoCo), or 'mock'",
|
||||
)
|
||||
)
|
||||
declared_arguments.append(
|
||||
DeclareLaunchArgument(
|
||||
"mock_sensor_commands",
|
||||
"use_fake_hardware",
|
||||
default_value="false",
|
||||
description="Enable mock command interfaces for sensors used for simple simulations. \
|
||||
Used only if 'hardware_type' parameter is 'mock'.",
|
||||
)
|
||||
)
|
||||
declared_arguments.append(
|
||||
description="Use fake hardware instead of real hardware.",
|
||||
),
|
||||
DeclareLaunchArgument(
|
||||
"robot_controller",
|
||||
default_value="joint_trajectory_controller",
|
||||
choices=["forward_position_controller",
|
||||
"joint_trajectory_controller"],
|
||||
description="Robot controller to start.",
|
||||
)
|
||||
)
|
||||
),
|
||||
DeclareLaunchArgument(
|
||||
"runtime_config_package",
|
||||
default_value="openarm_bringup",
|
||||
description="Package with the controller's configuration in config folder.",
|
||||
),
|
||||
DeclareLaunchArgument(
|
||||
"arm_prefix",
|
||||
default_value="",
|
||||
description="Prefix for the arm.",
|
||||
),
|
||||
DeclareLaunchArgument(
|
||||
"can_interface",
|
||||
default_value="can0",
|
||||
description="CAN interface to use.",
|
||||
),
|
||||
DeclareLaunchArgument(
|
||||
"controllers_file",
|
||||
default_value="openarm_v10_controllers.yaml",
|
||||
description="Controllers file(s) to use. Can be a single file or comma-separated list of files.",
|
||||
),
|
||||
]
|
||||
|
||||
# Initialize Arguments
|
||||
runtime_config_package = LaunchConfiguration("runtime_config_package")
|
||||
controllers_file = LaunchConfiguration("controllers_file")
|
||||
# Initialize launch configurations
|
||||
description_package = LaunchConfiguration("description_package")
|
||||
description_file = LaunchConfiguration("description_file")
|
||||
prefix = LaunchConfiguration("prefix")
|
||||
hardware_type = LaunchConfiguration("hardware_type")
|
||||
mock_sensor_commands = LaunchConfiguration("mock_sensor_commands")
|
||||
arm_type = LaunchConfiguration("arm_type")
|
||||
use_fake_hardware = LaunchConfiguration("use_fake_hardware")
|
||||
robot_controller = LaunchConfiguration("robot_controller")
|
||||
|
||||
# Get URDF via xacro
|
||||
robot_description_content = Command(
|
||||
[
|
||||
PathJoinSubstitution([FindExecutable(name="xacro")]),
|
||||
" ",
|
||||
PathJoinSubstitution(
|
||||
[FindPackageShare(description_package),
|
||||
"urdf", description_file]
|
||||
),
|
||||
" ",
|
||||
"prefix:=",
|
||||
prefix,
|
||||
" ",
|
||||
"hardware_type:=",
|
||||
hardware_type,
|
||||
" ",
|
||||
"mock_sensor_commands:=",
|
||||
mock_sensor_commands,
|
||||
" ",
|
||||
]
|
||||
runtime_config_package = LaunchConfiguration("runtime_config_package")
|
||||
controllers_file = LaunchConfiguration("controllers_file")
|
||||
can_interface = LaunchConfiguration("can_interface")
|
||||
arm_prefix = LaunchConfiguration("arm_prefix")
|
||||
# Configuration file paths
|
||||
controllers_file = PathJoinSubstitution(
|
||||
[FindPackageShare(runtime_config_package), "config",
|
||||
"v10_controllers", controllers_file]
|
||||
)
|
||||
|
||||
robot_description = {"robot_description": robot_description_content}
|
||||
|
||||
robot_controllers = PathJoinSubstitution(
|
||||
[FindPackageShare(runtime_config_package), "config", controllers_file]
|
||||
# Robot nodes spawner (both state publisher and control)
|
||||
robot_nodes_spawner_func = OpaqueFunction(
|
||||
function=robot_nodes_spawner,
|
||||
args=[description_package, description_file, arm_type,
|
||||
use_fake_hardware, controllers_file, can_interface, arm_prefix]
|
||||
)
|
||||
# RViz configuration
|
||||
rviz_config_file = PathJoinSubstitution(
|
||||
[FindPackageShare(description_package), "rviz", "openarm.rviz"]
|
||||
[FindPackageShare(description_package), "rviz",
|
||||
"robot_description.rviz"]
|
||||
)
|
||||
|
||||
control_node = Node(
|
||||
package="controller_manager",
|
||||
executable="ros2_control_node",
|
||||
output="both",
|
||||
parameters=[robot_description, robot_controllers],
|
||||
)
|
||||
robot_state_pub_node = Node(
|
||||
package="robot_state_publisher",
|
||||
executable="robot_state_publisher",
|
||||
output="both",
|
||||
parameters=[robot_description],
|
||||
)
|
||||
rviz_node = Node(
|
||||
package="rviz2",
|
||||
executable="rviz2",
|
||||
@ -161,94 +186,50 @@ def generate_launch_description():
|
||||
arguments=["-d", rviz_config_file],
|
||||
)
|
||||
|
||||
# Joint state broadcaster spawner
|
||||
joint_state_broadcaster_spawner = Node(
|
||||
package="controller_manager",
|
||||
executable="spawner",
|
||||
arguments=[
|
||||
"joint_state_broadcaster",
|
||||
"--controller-manager",
|
||||
"/controller_manager",
|
||||
],
|
||||
arguments=["joint_state_broadcaster",
|
||||
"--controller-manager", "/controller_manager"],
|
||||
)
|
||||
|
||||
robot_controller_names = [robot_controller]
|
||||
robot_controller_spawners = []
|
||||
for controller in robot_controller_names:
|
||||
robot_controller_spawners += [
|
||||
Node(
|
||||
# Controller spawners
|
||||
robot_controller_spawner = Node(
|
||||
package="controller_manager",
|
||||
executable="spawner",
|
||||
arguments=[controller, "-c", "/controller_manager"],
|
||||
arguments=[robot_controller, "-c", "/controller_manager"],
|
||||
)
|
||||
]
|
||||
|
||||
inactive_robot_controller_names = []
|
||||
inactive_robot_controller_spawners = []
|
||||
for controller in inactive_robot_controller_names:
|
||||
inactive_robot_controller_spawners += [
|
||||
Node(
|
||||
gripper_controller_spawner = Node(
|
||||
package="controller_manager",
|
||||
executable="spawner",
|
||||
arguments=[controller, "-c",
|
||||
"/controller_manager", "--inactive"],
|
||||
arguments=["gripper_controller", "-c", "/controller_manager"],
|
||||
)
|
||||
]
|
||||
|
||||
# Delay loading and activation of `joint_state_broadcaster` after start of ros2_control_node
|
||||
delay_joint_state_broadcaster_spawner_after_ros2_control_node = (
|
||||
RegisterEventHandler(
|
||||
event_handler=OnProcessStart(
|
||||
target_action=control_node,
|
||||
on_start=[
|
||||
TimerAction(
|
||||
period=3.0,
|
||||
# Timing and sequencing
|
||||
delayed_joint_state_broadcaster = TimerAction(
|
||||
period=1.0,
|
||||
actions=[joint_state_broadcaster_spawner],
|
||||
),
|
||||
],
|
||||
)
|
||||
)
|
||||
)
|
||||
|
||||
# Delay loading and activation of robot_controller_names after `joint_state_broadcaster`
|
||||
delay_robot_controller_spawners_after_joint_state_broadcaster_spawner = []
|
||||
for i, controller in enumerate(robot_controller_spawners):
|
||||
delay_robot_controller_spawners_after_joint_state_broadcaster_spawner += [
|
||||
RegisterEventHandler(
|
||||
event_handler=OnProcessExit(
|
||||
target_action=(
|
||||
robot_controller_spawners[i - 1]
|
||||
if i > 0
|
||||
else joint_state_broadcaster_spawner
|
||||
),
|
||||
on_exit=[controller],
|
||||
delayed_robot_controller = TimerAction(
|
||||
period=1.0,
|
||||
actions=[robot_controller_spawner],
|
||||
)
|
||||
delayed_gripper_controller = TimerAction(
|
||||
period=1.0,
|
||||
actions=[gripper_controller_spawner],
|
||||
)
|
||||
]
|
||||
|
||||
# Delay start of inactive_robot_controller_names after other controllers
|
||||
delay_inactive_robot_controller_spawners_after_joint_state_broadcaster_spawner = []
|
||||
for i, controller in enumerate(inactive_robot_controller_spawners):
|
||||
delay_inactive_robot_controller_spawners_after_joint_state_broadcaster_spawner += [
|
||||
RegisterEventHandler(
|
||||
event_handler=OnProcessExit(
|
||||
target_action=(
|
||||
inactive_robot_controller_spawners[i - 1]
|
||||
if i > 0
|
||||
else robot_controller_spawners[-1]
|
||||
),
|
||||
on_exit=[controller],
|
||||
)
|
||||
)
|
||||
]
|
||||
|
||||
return LaunchDescription(
|
||||
declared_arguments
|
||||
+ [
|
||||
control_node,
|
||||
robot_state_pub_node,
|
||||
declared_arguments + [
|
||||
robot_nodes_spawner_func,
|
||||
rviz_node,
|
||||
delay_joint_state_broadcaster_spawner_after_ros2_control_node,
|
||||
] +
|
||||
[
|
||||
delayed_joint_state_broadcaster,
|
||||
delayed_robot_controller,
|
||||
delayed_gripper_controller,
|
||||
]
|
||||
+ delay_robot_controller_spawners_after_joint_state_broadcaster_spawner
|
||||
+ delay_inactive_robot_controller_spawners_after_joint_state_broadcaster_spawner
|
||||
)
|
||||
|
||||
@ -1,51 +0,0 @@
|
||||
# Copyright 2025 Reazon Holdings, 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.
|
||||
|
||||
#
|
||||
# Source of this file are templates in
|
||||
# [RosTeamWorkspace](https://github.com/StoglRobotics/ros_team_workspace) repository.
|
||||
#
|
||||
# Author: Dr. Denis
|
||||
#
|
||||
|
||||
from launch import LaunchDescription
|
||||
from launch.substitutions import PathJoinSubstitution
|
||||
from launch_ros.actions import Node
|
||||
from launch_ros.substitutions import FindPackageShare
|
||||
|
||||
|
||||
def generate_launch_description():
|
||||
position_goals = PathJoinSubstitution(
|
||||
[
|
||||
FindPackageShare("openarm_bringup"),
|
||||
"config",
|
||||
"test_goal_publishers_config.yaml",
|
||||
]
|
||||
)
|
||||
|
||||
return LaunchDescription(
|
||||
[
|
||||
Node(
|
||||
package="ros2_controllers_test_nodes",
|
||||
executable="publisher_forward_position_controller",
|
||||
name="publisher_forward_position_controller",
|
||||
parameters=[position_goals],
|
||||
output={
|
||||
"stdout": "screen",
|
||||
"stderr": "screen",
|
||||
},
|
||||
)
|
||||
]
|
||||
)
|
||||
@ -1,51 +0,0 @@
|
||||
# Copyright 2025 Reazon Holdings, 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.
|
||||
|
||||
#
|
||||
# Source of this file are templates in
|
||||
# [RosTeamWorkspace](https://github.com/StoglRobotics/ros_team_workspace) repository.
|
||||
#
|
||||
# Author: Dr. Denis
|
||||
#
|
||||
|
||||
from launch import LaunchDescription
|
||||
from launch.substitutions import PathJoinSubstitution
|
||||
from launch_ros.actions import Node
|
||||
from launch_ros.substitutions import FindPackageShare
|
||||
|
||||
|
||||
def generate_launch_description():
|
||||
position_goals = PathJoinSubstitution(
|
||||
[
|
||||
FindPackageShare("openarm_bringup"),
|
||||
"config",
|
||||
"test_goal_publishers_config.yaml",
|
||||
]
|
||||
)
|
||||
|
||||
return LaunchDescription(
|
||||
[
|
||||
Node(
|
||||
package="ros2_controllers_test_nodes",
|
||||
executable="publisher_joint_trajectory_controller",
|
||||
name="publisher_joint_trajectory_controller",
|
||||
parameters=[position_goals],
|
||||
output={
|
||||
"stdout": "screen",
|
||||
"stderr": "screen",
|
||||
},
|
||||
)
|
||||
]
|
||||
)
|
||||
@ -1,7 +1,7 @@
|
||||
<?xml version="1.0"?>
|
||||
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
|
||||
<!--
|
||||
Copyright 2025 Reazon Holdings, Inc.
|
||||
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.
|
||||
@ -17,7 +17,7 @@
|
||||
-->
|
||||
<package format="3">
|
||||
<name>openarm_bringup</name>
|
||||
<version>0.3.0</version>
|
||||
<version>1.0.0</version>
|
||||
<description>Bringup script for OpenArm</description>
|
||||
<maintainer email="t95zhou@uwaterloo.ca">Thomason Zhou</maintainer>
|
||||
<license>Apache-2.0</license>
|
||||
|
||||
295
openarm_bringup/rviz/bimanual.rviz
Normal file
295
openarm_bringup/rviz/bimanual.rviz
Normal file
@ -0,0 +1,295 @@
|
||||
Panels:
|
||||
- Class: rviz_common/Displays
|
||||
Help Height: 138
|
||||
Name: Displays
|
||||
Property Tree Widget:
|
||||
Expanded:
|
||||
- /Global Options1
|
||||
- /Status1
|
||||
- /RobotModel1
|
||||
Splitter Ratio: 0.5
|
||||
Tree Height: 685
|
||||
- Class: rviz_common/Selection
|
||||
Name: Selection
|
||||
- Class: rviz_common/Tool Properties
|
||||
Expanded:
|
||||
- /2D Goal Pose1
|
||||
- /Publish Point1
|
||||
Name: Tool Properties
|
||||
Splitter Ratio: 0.5886790156364441
|
||||
- Class: rviz_common/Views
|
||||
Expanded:
|
||||
- /Current View1
|
||||
Name: Views
|
||||
Splitter Ratio: 0.5
|
||||
- Class: rviz_common/Time
|
||||
Experimental: false
|
||||
Name: Time
|
||||
SyncMode: 0
|
||||
SyncSource: ""
|
||||
Visualization Manager:
|
||||
Class: ""
|
||||
Displays:
|
||||
- Alpha: 0.5
|
||||
Cell Size: 1
|
||||
Class: rviz_default_plugins/Grid
|
||||
Color: 160; 160; 164
|
||||
Enabled: true
|
||||
Line Style:
|
||||
Line Width: 0.029999999329447746
|
||||
Value: Lines
|
||||
Name: Grid
|
||||
Normal Cell Count: 0
|
||||
Offset:
|
||||
X: 0
|
||||
Y: 0
|
||||
Z: 0
|
||||
Plane: XY
|
||||
Plane Cell Count: 10
|
||||
Reference Frame: <Fixed Frame>
|
||||
Value: true
|
||||
- Alpha: 1
|
||||
Class: rviz_default_plugins/RobotModel
|
||||
Collision Enabled: false
|
||||
Description File: ""
|
||||
Description Source: Topic
|
||||
Description Topic:
|
||||
Depth: 5
|
||||
Durability Policy: Volatile
|
||||
History Policy: Keep Last
|
||||
Reliability Policy: Reliable
|
||||
Value: /robot_description
|
||||
Enabled: true
|
||||
Links:
|
||||
All Links Enabled: true
|
||||
Expand Joint Details: false
|
||||
Expand Link Details: false
|
||||
Expand Tree: false
|
||||
Link Tree Style: Links in Alphabetic Order
|
||||
openarm_body_link0:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
openarm_left_hand:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
openarm_left_hand_tcp:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
openarm_left_left_finger:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
openarm_left_link0:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
openarm_left_link1:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
openarm_left_link2:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
openarm_left_link3:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
openarm_left_link4:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
openarm_left_link5:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
openarm_left_link6:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
openarm_left_link7:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
openarm_left_link8:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
openarm_left_right_finger:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
openarm_right_hand:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
openarm_right_hand_tcp:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
openarm_right_left_finger:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
openarm_right_link0:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
openarm_right_link1:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
openarm_right_link2:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
openarm_right_link3:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
openarm_right_link4:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
openarm_right_link5:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
openarm_right_link6:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
openarm_right_link7:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
openarm_right_link8:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
openarm_right_right_finger:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
world:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Mass Properties:
|
||||
Inertia: false
|
||||
Mass: false
|
||||
Name: RobotModel
|
||||
TF Prefix: ""
|
||||
Update Interval: 0
|
||||
Value: true
|
||||
Visual Enabled: true
|
||||
Enabled: true
|
||||
Global Options:
|
||||
Background Color: 48; 48; 48
|
||||
Fixed Frame: world
|
||||
Frame Rate: 30
|
||||
Name: root
|
||||
Tools:
|
||||
- Class: rviz_default_plugins/Interact
|
||||
Hide Inactive Objects: true
|
||||
- Class: rviz_default_plugins/MoveCamera
|
||||
- Class: rviz_default_plugins/Select
|
||||
- Class: rviz_default_plugins/FocusCamera
|
||||
- Class: rviz_default_plugins/Measure
|
||||
Line color: 128; 128; 0
|
||||
- Class: rviz_default_plugins/SetInitialPose
|
||||
Covariance x: 0.25
|
||||
Covariance y: 0.25
|
||||
Covariance yaw: 0.06853891909122467
|
||||
Topic:
|
||||
Depth: 5
|
||||
Durability Policy: Volatile
|
||||
History Policy: Keep Last
|
||||
Reliability Policy: Reliable
|
||||
Value: /initialpose
|
||||
- Class: rviz_default_plugins/SetGoal
|
||||
Topic:
|
||||
Depth: 5
|
||||
Durability Policy: Volatile
|
||||
History Policy: Keep Last
|
||||
Reliability Policy: Reliable
|
||||
Value: /goal_pose
|
||||
- Class: rviz_default_plugins/PublishPoint
|
||||
Single click: true
|
||||
Topic:
|
||||
Depth: 5
|
||||
Durability Policy: Volatile
|
||||
History Policy: Keep Last
|
||||
Reliability Policy: Reliable
|
||||
Value: /clicked_point
|
||||
Transformation:
|
||||
Current:
|
||||
Class: rviz_default_plugins/TF
|
||||
Value: true
|
||||
Views:
|
||||
Current:
|
||||
Class: rviz_default_plugins/Orbit
|
||||
Distance: 2.1203250885009766
|
||||
Enable Stereo Rendering:
|
||||
Stereo Eye Separation: 0.05999999865889549
|
||||
Stereo Focal Distance: 1
|
||||
Swap Stereo Eyes: false
|
||||
Value: false
|
||||
Focal Point:
|
||||
X: 0
|
||||
Y: 0
|
||||
Z: 0
|
||||
Focal Shape Fixed Size: true
|
||||
Focal Shape Size: 0.05000000074505806
|
||||
Invert Z Axis: false
|
||||
Name: Current View
|
||||
Near Clip Distance: 0.009999999776482582
|
||||
Pitch: 0.410398006439209
|
||||
Target Frame: <Fixed Frame>
|
||||
Value: Orbit (rviz)
|
||||
Yaw: 0.07539838552474976
|
||||
Saved: ~
|
||||
Window Geometry:
|
||||
Displays:
|
||||
collapsed: false
|
||||
Height: 1162
|
||||
Hide Left Dock: false
|
||||
Hide Right Dock: false
|
||||
QMainWindow State: 000000ff00000000fd0000000400000000000001da0000039bfc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b000000ab00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c00610079007301000000690000039b0000017800fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000014d0000039bfc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a0056006900650077007301000000690000039b0000012300fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000081400000051fc0100000002fb0000000800540069006d00650100000000000008140000046000fffffffb0000000800540069006d00650100000000000004500000000000000000000004d50000039b00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
|
||||
Selection:
|
||||
collapsed: false
|
||||
Time:
|
||||
collapsed: false
|
||||
Tool Properties:
|
||||
collapsed: false
|
||||
Views:
|
||||
collapsed: false
|
||||
Width: 2068
|
||||
X: 60
|
||||
Y: 64
|
||||
@ -1,30 +0,0 @@
|
||||
#!/bin/bash
|
||||
#
|
||||
# Copyright 2025 Reazon Holdings, 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 script initializes the CAN interface on a Linux system.
|
||||
|
||||
echo Using CAN interface: $1 with $2
|
||||
|
||||
if [ ! -e $1 ]; then
|
||||
echo "Device $1 does not exist."
|
||||
exit 1
|
||||
fi
|
||||
|
||||
bitrate=1000000
|
||||
sudo slcand -o -c -s8 $1
|
||||
sudo ip link set $2 type can bitrate $bitrate
|
||||
sudo ip link set $2 up
|
||||
sudo ip link show $2
|
||||
@ -17,7 +17,7 @@
|
||||
-->
|
||||
<package format="3">
|
||||
<name>openarm_hardware</name>
|
||||
<version>0.3.0</version>
|
||||
<version>1.0.0</version>
|
||||
<description>Hardware interface for OpenArm</description>
|
||||
<maintainer email="t95zhou@uwaterloo.ca">Thomason Zhou</maintainer>
|
||||
<license>Apache-2.0</license>
|
||||
|
||||
Loading…
Reference in New Issue
Block a user