Skip to content

Commit 617931d

Browse files
authored
Make Gripper velocity and force configurable through URDF (Kinovarobotics#137)
* add params for gripper max force and velocity Previously the gripper force and velocity were hard coded to 100 they now accept a percentage but default to 100
1 parent 22572c7 commit 617931d

File tree

18 files changed

+319
-175
lines changed

18 files changed

+319
-175
lines changed

kortex_bringup/launch/gen3.launch.py

Lines changed: 29 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -57,6 +57,7 @@ def generate_launch_description():
5757
declared_arguments.append(
5858
DeclareLaunchArgument(
5959
"controllers_file",
60+
default_value="ros2_controllers.yaml",
6061
description="Robot controller to start.",
6162
)
6263
)
@@ -67,13 +68,34 @@ def generate_launch_description():
6768
description="Name of the gripper attached to the arm",
6869
)
6970
)
71+
declared_arguments.append(
72+
DeclareLaunchArgument(
73+
"gripper_joint_name",
74+
default_value="robotiq_85_left_knuckle_joint",
75+
description="Name of the gripper attached to the arm",
76+
)
77+
)
7078
declared_arguments.append(
7179
DeclareLaunchArgument(
7280
"use_internal_bus_gripper_comm",
7381
default_value="true",
7482
description="Use internal bus for gripper communication?",
7583
)
7684
)
85+
declared_arguments.append(
86+
DeclareLaunchArgument(
87+
"gripper_max_velocity",
88+
default_value="100.0",
89+
description="Max velocity for gripper commands",
90+
)
91+
)
92+
declared_arguments.append(
93+
DeclareLaunchArgument(
94+
"gripper_max_force",
95+
default_value="100.0",
96+
description="Max force for gripper commands",
97+
)
98+
)
7799
declared_arguments.append(
78100
DeclareLaunchArgument("launch_rviz", default_value="true", description="Launch RViz?")
79101
)
@@ -86,6 +108,9 @@ def generate_launch_description():
86108
robot_controller = LaunchConfiguration("robot_controller")
87109
gripper = LaunchConfiguration("gripper")
88110
use_internal_bus_gripper_comm = LaunchConfiguration("use_internal_bus_gripper_comm")
111+
gripper_max_velocity = LaunchConfiguration("gripper_max_velocity")
112+
gripper_max_force = LaunchConfiguration("gripper_max_force")
113+
gripper_joint_name = LaunchConfiguration("gripper_joint_name")
89114
launch_rviz = LaunchConfiguration("launch_rviz")
90115
controllers_file = LaunchConfiguration("controllers_file")
91116

@@ -100,8 +125,12 @@ def generate_launch_description():
100125
"robot_controller": robot_controller,
101126
"gripper": gripper,
102127
"use_internal_bus_gripper_comm": use_internal_bus_gripper_comm,
128+
"gripper_max_velocity": gripper_max_velocity,
129+
"gripper_max_force": gripper_max_force,
130+
"gripper_joint_name": gripper_joint_name,
103131
"launch_rviz": launch_rviz,
104132
"controllers_file": controllers_file,
133+
"description_file": "gen3.xacro",
105134
}.items(),
106135
)
107136

0 commit comments

Comments
 (0)