CAN Interface Available for Testing

So, what part of your command expresses the "odrv0.axis0.controller.pos_setpoint = " part?
You are just trying (and failing) to send the number 10000, which makes no sense, unless the ODrive is set up to expect this, and treats all numbers recieved as position setpoints for axis 0.

As to bitshifting, you are doing it twice, I think. Once in your head, and a second time in the code. You don’t need to write each byte of the number you are trying to send.

So your bytes are:
(10000 & 0xFF)
((10000 >> 8) & 0xFF)
((10000 >> 16) & 0xFF)
((10000 >> 24) & 0xFF)

Tom

Hi Tom,
Sorry for the late reply . I was out of town.

To set axis0 position to 10000:
Axis ID = 0x03
Command ID = 0x00C

CAN Message ID: = 0x03 << 5 + 0x00C = 0x6C

@seatle OK, having RTFA above, I have got it working on my odrive

I am using axis1 with default CAN settings, RazorsEdge branch. Node ID is 63 (0x3f), apparently, which translates to 0x7e when shifted left by 5 bits.

In [72]: odrv0.can
Out[72]: 
error = 0x0000 (int)
config:
  baud_rate = 250000 (int)
can_protocol = 0 (int)
set_baud_rate(baudRate: int)
In [73]: odrv0.axis1.config.can_node_id
Out[73]: 63

I am using a raspberry pi with “skpang” CAN hat. I have installed the can-utils package to easily send CAN frames from the command line.

First, I set up the CAN interface like so:

pi@rpi:~ $ sudo ip link set dev can0 down
pi@rpi:~ $ sudo ip link set dev can0 type can bitrate 250000
pi@rpi:~ $ sudo ip link set dev can0 up

Then I run candump can0 - I can see heartbeat messages from each axis:

  can0  001   [8]  00 00 00 00 01 00 00 00
  can0  7E1   [8]  00 00 00 00 08 00 00 00
  can0  001   [8]  00 00 00 00 01 00 00 00
  can0  7E1   [8]  00 00 00 00 08 00 00 00
  can0  001   [8]  00 00 00 00 01 00 00 00

So it works! :slight_smile:
But I can’t see any messages because of the spam…
In odrivetool I set the heartbeat rate to be 10000 ms (10s) to avoid spamming my terminal:

In [70]: odrv0.axis1.config.can_heartbeat_rate_ms=10000
In [71]: odrv0.axis0.config.can_heartbeat_rate_ms=10000

Let’s say I want to query the DC-bus voltage.
I use Ruby (IRB) to calculate my message in hex, knowing that my node-ID is 63(dec) and the “get DC Bus” is 0x17 (hex):

irb(main):014:0> ((63 << 5) + 0x17).to_s(16)
=> "7f7"

So, leaving candump running in another terminal, I run cansend to query the DC-Bus voltage, like so:

pi@rpi:~ $ cansend can0 7f7#R

In the first terminal I look for my message and response:

  can0  7F7   [0]  remote request
  can0  7F7   [8]  33 F5 42 41 00 00 00 00

Nice, I have a response. But it’s encoded as a float. So I’ll again use Ruby to decode it…

irb(main):022:0> "\x33\xF5\x42\x41".unpack("f")  
=> [12.184863090515137]

12.1848 volts. Looks about right.

Now here’s the bit maybe you didn’t do, I send the axis enable command:

pi@rpi:~ $ cansend can0 7e7#08

8 being the value of AXIS_STATE_CLOSED_LOOP_CONTROL
I hear the motor start and it is now holding position at zero. Success!

Now, I can try sending a position command:

irb(main):023:0> ((63 << 5) + 0x0B).to_s(16)                             
=> "7eb"
pi@rpi:~ $ cansend can0 7eb#00
pi@rpi:~ $ cansend can0 7eb#08
pi@rpi:~ $ cansend can0 7eb#ff
pi@rpi:~ $ cansend can0 7eb#ff.ff

Nothing happens… I go back to odrivetool.

In [75]: odrv0.axis1.controller.input_pos
Out[75]: 0.0
In [76]: odrv0.axis1.controller.input_pos=100
In [77]: odrv0.axis1.controller.input_pos=1000

Still nothing. Turns out this was because input_mode was not set (should have been saved from my config, but maybe it didn’t…?)

In [80]: odrv0.axis1.controller.config.input_mode
Out[80]: 0
In [81]: INPUT_MODE_PASSTHROUGH
Out[81]: 1
In [82]: odrv0.axis1.controller.config.input_mode=1

Now, it sort of seems to work, but the motor only twitches slightly… I tried different values and it eventually shuts off completely.
It turns out I was sending the wrong command. The command values used by RazorsEdge have changed since the top post in this thread.
RTFS here: https://github.com/Wetmelon/ODrive/blob/RazorsEdge/Firmware/communication/can_simple.hpp

Counting down the enum, it seems I should be sending command number 12, not 11. Move_to_pos is replaced by set_controller_modes, which explains why I was getting confused earlier.

Now it works.

MSG_SET_INPUT_POS is command ID 12, and has three parameters:
Position (int32, little endian)
Velocity feedforward (int16, little endian)
Torque feedforward (int16, little endian)
I can leave the feedforward terms as zero, and just set the input_pos:

irb(main):026:0> ((63 << 5) + 0x0C).to_s(16)
=> "7ec"
irb(main):031:0> [1000,0,0].pack("l<s<s<")
=> "\xE8\x03\x00\x00\x00\x00\x00\x00"
pi@rpi:~ $ cansend can0 7ec#e8.03.00.00.00.00.00.00
pi@rpi:~ $ cansend can0 7ec#00.00.00.00.00.00.00.00

The motor moves to position 1000, and back again. :smiley:

5 Likes

So, for your C code on the arduino, I’d probably do something like this:

#define CMD_SET_INPUT_POS 12
void setInputPos(uint16_t axis_node_id, int32_t pos, int16_t vff = 0, int16_t tff = 0)
{
    uint64_t data = pos + (vff << 32) + (tff << 48);
    CAN0.sendMsgBuf((axis_node_id << 5) | CMD_SET_INPUT_POS, (unsigned char*)(&data));
}

...
uint8 my_axis_id = 0x03;
setInputPos(my_axis_id, 1000);

Just to check my bitshift operators, again Ruby’s array:pack comes in really handy :stuck_out_tongue:

irb(main):038:0> [1000 + (1 << 32) + (1 << 48)].pack("Q<")
=> "\xE8\x03\x00\x00\x01\x00\x01\x00"

irb(main):041:0> [1000 + (1 << 32) + (1 << 48)].pack("Q<").unpack("l<s<s<")
=> [1000, 1, 1]

Yeah, sorry - RazorsEdge commands don’t quite match the CAN branch commands due to the changes introduced by the input_filter branch.

I believe the protocol documentation on the RazorsEdge branch is up to date, however https://github.com/Wetmelon/ODrive/blob/RazorsEdge/docs/can-protocol.md

Hey Wetmelon, thanks for all the work on implementing CAN for Odrive!

I was reading through this entire post, some of the PR’s on your fork, and the PR you have on the main Repo. What is the general plan for getting your CAN work in the master repository? Is there a list of things that need to be fixed, validated, and tested?

I was wondering because after reading this thread, it seems like a lot of people have not had an easy getting a test setup for CAN. I have done quite a bit of work with a PCIe PCAN card using SocketCAN, but was thinking about developing a quick STM32 and SN65HVD242D board or maybe an existing board/shield combo. Do you think it is worth developing something new or using something existing? Either way, I would like to set that up and create a pretty decent write-up so that we can get more people using CAN without a lot of troubleshooting on a bunch of different setups. What are you thoughts?

There are a couple of us setting up a CAN rig for testing in the RazorsFrozen branch. We will be testing with both a Teensy and a Raspberry Pi (with CAN hat and cantools or socketCAN). It’s always worth doing write-ups and more testing :smiley:

Hi everyone!

Is there at the moment the possibility to feed the watchdog through CAN?
Thank you :slight_smile:

Hi Matteo,

The watchdog is fed any time an axis receives a valid message.

Hi @Wetmelon, thank you!

Is there also any possiblity to use the ramped velocity control with CAN messages or any workaround I could try?

You can set the input and control mode with MSG_SET_CONTROLLER_MODES then use input_vel, but it seems you can’t change the acceleration limits…

1 Like

Hey, quick question.

Vel FF
Current FF

Anyone know what the above signals are for? They can be found in the ‘Set Pos Setpoint’ command. Thanks.

These are feedforward terms for the velocity and torque controllers, and are very optional. For example if you are holding a load, you could set a torque feedforward equivalent to the constant torque produced by the load, so the position controller has less to correct for. This can help to get better positioning accuracy without relying on a high integral gain.
They would normally be used by an automated controller that is aware of the motion profile it is sending to the robot.

1 Like

I’m looking at the CAN implementation, noticed that the 11 bit IDs are split into 6 and 5, so up to 64 devices and 32 possible commands. Of which, 24 CAN IDs are already defined.

I usually find it necessary to send other values to motor drivers from a master. I’ve been doing this over multidrop serial data in the past. CAN seems to be a better choice going forward.

For example:

  • PID values
  • Current Limit value or max PWM value
  • Maximum position error limit
  • Set motor stop on position error or limit switch
  • Reset position to zero (or other value) on position error or limit switch

These are some of the things I need to do when I’m homing, then I send new values when I’m in runmode. I prefer to allow the master to store these values and not rely on the motor driver to store them. Less things to update when things change.

Is there any plan to use up the remaining 7 or 8 IDs?

Those sound like decent reasons :slight_smile:

Also we’ve implemented homing, so I can probably make a “home axis” command or similar.

Thanks for listening.

Here, have implemented CAN control long ago and over time, ran out of bus bandwidth @ 500kbps. Couldn’t go the 1Mbps due to cable length requirements. Eventually was telescoping the bus over 10/100 Ethernet and fiber for longer hauls, but still had to stick to 500kbps.

The importance of ID priority cannot be understated on a busy bus. IDs closer to 0x000 get priority. Your ID scheme and support of CANOpen might be questioned in the future, when a busy bus is encountered. I had set packet IDs lowest as I cared about set-position, being updated every 5ms - ~18ms, depending on the type of device I was controlling and how critical the motion coordination needed to be.

I’ve seen CAN buffers overflow (older microcontroller devices were slow and had few frames in the buffer) and had to implement extensive ID filtering in the devices as well as the Eth to CAN bridges. If you get to that point with CAN, you’re pretty much doomed, and better off looking at CAN FD or parallel busses.

If I were to re-implement a protocol now, I’d swap your node ID and command ID, and make ‘Set Position Setpoint’ CMD ID = 0x001, saving estop = 0x000. Then go up from there, based on the time sensitivity of the CMD.

Certainly not telling you what to do, but sharing some insight from doing motion control over CAN, since '04. Here, was all brush DC servo motors, max out at 16 motors on one bus.

When I type odrv0.axis0.config.can_node_id = 3
I get " AttributeError: ‘RemoteObject’ object has no attribute"

Do I need a firmware update?

You need to flash the firmware as detailed here. However, the firmware CAN branch (linked above in the original post) recently became unavailable. Hopefully it’s back soon, since im also looking to use CAN as well.

I like your biped project btw, looking forward to your next vid :grinning:.

1 Like

All of the CAN features have been integrated into devel now, so please use this branch

1 Like

Has anyone had success getting CAN communication to work on the devel branch? I’ve got my V3.5 48v dual axis odrive flashed to the head of devel. I’ve got the odrive’s CAN pins hooked up to a CAN network with 2 raspberry pi zeros connected via MPC2515 CAN boards

The raspis have the CAN bus initialized as follows :

sudo /sbin/ip link set can0 up type can bitrate 250000

I configured the odrive to have the same CAN data rate and I set each axis to have a custom can ID then saved the configuration (as shown in the CAN documentation).

I can send CAN messages between the raspis just fine but when I connect the odrive CAN pins then the messages won’t come through between the two raspis and I don’t see any heartbeat messages from the odrive axes. When I disconnect either of the odrive CAN pins from the CAN bus then the raspi CAN messages that didn’t come through show up all at once on the other raspi. I’ve tried all possible combinations of the odrive CAN terminating resistor dip switch along with the CAN resistors on the raspis CAN boards. I’ve also tried just having one of the raspis hooked up to the odrive with the same results. Anyone have any ideas? Thanks.