88
99#define REQUEST_PENDING 0xff
1010
11+ // clang-format off
12+ // (clang-format gets confused by the lambdas inside the macro)
1113#define CREATE_CAN_INTF_WRAPPER (TIntf ) \
1214 static inline ODriveCanIntfWrapper wrap_can_intf (TIntf& intf) { \
1315 return { \
1416 &intf, \
15- [](void * intf, uint32_t id, uint8_t length, const uint8_t * data) { return sendMsg (*(TIntf*)intf, id, length, data); }, \
16- [](void * intf) { pumpEvents (*(TIntf*)intf); } \
17+ [](void * intf, uint32_t id, uint8_t length, const uint8_t * data) { \
18+ return sendMsg (*(TIntf*)intf, id, length, data); \
19+ }, \
20+ [](void * intf) { pumpEvents (*(TIntf*)intf); }, \
1721 }; \
1822 }
19-
23+ // clang-format on
2024
2125struct ODriveCanIntfWrapper {
22- bool sendMsg (uint32_t id, uint8_t length, const uint8_t * data) {
23- return (*send_msg_)(can_intf_, id, length, data);
24- }
25- void pump_events () {
26- (*pump_events_)(can_intf_);
27- }
26+ bool sendMsg (uint32_t id, uint8_t length, const uint8_t * data) { return (*send_msg_)(can_intf_, id, length, data); }
27+ void pump_events () { (*pump_events_)(can_intf_); }
2828
2929 void * can_intf_;
3030 bool (*send_msg_)(void * intf, uint32_t id, uint8_t length, const uint8_t * data);
@@ -33,193 +33,195 @@ struct ODriveCanIntfWrapper {
3333
3434class ODriveCAN {
3535public:
36- ODriveCAN (const ODriveCanIntfWrapper& can_intf, uint32_t node_id)
37- : can_intf_(can_intf), node_id_(node_id) {};
36+ ODriveCAN (const ODriveCanIntfWrapper& can_intf, uint32_t node_id) : can_intf_(can_intf), node_id_(node_id) {}
3837
3938 /* *
4039 * @brief Clear all errors on the ODrive.
41- *
40+ *
4241 * This function returns immediately and does not check if the ODrive
4342 * received the CAN message.
4443 */
4544 bool clearErrors ();
46-
45+
4746 /* *
4847 * @brief Tells the ODrive to change its axis state.
49- *
48+ *
5049 * This function returns immediately and does not check if the ODrive
5150 * received the CAN message.
5251 */
5352 bool setState (ODriveAxisState requested_state);
54-
53+
5554 /* *
5655 * @brief Sets the control mode and input mode of the ODrive.
57- *
56+ *
5857 * This function returns immediately and does not check if the ODrive
5958 * received the CAN message.
6059 */
6160 bool setControllerMode (uint8_t control_mode, uint8_t input_mode);
62-
61+
6362 /* *
6463 * @brief Sends a position setpoint with optional velocity and torque feedforward.
65- *
64+ *
6665 * This function returns immediately and does not check if the ODrive
6766 * received the CAN message.
6867 */
6968 bool setPosition (float position, float velocity_feedforward = 0 .0f , float torque_feedforward = 0 .0f );
7069
7170 /* *
7271 * @brief Sends a velocity setpoint with optional torque feedforward.
73- *
72+ *
7473 * This function returns immediately and does not check if the ODrive
7574 * received the CAN message.
7675 */
7776 bool setVelocity (float velocity, float torque_feedforward = 0 .0f );
7877
7978 /* *
8079 * @brief Sends a torque setpoint to the ODrive.
81- *
80+ *
8281 * This function returns immediately and does not check if the ODrive
8382 * received the CAN message.
8483 */
8584 bool setTorque (float torque);
8685
8786 /* *
8887 * @brief Sets the velocity and current limits
89- *
88+ *
9089 * This function returns immediately and does not check if the ODrive
9190 * received the CAN message.
9291 */
9392 bool setLimits (float velocity_limit, float current_soft_max);
9493
9594 /* *
9695 * @brief Sets the position gain
97- *
96+ *
9897 * This function returns immediately and does not check if the ODrive
9998 * received the CAN message.
10099 */
101100 bool setPosGain (float pos_gain);
102-
101+
103102 /* *
104103 * @brief Sets the velocity and velocity integrator gains
105- *
104+ *
106105 * This function returns immediately and does not check if the ODrive
107106 * received the CAN message.
108107 */
109108 bool setVelGains (float vel_gain, float vel_integrator_gain);
110-
109+
111110 /* *
112111 * @brief Sets the encoder's absolute position and enables absolute positioning
113- *
112+ *
114113 * This function returns immediately and does not check if the ODrive
115114 * received the CAN message.
116115 */
117116 bool setAbsolutePosition (float abs_pos);
118-
117+
119118 /* *
120119 * @brief Sets the coast velocity for subsequent trapezoidal moves
121- *
120+ *
122121 * This function returns immediately and does not check if the ODrive
123122 * received the CAN message.
124123 */
125124 bool setTrapezoidalVelLimit (float vel_limit);
126-
125+
127126 /* *
128127 * @brief Sets the acceleration and deceleration values for subsequent trapezoidal moves
129- *
128+ *
130129 * This function returns immediately and does not check if the ODrive
131130 * received the CAN message.
132131 */
133132 bool setTrapezoidalAccelLimits (float accel_limit, float decel_limit);
134133
135134 /* *
136135 * @brief Requests motor current. Iq_measured represents torque-generating current
137- *
136+ *
138137 * This function will block and wait for up to timeout_ms (default 10msec) for ODrive to reply
139138 */
140139 bool getCurrents (Get_Iq_msg_t& msg, uint16_t timeout_ms = 10 );
141140
142141 /* *
143- * @brief Requests motor temperature
144- *
142+ * @brief Requests motor temperature
143+ *
145144 * This function will block and wait for up to timeout_ms (default 10msec) for ODrive to reply
146145 */
147146 bool getTemperature (Get_Temperature_msg_t& msg, uint16_t timeout_ms = 10 );
148147
149148 /* *
150149 * @brief Requests error information
151- *
150+ *
152151 * This function will block and wait for up to timeout_ms (default 10msec) for ODrive to reply
153152 */
154153 bool getError (Get_Error_msg_t& msg, uint16_t timeout_ms = 10 );
155154
156155 /* *
157156 * @brief Requests hardware and firmware version information
158- *
157+ *
159158 * This function will block and wait for up to timeout_ms (default 10msec) for ODrive to reply
160159 */
161160 bool getVersion (Get_Version_msg_t& msg, uint16_t timeout_ms = 10 );
162161
163162 /* *
164163 * @brief Requests encoder feedback data.
165- *
164+ *
166165 * This function will block and wait for up to timeout_ms (default 10msec) for ODrive to reply
167166 */
168167 bool getFeedback (Get_Encoder_Estimates_msg_t& msg, uint16_t timeout_ms = 10 );
169168
170169 /* *
171170 * @brief Requests ODrive DC bus voltage and current
172- *
171+ *
173172 * This function will block and wait for up to timeout_ms (default 10msec) for ODrive to reply
174173 * May trigger onBusVI callback if it's registered.
175174 */
176175 bool getBusVI (Get_Bus_Voltage_Current_msg_t& msg, uint16_t timeout_ms = 10 );
177176
178177 /* *
179178 * @brief Requests mechanical and electrical power data (used for spinout detection)
180- *
179+ *
181180 * This function will block and wait for up to timeout_ms (default 10msec) for ODrive to reply
182181 */
183182 bool getPower (Get_Powers_msg_t& msg, uint16_t timeout_ms = 10 );
184-
183+
185184 enum ResetAction : uint8_t {
186185 Reboot = 0 ,
187186 SaveConfiguration = 1 ,
188187 EraseConfiguration = 2 ,
189188 };
190-
189+
191190 /* *
192191 * @brief Resets the ODrive with the given action
193- *
192+ *
194193 * Valid actions:
195194 * - Reboot (0)
196195 * - Save (1)
197196 * - Erase (2)
198197 *
199198 */
200199 bool reset (ResetAction action = ResetAction::Reboot);
201-
200+
202201 /* *
203202 * @brief Registers a callback for ODrive feedback processing.
204203 */
205- void onFeedback (void (*callback)(Get_Encoder_Estimates_msg_t& feedback, void * user_data), void* user_data = nullptr) {
206- feedback_callback_ = callback;
204+ void onFeedback (
205+ void (*callback)(Get_Encoder_Estimates_msg_t& feedback, void * user_data),
206+ void* user_data = nullptr
207+ ) {
208+ feedback_callback_ = callback;
207209 feedback_user_data_ = user_data;
208210 }
209211
210212 /* *
211213 * @brief Registers a callback for ODrive axis state feedback.
212214 */
213215 void onStatus (void (*callback)(Heartbeat_msg_t& feedback, void * user_data), void* user_data = nullptr) {
214- axis_state_callback_ = callback;
216+ axis_state_callback_ = callback;
215217 axis_state_user_data_ = user_data;
216218 }
217-
219+
218220 /* *
219221 * @brief Registers a callback for ODrive torques feedback processing.
220222 */
221223 void onTorques (void (*callback)(Get_Torques_msg_t& feedback, void * user_data), void* user_data = nullptr) {
222- torques_callback_ = callback;
224+ torques_callback_ = callback;
223225 torques_user_data_ = user_data;
224226 }
225227
@@ -234,7 +236,10 @@ class ODriveCAN {
234236 /* *
235237 * @brief Registers a callback for ODrive bus voltage/current feedback.
236238 */
237- void onBusVI (void (*callback)(Get_Bus_Voltage_Current_msg_t& feedback, void * user_data), void* user_data = nullptr) {
239+ void onBusVI (
240+ void (*callback)(Get_Bus_Voltage_Current_msg_t& feedback, void * user_data),
241+ void* user_data = nullptr
242+ ) {
238243 busVI_callback_ = callback;
239244 busVI_user_data_ = user_data;
240245 }
@@ -262,7 +267,7 @@ class ODriveCAN {
262267
263268 /* *
264269 * @brief Sends a request message and awaits a response.
265- *
270+ *
266271 * Blocks until the response is received or the timeout is reached. Returns
267272 * false if the ODrive does not respond within the specified timeout.
268273 */
@@ -274,7 +279,9 @@ class ODriveCAN {
274279 0 , // no data
275280 nullptr // RTR=1
276281 );
277- if (!awaitMsg (timeout_ms)) return false ;
282+ if (!awaitMsg (timeout_ms)) {
283+ return false ;
284+ }
278285 msg.decode_buf (buffer_);
279286 return true ;
280287 }
@@ -286,26 +293,22 @@ class ODriveCAN {
286293 bool send (const T& msg) {
287294 uint8_t data[8 ] = {};
288295 msg.encode_buf (data);
289- return can_intf_.sendMsg (
290- (node_id_ << ODriveCAN::kNodeIdShift ) | msg.cmd_id ,
291- msg.msg_length ,
292- data
293- );
296+ return can_intf_.sendMsg ((node_id_ << ODriveCAN::kNodeIdShift ) | msg.cmd_id , msg.msg_length , data);
294297 }
295298
296299 /* *
297300 * @brief Get value at the endpoint
298- *
301+ *
299302 * @tparam T The data type expected from the endpoint
300303 * @param endpoint_id Unique ID from flat_endpoints.json
301304 * @param timeout_ms Time to wait for a response from ODrive
302- *
305+ *
303306 * @return T Data from the endpoint, or 0 on timeout
304307 *
305308 * Blocks until the response is received or the timeout is reached.
306309 *
307310 */
308- template <typename T>
311+ template <typename T>
309312 T getEndpoint (uint16_t endpoint_id, uint16_t timeout_ms = 10 ) {
310313 uint8_t data[8 ] = {};
311314 data[0 ] = 0 ; // Opcode read
@@ -316,7 +319,9 @@ class ODriveCAN {
316319
317320 requested_msg_id_ = 0x005 ; // Await TxSdo message
318321 can_intf_.sendMsg ((node_id_ << ODriveCAN::kNodeIdShift ) | 0x004 , 8 , data);
319- if (!awaitMsg (timeout_ms)) return T{};
322+ if (!awaitMsg (timeout_ms)) {
323+ return T{};
324+ }
320325
321326 T ret{};
322327 memcpy (&ret, &buffer_[4 ], sizeof (T));
@@ -325,15 +330,15 @@ class ODriveCAN {
325330
326331 /* *
327332 * @brief Set endpoint to value
328- *
333+ *
329334 * @tparam T Type of the value from flat_endpoints.json
330335 * @param endpoint_id Unique ID of endpoint from flat_endpoints.json
331336 * @param value value to write to the endpoint
332337 *
333338 * This function returns immediately and does not check if the ODrive
334339 * received the CAN message.
335340 */
336- template <typename T>
341+ template <typename T>
337342 bool setEndpoint (uint16_t endpoint_id, T value) {
338343 uint8_t data[8 ] = {};
339344 data[0 ] = 1 ; // Opcode write
@@ -371,7 +376,7 @@ class ODriveCAN {
371376 void * busVI_user_data_;
372377 void * currents_user_data_;
373378 void * error_user_data_;
374-
379+
375380 void (*axis_state_callback_)(Heartbeat_msg_t& feedback, void * user_data) = nullptr;
376381 void (*feedback_callback_)(Get_Encoder_Estimates_msg_t& feedback, void * user_data) = nullptr;
377382 void (*torques_callback_)(Get_Torques_msg_t& feedback, void * user_data) = nullptr;
0 commit comments