Skip to content

Commit e26c891

Browse files
committed
Style: refactor of the comments and clarity of the code
1 parent 033781e commit e26c891

File tree

2 files changed

+79
-32
lines changed

2 files changed

+79
-32
lines changed

params/lx16a_params.yaml

+3-1
Original file line numberDiff line numberDiff line change
@@ -1,12 +1,14 @@
11
lx16a_controller:
22
ros__parameters:
3+
# default settings when using the motor params settings service
34
default_angle_offset: 0
45
default_angle_min: 0
56
default_angle_max: 240
67
default_voltage_min: 4500
78
default_voltage_max: 12000
89
default_temperature_limit: 85
10+
911
log_level: 0 #UNSET: 0 DEBUG: 10 INFO: 20 WARN: 30 ERROR: 40 FATAL: 50
1012
port: "/dev/ttyUSB0"
11-
scan_connected_servos: False
13+
scan_connected_servos: False # Allow the port to be scanned for all connected motors ids. Note: When the node is started, there is a 4 to 5 second delay due to the broadcast of the 253 ids.
1214

src/lx16a_node.py

+76-31
Original file line numberDiff line numberDiff line change
@@ -1,19 +1,25 @@
11
#!/usr/bin/env python3
2+
3+
# Import necessary libraries
24
import rclpy
35
from rclpy.node import Node
46
from pylx16a.lx16a import LX16A
57
from ros2_lx16a_driver.srv import GetLX16AInfo, SetLX16AParams, SetLX16ATorque
68
from std_msgs.msg import Float32MultiArray, Int32MultiArray
7-
from rclpy.logging import LoggingSeverity
8-
import threading
9-
import sys
10-
import time
119

1210
class LX16AController(Node):
11+
"""
12+
ROS 2 Node for controlling LX-16A servos.
13+
14+
This node provides services to get servo information, set parameters, and control torque.
15+
It also subscribes to position and velocity commands to move the servos in real-time.
16+
"""
17+
1318
def __init__(self):
1419
super().__init__('lx16a_controller')
1520

16-
# Définir les paramètres avec des valeurs par défaut
21+
22+
# Declare ROS 2 parameters with default values
1723
self.declare_parameter('default_angle_offset', 0)
1824
self.declare_parameter('default_angle_min', 0)
1925
self.declare_parameter('default_angle_max', 240)
@@ -24,7 +30,8 @@ def __init__(self):
2430
self.declare_parameter('port', '/dev/ttyUSB0')
2531
self.declare_parameter('scan_connected_servos', False)
2632

27-
# Charger les paramètres
33+
34+
# Store default parameter values
2835
self.default_values = {
2936
'angle_offset': self.get_parameter('default_angle_offset').value,
3037
'angle_min': self.get_parameter('default_angle_min').value,
@@ -34,10 +41,12 @@ def __init__(self):
3441
'temperature_limit': self.get_parameter('default_temperature_limit').value,
3542
}
3643

37-
# Manage log verbosity
44+
45+
# Set logger verbosity level
3846
self.get_logger().set_level(self.get_parameter('log_level').value)
3947

40-
# Initialize the LX-16A bus
48+
49+
# Initialize communication with LX-16A servos
4150
try:
4251
LX16A.initialize(self.get_parameter('port').value)
4352
self.servos = {}
@@ -48,31 +57,35 @@ def __init__(self):
4857
self.destroy_node()
4958
return
5059

51-
# Create services
60+
61+
# Create ROS 2 services
5262
self.srv_get = self.create_service(GetLX16AInfo, '/lx16a_get_info', self.handle_get_info)
5363
self.srv_set_params = self.create_service(SetLX16AParams, '/lx16a_set_params', self.handle_set_params)
5464
self.srv_set_torque = self.create_service(SetLX16ATorque, '/lx16a_set_torque', self.handle_set_torque)
5565

56-
# Create subscriber for position control
66+
67+
# Create ROS 2 subscribers
5768
self.position_subscriber = self.create_subscription(
58-
Float32MultiArray, # Message type
59-
'/cmd_pose_lx16a', # Topic name
60-
self.handle_position_command, # Callback
61-
10 # Queue size
69+
Float32MultiArray, '/cmd_pose_lx16a', self.handle_position_command, 10
6270
)
63-
64-
# Create subscriber for velocity control
6571
self.velocity_subscriber = self.create_subscription(
66-
Int32MultiArray, # Message type
67-
'/cmd_vel_lx16a', # Topic name
68-
self.handle_velocity_command, # Callback
69-
10 # Queue size
72+
Int32MultiArray, '/cmd_vel_lx16a', self.handle_velocity_command, 10
7073
)
7174

75+
7276
self.get_logger().info('LX-16A driver ready')
7377

78+
7479
def get_servo(self, servo_id):
75-
"""Returns an instance of a given servo, creates it if necessary."""
80+
"""
81+
Retrieve and create an instance of a servo with a given ID.
82+
83+
Parameters:
84+
servo_id (int): ID of the servo.
85+
86+
Returns:
87+
LX16A: Servo instance or None if an error occurs.
88+
"""
7689
if servo_id not in self.servos:
7790
try:
7891
self.servos[servo_id] = LX16A(servo_id)
@@ -82,17 +95,29 @@ def get_servo(self, servo_id):
8295
return None
8396
return self.servos[servo_id]
8497

98+
8599
def handle_get_info(self, request, response):
86-
"""Service to get detailed information of a servo."""
100+
"""
101+
Handle the GetLX16AInfo service to retrieve servo information.
102+
103+
Parameters:
104+
request (GetLX16AInfo.Request): Service request.
105+
response (GetLX16AInfo.Response): Service response.
106+
107+
Returns:
108+
GetLX16AInfo.Response: Populated response with servo details.
109+
"""
87110
servo_id = int(request.id)
88111
servo = self.get_servo(servo_id)
89112

113+
90114
if servo is None:
91115
self.get_logger().error(f"Servo {servo_id} not available.")
92-
return response # Leave response empty if the servo is not found
116+
return response
117+
93118

94119
try:
95-
# Retrieve servo information
120+
# Retrieve detailed information about the servo
96121
response.angle_offset = int(servo.get_angle_offset())
97122
response.angle_min = int(servo.get_angle_limits()[0])
98123
response.angle_max = int(servo.get_angle_limits()[1])
@@ -114,16 +139,19 @@ def handle_get_info(self, request, response):
114139
response.physical_angle = servo.get_physical_angle()
115140
response.commanded_angle = servo.get_commanded_angle()
116141

142+
117143
self.get_logger().info(f"Information for servo {servo_id} retrieved.")
118144
except Exception as e:
119145
self.get_logger().error(f"Error retrieving info for servo {servo_id}: {e}")
120-
# Empty response if an error occurs
121-
return response
146+
122147

123148
return response
124149

150+
125151
def handle_set_params(self, request, response):
126-
"""Service to set the parameters of a servo."""
152+
"""
153+
Handle the SetLX16AParams service to update servo parameters.
154+
"""
127155
servo_id = int(request.id)
128156
servo = self.get_servo(servo_id)
129157

@@ -159,8 +187,11 @@ def handle_set_params(self, request, response):
159187

160188
return response
161189

190+
162191
def handle_set_torque(self, request, response):
163-
"""Service to set torque of a servo."""
192+
"""
193+
Handle the SetLX16ATorque service to enable or disable servo torque.
194+
"""
164195
servo_id = int(request.id)
165196
servo = self.get_servo(servo_id)
166197

@@ -185,8 +216,11 @@ def handle_set_torque(self, request, response):
185216

186217
return response
187218

219+
188220
def handle_position_command(self, msg):
189-
"""Callback to handle position command for servos."""
221+
"""
222+
Handle position commands received on the '/cmd_pose_lx16a' topic.
223+
"""
190224
if len(msg.data) == 0:
191225
self.get_logger().warn("No position command received.")
192226
return
@@ -202,8 +236,11 @@ def handle_position_command(self, msg):
202236
except Exception as e:
203237
self.get_logger().error(f"Error moving servo {i}: {e}")
204238

239+
205240
def handle_velocity_command(self, msg):
206-
"""Callback to handle velocity command for servos."""
241+
"""
242+
Handle velocity commands received on the '/cmd_vel_lx16a' topic.
243+
"""
207244
if len(msg.data) == 0:
208245
self.get_logger().warn("No velocity command received.")
209246
return
@@ -218,7 +255,11 @@ def handle_velocity_command(self, msg):
218255
except Exception as e:
219256
self.get_logger().error(f"Error commanding servo {i}: {e}")
220257

258+
221259
def scan_connected_servos(self):
260+
"""
261+
Scan and log all connected servos on the LX-16A bus.
262+
"""
222263
connected_ids = []
223264
for servo_id in range(254):
224265
try:
@@ -233,7 +274,11 @@ def scan_connected_servos(self):
233274
self.get_logger().warn("\033[31mNo servos detected.\033[0m")
234275
return connected_ids
235276

277+
236278
def main(args=None):
279+
"""
280+
Main function to initialize and spin the ROS 2 node.
281+
"""
237282
rclpy.init(args=args)
238283
node = LX16AController()
239284

@@ -245,8 +290,8 @@ def main(args=None):
245290
rclpy.shutdown() # Shutdown if the context is still valid
246291

247292

248-
249293
if __name__ == '__main__':
250294
main()
251295

252296

297+

0 commit comments

Comments
 (0)