-
Notifications
You must be signed in to change notification settings - Fork 50
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
Errors 'CAN not ready' when init Schunk lwa4p in Indigo #59
Comments
I guess you are using debians, right? It might also be related to ros-industrial/ros_canopen#102 |
What do you mean by "chaos"? The time sequence is well defined per CANopen node. The currently released version has some bugs.. I will release a new version after ros-industrial/ros_canopen#150 was tested and merged. |
And @ipa-fxm is right with ros-industrial/ros_canopen#102. Please increase the queue length. |
@ipa-mdl I traced the communication using PCAN View in Windows, the data are in the tracedata1.xls, where 0908(sheet 1) shows trace by original package, 0924(sheet 2) is the trace by my modified package. According to the canopen protocol and the means of IDs, in sheet 0908, we can see the configuration for node 3 starts firstly (the yellow 17th raw), and the sync(the green 108 raw) begins immediately after the start of configuration of next node 4(the yellow 107th raw), then the PDO for node 3 and SDO for node 4 are running at the same time(this is what I mean chaos). Actually I don't think it is a necessary time to start the sync(why cannot sync starts after all nodes are operational), so what I did is postpone the running time of sync, like sheet 0928, the sync starts after finishing configuration of all the 6 nodes(green 606th raw). One more question is, as we can see form the light blue parts in sheet 0908, the nodes which have been configured are reset again from the first node(node 3 in this example). Why all the former nodes are reset repeatedly again and again when configuring the current node. It is just an doubt, as I am not very familiar to the canopen mechanism, I am still knowing nothing where the sync defined in the program, I am learning. Could you give me some advice if You get an answer. Thanks. NOTE: I donnot know to attach thetracedata1.xlsx here, so I send it to you by email, please check it. |
@ipa-fxm 1, I am not sure about what do you mean by 'using debians'. I am using Ubuntu, and the indigo-dev-packages ros_canopen and schunk_robots are built in catkin workspace by git clone the github links, so I can modify it. 2, I have changed the value of queue length to 15, 20, and other numbers, but it seems no obvious differences as the results of default value 10. The thing is, how do I know which value for the txqueuelen is the most suitable one. 3, I also tested in the lowlatency kernel of Ubuntu, it is the same errors and similar performance. Thanks. |
Then you are using the source instead of the "debians" (
It should be greater than the number of sent packages per SYNC plus some buffer for SDOs. 15-20 should be suitable for a LWA4P.
This is the intended behaviour. What's wrong with it?
Instead of the colour can you list the timestamp or line number, please? It is a long document..
What do you mean by "defined"? |
Back to your init problem: A txqueuelen of 20 should work for you. Please double check the value with The CAN trace looks fine so far. Did it really end at the last message? |
@ipa-mdl |
@ipa-mdl
and the init service responds:
It seems a break after success init, the candump file is candump-2015-11-04_092135.log. The thing is when you relaunch the robot node, it works well. But if you restart the arm, same results: first init fails, after that no errors. I am still not clearly understanding the mechanism of the initialization. For a clearer view, I postponed(deleted) the sync and PDO parts, data as in candump-2015-11-04_093045.log. For example, from Line 475 to Line 499, it's a switch state process, the former node (node 7) goes to 'operational', then a two-stage follows (stage one: Line 476 ~ Line 483; stage two: Line 484 ~ Line 499), the first stage finishes the former five operational nodes? The second stage seems to start the bootup of the next node and reset the former five nodes? Is that right? If it is, can we bootup the new node directly, without reset the former nodes? Because it seems the messages in the 1st stage duplicated again in the 2nd stage. -----------The two log files emailed.--------- as suggested, I attached both the files in gist.github |
@ipa-mdl
why is the state UNKNOWN but not UP? |
This relates to the kernel driver.
Can explain this a little more?
I guess you mix some things up.
Does not belong to the initialization. This is part of the asynchonous diagnostics job that polls the error register of all initialized nodes.
Resets the error counter for node 7. |
And please stop sending attachment via e-mail, use https://gist.github.com/ instead. |
@ipa-mdl
yes, I restart the arm while the driver is running: what I did is, i turned off all the power switches of the manipulator and then turned on, leaving the pcan usb plugged into the computer, then carried on the next test(run prepare.sh and launch robot.launch). |
Please try to run prepare.sh before you power on the robot. It addition I recommend the network device in the config (http://wiki.ros.org/socketcan_interface#Initialize_NIC) and to run prepare.sh only if you really need to restart the kernel driver for the device. |
@ipa-mdl
Furthermore, could you tell me what does the 'controller problems' in the responds mean? Is it a problem of hardware? Or?
|
I will give it a try on our LWA4D as soon as I find some time.
It means that socketcan_interface received an error frame.. |
I was not able to reproduce your error. My test procedure was:
(4. and 5. could be switched.) |
Thanks very much for your time, I have learn more and will test more on it. |
I faced the same difficulties with our arm now.. Please make sure that you have a power supply that outputs up to 12A (according to LWA4P manual/datasheet). |
Sorry to feedback late, the output of our power supply is DC24V/20A, I think it satisfies completely. |
Hello,
Here is the script that I use to prepare ros-indigo under ubuntu 14.04 and can0 configs. |
@ammarnajjar: I don't think that your error is related to this issue.
Lost arbitration should almost never happen. Your scipt and logs look fine until Do you know which firmware your LWA4P is running on? PS: +1 for all the well-prepared logs and the great script :) |
Dear sir
the error like this
what should i do to handle this error? |
this issue is being warmed up over and over... |
Hi,
I am trying to move the schunk lwa4p arm using the package of indigo version. But errors like 'CAN not ready' 'message: cannot reset node ' '' frequently appear when I call the service /arm/driver/init.
The configuration status is:
The program running order:
I considered it as an issue of time sequence, as I found that the Sync, SDO and PDO running simutaneously like chaos. So I delayed the sync starting time after the SDO initialization finished(not completely, except the last node), by adding a conditional flag in the function of switchState() in the node.cpp in the package of canopen_master, as follows:
The current status is: as long as I have tested, it fails at the first one or two tries(relaunch the robot node) every time I restart the arm, but after that it works stably(no errors and can move the arm).
Errors in the first one or two tries:
The question here is: I am not sure whether what I have understood and changed is reasonable or not. The fact is it truly increases the probability of successful initialization. Could anyone give me some instructions about it? Or any other method to solve it? Thanks very much.
The text was updated successfully, but these errors were encountered: