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
9 changes: 9 additions & 0 deletions kortex_bringup/launch/gen3.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -61,6 +61,13 @@ def generate_launch_description():
description="Robot controller to start.",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"vision",
default_value="false",
description="Is vision module (camera) present on the robot?",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"controllers_file",
Expand Down Expand Up @@ -115,6 +122,7 @@ def generate_launch_description():
use_fake_hardware = LaunchConfiguration("use_fake_hardware")
fake_sensor_commands = LaunchConfiguration("fake_sensor_commands")
robot_controller = LaunchConfiguration("robot_controller")
vision = LaunchConfiguration("vision")
gripper = LaunchConfiguration("gripper")
use_internal_bus_gripper_comm = LaunchConfiguration("use_internal_bus_gripper_comm")
gripper_max_velocity = LaunchConfiguration("gripper_max_velocity")
Expand All @@ -132,6 +140,7 @@ def generate_launch_description():
"use_fake_hardware": use_fake_hardware,
"fake_sensor_commands": fake_sensor_commands,
"robot_controller": robot_controller,
"vision": vision,
"gripper": gripper,
"use_internal_bus_gripper_comm": use_internal_bus_gripper_comm,
"gripper_max_velocity": gripper_max_velocity,
Expand Down
13 changes: 12 additions & 1 deletion kortex_bringup/launch/kortex_control.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,7 @@ def launch_setup(context, *args, **kwargs):
description_file = LaunchConfiguration("description_file")
robot_name = LaunchConfiguration("robot_name")
prefix = LaunchConfiguration("prefix")
vision = LaunchConfiguration("vision")
gripper = LaunchConfiguration("gripper")
gripper_max_velocity = LaunchConfiguration("gripper_max_velocity")
gripper_max_force = LaunchConfiguration("gripper_max_force")
Expand All @@ -59,7 +60,7 @@ def launch_setup(context, *args, **kwargs):

# if we are using fake hardware then we can't use the internal gripper communications of the hardware
use_fake_hardware_value = use_fake_hardware.perform(context)
if use_fake_hardware_value == "true":
if use_fake_hardware_value == "true" or gripper.perform(context) == "":
use_internal_bus_gripper_comm = "false"

robot_description_content = Command(
Expand Down Expand Up @@ -91,6 +92,9 @@ def launch_setup(context, *args, **kwargs):
"fake_sensor_commands:=",
fake_sensor_commands,
" ",
"vision:=",
vision,
" ",
"gripper:=",
gripper,
" ",
Expand Down Expand Up @@ -300,6 +304,13 @@ def generate_launch_description():
have to be updated.",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"vision",
default_value="false",
description="Is vision module (camera) present on the robot?",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"gripper",
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@
<param name="connection_inactivity_timeout_ms">${connection_inactivity_timeout_ms}</param>
<param name="tf_prefix">"${tf_prefix}"</param>
<param name="use_internal_bus_gripper_comm">${use_internal_bus_gripper_comm}</param>
<param name="gripper_joint_name">${gripper_joint_name}</param>
<param name="gripper_joint_name">${prefix}${gripper_joint_name}</param>
<param name="gripper_max_velocity">${gripper_max_velocity}</param>
<param name="gripper_max_force">${gripper_max_force}</param>
</xacro:unless>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@
<param name="connection_inactivity_timeout_ms">${connection_inactivity_timeout_ms}</param>
<param name="tf_prefix">"${tf_prefix}"</param>
<param name="use_internal_bus_gripper_comm">${use_internal_bus_gripper_comm}</param>
<param name="gripper_joint_name">${gripper_joint_name}</param>
<param name="gripper_joint_name">${prefix}${gripper_joint_name}</param>
<param name="gripper_max_velocity">${gripper_max_velocity}</param>
<param name="gripper_max_force">${gripper_max_force}</param>
</xacro:unless>
Expand Down