urdf/ros2_control: add control gain config (#38)
To make gain configurable.
This commit is contained in:
parent
c5a1e337c2
commit
73ca62f3e4
41
config/arm/v10/control_gains.yaml
Normal file
41
config/arm/v10/control_gains.yaml
Normal file
@ -0,0 +1,41 @@
|
||||
# Copyright 2026 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.
|
||||
|
||||
joint1:
|
||||
kp: 70.0
|
||||
kd: 2.75
|
||||
|
||||
joint2:
|
||||
kp: 70.0
|
||||
kd: 2.5
|
||||
|
||||
joint3:
|
||||
kp: 70.0
|
||||
kd: 2.0
|
||||
|
||||
joint4:
|
||||
kp: 60.0
|
||||
kd: 2.0
|
||||
|
||||
joint5:
|
||||
kp: 10.0
|
||||
kd: 0.7
|
||||
|
||||
joint6:
|
||||
kp: 10.0
|
||||
kd: 0.6
|
||||
|
||||
joint7:
|
||||
kp: 10.0
|
||||
kd: 0.5
|
||||
@ -3,6 +3,7 @@
|
||||
<xacro:macro name="openarm_robot"
|
||||
params="arm_type
|
||||
joint_limits
|
||||
control_gains
|
||||
kinematics
|
||||
kinematics_link
|
||||
kinematics_offset
|
||||
@ -102,6 +103,7 @@
|
||||
<xacro:if value="${ros2_control}">
|
||||
<xacro:openarm_bimanual_ros2_control
|
||||
arm_type="${arm_type}"
|
||||
control_gains="${control_gains}"
|
||||
left_can_interface="${left_can_interface}"
|
||||
right_can_interface="${right_can_interface}"
|
||||
use_fake_hardware="${use_fake_hardware}"
|
||||
@ -160,6 +162,7 @@
|
||||
|
||||
<xacro:openarm_arm_ros2_control
|
||||
arm_type="${arm_type}"
|
||||
control_gains="${control_gains}"
|
||||
arm_prefix="${arm_prefix_modified}"
|
||||
can_interface="${can_interface}"
|
||||
use_fake_hardware="${use_fake_hardware}"
|
||||
|
||||
@ -52,7 +52,8 @@
|
||||
<xacro:openarm_robot
|
||||
arm_type="v10"
|
||||
body_type="v10"
|
||||
joint_limits="${xacro.load_yaml('$(find openarm_description)/config//arm/v10/joint_limits.yaml')}"
|
||||
joint_limits="${xacro.load_yaml('$(find openarm_description)/config/arm/v10/joint_limits.yaml')}"
|
||||
control_gains="${xacro.load_yaml('$(find openarm_description)/config/arm/v10/control_gains.yaml')}"
|
||||
inertials="${xacro.load_yaml('$(find openarm_description)/config/arm/v10/inertials.yaml')}"
|
||||
kinematics="${xacro.load_yaml('$(find openarm_description)/config/arm/v10/kinematics.yaml')}"
|
||||
kinematics_link="${xacro.load_yaml('$(find openarm_description)/config/arm/v10/kinematics_link.yaml')}"
|
||||
|
||||
@ -3,6 +3,7 @@
|
||||
|
||||
<xacro:macro name="openarm_bimanual_ros2_control"
|
||||
params="arm_type
|
||||
control_gains
|
||||
left_can_interface:=^|can1
|
||||
right_can_interface:=^|can0
|
||||
use_fake_hardware:=^|false
|
||||
@ -27,6 +28,20 @@
|
||||
<param name="arm_prefix">${left_arm_prefix}</param>
|
||||
<param name="hand">${hand}</param>
|
||||
<param name="can_fd">${can_fd}</param>
|
||||
<param name="kp1">${control_gains['joint1']['kp']}</param>
|
||||
<param name="kp2">${control_gains['joint2']['kp']}</param>
|
||||
<param name="kp3">${control_gains['joint3']['kp']}</param>
|
||||
<param name="kp4">${control_gains['joint4']['kp']}</param>
|
||||
<param name="kp5">${control_gains['joint5']['kp']}</param>
|
||||
<param name="kp6">${control_gains['joint6']['kp']}</param>
|
||||
<param name="kp7">${control_gains['joint7']['kp']}</param>
|
||||
<param name="kd1">${control_gains['joint1']['kd']}</param>
|
||||
<param name="kd2">${control_gains['joint2']['kd']}</param>
|
||||
<param name="kd3">${control_gains['joint3']['kd']}</param>
|
||||
<param name="kd4">${control_gains['joint4']['kd']}</param>
|
||||
<param name="kd5">${control_gains['joint5']['kd']}</param>
|
||||
<param name="kd6">${control_gains['joint6']['kd']}</param>
|
||||
<param name="kd7">${control_gains['joint7']['kd']}</param>
|
||||
</xacro:unless>
|
||||
</hardware>
|
||||
|
||||
@ -78,6 +93,20 @@
|
||||
<param name="arm_prefix">${right_arm_prefix}</param>
|
||||
<param name="hand">${hand}</param>
|
||||
<param name="can_fd">${can_fd}</param>
|
||||
<param name="kp1">${control_gains['joint1']['kp']}</param>
|
||||
<param name="kp2">${control_gains['joint2']['kp']}</param>
|
||||
<param name="kp3">${control_gains['joint3']['kp']}</param>
|
||||
<param name="kp4">${control_gains['joint4']['kp']}</param>
|
||||
<param name="kp5">${control_gains['joint5']['kp']}</param>
|
||||
<param name="kp6">${control_gains['joint6']['kp']}</param>
|
||||
<param name="kp7">${control_gains['joint7']['kp']}</param>
|
||||
<param name="kd1">${control_gains['joint1']['kd']}</param>
|
||||
<param name="kd2">${control_gains['joint2']['kd']}</param>
|
||||
<param name="kd3">${control_gains['joint3']['kd']}</param>
|
||||
<param name="kd4">${control_gains['joint4']['kd']}</param>
|
||||
<param name="kd5">${control_gains['joint5']['kd']}</param>
|
||||
<param name="kd6">${control_gains['joint6']['kd']}</param>
|
||||
<param name="kd7">${control_gains['joint7']['kd']}</param>
|
||||
</xacro:unless>
|
||||
</hardware>
|
||||
|
||||
|
||||
@ -3,6 +3,7 @@
|
||||
|
||||
<xacro:macro name="openarm_arm_ros2_control"
|
||||
params="arm_type
|
||||
control_gains
|
||||
can_interface
|
||||
use_fake_hardware:=^|false
|
||||
fake_sensor_commands:=^|false
|
||||
@ -27,6 +28,20 @@
|
||||
<param name="arm_prefix">${arm_prefix}</param>
|
||||
<param name="hand">${hand}</param>
|
||||
<param name="can_fd">${can_fd}</param>
|
||||
<param name="kp1">${control_gains['joint1']['kp']}</param>
|
||||
<param name="kp2">${control_gains['joint2']['kp']}</param>
|
||||
<param name="kp3">${control_gains['joint3']['kp']}</param>
|
||||
<param name="kp4">${control_gains['joint4']['kp']}</param>
|
||||
<param name="kp5">${control_gains['joint5']['kp']}</param>
|
||||
<param name="kp6">${control_gains['joint6']['kp']}</param>
|
||||
<param name="kp7">${control_gains['joint7']['kp']}</param>
|
||||
<param name="kd1">${control_gains['joint1']['kd']}</param>
|
||||
<param name="kd2">${control_gains['joint2']['kd']}</param>
|
||||
<param name="kd3">${control_gains['joint3']['kd']}</param>
|
||||
<param name="kd4">${control_gains['joint4']['kd']}</param>
|
||||
<param name="kd5">${control_gains['joint5']['kd']}</param>
|
||||
<param name="kd6">${control_gains['joint6']['kd']}</param>
|
||||
<param name="kd7">${control_gains['joint7']['kd']}</param>
|
||||
</xacro:if>
|
||||
</hardware>
|
||||
|
||||
|
||||
Loading…
Reference in New Issue
Block a user