ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
1

ros_canopen driver node throws internal error right after initializing schunk_lwa4p arm

asked 2015-06-23 05:08:01 -0500

Marcel Usai gravatar image

updated 2015-07-22 03:32:51 -0500

Hi there,

I am using a schunk lwa and ros_canopen. Recently, I am having issues with the driver node: After initializing the arm, the driver node throws an internal error (but normally it does not crash), just a few seconds after initializing the arm or right after starting a movement. The usual error message looks similar to this:

[ INFO] [1435053398.073349599]: waitForService: Service [/powerball/robot/controller_manager/load_controller] is now available.
[ INFO] [1435053398.259478563]: joint_trajectory_controller loaded
[ INFO] [1435053398.429607440]: joint_group_position_controller loaded
[ INFO] [1435053398.509686775]: joint_group_velocity_controller loaded
[ INFO] [1435053398.519499166]: Switched Controllers. From no_stop_controller_defined to joint_trajectory_controller
error: 4
[ INFO] [1435053405.571193079]: Current state: 2 device error: system:0 internal_error: 4 (controller problems;)
[ INFO] [1435053405.571277714]: Current state: 1 device error: system:0 internal_error: 4 (controller problems;)
ID: 4
error: 64
[ INFO] [1435053405.571372578]: Current state: 1 device error: system:0 internal_error: 64 (bus off;)
ID: 64

Sometimes, it only is the controller problems error.

Besides this error, all works well, I can move the arm and have no further troubles, but this is very annoying. I am very thankful for any piece of advice.

Best regards, Marcel

edit: I read the state/ error state of the arm's modules:

state 0x8228: Fault
error register 0x21: Generic + Device profile specific error
manufacturer status 0x8810: SMP command code = CMD_ERROR, SMP error code = INFO_TIMEOUT
0x1003/1 predefined_error_field 0x00108250: CANopen error code = RPDO timeout, SMP error code = INFO_TIMEOUT
0x1003/2 predefined_error_field 0x00E16100: CANopen error code = Internal software û generic, SMP error code = ERROR_INTERNAL
error_detail 1501.000000

After above described error occured, the arm's modules are set to this state. Simple disabling and enabling cleares the error. When using another software (SCHUNK LWA Tool), I do not get any of these errors.

Second edit: Using the newest indigo dev version of ros_canopen (0.6.4, built from source), about 15 seconds after initialization

[ INFO] [1435070986.332901665]: Initializing XXX
[ INFO] [1435070986.333176067]: Current state: 1 device error: system:0 internal_error: 0 (OK)
[ INFO] [1435070986.333333000]: Current state: 2 device error: system:0 internal_error: 0 (OK)
[ INFO] [1435070988.006267810]: waitForService: Service [/powerball/robot/controller_manager/load_controller] has not been advertised, waiting...
[ INFO] [1435070993.026895499]: waitForService: Service [/powerball/robot/controller_manager/load_controller] has not been advertised, waiting...
[ INFO] [1435070998.044590351]: waitForService: Service [/powerball/robot/controller_manager/load_controller] has not been advertised, waiting...
[ INFO] [1435070999.420373195]: waitForService: Service [/powerball/robot/controller_manager/load_controller] is now available.
[ INFO] [1435070999.524246324]: joint_trajectory_controller loaded
[ INFO] [1435070999.584108329]: joint_group_position_controller loaded
[ INFO] [1435070999.703987054]: joint_group_velocity_controller loaded
[ INFO] [1435070999.724046596]: Switched Controllers. From no_stop_controller_defined to joint_trajectory_controller

I get

[ERROR] [1435071040.303861963]: CAN not ready
[ERROR] [1435071050.303888404]: CAN not ready; RPDO timeout; RPDO timeout; RPDO timeout; RPDO timeout; RPDO timeout; RPDO timeout; RPDO timeout; RPDO timeout; RPDO timeout; RPDO timeout; RPDO timeout; RPDO timeout; CAN not ready

instead of the above messages. When sending a goal right after initialization, I get

error: 4
[ INFO] [1435071040.297516982]: Current state: 2 device error: system:0 internal_error: 4 (controller problems;)
[ INFO] [1435071040.297602617]: Current state: 1 device error: system:0 internal_error: 4 (controller ...
(more)
edit retag flag offensive close merge delete

Comments

hi, I am working with the same hard and software. can i pass you my email adress and ask you some questions? felix.watzlawik@googlemail.com

felixwatzlawik gravatar image felixwatzlawik  ( 2015-06-23 07:02:15 -0500 )edit

1 Answer

Sort by » oldest newest most voted
2

answered 2015-07-06 13:48:25 -0500

Mathias Lüdtke gravatar image

updated 2015-07-06 13:50:00 -0500

It looks like the CAN device driver has problems while sending out messages. The ros_canopen driver sends updates in burst writes, so the queue just might have run full.

Which CAN driver do you use? For the mainline kernel driver it might help to set the TX queuelen to a higher value with: sudo ip link set <network> txqueuelen 15 # it defaults to 10.

If this does not help, can you please provide a candump? (e.g. via gist.github.com ).

I have just filed an issue for the queue overrun: https://github.com/ros-industrial/ros...

edit flag offensive delete link more

Comments

I use PEAK driver, version 7.12. I set txqueuelen to 20, this resulted in the CAN not ready error being delayed. candump see here

Marcel Usai gravatar image Marcel Usai  ( 2015-07-21 10:37:25 -0500 )edit

I am not sure if the PEAK driver uses txqueuelen. According to your candump the driver issued 20000004#000C000000000000 (see linux/can/error.h for reference). The TX and RX errors reach the warning level and the driver stops.

Mathias Lüdtke gravatar image Mathias Lüdtke  ( 2015-07-21 15:25:29 -0500 )edit

Which bitrate do you use? And have you tried the mainline kernel driver? How often does the error occur? Do you have an end resistor at the PEAK side of the CAN bus?

Mathias Lüdtke gravatar image Mathias Lüdtke  ( 2015-07-21 15:37:31 -0500 )edit

using ip -details -statistics link show can0, I could see qlen rise from 10 to 20, so I think, it uses txqueuelen. Bitrate is 500k. Not tried mainline kernel driver.

Marcel Usai gravatar image Marcel Usai  ( 2015-07-22 01:59:39 -0500 )edit

This error occurs always after a certain period of time. When using qlen of 10, it occurs right after initialization, whereas using a qlen of 20, it takes some time and I can even move the arm in this time. I have an end resistor set at the peak side.

Marcel Usai gravatar image Marcel Usai  ( 2015-07-22 02:01:08 -0500 )edit

using the ros_control and ros_canopen version from the ros distro, I do not get CAN not ready errors. But therefore, I got the other errors (see first block of code in question) once in five tries of a test sequence. This is less than before I submitted the question, might be the greater qlen.

Marcel Usai gravatar image Marcel Usai  ( 2015-07-22 03:24:10 -0500 )edit

You should get the CAN not ready in the new driver as well, I will have a look for regressing bugs.. Your CAN dump lists only 9 messages in each cycle, so I do not think that it is related to the txqueuelen.

Mathias Lüdtke gravatar image Mathias Lüdtke  ( 2015-07-22 03:42:58 -0500 )edit

If you want to stick to the PEAK driver, then please update to the latest version. v7.15.1 was released today, it includes some fixes for the USB device, so it might help. However, I recommend the mainline kernel driver ;)

Mathias Lüdtke gravatar image Mathias Lüdtke  ( 2015-07-22 03:49:55 -0500 )edit
1

I had some time to run tests with a LWA4D, and I got the same problems with the mainline kernel driver. Further I have discovered that the driver crashes on shutdown, I have filed an issue for this: https://github.com/ros-industrial/ros... This might influence the kernel driver..

Mathias Lüdtke gravatar image Mathias Lüdtke  ( 2015-07-22 16:10:44 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2015-06-23 05:08:01 -0500

Seen: 1,273 times

Last updated: Jul 22 '15