@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! 
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. 