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

ROS_CANopen faults on init.

asked 2019-12-16 13:50:34 -0600

updated 2019-12-16 13:53:41 -0600

I have a Bechoff CANopen bus terminal I'm trying to interface with. However, the driver fails on init and faults with the following error. I'm fairly new to CAN and am having a hard time debugging this.

Snapshot of terminal upon launching the canopen_chain_node -

sidd@ubuntu:~$ roslaunch canopen_chain_node chain.launch yaml:=path/to/bus.yaml
[ INFO] [1576523526.299477632]: Initializing...
[ INFO] [1576523526.301994944]: Current state: 1 device error: system:0 internal_error: 0 (OK)
[ INFO] [1576523526.302596992]: Current state: 2 device error: system:0 internal_error: 0 (OK)
[ INFO] [1576523527.617270944]: Current state: 2 device error: system:125 internal_error: 0 (OK)
[ INFO] [1576523527.617470912]: Current state: 0 device error: system:125 internal_error: 0 (OK)
[ INFO] [1576523527.617731168]: Current state: 0 device error: system:0 internal_error: 0 (OK)
[ INFO] [1576523527.617830624]: Current state: 0 device error: system:0 internal_error: 0 (OK)
[ERROR] [1576523527.618035712]: CAN not ready
[ERROR] [1576523527.618344320]: Initializing failed: PDO error: _Map_base::at

The bus.yaml file with parameters looks like this -

bus:
    device: can0
    loopback: false
sync:
    interval_ms: 10
#    update_ms: 10
    overflow: 0
heartbeat:
    rate: 20
    msg: "707#00"

nodes:
    node1:
        id: 7
        eds_file: "/home/sidd/ws/install/share/sidd_canopen/BK5120.eds"
        publish: ["2000sub1!"]

Upon calling the /driver/init service, I get the error -

sidd@ubuntu:~$ rosservice call /driver/init
success: False
message: "PDO error: _Map_base::at"

I tried doing a candump to get the raw frames, and this is what it prints out -

sidd@ubuntu:~$ candump can0
can0  707   [1]  00
can0  000   [2]  82 07
can0  707   [1]  00
can0  607   [8]  2B 17 10 00 00 00 00 00
can0  587   [8]  60 17 10 00 00 00 00 00
can0  000   [2]  02 07

I've also monitored the error counters by running and don't see anything suspicious -

sidd@ubuntu:~$ ip -details -statistics link show can0
8: can0: <NOARP,UP,LOWER_UP,ECHO> mtu 16 qdisc pfifo_fast state UNKNOWN mode DEFAULT group default qlen 10
    link/can  promiscuity 0 
    can state ERROR-ACTIVE (berr-counter tx 0 rx 0) restart-ms 0 
    bitrate 250000 sample-point 0.875 
    tq 20 prop-seg 87 phase-seg1 87 phase-seg2 25 sjw 1
    mttcan: tseg1 2..255 tseg2 0..127 sjw 1..127 brp 1..511 brp-inc 1
    mttcan: dtseg1 1..31 dtseg2 0..15 dsjw 1..15 dbrp 1..15 dbrp-inc 1
    clock 50000000
    re-started bus-errors arbit-lost error-warn error-pass bus-off
    0          0          0          0          0          0         numtxqueues 1 numrxqueues 1 gso_max_size 65536 gso_max_segs 65535 
    RX: bytes  packets  errors  dropped overrun mcast   
    57         15       0       0       0       0       
    TX: bytes  packets  errors  dropped carrier collsns 
    72         18       0       0       0       0

EDS file I'm using attached as a github gist

I see this github issue here with the same error code, but that's not very useful and I doubt the issues are related.

Any help would be appreciated!

edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
0

answered 2020-02-27 11:06:19 -0600

updated 2020-02-27 11:08:17 -0600

Answering my own question, thanks to @GuillaumeB for the pointers.

Essentially the problem was that my EDS file needed updates to adhere to the CiA 306DS standard. Without a proper understanding, I edited the EDS file which resulted in this error. Reverting back to the original version from the manufacturer and fixing the original errors in the EDS file fixed the problem for me.

Yes the original EDS file I got from the manufacturer did not work out the box, and the ros_canopen implementation is pretty strict about following the 306DS standard.

For anyone else having similar trouble, I'd recommend using the caneds software to make sure the eds file is right. (It's a windows exe, but V3.6 is supposed to be compatible with wine on Ubuntu)

edit flag offensive delete link more
1

answered 2019-12-17 08:21:16 -0600

GuillaumeB gravatar image

First I don't understand why your CANopen node should send the msg 707#00. That would be the boot-up message from your node 7 (the node you are trying to control) I would rather do something like 701#05. Second, you should double-check your EDS. The value you are are trying to pull 2000sub01 is not mapped in your PDOs. (So Ros CANopen is gonna use SDO) The problem apparently comes from your PDO mapping (from your EDS file). First, you have two PDO activated (180 and 280+id) (1800 and 1801). You have to check that they are correctly mapped (1A00 and 1A01) 1A00 says you have two entries. 1A00sub01 as DefaultValue=0x60000108 it means that you want to map 0x08 bits from the object 6000sub01 You are indicating the object 6000sub01 which doesn't exist in your EDS. If you look at the second PDO 1A01sub01 default value is DefaultValue=0x64010110 and object 6401sub01 exist in your EDS it's Analogue Input 1.

So either you deactivated the first TPDO (1800) or you remap it (1A00) with for example your 2000sub01 value

Let me know if it works

edit flag offensive delete link more

Comments

I see. Ok I updated the eds file here. I now run into the error -

[ INFO] [1576597003.552654656]: Initializing...
[ INFO] [1576597003.555253792]: Current state: 1 device error: system:0 internal_error: 0 (OK)
[ INFO] [1576597003.555966432]: Current state: 2 device error: system:0 internal_error: 0 (OK)
[ERROR] [1576597004.876764384]: abort6000#2, reason: Sub-index does not exist.
[ERROR] [1576597004.876970496]: Could not process message
[ INFO] [1576597004.877495456]: Current state: 0 device error: system:0 internal_error: 0 (OK)
[ INFO] [1576597004.877748128]: Current state: 0 device error: system:0 internal_error: 0 (OK)
[ERROR] [1576597004.878175328]: Initializing failed: /tmp/binarydeb/ros-melodic-canopen-master-0.8.2/src/sdo.cpp(429): Throw in function void canopen::SDOClient::transmitAndWait(const canopen::ObjectDict::Entry&, const canopen::String&, canopen:
Sidd gravatar image Sidd  ( 2019-12-17 09:41:22 -0600 )edit

But according the eds I used the 6000 subindex2 does exist here

Sidd gravatar image Sidd  ( 2019-12-17 09:42:19 -0600 )edit

I did however deactivate the 1a00sub2, (set it's default value to 0x0 and it looks like it initialized ok...

process[canopen_chain-2]: started with pid [945]
[ INFO] [1576597355.238340096]: Initializing...
[ INFO] [1576597355.240405152]: Current state: 1 device error: system:0 internal_error: 0 (OK)
[ INFO] [1576597355.240761536]: Current state: 2 device error: system:0 internal_error: 0 (OK)
[ERROR] [1576597358.587319584]: EMCY received: 87#0000000000000000
[ INFO] [1576597358.589335488]: Initializing successful
Sidd gravatar image Sidd  ( 2019-12-17 09:45:23 -0600 )edit

Did you just add a section in your EDS? The EDS is just a representation of how data are organized inside your device. You cannot just add a section (6000sub00) like this If this memory doesn't exist in your device. Before using the ros-canopen I highly advise you to read about canopen (ex this: https://hg.beremiz.org/CanFestival-3/...) and also to try to get your data by just sending raw canbus frames (with cangen and candump), to really understand how it works.

GuillaumeB gravatar image GuillaumeB  ( 2019-12-17 10:05:36 -0600 )edit

Thanks for the link, I'll take a look at it. I modified the original EDS file from the Beckhoff website to remove the 6000 registers since I read somewhere that the ROS CANopen driver is 402 and that reserves the 0x6000 to 0x67FF objects.

Sidd gravatar image Sidd  ( 2019-12-17 10:17:46 -0600 )edit

I see, you should keep the original EDS (At least the OD structure). The 402 Can standard is only followed by motor node (Have a look here: http://wiki.ros.org/ros_canopen). since you are using chainnode it's fine

GuillaumeB gravatar image GuillaumeB  ( 2019-12-17 10:50:07 -0600 )edit

Question Tools

2 followers

Stats

Asked: 2019-12-16 13:50:34 -0600

Seen: 944 times

Last updated: Feb 27 '20