Closed t-kitajima closed 5 years ago
When debugging using gdb, an error appears when adrress: 621, length: 2. I set the break point on line 1217 of dynamixel_driver.cpp and checked the value.
It seems to be an error in the execution of the following line.
sdk_error.dxl_getdata_result = syncReadHandler_[index].groupSyncRead->isAvailable(id[i], address, length);
... logging to /home/kitajima/.ros/log/3db22f10-4ef6-11e9-ab60-d46d6d3132ab/roslaunch-kitajima-P51-24872.log
Checking log directory for disk usage. This may take awhile.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.
started roslaunch server http://192.168.1.117:40729/
SUMMARY
========
PARAMETERS
* /dynamixel_info: /home/kitajima/ca...
* /dynamixel_workbench/dxl_read_period: 0.01
* /dynamixel_workbench/dxl_write_period: 0.01
* /dynamixel_workbench/mobile_robot_config/radius_of_wheel: 0.033
* /dynamixel_workbench/mobile_robot_config/seperation_between_wheels: 0.16
* /dynamixel_workbench/publish_period: 0.01
* /dynamixel_workbench/use_cmd_vel_topic: False
* /dynamixel_workbench/use_joint_states_topic: True
* /dynamixel_workbench/use_moveit: False
* /rosdistro: kinetic
* /rosversion: 1.12.14
NODES
/
dynamixel_workbench (dynamixel_workbench_controllers/dynamixel_workbench_controllers)
auto-starting new master
process[master]: started with pid [24882]
ROS_MASTER_URI=http://192.168.1.117:11311/
setting /run_id to 3db22f10-4ef6-11e9-ab60-d46d6d3132ab
process[rosout-1]: started with pid [24895]
started core service [/rosout]
process[dynamixel_workbench-2]: started with pid [24906]
GNU gdb (Ubuntu 7.11.1-0ubuntu1~16.5) 7.11.1
Copyright (C) 2016 Free Software Foundation, Inc.
License GPLv3+: GNU GPL version 3 or later <http://gnu.org/licenses/gpl.html>
This is free software: you are free to change and redistribute it.
There is NO WARRANTY, to the extent permitted by law. Type "show copying"
and "show warranty" for details.
This GDB was configured as "x86_64-linux-gnu".
Type "show configuration" for configuration details.
For bug reporting instructions, please see:
<http://www.gnu.org/software/gdb/bugs/>.
Find the GDB manual and other documentation resources online at:
<http://www.gnu.org/software/gdb/documentation/>.
For help, type "help".
Type "apropos word" to search for commands related to "word"...
Reading symbols from /home/kitajima/catkin_ws/devel/lib/dynamixel_workbench_controllers/dynamixel_workbench_controllers...done.
(gdb) b dynamixel_driver.cpp:1217
No source file named dynamixel_driver.cpp.
Make breakpoint pending on future shared library load? (y or [n]) y
Breakpoint 1 (dynamixel_driver.cpp:1217) pending.
(gdb) r
Starting program: /home/kitajima/catkin_ws/devel/lib/dynamixel_workbench_controllers/dynamixel_workbench_controllers /dev/ttyUSB0 57600 __name:=dynamixel_workbench __log:=/home/kitajima/.ros/log/3db22f10-4ef6-11e9-ab60-d46d6d3132ab/dynamixel_workbench-2.log
[tcsetpgrp failed in terminal_inferior: デバイスに対する不適切なioctlです]
[tcsetpgrp failed in terminal_inferior: デバイスに対する不適切なioctlです]
[Thread debugging using libthread_db enabled]
Using host libthread_db library "/lib/x86_64-linux-gnu/libthread_db.so.1".
[tcsetpgrp failed in terminal_inferior: デバイスに対する不適切なioctlです]
[New Thread 0x7ffff13a9700 (LWP 24925)]
[New Thread 0x7ffff0ba8700 (LWP 24926)]
[New Thread 0x7fffebfff700 (LWP 24927)]
[New Thread 0x7fffeb7fe700 (LWP 24932)]
[ INFO] [1553515539.193762203]: Name : pan, ID : 1, Model Number : 51200
[ INFO] [1553515539.233719418]: Name : tilt, ID : 2, Model Number : 54024
[ INFO] [1553515539.323814519]: [DynamixelDriver] Succeeded to add sync write handler
[ INFO] [1553515539.323869421]: [DynamixelDriver] Succeeded to add sync write handler
[New Thread 0x7fffeaffd700 (LWP 24956)]
Thread 1 "dynamixel_workb" hit Breakpoint 1, DynamixelDriver::getSyncReadData (this=0x878720, index=0 '\000', id=0x7fffffffc370 "\001\002\377\377\377\177",
id_num=2 '\002', address=621, length=2, data=0x7fffffffc3a0, log=0x7fffffffc508)
at /home/kitajima/catkin_ws/src/dynamixel-workbench/dynamixel_workbench_toolbox/src/dynamixel_workbench_toolbox/dynamixel_driver.cpp:1217
1217 if (log != NULL) *log = "groupSyncRead getdata failed";
(gdb) l
1212 sdk_error.dxl_getdata_result = syncReadHandler_[index].groupSyncRead->isAvailable(id[i],
1213 address,
1214 length);
1215 if (sdk_error.dxl_getdata_result != true)
1216 {
1217 if (log != NULL) *log = "groupSyncRead getdata failed";
1218 return false;
1219 }
1220 else
1221 {
(gdb) p sdk_error.dxl_getdata_result
$1 = false
(gdb) p id[i]
$2 = 1 '\001'
(gdb) p address
$3 = 621
(gdb) p length
$4 = 2
(gdb)
@t-kitajima Sorry for late reply kitajima san. Dynamixel-Workbench have not supported A firmware for Dynamixel Pro series.
@routiful The firmware used when this problem occurred is not A firmware. I think that take in the modification of PR will solve the problem. modified address range check logic of GroupSyncRead::isAvailable#294
@ROBOTIS-zerom Please review pull-request arise from Japan branch.
@routiful The PR I sent was not correct. But when I was discussing with ROBOTIS-zerom, I found a suspicious spot. The calculation process of data_length is the sum of the values related to the address of the control table. In fact, this process seems to have problems, as there are areas not used for addresses. e.g. H54-200-S500-R
Address | Size | Data Name |
---|---|---|
611 | 4 | Present Position |
615 | 4 | Present Velocity |
619 | 2 | not use area |
621 | 2 | Present Current |
The calculation process is right, but as @t-kitajima mentioned it, the datalength shouldn't be 10 for this model. The current dynmiaxel_workbench_controller line 255 & 266, groupSyncRead function reads Present Position & Present Velocity & Present Current, all together.
However, when the function checks "Present Current",
startaddress : 611 datalength : 10 address(Present Current) : 621 data_length : 2 611 + 10 < 623 returns false.
@t-kitajima
It should work now. Please let me know if you run into any other problems
Regards, Ryan
I am having a very similar issue using two types of dynamixels with a USB U2D2 controller. I downloaded the latest dynamixel_workbench this morning. and I have three types of servos the Pro series M42 & H42 and some XM540 and XM430. Is there a solution to this issue?????
ubuntu@ubiquityrobot:~/catkin_ws/src/dynamixel-workbench/dynamixel_workbench_toolbox/src/dynamixel_workbench_toolbox$ roslaunch dynamixel_workbench_controllers dynamixel_controllers.launch ... logging to /home/ubuntu/.ros/log/7377eb4e-d0dc-11e5-9d13-b827eb7765da/roslaunch-ubiquityrobot-6450.log Checking log directory for disk usage. This may take awhile. Press Ctrl-C to interrupt Done checking log file disk usage. Usage is <1GB.
started roslaunch server http://localhost:34549/
PARAMETERS
NODES / dynamixel_workbench (dynamixel_workbench_controllers/dynamixel_workbench_controllers)
ROS_MASTER_URI=http://localhost:11311
process[dynamixel_workbench-1]: started with pid [6467] [ INFO] [1562188127.685684295]: Name : arm.upper.left, ID : 5, Model Number : 2100 [ INFO] [1562188127.726381166]: Name : arm.upper.right, ID : 6, Model Number : 2100 [ INFO] [1562188127.766423927]: Name : head.tilt.left, ID : 21, Model Number : 1020 [ INFO] [1562188127.806407158]: Name : head.tilt.right, ID : 22, Model Number : 1020 [ INFO] [1562188127.846409346]: Name : neck.pan, ID : 20, Model Number : 1020 [ INFO] [1562188127.886369764]: Name : shoulder.main.left, ID : 1, Model Number : 2000 [ INFO] [1562188127.926390859]: Name : shoulder.main.right, ID : 2, Model Number : 2000 [ INFO] [1562188127.966413411]: Name : shoulder.roll.left, ID : 3, Model Number : 2000 [ INFO] [1562188128.006378152]: Name : shoulder.roll.right, ID : 4, Model Number : 2000 [ INFO] [1562188128.411705263]: [DynamixelDriver] Succeeded to add sync write handler [ INFO] [1562188128.412116406]: [DynamixelDriver] Succeeded to add sync write handler [ERROR] [1562188128.555661257]: [TxRxResult] There is no status packet! [ERROR] [1562188128.556194482]: groupSyncRead getdata failed [ERROR] [1562188128.556425002]: groupSyncRead getdata failed [ERROR] [1562188128.556654948]: groupSyncRead getdata failed
@tomsepe
The issue here was that our package didn't work when using dxl pro motors, not about the problem occurring when using different types of motors. The bug about it has been fixed already so I recommend you only use pro models or only use X models.
Regards, Ryan
Ryan,
i appreciate the fast response but your answer is unacceptable.
i have purchase about $23k of pro and x series motors to use for 2 humanoid robots that I am building to be completed in September. my budget does not allow to use only pro servos, also the form factor is too big for the forearms and hands.
There has to be a different solution. perhaps I use 2 usb-serial converters.. or I use a different controller or a different software library.
On Wed, Jul 3, 2019 at 5:15 PM Ryan notifications@github.com wrote:
@tomsepe https://github.com/tomsepe
The issue here was that our package didn't work when using dxl pro motors, not about the problem occurring when using different types of motors. The bug about it has been fixed already so I recommend you only use pro models or only use X models.
Regards, Ryan
— You are receiving this because you were mentioned. Reply to this email directly, view it on GitHub https://github.com/ROBOTIS-GIT/dynamixel-workbench/issues/234?email_source=notifications&email_token=AANG3OK4FGDREUQVYJAUHWDP5U6LPA5CNFSM4HAZTPYKYY3PNVWWK3TUL52HS4DFVREXG43VMVBW63LNMVXHJKTDN5WW2ZLOORPWSZGODZF7J3Y#issuecomment-508294383, or mute the thread https://github.com/notifications/unsubscribe-auth/AANG3OMZRF5JOW6MCZ266MTP5U6LPANCNFSM4HAZTPYA .
-- TOM SEPE SEPE PRODUCTIONS ART_DESIGN_FABRICATION +1 510 499 0946 <+1%20510%20499%200946> mobile thomas@tomsepe.com
@tomsepe
If you want to use the Dynamixel Workbench package, you should do as I said (use the same type of motors). There is another package, Dynamixel SDK, you can use to control your (even different types of) motors. I will attach the link below.
Regards, Ryan
ISSUE TEMPLATE ver. 1.0.0
How to setup? (ex, U2D2, OpenCR,...)
Which Dynamixel have you used? and how many? (Please describe below format to all connected Dynamixels)
Model Name H42-20-S300-R(ID:1) H54-200-S500-R(ID:2)
Baud Rate of Dynamixels 57600
Protocol Version 2.0
Write down the commands you used in order
Copy and Paste your error message on terminal
started roslaunch server http://192.168.1.117:46387/
SUMMARY
PARAMETERS
NODES / dynamixel_workbench (dynamixel_workbench_controllers/dynamixel_workbench_controllers)
auto-starting new master process[master]: started with pid [16081] ROS_MASTER_URI=http://192.168.1.117:11311/
setting /run_id to 74ec3fc8-4eda-11e9-ab60-d46d6d3132ab process[rosout-1]: started with pid [16094] started core service [/rosout] process[dynamixel_workbench-2]: started with pid [16106] [ INFO] [1553503579.163088091]: Name : pan, ID : 1, Model Number : 51200 [ INFO] [1553503579.203013999]: Name : tilt, ID : 2, Model Number : 54024 [ INFO] [1553503579.293156652]: [DynamixelDriver] Succeeded to add sync write handler [ INFO] [1553503579.293221377]: [DynamixelDriver] Succeeded to add sync write handler [ERROR] [1553503579.327025671]: groupSyncRead getdata failed [ERROR] [1553503579.338059314]: groupSyncRead getdata failed [ERROR] [1553503579.349049393]: groupSyncRead getdata failed [ERROR] [1553503579.360058931]: groupSyncRead getdata failed [ERROR] [1553503579.371067474]: groupSyncRead getdata failed [ERROR] [1553503579.382052598]: groupSyncRead getdata failed [ERROR] [1553503579.393008850]: groupSyncRead getdata failed [ERROR] [1553503579.404002915]: groupSyncRead getdata failed [ERROR] [1553503579.414981298]: groupSyncRead getdata failed [ERROR] [1553503579.425987180]: groupSyncRead getdata failed [ERROR] [1553503579.436980482]: groupSyncRead getdata failed [ERROR] [1553503579.447980200]: groupSyncRead getdata failed ...