CAN Interface Available for Testing

Sorry, 0x00B is move_to_pos. It doesn’t support current control mode. What message ID are you sending?

EDIT: OH, I see what you’re doing with the control mode.

Current Setpoint signal has a factor of 0.01, so if you want -10mA (-0.01A), you have to send the value “-1” on the CAN bus. This gets multiplied by 0.01f once it’s received, to turn it back into -0.01A which is then sent to the set_current_setpoint() function.

void CANSimple::set_current_setpoint_callback(Axis* axis, CAN_message_t& msg) {
    axis->controller_.set_current_setpoint(get_32bit_val(msg, 0) * 0.01f);
}

Sorry, current setpiont will be divided by 10, then the unit will become mA, it’s the same.(case 3: set_point /= 10;break; // mA)

Edit: Or get_32bit_val(msg, 0) turns (int) into (unsigned int)?

Edit: Since the current setpiont will be divided by 10, a number smaller than -10 will become zero in my case. So all negative numbers don’t work.

Looks like there was an issue in get_32bit_val. It should be corrected now. Please update to the newest commit

Side note:

If you’re using C or C++ and you want to send a Float value, the best way to do so is with a memcpy:

float myFloat = 1234.56789;
uint8_t buf[8] = {0}; // Zero-initialize the buffer

std::memcpy(&buf[0], &myFloat, sizeof(myFloat));

// Send buffer over CAN

However, you must verify that the data is populated according to the endianness specified for that specific signal. If it’s backwards, simply use a std::reverse to flip it as an intermediate step.

Using unions or fancy casts to accomplish this float -> byte array conversion is undefined behaviour.

1 Like

:+1:Thanks for the effort to develop this. This is something I’ve been really waiting for! It was also
easy to add custom commands too. It seems quite robust compared to USB which I was having issues
when running for a while (disconnects and reconnects although ODrive didn’t reset)
What kind of hardware are you using to send CAN messages from PC?

Err, I wrote some custom software for a Cypress PSoC 5LP running in a custom “breakout board” PCB.
Don’t do what I did to talk on CAN lol.

Get yourself something like a PCAN or a Vector CAN Case module, or similar CAN-to-USB converters. I believe there is an open-source one that’s low cost.

yea that stuff is outside of my abilities… I am using CAN-USB converter but I wish this one had some message filtering functions.
I did end up temporarily disabling heartbeat message. Maybe heartbeat rate can be made to be configurable?(just my personal opinion but seemed to be too much when you have several devices on the bus)

Oh, yeah, that’s a good point. If you’re not using a graphical display with nice updates I could see that being really annoying. Will make a change

EDIT: Updated. Set axis.config.can_heartbeat_rate_ms = 0 to disable heartbeat.

1 Like

I’m having some issues with setting the Trap_traj velocity and acc/dec.
My CAN-ID is set to 1.
COB ID: 1 << 5 + 0x012 (acc/dec) = 0x032

I’m sending a floating point, but no matter what i send i dont see any changes from Anaconda terminal. The motor velocity and acc/dec does not change.

Is there something i need to do prior to set those values?

1 Like

Kakskiv, I am also using it and I can see it updating values in
axisN.trap_traj.config. Do other commands work as expected?

1 Like

I have a different problem. I am not sure why but
header.RTR == 1 instead of 2 (CAN_RTR_REMOTE)
and thus fails this check everytime
rxmsg.rtr = (header.RTR == CAN_RTR_REMOTE) ? true : false;
here is a screenshot of the debugger.

Oh for crying out loud. Why they hell is CAN_RTR_REMOTE == 2?

After digging, CAN_RTR_REMOTE is only used to validate the header.RTR… when transmitting. Stupid.

Ok, I’ve updated the branch. I’ve also pulled in devel, which comes with a communications watchdog. CANSimple will “feed” the watchdog whenever an axis receives a valid message. If you just want to update the watchdog but don’t want to do anything else, send either a CO_NMT (0x000) or CO_HEARTBEAT (0x700). The watchdog is set through axis.config, and is disabled by setting it = 0. By default it is disabled.

May I ask what kind of CAN-USB converter you are using? I want to get started with CAN communication from computer to ODrive. Unfortunately, concerning hardware, I do not really know where to start.
It would be convenient to use USB, but ethernet is also an option.

Concerning software I will be using python-can.

hi walflats, I am using this CAN-serial type converter (https://www.mirifica.it/100218/systembase/scan).
Its actually CAN-RS232 so I use FTDI based RS232-USB converter as well. This type of converter uses ascii text (something like “t06c81027000000000000\r”). You can configure basic params like baudrate and auto error recovery. If you are planning to use python-can library their supported interface list seems to be a good place to start (https://python-can.readthedocs.io/en/3.1.1/interfaces.html). There is an arduino based project compatible with python-can as well (https://github.com/latonita/arduino-canbus-monitor).

1 Like

Thanks, I’ll take a look into the supported interfaces!

@Wetmelon, can you review this PR? thanks,

Hello everybody,

Thanks a lot for this CAN interface, it works fine for me with a Nucleo Board and with a Microchip CAN BUS Analyser.
I just encountered a little problem :
I have configured my Odrive in current control and set the node ID of Axis0 to 0. The command ID is 0x00E.
As I understand, the Current Setpoint signal has a factor of 0.01. So when I want to set the current to 1A, I need to send 100 (0x64).
I get this message :
-msg.id=0x00E
-msg.len=4
-msg.data[0]=0x64
-msg.data[1]=0x00
-msg.data[2]=0x00
-msg.data[3]=0x00

When I send it, it works fine and when I checked with Odrivetool, the current_set_point is correctly set to 1.0f. I tried with different integer values like 2A, 3A, etc… and it works fine too.
My problem is when I want to send a decimal number, like 1.5A for example, I need to send 150 (0x96). So my message is :
-msg.id=0x00E
-msg.len=4
-msg.data[0]=0x96
-msg.data[1]=0x00
-msg.data[2]=0x00
-msg.data[3]=0x00

But I send this, the current_set_point in Odrive is 1.0f. Same when I want to set 2.5A, the current_set_point is 2.0f. It looks like the value is always round to the smallest nearest integer value.
I get the same behaviour with negativ current setpoint.
Does anyone encounter the same problem?

Thanks a lot for your reading

Timothée

Hi Timothée, thanks for the detailed bug report. I was able to reproduce and fix it. Please update to the newest version of the branch.

Hi @Wetmelon,

I just tried the new update and everything work fine now! Thanks a lot.

Have a nice day

Timothée

Hi Timothée
Would you please post the url where you bought this nucleo board and the one for the microship can bus analyser

Thanks