openarm_ros2/openarm_bimanual_moveit_config/config/ros2_controllers.yaml

85 lines
2.2 KiB
YAML
Raw Normal View History

# 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 config file is used by ros2_control
controller_manager:
ros__parameters:
update_rate: 100 # Hz
left_arm_controller:
type: joint_trajectory_controller/JointTrajectoryController
right_arm_controller:
type: joint_trajectory_controller/JointTrajectoryController
left_gripper_controller:
type: position_controllers/GripperActionController
right_gripper_controller:
type: position_controllers/GripperActionController
joint_state_broadcaster:
type: joint_state_broadcaster/JointStateBroadcaster
left_arm_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
command_interfaces:
- position
state_interfaces:
- position
- velocity
- effort
right_arm_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
command_interfaces:
- position
state_interfaces:
- position
- velocity
- effort
left_gripper_controller:
ros__parameters:
joints:
- openarm_left_finger_joint1
command_interfaces:
- position
state_interfaces:
- position
right_gripper_controller:
ros__parameters:
joints:
- openarm_right_finger_joint1
command_interfaces:
- position
state_interfaces:
- position