ros_canopen icon indicating copy to clipboard operation
ros_canopen copied to clipboard

Add CAN error handling to socketcan_bridge

Open mathias-luedtke opened this issue 8 years ago • 3 comments

Currently, the socketcan_bridge nodes to not handle error. There is no inteface to read the state or any way to recover the interface.

(via http://answers.ros.org/question/267980/socketcan_bridge_node-error-handling/)

mathias-luedtke avatar Aug 04 '17 15:08 mathias-luedtke

Anyone wishing to reproduce this issue, can follow these steps:

Setup vcan0:

$ sudo ip link add dev vcan0 type vcan
$ sudo ip link set up vcan0

Run the socketcan bridge node:

$ roscore
$ rosrun socketcan_bridge socketcan_bridge_node _can_device:=vcan0

Send can frames, for example:

import rospy
from can_msgs.msg import Frame

rospy.init_node('sender')
pub = rospy.Publisher('/sent_messages', Frame, queue_size=20)
rate = rospy.Rate(13)

counter = 1
while not rospy.is_shutdown():
    frame = Frame()
    frame.id = 13
    frame.dlc = 3
    frame.data = bytes([55, 11, counter])
    counter += 17
    while counter >= 256:
        counter -= 256
    pub.publish(frame)
    rate.sleep()

Inject an error with the below:


import socket
import struct
import sys

assert sys.version_info.major == 3

CAN_ERR_FLAG = 0x2000_0000
CAN_ERR_LOSTARB = 0x2
CAN_ERR_BUSOFF = 0x40
CAN_ERR_MASK = 0x1FFF_FFFF


def pack_msg(msg_id, payload):
    """ Pack bytes according to socketcan. """
    ln = len(payload)
    flags = 0

    part1 = struct.pack('=IBB2x', msg_id, ln, flags)
    assert ln <= 8
    padding_size = 8 - ln
    part2 = payload + bytes([0] * padding_size)
    assert len(part2) == 8
    xmit = part1 + part2
    assert len(xmit) == 16
    return xmit


def emit(sock, msg_id, payload):
    xmit = pack_msg(msg_id, payload)
    sock.send(xmit)

def inject_error(sock, err):
    emit(sock, CAN_ERR_FLAG | err, bytes([0] * 8))

def main():
    device = 'vcan0'

    # Create socket:
    sock = socket.socket(socket.PF_CAN, socket.SOCK_RAW, socket.CAN_RAW)
    sock.bind((device,))

    try:
        emit(sock, 0x133, bytes([1,2,3]))
        inject_error(sock, CAN_ERR_BUSOFF)
    finally:
        sock.close()

main()

windelbouwman avatar Feb 26 '21 16:02 windelbouwman

@ipa-mdl what is your opinion of possible solution here? There is a proposal to call recover when an error is reported, is this correct or not?

My ideas for implementation or what has been proposed:

  • Listen to state changes, and call driver recover function when entering error state.
  • When sending a message, check for success, if failed, call recover and retry.
  • Handle error frames, but leave the state of the driver as is.

Any more suggestions?

windelbouwman avatar Mar 01 '21 08:03 windelbouwman

Listen to state changes, and call driver recover function when entering error state.

This the preferred way

When sending a message, check for success, if failed, call recover and retry.

This might be very complicated to implement (properly)..

  • Wait for restart delay
  • How many retries?
  • Queuing of old messages..

Handle error frames, but leave the state of the driver as is.

For now there is the choice to ignore certain errors. Handling must be done in sub classes.


canopen_chain_node has a recoverservice. Something similar might might be useful for socketcan_bridge as well. Together with a simple diagnostics topics, users can recover whenever it is necessary. It could as well be an optional flag for the bridge. And offline-queuing could be added on top of it, but would need some configuration.

mathias-luedtke avatar Mar 01 '21 14:03 mathias-luedtke