Real alternatives for unreliable usb connection

Im very pleased with odrive, however the big problem it has is the usb connection issue. the main problem i have is:
AttributeError: ‘RemoteObject’ object has no attribute 'axis0’

Usb connection is very unreliable in any real implementation of odrive with big motors.

im running 2 odrives via python usb. my py application is communicating with then and updating position, and VG and PG on real time.

ive managed to get it somewhat stable with a combination of short usb cables, and placement of them, but its obvious there is EMI interferance with the USB line. However it may fail randomly.

ive added an usb isolator in between odrive and the PC and it made it worse.

I would like a rock solid system. What is the alternative?
Ive read this forum and people seem to had success with arduino

would it be possible to have an arduino connected via serial to odrive, and then connect my pc via usb to arduino and send the commands via serial? can i have 2 odrives at the same time like so? can i change position, and VG and PG like so?
would usb EMI problems appear in the arduino usb line in an approach like so?

Is this usb problem going to be solved with odrive V4?

thanks

if i purchase this cable:
https://uk.rs-online.com/web/p/development-tool-accessories/0429307/
and connect to odrive via UART, and launch odrivetool like so:
odrivetool --path serial:/dev/ttyS0.
will this prevent EMI interference with the USB communication?

thanks,

That’s what CAN is for.
Get a USB-CAN adapter like this one (should work on windows or linux, but linux e.g. raspberry pi highly recommended)

USB is great for flexible and powerful configuration and debugging. But when it comes to robust and reliable control in a high-EMI environment, CAN is king.
You can of course use CAN from Arduino if that is your tool of choice (e.g. mcp2515) but personally I find the python-CAN libraries very easy to use.

e.g. this test example: (you may need to modify it e.g. the mouse input stuff is super hacky)

import time
import can
import struct
from evdev import InputDevice, categorize, ecodes
dev = InputDevice('/dev/input/event0')   # need to change for your device
# to find out which is the mouse, hd /dev/input/event0 (move the mouse) then try event1 etc


bustype = 'socketcan'
channel = 'can1'

bus = can.interface.Bus(channel=channel, bustype=bustype)

#** odrive_can_cmd()
# see: https://github.com/ODriveRobotics/ODrive/blob/master/docs/can-protocol.md
# @param node_id: ODrive assigned CAN bus node ID, one per axis
# @param cmd_id: CMD ID as per messages table
# @param data: Python list of signals, according to messages table
# @param format: Python Struct.pack format string for signals in 8-byte CAN message, encoded according to signals table

def odrive_can_cmd(node_id, cmd_id, data=[], format=''):
        data_frame = struct.pack(format , *data)
        msg = can.Message(arbitration_id=((node_id << 5) | cmd_id), data=data_frame, is_extended_id=False)
        bus.send(msg)

# read initial pos from periodic broadcast msgs  (this is a SLOW way todo it, but it's ok as we only need it once here)
def odrive_getPos(node_id):
        while(1):
            msg = bus.recv()
            if(msg.arbitration_id == (node_id << 5) + 0x9):
                 data = struct.unpack('ff', msg.data)
                 return data[0]

# Constants
ODCMD_SET_INPUT_POS = 0x00c
ODCMD_RESET_ERRORS = 0x018
ODCMD_SET_AXIS_STATE = 0x007
AXIS_STATE_CLOSED_LOOP_CONTROL = 8

node_id_x=10
node_id_y=11


xpos = odrive_getPos(node_id_x)
ypos = odrive_getPos(node_id_y)
print("Initial pos x=%f, y=%f" % (xpos, ypos))
# set input_pos to current position - sometimes this is not done by ODrive e.g in input_filter mode
odrive_can_cmd(node_id_x, ODCMD_SET_INPUT_POS, [xpos, 0, 0], 'fhh')
odrive_can_cmd(node_id_y, ODCMD_SET_INPUT_POS, [ypos, 0, 0], 'fhh')


# clear faults
odrive_can_cmd(node_id_x, ODCMD_RESET_ERRORS)
odrive_can_cmd(node_id_y, ODCMD_RESET_ERRORS)
# put into position-hold
odrive_can_cmd(node_id_x, ODCMD_SET_AXIS_STATE, [AXIS_STATE_CLOSED_LOOP_CONTROL], 'h')
odrive_can_cmd(node_id_y, ODCMD_SET_AXIS_STATE, [AXIS_STATE_CLOSED_LOOP_CONTROL], 'h')


def mousecan(xpos, ypos):
    for event in dev.read_loop():
        if (event.type == ecodes.EV_REL):
            if(event.code == 0):
                 xpos = xpos - event.value * 0.002
                 odrive_can_cmd(node_id_x, ODCMD_SET_INPUT_POS, [xpos, 0, 0], 'fhh')

            if(event.code == 1):
                 ypos = ypos - event.value * 0.002
                 odrive_can_cmd(node_id_y, ODCMD_SET_INPUT_POS, [ypos, 0, 0], 'fhh')

            print("xpos: %f ypos: %f" % (xpos, ypos))

mousecan(xpos, ypos)
3 Likes

Thanks for the info and examples.
ive looked at the can messages docs, and it looks like setting PG and VG is not supported:

I would need to set axis position, PG and VG on real time, so i think so far it will not be usable.
ive ordered an UART usb adaptor, hopefully this helps with interference.
cheers

I wish you luck with UART, but beware that as a single-ended, non-isolated interface, it is NOT immune to noise or ground-loops. Whereas the CAN adapter I linked is isolated, and CAN uses differential signaling to make it immune to common-mode noise. At the very least, you will need to use the ferrite rings, and you may need a USB isolator (or better, an RS232 isolator / isolated USB-serial adapter)

As for position & velocity gains, these are very easily added to the CAN protocol.

See can_simple.cpp in the ODrive source.
All you’d need to do, is add a few messages to that switch statement.

Actually what i’d really like to see, would be CAN messages configurable in the same way as analogue inputs, with a Fibre endpoint ID.
There could be a default set (or better, a flag to enable the default protocol messages, which are hardcoded) but a set of 8 or so user-definable messages, which report or set any variable in the system.

Something like
odrv0.axis0.can.user_defined.config.msg1.arb_id : int
odrv0.axis0.can.user_defined.config.msg1.endpoint : fibre_endpoint_t
odrv0.axis0.can.user_defined.config.msg1.direction : CAN_USER_DIR_TX | CAN_USER_DIR_RX
odrv0.axis0.can.user_defined.config.msg1.tx_rate_ms : int

@Samuel is this feasible? Should I start a thread / issue for it?
I’d put in a PR, but it could take me a while as i’m not all that familiar with the internal workings of Fibre.

The other really nice thing about doing it this way is, it ought to be possible to write a DBC file and have a module for ODriveTool that automatically configures the custom protocol to match the DBC. (instead of having to manually write a DBC file to match whatever is programmed in to the ODrive)
Then, automotive-standard CAN tools are able to interact with the ODrive in ways that will be familiar to automotive CAN users.

Hi , i really appreciate your help
i mostly program in python, not really a C person.
but i understand in principle what you say. however i dont think i have the capacity to implement that.

it would be ideal if these 3 messages could be added to the can protocol and pushed to the main branch

axis0.controller.config.vel_gain
axis0.controller.config.pos_gain
axis0.controller.input_pos

thanks again

It should be pretty simple to do this, controller.input_pos is already there as a CAN command - but you will need to add commands for the gains.
You need to edit just can_simple.hpp and can_simple.cpp following the examples of other functions in those files.
e.g. this should work (i haven’t tried it)
(also i assume you know how to read a diff - the lines with + are the ones i’ve added, the rest is just context)

diff --git a/Firmware/communication/can/can_simple.cpp b/Firmware/communication/can/can_simple.cpp
index 3a24ead1..26a4eb82 100644
--- a/Firmware/communication/can/can_simple.cpp
+++ b/Firmware/communication/can/can_simple.cpp
@@ -144,6 +144,12 @@ void CANSimple::do_command(Axis& axis, const can_Message_t& msg) {
         case MSG_SET_LINEAR_COUNT:
             set_linear_count_callback(axis, msg);
             break;
+        case MSG_SET_GAIN_POS:
+            set_pos_gain_callback(axis, msg);
+            break;
+        case MSG_SET_GAIN_VEL:
+            set_vel_gain_callback(axis, msg);
+            break;
         default:
             break;
     }
@@ -271,6 +277,15 @@ void CANSimple::set_limits_callback(Axis& axis, const can_Message_t& msg) {
     axis.motor_.config_.current_lim = can_getSignal<float>(msg, 32, 32, true);
 }

+void CANSimple::set_gain_pos_callback(Axis& axis, const can_Message_t& msg) {
+    axis.controller_.config_.pos_gain = can_getSignal<float>(msg, 0, 32, true);
+}
+
+void CANSimple::set_gain_vel_callback(Axis& axis, const can_Message_t& msg) {
+    axis.controller_.config_.vel_gain = can_getSignal<float>(msg, 0, 32, true);
+    axis.motor_.config_.vel_integrator_gain = can_getSignal<float>(msg, 32, 32, true);
+}
+
 void CANSimple::start_anticogging_callback(const Axis& axis, const can_Message_t& msg) {
     axis.controller_.start_anticogging_calibration();
 }
diff --git a/Firmware/communication/can/can_simple.hpp b/Firmware/communication/can/can_simple.hpp
index b2e14018..614c0e2a 100644
--- a/Firmware/communication/can/can_simple.hpp
+++ b/Firmware/communication/can/can_simple.hpp
@@ -33,6 +33,8 @@ class CANSimple {
         MSG_GET_VBUS_VOLTAGE,
         MSG_CLEAR_ERRORS,
         MSG_SET_LINEAR_COUNT,
+        MSG_SET_GAIN_POS,
+        MSG_SET_GAIN_VEL,
         MSG_CO_HEARTBEAT_CMD = 0x700,  // CANOpen NMT Heartbeat  SEND
     };

@@ -70,6 +72,8 @@ class CANSimple {
     static void set_input_torque_callback(Axis& axis, const can_Message_t& msg);
     static void set_controller_modes_callback(Axis& axis, const can_Message_t& msg);
     static void set_limits_callback(Axis& axis, const can_Message_t& msg);
+    static void set_pos_gain_callback(Axis& axis, const can_Message_t& msg);
+    static void set_vel_gain_callback(Axis& axis, const can_Message_t& msg);
     static void set_traj_vel_limit_callback(Axis& axis, const can_Message_t& msg);
     static void set_traj_accel_limits_callback(Axis& axis, const can_Message_t& msg);
     static void set_traj_inertia_callback(Axis& axis, const can_Message_t& msg);

As for pushing to the main branch, that’s up to the devs (i’m just a user like you) but I suspect these commands are left out for good reasons.

  1. setting control gains is a fairly unusual (and potentially quite violent/destructive) thing to do a control system when not in commissioning-mode, and must not be done accidentally when connected to a delicate load, for example. If these messages were in the default protocol, then people could accidentally set absurd control gains which would cause massive and violent vibrations, so this is really only for people who know what they are doing, i.e. are not afraid to edit the code.
    That’s why I’d like to make the CAN configurable by the user - that way, it is powerful enough for power-users, but the default configuration remains safe and simple enough for novices.
    But like I say, implementing it that way is a bit beyond my own knowledge of the system, more Samuel or @wetmelon’s domain
  2. “CAN simple” is a pretty dumb protocol, as CAN protocols go. It is designed to be as simple as possible to understand. Adding too much stuff in there would defeat the object of it.

Hi, thanks again for the kind examples. I might give it a go.
Once I have my modified source code, what is the process to put it into odrive?
Cheers

You need to then build the firmware with ‘tup’ following the developer guide:

Once built, you can flash it with odrivetool:
odrivetool dfu Firmware/build/ODriveFirmware.hex

Then I succeeded in my goal :smiley: Adding gain adjustment is definitely valuable though, gain scheduling is a fairly common thing to do in systems.

Pull Request: Add pos_gain and vel_gains CAN messages by Wetmelon · Pull Request #630 · odriverobotics/ODrive · GitHub

Thanks a lot!! i hope this gets merged.

ive ordered the can adapter and will try as soon as i get it delivered and the patch is merged.
cheers.

Hi i am quite new to the concept of CAN , i came looking for a solution for how unreliable USB can be at times .
i was looking to connect my Raspberry Pi to my odrive via a canbus connection instead of a usb connection . How should i go about this , i currently have a MCP2515 CAN BUS shield which has a TJA1050 CAN transciever chip on it , am i better off using the USB to CAN connector or is there some other CAN Controller which i can use to connect to the Odrive board , if so please let me know

We have a CAN guide for this :slight_smile:

I have tried the RS485 HAT as linked above however whenever I try to perform the candump function it doesn’t return anything it just stalls and does nothing , this was the case even with a MCP2515 CAN shield
Could there be some problem with the Raspberry Pi

Did you add the devicetree overlay to the boot.txt file as per the instructions?

dtparam=spi-on
dtoverlay=mcp2515-can0,oscillator=12000000,interrupt=25
dtoverlay=spi0-hw-cs

when i used this i got a Failed to load overlay ‘spio-hw-cs’
dterror : overlay 'spio-hw-cs’is deprecated:no longer necessary

i went ahead and tried pulling the canbus connection up with

sudo ip link set can0 up type can bitrate 250000

on returning ifconfig can0 i get

can0: flags=193<UP,RUNNING,NOARP>   mtu 16
unspec 00-00-00-00-00-00-00-00-00-00-00-00-00-00-00-00  txqueuelen 10  (UNSPEC)
RX packets 0  bytes 0 (0.0 B)
RX errors 0  dropped 0  overruns 0  frame 0
TX packets 0  bytes 0 (0.0 B)
TX errors 0  dropped 0 overruns 0  carrier 0  collisions 0

however when i use candump can0 or candump any i dont get anything
i even removed the dtoverlay=spi0-hw-cs line and rebooted and tried candump same result
the same case happened with a mcp2515 can sheild as well

You forgot to close your code block :wink: but that’s OK I can still read your post

That’s fine, you can remove the second dtoverlay line - as it says, it’s covered by the first and no longer needed.

Make sure that ODrive is configured to send CAN messages and at the baud rate that you set.
Also make sure the termination is correct. Should be 120R each end, which will measure as 60 Ohms between CANH and CANL.

Also make sure that the oscillator value in the config.txt matches the frequency of the crystal on your board. e.g. if you can see a metal component with “16.0000” written on it, then you have a 16MHz crystal and so you need to change oscillator=12000000

FWIW the devicetree for my CAN hat is slightly different. I have:

dtparam=spi=on
dtoverlay=mcp2515-can0,oscillator=16000000,interrupt=25
dtoverlay=spi-bcm2835-overlay

That last line is specific to the Raspberry Pi 4, I think.

Hello,

I have the same problem with Woke. It’s been 2 years since this topic, but I’m still stuck here. I read a lot of things but I couldn’t figure it out.

I set the bitrate 500000 both odrive and RPi 4 and my oscillator is 12000000. I am using the RS485/CAN HAT for MCP2515.

The resistance value between CanH and CanL on the Odrive side is 74.2 ohms and on the CAN HAT side this value is 44.2 ohms. Is there any problem with that? When I send the candump can0 or candump any I don’t get any thing.

Also when I try to run can_dbc_example.py I get:

pi4@pi4:~/ODrive-fw-v0.5.4/tools $ python3 can_dbc_example.py 

Requesting AXIS_STATE_FULL_CALIBRATION_SEQUENCE (0x03) on axisID: 3
{'Axis_Requested_State': 3}
Timestamp:        0.000000        ID: 0067    S Rx                DL:  8    03 00 00 00 00 00 00 00
Message sent on socketcan channel 'can0'
Waiting for calibration to finish...

But nothings happen on the motor. In the odrivetool I set the axis1 node ID 3.

I am new to the CAN bus communication system. Pls help me.