You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
I just want to use a dynamixel motor (PM42) with operanting mode: 4 (extended position control mode). I have already created a new file yaml for the dynamixel_controllers.launch, and use the command line "rosservice call /dynamixel_workbench/dynamixel_command command: ' ' .... " and it works, but I want to make a python script with a client for dynamixel_command, but It gives me an error. Maybe this is something very simple, but if you can help me, I will be very grateful!
raceback (most recent call last):
File "/home/me/catkin_ws/devel/lib/my_dynamixel_tutorial/control_position_spool.py", line 15, in <module>
exec(compile(fh.read(), python_script, 'exec'), context)
File "/home/me/catkin_ws/src/my_dynamixel_tutorial/src/control_position_spool.py", line 21, in <module>
is_success = client_pos(request)
File "/opt/ros/noetic/lib/python3/dist-packages/rospy/impl/tcpros_service.py", line 442, in __call__
return self.call(*args, **kwds)
File "/opt/ros/noetic/lib/python3/dist-packages/rospy/impl/tcpros_service.py", line 498, in call
request = rospy.msg.args_kwds_to_message(self.request_class, args, kwds)
File "/opt/ros/noetic/lib/python3/dist-packages/rospy/msg.py", line 122, in args_kwds_to_message
return data_class(*args)
File "/home/me/catkin_ws/devel/lib/python3/dist-packages/dynamixel_workbench_msgs/srv/_DynamixelCommand.py", line 42, in __init__
super(DynamixelCommandRequest, self).__init__(*args, **kwds)
File "/opt/ros/noetic/lib/python3/dist-packages/genpy/message.py", line 354, in __init__
raise TypeError('Invalid number of arguments, args should be %s' % str(self.__slots__) + ' args are' + str(args))
TypeError: Invalid number of arguments, args should be ['command', 'id', 'addr_name', 'value'] args are(<dynamixel_workbench_msgs.srv._DynamixelCommand.DynamixelCommand object at 0x7f085cec16a0>,)
The text was updated successfully, but these errors were encountered:
Hi @NAEE09
Apologies for the delayed response.
The issue in your script is due to the way you are trying to call the DynamixelCommand service. The DynamixelCommandRequest object, which is the expected input for the service, requires the fields command, id, addr_name, and value to be specified individually. However, in your script, you are incorrectly creating a DynamixelCommand object and passing it directly, which results in a TypeError.
Here’s how to fix the issue:
Correct Python Client Script:
#!/usr/bin/env python
import rospy
from dynamixel_workbench_msgs.srv import DynamixelCommand
if __name__ == "__main__":
rospy.init_node('set_position') # Initialize the ROS node
rospy.wait_for_service('dynamixel_workbench/dynamixel_command') # Wait for the service to become available
# Create a client for the DynamixelCommand service
client_pos = rospy.ServiceProxy('dynamixel_workbench/dynamixel_command', DynamixelCommand)
try:
# Call the service with the correct parameters
response = client_pos(
command='', # Empty string for command
id=1, # Dynamixel ID
addr_name='Goal_Position', # Address name to write
value=263000 # Value to write
)
# Check the response from the service
if response.comm_result:
rospy.loginfo("Successfully sent the goal position!")
else:
rospy.logerr("Failed to send the goal position.")
except rospy.ServiceException as e:
rospy.logerr(f"Service call failed: {e}")
Key Fixes:
Directly Pass Parameters to ServiceProxy: Instead of creating a DynamixelCommand object manually, pass the required fields (command, id, addr_name, and value) directly to the ServiceProxy call.
Proper Error Handling: Added error handling to log the service exception if it occurs.
If you get the "Failed to send the goal position" error, try decreasing the value.
This corrected script should work as intended for setting the goal position. Let me know if you encounter further issues!
HI!!
I just want to use a dynamixel motor (PM42) with operanting mode: 4 (extended position control mode). I have already created a new file yaml for the dynamixel_controllers.launch, and use the command line "rosservice call /dynamixel_workbench/dynamixel_command command: ' ' .... " and it works, but I want to make a python script with a client for dynamixel_command, but It gives me an error. Maybe this is something very simple, but if you can help me, I will be very grateful!
Model Name: PM42-010-S260-R
yaml file:
Client script
The commands I used in order
Error message on terminal
The text was updated successfully, but these errors were encountered: