Skip to content

Commit 77fabc5

Browse files
committed
autosync
1 parent 9a0868b commit 77fabc5

16 files changed

+369
-330
lines changed

README.md

Lines changed: 5 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,8 @@
11
# ODriveArduino
22
Arduino library for controlling [ODrive motor controllers](https://odriverobotics.com/).
33

4-
See https://docs.odriverobotics.com/v/latest/guides/arduino-guide.html for usage instructions.
4+
Supports UART and CAN communication.
5+
6+
See https://docs.odriverobotics.com/v/latest/guides/arduino-uart-guide.html for usage instructions with UART.
7+
8+
See https://docs.odriverobotics.com/v/latest/guides/arduino-can-guide.html for usage instructions with CAN.
Lines changed: 269 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,269 @@
1+
2+
#include <Arduino.h>
3+
#include "ODriveCAN.h"
4+
5+
// Documentation for this example can be found here:
6+
// https://docs.odriverobotics.com/v/latest/guides/arduino-can-guide.html
7+
8+
9+
/* Configuration of example sketch -------------------------------------------*/
10+
11+
// CAN bus baudrate. Make sure this matches for every device on the bus
12+
#define CAN_BAUDRATE 250000
13+
14+
// ODrive node_id for odrv0
15+
#define ODRV0_NODE_ID 0
16+
17+
// Uncomment below the line that corresponds to your hardware.
18+
// See also "Board-specific settings" to adapt the details for your hardware setup.
19+
20+
// #define IS_TEENSY_BUILTIN // Teensy boards with built-in CAN interface (e.g. Teensy 4.1). See below to select which interface to use.
21+
// #define IS_ARDUINO_BUILTIN // Arduino boards with built-in CAN interface (e.g. Arduino Uno R4 Minima)
22+
// #define IS_MCP2515 // Any board with external MCP2515 based extension module. See below to configure the module.
23+
24+
25+
/* Board-specific includes ---------------------------------------------------*/
26+
27+
#if defined(IS_TEENSY_BUILTIN) + defined(IS_ARDUINO_BUILTIN) + defined(IS_MCP2515) != 1
28+
#warning "Select exactly one hardware option at the top of this file."
29+
30+
#if CAN_HOWMANY > 0 || CANFD_HOWMANY > 0
31+
#define IS_ARDUINO_BUILTIN
32+
#warning "guessing that this uses HardwareCAN"
33+
#else
34+
#error "cannot guess hardware version"
35+
#endif
36+
37+
#endif
38+
39+
#ifdef IS_ARDUINO_BUILTIN
40+
// See https://github.com/arduino/ArduinoCore-API/blob/master/api/HardwareCAN.h
41+
// and https://github.com/arduino/ArduinoCore-renesas/tree/main/libraries/Arduino_CAN
42+
43+
#include <Arduino_CAN.h>
44+
#include <ODriveHardwareCAN.hpp>
45+
#endif // IS_ARDUINO_BUILTIN
46+
47+
#ifdef IS_MCP2515
48+
// See https://github.com/sandeepmistry/arduino-CAN/
49+
#include "MCP2515.h"
50+
#include "ODriveMCPCAN.hpp"
51+
#endif // IS_MCP2515
52+
53+
#ifdef IS_TEENSY_BUILTIN
54+
// See https://github.com/tonton81/FlexCAN_T4
55+
// clone https://github.com/tonton81/FlexCAN_T4.git into /src
56+
#include <FlexCAN_T4.h>
57+
#include "ODriveFlexCAN.hpp"
58+
struct ODriveStatus; // hack to prevent teensy compile error
59+
#endif // IS_TEENSY_BUILTIN
60+
61+
62+
63+
64+
/* Board-specific settings ---------------------------------------------------*/
65+
66+
67+
/* Teensy */
68+
69+
#ifdef IS_TEENSY_BUILTIN
70+
71+
FlexCAN_T4<CAN1, RX_SIZE_256, TX_SIZE_16> can_intf;
72+
73+
bool setupCan() {
74+
can_intf.begin();
75+
can_intf.setBaudRate(CAN_BAUDRATE);
76+
can_intf.setMaxMB(16);
77+
can_intf.enableFIFO();
78+
can_intf.enableFIFOInterrupt();
79+
can_intf.onReceive(onCanMessage);
80+
return true;
81+
}
82+
83+
#endif // IS_TEENSY_BUILTIN
84+
85+
86+
/* MCP2515-based extension modules -*/
87+
88+
#ifdef IS_MCP2515
89+
90+
MCP2515Class& can_intf = CAN;
91+
92+
// chip select pin used for the MCP2515
93+
#define MCP2515_CS 10
94+
95+
// interrupt pin used for the MCP2515
96+
// NOTE: not all Arduino pins are interruptable, check the documentation for your board!
97+
#define MCP2515_INT 2
98+
99+
// freqeuncy of the crystal oscillator on the MCP2515 breakout board.
100+
// common values are: 16 MHz, 12 MHz, 8 MHz
101+
#define MCP2515_CLK_HZ 8000000
102+
103+
104+
static inline void receiveCallback(int packet_size) {
105+
if (packet_size > 8) {
106+
return; // not supported
107+
}
108+
CanMsg msg = {.id = (unsigned int)CAN.packetId(), .len = (uint8_t)packet_size};
109+
CAN.readBytes(msg.buffer, packet_size);
110+
onCanMessage(msg);
111+
}
112+
113+
bool setupCan() {
114+
// configure and initialize the CAN bus interface
115+
CAN.setPins(MCP2515_CS, MCP2515_INT);
116+
CAN.setClockFrequency(MCP2515_CLK_HZ);
117+
if (!CAN.begin(CAN_BAUDRATE)) {
118+
return false;
119+
}
120+
121+
CAN.onReceive(receiveCallback);
122+
return true;
123+
}
124+
125+
#endif // IS_MCP2515
126+
127+
128+
/* Arduinos with built-in CAN */
129+
130+
#ifdef IS_ARDUINO_BUILTIN
131+
132+
HardwareCAN& can_intf = CAN;
133+
134+
bool setupCan() {
135+
return can_intf.begin((CanBitRate)CAN_BAUDRATE);
136+
}
137+
138+
#endif
139+
140+
141+
/* Example sketch ------------------------------------------------------------*/
142+
143+
// Instantiate ODrive objects
144+
ODriveCAN odrv0(wrap_can_intf(can_intf), ODRV0_NODE_ID); // Standard CAN message ID
145+
ODriveCAN* odrives[] = {&odrv0}; // Make sure all ODriveCAN instances are accounted for here
146+
147+
struct ODriveUserData {
148+
Heartbeat_msg_t last_heartbeat;
149+
bool received_heartbeat = false;
150+
Get_Encoder_Estimates_msg_t last_feedback;
151+
bool received_feedback = false;
152+
};
153+
154+
// Keep some application-specific user data for every ODrive.
155+
ODriveUserData odrv0_user_data;
156+
157+
// Called every time a Heartbeat message arrives from the ODrive
158+
void onHeartbeat(Heartbeat_msg_t& msg, void* user_data) {
159+
ODriveUserData* odrv_user_data = static_cast<ODriveUserData*>(user_data);
160+
odrv_user_data->last_heartbeat = msg;
161+
odrv_user_data->received_heartbeat = true;
162+
}
163+
164+
// Called every time a feedback message arrives from the ODrive
165+
void onFeedback(Get_Encoder_Estimates_msg_t& msg, void* user_data) {
166+
ODriveUserData* odrv_user_data = static_cast<ODriveUserData*>(user_data);
167+
odrv_user_data->last_feedback = msg;
168+
odrv_user_data->received_feedback = true;
169+
}
170+
171+
// Called for every message that arrives on the CAN bus
172+
void onCanMessage(const CanMsg& msg) {
173+
for (auto odrive: odrives) {
174+
onReceive(msg, *odrive);
175+
}
176+
}
177+
178+
void setup() {
179+
Serial.begin(115200);
180+
181+
// Wait for up to 3 seconds for the serial port to be opened on the PC side.
182+
// If no PC connects, continue anyway.
183+
for (int i = 0; i < 30 && !Serial; ++i) {
184+
delay(100);
185+
}
186+
delay(200);
187+
188+
189+
Serial.println("Starting ODriveCAN demo");
190+
191+
// Register callbacks for the heartbeat and encoder feedback messages
192+
odrv0.onFeedback(onFeedback, &odrv0_user_data);
193+
odrv0.onStatus(onHeartbeat, &odrv0_user_data);
194+
195+
// Configure and initialize the CAN bus interface. This function depends on
196+
// your hardware and the CAN stack that you're using.
197+
if (!setupCan()) {
198+
Serial.println("CAN failed to initialize: reset required");
199+
while (true); // spin indefinitely
200+
}
201+
202+
Serial.println("Waiting for ODrive...");
203+
while (!odrv0_user_data.received_heartbeat) {
204+
pumpEvents(can_intf);
205+
delay(100);
206+
}
207+
208+
Serial.println("found ODrive");
209+
210+
// request bus voltage and current (1sec timeout)
211+
Serial.println("attempting to read bus voltage and current");
212+
Get_Bus_Voltage_Current_msg_t vbus;
213+
if (!odrv0.request(vbus, 1)) {
214+
Serial.println("vbus request failed!");
215+
while (true); // spin indefinitely
216+
}
217+
218+
Serial.print("DC voltage [V]: ");
219+
Serial.println(vbus.Bus_Voltage);
220+
Serial.print("DC current [A]: ");
221+
Serial.println(vbus.Bus_Current);
222+
223+
Serial.println("Enabling closed loop control...");
224+
while (odrv0_user_data.last_heartbeat.Axis_State != ODriveAxisState::AXIS_STATE_CLOSED_LOOP_CONTROL) {
225+
odrv0.clearErrors();
226+
delay(1);
227+
odrv0.setState(ODriveAxisState::AXIS_STATE_CLOSED_LOOP_CONTROL);
228+
229+
// Pump events for 150ms. This delay is needed for two reasons;
230+
// 1. If there is an error condition, such as missing DC power, the ODrive might
231+
// briefly attempt to enter CLOSED_LOOP_CONTROL state, so we can't rely
232+
// on the first heartbeat response, so we want to receive at least two
233+
// heartbeats (100ms default interval).
234+
// 2. If the bus is congested, the setState command won't get through
235+
// immediately but can be delayed.
236+
for (int i = 0; i < 15; ++i) {
237+
delay(10);
238+
pumpEvents(can_intf);
239+
}
240+
}
241+
242+
Serial.println("ODrive running!");
243+
}
244+
245+
void loop() {
246+
pumpEvents(can_intf); // This is required on some platforms to handle incoming feedback CAN messages
247+
248+
float SINE_PERIOD = 2.0f; // Period of the position command sine wave in seconds
249+
250+
float t = 0.001 * millis();
251+
252+
float phase = t * (TWO_PI / SINE_PERIOD);
253+
254+
odrv0.setPosition(
255+
sin(phase), // position
256+
cos(phase) * (TWO_PI / SINE_PERIOD) // velocity feedforward (optional)
257+
);
258+
259+
// print position and velocity for Serial Plotter
260+
if (odrv0_user_data.received_feedback) {
261+
Get_Encoder_Estimates_msg_t feedback = odrv0_user_data.last_feedback;
262+
odrv0_user_data.received_feedback = false;
263+
Serial.print("odrv0-pos:");
264+
Serial.print(feedback.Pos_Estimate);
265+
Serial.print(",");
266+
Serial.print("odrv0-vel:");
267+
Serial.println(feedback.Vel_Estimate);
268+
}
269+
}
Lines changed: 5 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -1,9 +1,9 @@
11

2-
#include <ODriveArduino.h>
2+
#include <ODriveUART.h>
33
#include <SoftwareSerial.h>
44

55
// Documentation for this example can be found here:
6-
// https://docs.odriverobotics.com/v/latest/guides/arduino-guide.html
6+
// https://docs.odriverobotics.com/v/latest/guides/arduino-uart-guide.html
77

88

99
////////////////////////////////
@@ -37,7 +37,7 @@ int baudrate = 19200; // Must match what you configure on the ODrive (see docs f
3737
// int baudrate = 115200; // Must match what you configure on the ODrive (see docs for details)
3838

3939

40-
ODriveArduino odrive(odrive_serial);
40+
ODriveUART odrive(odrive_serial);
4141

4242
void setup() {
4343
odrive_serial.begin(baudrate);
@@ -50,6 +50,8 @@ void setup() {
5050
while (odrive.getState() == AXIS_STATE_UNDEFINED) {
5151
delay(100);
5252
}
53+
54+
Serial.println("found ODrive");
5355

5456
Serial.print("DC voltage: ");
5557
Serial.println(odrive.getParameterAsFloat("vbus_voltage"));

0 commit comments

Comments
 (0)