Open FFBoard
Open source force feedback firmware
ODriveCAN.h
Go to the documentation of this file.
1/*
2 * OdriveCAN.h
3 *
4 * Created on: Jun 21, 2021
5 * Author: Yannick
6 */
7
8#ifndef USEREXTENSIONS_SRC_ODRIVECAN_H_
9#define USEREXTENSIONS_SRC_ODRIVECAN_H_
10#include "MotorDriver.h"
11#include "cpp_target_config.h"
12#include "CAN.h"
13#include "Encoder.h"
14#include "thread.hpp"
15#include "CanHandler.h"
16#include "CommandHandler.h"
17#include "PersistentStorage.h"
18
19#ifdef ODRIVE
20#define ODRIVE_THREAD_MEM 256
21#define ODRIVE_THREAD_PRIO 25 // Must be higher than main thread
22
27
30
31enum class ODriveCAN_commands : uint32_t{
33};
34
36public:
37 ODriveCAN(uint8_t id);
38 virtual ~ODriveCAN();
39
40
41 //static ClassIdentifier info;
43 //static bool isCreatable();
44
45 void turn(int16_t power) override;
46 void stopMotor() override;
47 void startMotor() override;
48 Encoder* getEncoder() override;
49 bool hasIntegratedEncoder() {return true;}
50
51 template<class T>
52 void sendMsg(uint8_t cmd,T value){
53 CAN_tx_msg msg;
54 memcpy(&msg.data,&value,sizeof(T));
55 msg.header.rtr = false;
56 msg.header.length = sizeof(T);
57 msg.header.id = cmd | (nodeId << 5);
58 if(!port->sendMessage(msg)){
59 // Nothing
60 }
61 }
62
63 void sendMsg(uint8_t cmd,float value);
64 void requestMsg(uint8_t cmd);
65 bool motorReady() override;
66 void startAnticogging();
67
68 void Run();
69
70 void setTorque(float torque);
71
72 void canRxPendCallback(CANPort* port,CAN_rx_msg& msg) override;
73 void canErrorCallback(CANPort* port,uint32_t errcode);
74
75
76 float getPos_f() override;
77 uint32_t getCpr() override;
78 int32_t getPos() override;
79 void setPos(int32_t pos) override;
80 EncoderType getEncoderType() override;
81
82 void setMode(ODriveControlMode controlMode,ODriveInputMode inputMode);
84
85 void readyCb();
86
87 //void setCanRate(uint8_t canRate);
88
89 void saveFlash() override; // Write to flash here
90 void restoreFlash() override; // Load from flash
91
92 CommandStatus command(const ParsedCommand& cmd,std::vector<CommandReply>& replies) override;
93 void registerCommands();
94 std::string getHelpstring(){return "ODrive motor driver with CAN";};
95
96 void setCanFilter();
97
98private:
100 float lastPos = 0;
101 float lastSpeed = 0;
102 float posOffset = 0;
103 float lastVoltage = 0;
104 uint32_t lastVoltageUpdate = 0;
105 uint32_t lastCanMessage = 0;
106
107 uint32_t lastPosTime = 0;
108 bool posWaiting = false;
110
111 int8_t nodeId = 0; // 6 bits can ID
112 int8_t motorId = 0;
113
115 volatile uint32_t errors = 0; // Multiple flag bits can be set
116 // Not yet used by odrive (0.5.4):
117 volatile uint32_t odriveMotorFlags = 0;
118 volatile uint32_t odriveEncoderFlags = 0;
119 volatile uint32_t odriveControllerFlags = 0;
120
121 float maxTorque = 1.0; // range how to scale the torque output
122 volatile bool waitReady = true;
123
124 bool active = false;
125
126 int32_t filterId = 0;
128 bool connected = false;
129};
130
135class ODriveCAN1 : public ODriveCAN{
136public:
137 ODriveCAN1() : ODriveCAN{0} {inUse = true;}
138 const ClassIdentifier getInfo();
139 ~ODriveCAN1(){inUse = false;}
140 static bool isCreatable();
142 static bool inUse;
143};
144
149class ODriveCAN2 : public ODriveCAN{
150public:
151 ODriveCAN2() : ODriveCAN{1} {inUse = true;}
152 const ClassIdentifier getInfo();
153 ~ODriveCAN2(){inUse = false;}
154 static bool isCreatable();
156 static bool inUse;
157};
158
159#endif /* USEREXTENSIONS_SRC_ODRIVECAN_H_ */
160#endif
CommandStatus
EncoderType
Definition: Encoder.h:27
ODriveCAN_commands
Definition: ODriveCAN.h:31
ODriveAxisError
Definition: ODriveCAN.h:29
@ AXIS_ERROR_MIN_ENDSTOP_PRESSED
@ AXIS_ERROR_HOMING_WITHOUT_ENDSTOP
@ AXIS_ERROR_WATCHDOG_TIMER_EXPIRED
@ AXIS_ERROR_MAX_ENDSTOP_PRESSED
ODriveEncoderFlags
Definition: ODriveCAN.h:28
ODriveState
Definition: ODriveCAN.h:23
@ AXIS_STATE_ENCODER_OFFSET_CALIBRATION
@ AXIS_STATE_ENCODER_INDEX_SEARCH
@ AXIS_STATE_STARTUP_SEQUENCE
@ AXIS_STATE_ENCODER_HALL_PHASE_CALIBRATION
@ AXIS_STATE_CLOSED_LOOP_CONTROL
@ AXIS_STATE_ENCODER_DIR_FIND
@ AXIS_STATE_MOTOR_CALIBRATION
@ AXIS_STATE_FULL_CALIBRATION_SEQUENCE
@ AXIS_STATE_LOCKIN_SPIN
@ AXIS_STATE_UNDEFINED
@ AXIS_STATE_ENCODER_HALL_POLARITY_CALIBRATION
ODriveLocalState
Definition: ODriveCAN.h:26
ODriveInputMode
Definition: ODriveCAN.h:25
ODriveControlMode
Definition: ODriveCAN.h:24
Definition: CAN.h:119
virtual bool sendMessage(CAN_tx_msg &msg)=0
const ClassIdentifier getInfo()
Command handlers always have class infos. Works well with ChoosableClass.
Definition: ODriveCAN.cpp:24
static bool isCreatable()
Definition: ODriveCAN.cpp:32
static ClassIdentifier info
Definition: ODriveCAN.h:141
static bool inUse
Definition: ODriveCAN.h:142
static ClassIdentifier info
Definition: ODriveCAN.h:155
static bool isCreatable()
Definition: ODriveCAN.cpp:36
static bool inUse
Definition: ODriveCAN.h:156
const ClassIdentifier getInfo()
Command handlers always have class infos. Works well with ChoosableClass.
Definition: ODriveCAN.cpp:28
int8_t nodeId
Definition: ODriveCAN.h:111
void canRxPendCallback(CANPort *port, CAN_rx_msg &msg) override
Definition: ODriveCAN.cpp:389
void requestMsg(uint8_t cmd)
Definition: ODriveCAN.cpp:243
bool active
Definition: ODriveCAN.h:124
void setState(ODriveState state)
Definition: ODriveCAN.cpp:287
uint32_t lastVoltageUpdate
Definition: ODriveCAN.h:104
float lastSpeed
Definition: ODriveCAN.h:101
volatile ODriveLocalState state
Definition: ODriveCAN.h:127
void stopMotor() override
Definition: ODriveCAN.cpp:217
int32_t filterId
Definition: ODriveCAN.h:126
void setTorque(float torque)
Definition: ODriveCAN.cpp:271
void setPos(int32_t pos) override
Definition: ODriveCAN.cpp:237
float posOffset
Definition: ODriveCAN.h:102
std::string getHelpstring()
Definition: ODriveCAN.h:94
void Run()
Definition: ODriveCAN.cpp:150
void startAnticogging()
Definition: ODriveCAN.cpp:301
const ClassIdentifier getInfo()=0
Command handlers always have class infos. Works well with ChoosableClass.
ODriveCAN(uint8_t id)
Definition: ODriveCAN.cpp:40
void saveFlash() override
Definition: ODriveCAN.cpp:121
CANPort * port
Definition: ODriveCAN.h:99
void setCanFilter()
Definition: ODriveCAN.cpp:67
void readyCb()
void restoreFlash() override
Definition: ODriveCAN.cpp:92
void turn(int16_t power) override
Definition: ODriveCAN.cpp:292
void canErrorCallback(CANPort *port, uint32_t errcode)
Definition: ODriveCAN.cpp:385
volatile uint32_t odriveMotorFlags
Definition: ODriveCAN.h:117
int32_t getPos() override
Definition: ODriveCAN.cpp:263
bool hasIntegratedEncoder()
Definition: ODriveCAN.h:49
float getPos_f() override
Definition: ODriveCAN.cpp:251
void registerCommands()
Definition: ODriveCAN.cpp:79
uint32_t lastCanMessage
Definition: ODriveCAN.h:105
float lastVoltage
Definition: ODriveCAN.h:103
Encoder * getEncoder() override
Definition: ODriveCAN.cpp:230
float maxTorque
Definition: ODriveCAN.h:121
bool connected
Definition: ODriveCAN.h:128
void startMotor() override
Definition: ODriveCAN.cpp:224
bool reloadPosAfterStartup
Definition: ODriveCAN.h:109
int8_t motorId
Definition: ODriveCAN.h:112
virtual ~ODriveCAN()
Definition: ODriveCAN.cpp:61
void sendMsg(uint8_t cmd, T value)
Definition: ODriveCAN.h:52
bool posWaiting
Definition: ODriveCAN.h:108
volatile bool waitReady
Definition: ODriveCAN.h:122
volatile uint32_t odriveEncoderFlags
Definition: ODriveCAN.h:118
bool motorReady() override
Definition: ODriveCAN.cpp:260
CommandStatus command(const ParsedCommand &cmd, std::vector< CommandReply > &replies) override
Definition: ODriveCAN.cpp:306
void setMode(ODriveControlMode controlMode, ODriveInputMode inputMode)
Definition: ODriveCAN.cpp:282
uint32_t lastPosTime
Definition: ODriveCAN.h:107
volatile ODriveState odriveCurrentState
Definition: ODriveCAN.h:114
EncoderType getEncoderType() override
Definition: ODriveCAN.cpp:277
uint32_t getCpr() override
Definition: ODriveCAN.cpp:268
void sendMsg(uint8_t cmd, float value)
float lastPos
Definition: ODriveCAN.h:100
volatile uint32_t errors
Definition: ODriveCAN.h:115
volatile uint32_t odriveControllerFlags
Definition: ODriveCAN.h:119
CANPort & canport
static void * memcpy(void *dst, const void *src, size_t n)
Definition: ringbuffer.c:8
bool rtr
Definition: CAN.h:63
uint32_t id
Definition: CAN.h:60
uint32_t length
Definition: CAN.h:61
Definition: CAN.h:96
Definition: CAN.h:89
CAN_msg_header_tx header
Definition: CAN.h:92
uint8_t data[CAN_MSGBUFSIZE]
Definition: CAN.h:90