Skip to content

Commit 4bd6292

Browse files
Use a parameter for the serial port
1 parent c03469e commit 4bd6292

File tree

2 files changed

+19
-4
lines changed

2 files changed

+19
-4
lines changed

schunk_gripper_driver/launch/driver.launch.py

+15-1
Original file line numberDiff line numberDiff line change
@@ -16,16 +16,30 @@
1616

1717
from launch import LaunchDescription
1818
from launch_ros.actions import Node
19+
from launch.actions import DeclareLaunchArgument
20+
from launch.substitutions import LaunchConfiguration
21+
22+
23+
port = DeclareLaunchArgument(
24+
"port",
25+
default_value="/dev/pts/13",
26+
description="The gripper's serial port",
27+
)
28+
args = [port]
1929

2030

2131
def generate_launch_description():
2232
return LaunchDescription(
23-
[
33+
args
34+
+ [
2435
Node(
2536
package="schunk_gripper_driver",
2637
namespace="schunk",
2738
executable="driver.py",
2839
name="driver",
40+
parameters=[
41+
{"port": LaunchConfiguration("port")},
42+
],
2943
)
3044
]
3145
)

schunk_gripper_driver/schunk_gripper_driver/driver.py

+4-3
Original file line numberDiff line numberDiff line change
@@ -28,12 +28,13 @@ class Driver(Node):
2828

2929
def __init__(self, node_name: str, **kwargs):
3030
super().__init__(node_name, **kwargs)
31-
self.mb_client = ModbusSerialClient(
32-
port="/dev/pts/13", baudrate=9600, timeout=1
33-
)
31+
self.declare_parameter("port", rclpy.Parameter.Type.STRING)
32+
self.port = self.get_parameter_or("port", "/dev/ttyUSB0").value
33+
self.mb_client = ModbusSerialClient(port=self.port, baudrate=9600, timeout=1)
3434

3535
def on_configure(self, state: State) -> TransitionCallbackReturn:
3636
self.get_logger().info("on_configure() is called.")
37+
self.get_logger().info(f"Connecting on port {self.port}")
3738
if not self.mb_client.connect():
3839
self.get_logger().warn("Modbus client connect failed")
3940
return TransitionCallbackReturn.FAILURE

0 commit comments

Comments
 (0)