-
Notifications
You must be signed in to change notification settings - Fork 238
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
Problem with syncRead of dynamixel workbench #262
Comments
Hi @p123ad |
Thank you for that good explanation! But is it than possible to have two different syncReadHandler? Can I split up the motors by TTL or RS-485? |
Yes, you can create multiple handlers with different object names. |
hey, But I can not find the solution for that! Do you have any sugggestions? |
The Workbench libary in OpenCR allows you to create up to 5 handlers. uint8_t dxl_ttl_id[4] = {
HEAD_PITCH,
NECK_YAW,
RIGHT_HIP_YAW,
RIGHT_HIP_ROLL };
uint8_t dxl_485_id[3] = {
RIGHT_SHOULDER_ROLL,
RIGHT_SHOULDER_PITCH,
RIGHT_ELBOW_PITCH };
// Writing to TTL / RS-485 DYNAMIXEL with SyncWrite doesn't need to be differentiated.
result = dxl_wb.addSyncWriteHandler(dxl_id[0], "Goal_Position", &log);
// This handler with handler_index = 0 will be used to read from TTL DYNAMIXEL
// handler_index is automatically increased in addSyncReadHander()
result = dxl_wb.addSyncReadHandler(dxl_ttl_id[0], "Present_Position", &log);
// This handler with handler_index = 1 will be used to read from RS-485 DYNAMIXEL
result = dxl_wb.addSyncReadHandler(dxl_485_id[0], "Present_Position", &log);
...
// Read from TTL DYNAMIXEL
result = dxl_wb.syncRead(0, &log);
...
// Read from RS-485 DYNAMIXEL
result = dxl_wb.syncRead(1, &log); |
Thank you for the quick response! That was also my idea, but it is not working: Code:
|
Hello,
I am trying to sync read and write data to multiple Dynamixels.
Setup:
OpenCR board
2x MX430-W350-T
2x XM540-W270-T
2x XM540-W270-R
Writing is no problem.
But reading produces problems:
Can it be that the problem comes up because of the difference between TTL and RS485 ?
When I sync read only the first four dynamixels which use TTL it wors fine. And only reading the 3 Motors with RS485 alone works also fine.
Thank you for your help!
The text was updated successfully, but these errors were encountered: