Open FFBoard
Open source force feedback firmware
TMC4671 Class Reference

#include <TMC4671.h>

Inheritance diagram for TMC4671:
cpp_freertos::Thread ExtiHandler SPIDevice CommandHandler Encoder PersistentStorage MotorDriver TMC_1 TMC_2

Classes

class  TMC_ExternalEncoderUpdateThread
 

Public Member Functions

const ClassIdentifier getInfo ()
 Command handlers always have class infos. Works well with ChoosableClass. More...
 
const ClassType getClassType () override
 
 TMC4671 (SPIPort &spiport, OutputPin cspin, uint8_t address=1)
 
void setHwType (TMC_HW_Ver type)
 
void setAddress (uint8_t address)
 
uint8_t getSpiAddr ()
 
bool setSpiAddr (uint8_t chan)
 
virtual ~TMC4671 ()
 
bool initialize ()
 
void initializeWithPower ()
 
void Run ()
 
bool motorReady ()
 
bool hasPower ()
 
int32_t getTmcVM ()
 
bool isSetUp ()
 
uint32_t readReg (uint8_t reg)
 
void writeReg (uint8_t reg, uint32_t dat)
 
void writeRegAsync (uint8_t reg, uint32_t dat)
 
void updateReg (uint8_t reg, uint32_t dat, uint32_t mask, uint8_t shift)
 
void setMotorType (MotorType motor, uint16_t poles)
 
void runOpenLoop (uint16_t ud, uint16_t uq, int32_t speed, int32_t accel, bool torqueMode=false)
 
void setOpenLoopSpeedAccel (int32_t speed, uint32_t accel)
 
bool calibrateAdcOffset (uint16_t time=500)
 
void setup_ABN_Enc (TMC4671ABNConf encconf)
 
void setup_AENC (TMC4671AENCConf encconf)
 
void setup_HALL (TMC4671HALLConf hallconf)
 
void bangInitEnc (int16_t power)
 
void estimateABNparams ()
 
void estimateExtEnc ()
 
bool checkEncoder ()
 
void calibrateAenc ()
 
void calibrateEncoder ()
 
void setEncoderType (EncoderType_TMC type)
 
uint32_t getEncCpr ()
 
void setAdcOffset (uint32_t adc_I0_offset, uint32_t adc_I1_offset)
 
void setAdcScale (uint32_t adc_I0_scale, uint32_t adc_I1_scale)
 
void setupFeedForwardTorque (int32_t gain, int32_t constant)
 
void setupFeedForwardVelocity (int32_t gain, int32_t constant)
 
void setFFMode (FFMode mode)
 
void setSequentialPI (bool sequential)
 
void setBiquadFlux (const TMC4671Biquad &filter)
 
void setBiquadTorque (const TMC4671Biquad &filter)
 
void setBiquadPos (const TMC4671Biquad &filter)
 
void setBiquadVel (const TMC4671Biquad &filter)
 
void setTorqueFilter (TMC4671Biquad_conf &conf)
 
bool pingDriver ()
 
std::pair< uint32_t, std::string > getTmcType ()
 
void changeState (TMC_ControlState newState, bool force=false)
 
bool externalEncoderAllowed ()
 
void setExternalEncoderAllowed (bool allow)
 
float getPwmFreq ()
 
void setPwmFreq (float freq)
 
void setBBM (uint8_t bbml, uint8_t bbmh)
 
void timerElapsed (TIM_HandleTypeDef *htim)
 
void setPositionExt (int32_t pos)
 
void stopMotor ()
 
void startMotor ()
 
void emergencyStop (bool reset)
 
void turn (int16_t power)
 
int16_t controlFluxDissipate ()
 
void setTorque (int16_t torque)
 
void setTargetPos (int32_t pos)
 
int32_t getTargetPos ()
 
void setTargetVelocity (int32_t vel)
 
int32_t getTargetVelocity ()
 
int32_t getVelocity ()
 
int16_t getTorque ()
 
void setFlux (int16_t flux)
 
int16_t getFlux ()
 
void setFluxTorque (int16_t flux, int16_t torque)
 
void setFluxTorqueFF (int16_t flux, int16_t torque)
 
std::pair< int32_t, int32_t > getActualTorqueFlux ()
 
int32_t getActualFlux ()
 
int32_t getActualTorque ()
 
void rampFlux (uint16_t target, uint16_t time_ms)
 
bool checkAdc ()
 
float getTemp ()
 
TMC_ControlState getState ()
 
void setPhiEtype (PhiE type)
 
PhiE getPhiEtype ()
 
void setPhiE_ext (int16_t phiE)
 
int16_t getPhiE ()
 
int16_t getPhiEfromExternalEncoder ()
 
int16_t getPhiE_Enc ()
 
void setGpioMode (TMC_GpioMode mode)
 
uint8_t getGpioPins ()
 
void setGpioPins (uint8_t pins)
 
void setPosSel (PosSelection psel)
 
void setVelSel (VelSelection vsel, uint8_t mode=0)
 
void setMotionMode (MotionMode mode, bool force=false)
 
MotionMode getMotionMode ()
 
void setUdUq (int16_t ud, int16_t uq)
 
void setBrakeLimits (uint16_t low, uint16_t high)
 
bool reachedPosition (uint16_t tolerance)
 
void setPids (TMC4671PIDConf pids)
 
TMC4671PIDConf getPids ()
 
void setLimits (TMC4671Limits limits)
 
TMC4671Limits getLimits ()
 
void setUqUdLimit (uint16_t limit)
 
void setTorqueLimit (uint16_t limit)
 
void setPidPrecision (TMC4671PidPrecision setting)
 
EncodergetEncoder () override
 
void setEncoder (std::shared_ptr< Encoder > &encoder) override
 
bool hasIntegratedEncoder () override
 
bool usingExternalEncoder ()
 
int32_t getPos () override
 
int32_t getPosAbs () override
 
void setPos (int32_t pos) override
 
void setTmcPos (int32_t pos)
 
uint32_t getCpr ()
 
void setCpr (uint32_t cpr)
 
EncoderType getEncoderType () override
 
uint32_t posToEnc (uint32_t pos)
 
uint32_t encToPos (uint32_t enc)
 
void exti (uint16_t GPIO_Pin)
 
bool findEncoderIndex (int32_t speed=10, uint16_t power=2500, bool offsetPhiM=false, bool zeroCount=false)
 
bool autohome ()
 
void zeroAbnUsingPhiM (bool offsetPhiE=false)
 
StatusFlags readFlags (bool maskedOnly=true)
 
void setStatusMask (StatusFlags mask)
 
void setStatusMask (uint32_t mask)
 
void setStatusFlags (uint32_t flags)
 
void setStatusFlags (StatusFlags flags)
 
void setEncoderIndexFlagEnabled (bool enabled, bool zeroEncoder=false)
 
void statusCheck ()
 
void saveFlash () override
 
void restoreFlash () override
 
uint16_t encodeEncHallMisc ()
 
void restoreEncHallMisc (uint16_t val)
 
void beginSpiTransfer (SPIPort *port)
 
void endSpiTransfer (SPIPort *port)
 
CommandStatus command (const ParsedCommand &cmd, std::vector< CommandReply > &replies)
 
void registerCommands ()
 
virtual std::string getHelpstring ()
 
- Public Member Functions inherited from MotorDriver
 MotorDriver ()
 
virtual ~MotorDriver ()
 
- Public Member Functions inherited from ChoosableClass
virtual ~ChoosableClass ()
 
uint16_t getSelectionID ()
 
- Public Member Functions inherited from PersistentStorage
 PersistentStorage ()
 
virtual ~PersistentStorage ()
 
void restoreFlashDelayed ()
 
- Public Member Functions inherited from Encoder
 Encoder ()
 
virtual ~Encoder ()
 
virtual float getPos_f ()
 
virtual float getPosAbs_f ()
 
- Public Member Functions inherited from CommandHandler
 CommandHandler (const char *clsname, uint16_t clsid, uint8_t instance=0)
 
virtual ~CommandHandler ()
 
virtual bool hasCommands ()
 
virtual void setCommandsEnabled (bool enable)
 
void registerCommands ()
 
virtual CommandStatus internalCommand (const ParsedCommand &cmd, std::vector< CommandReply > &replies)
 
virtual std::string getCommandsHelpstring ()
 
virtual std::string getCsvHelpstring ()
 
virtual uint8_t getCommandHandlerInstance ()
 
void broadcastCommandReply (CommandReply reply, uint32_t cmdId, CMDtype type)
 
void sendCommandReplyAsync (CommandReply reply, uint32_t cmdId, CMDtype type, CommandInterface *interface=nullptr)
 
virtual uint16_t getCommandHandlerID ()
 
virtual CmdHandlerInfogetCommandHandlerInfo ()
 
virtual bool isValidCommandId (uint32_t cmdid, uint32_t ignoredFlags=0, uint32_t requiredFlag=0)
 
virtual CmdHandlerCommanddefgetCommandFromName (const std::string &cmd, uint32_t ignoredFlags=0)
 
virtual CmdHandlerCommanddefgetCommandFromId (const uint32_t id, uint32_t ignoredFlags=0)
 
template<typename ID >
void registerCommand (const char *cmd, const ID cmdid, const char *help=nullptr, uint32_t flags=0)
 
- Public Member Functions inherited from SPIDevice
 SPIDevice (SPIPort &port, OutputPin csPin)
 
 SPIDevice (SPIPort &port, SPIConfig &spiConfig)
 
virtual ~SPIDevice ()
 
void assertChipSelect ()
 
void clearChipSelect ()
 
virtual bool updateCSPin (OutputPin &csPin)
 
virtual void spiTxCompleted (SPIPort *port)
 
virtual void spiRxCompleted (SPIPort *port)
 
virtual void spiTxRxCompleted (SPIPort *port)
 
virtual void spiRequestError (SPIPort *port)
 
virtual SPIConfiggetSpiConfig ()
 
- Public Member Functions inherited from ExtiHandler
 ExtiHandler ()
 
virtual ~ExtiHandler ()
 
- Public Member Functions inherited from cpp_freertos::Thread
 Thread (const std::string Name, uint16_t StackDepth, UBaseType_t Priority)
 
 Thread (const char *Name, uint16_t StackDepth, UBaseType_t Priority)
 
 Thread (uint16_t StackDepth, UBaseType_t Priority)
 
bool Start ()
 
virtual ~Thread ()
 
TaskHandle_t GetHandle ()
 
void Suspend ()
 
void Resume ()
 
void ResumeFromISR ()
 
void Notify ()
 
void NotifyFromISR ()
 
uint32_t WaitForNotification (TickType_t Timeout=portMAX_DELAY)
 
UBaseType_t GetPriority ()
 
UBaseType_t GetPriorityFromISR ()
 
void SetPriority (UBaseType_t NewPriority)
 
std::string GetName ()
 
char * GetName ()
 

Static Public Member Functions

static TMC4671MotConf decodeMotFromInt (uint16_t val)
 
static uint16_t encodeMotToInt (TMC4671MotConf mconf)
 
- Static Public Member Functions inherited from ChoosableClass
static bool isCreatable ()
 
- Static Public Member Functions inherited from PersistentStorage
static std::vector< PersistentStorage * > & getFlashHandlers ()
 
static void restoreFlashStartupCb ()
 
- Static Public Member Functions inherited from CommandHandler
static void logSerial (std::string string)
 Send a log formatted sequence. More...
 
static void logSerialDebug (std::string string)
 Send a log formatted sequence if debug is on. More...
 
static bool logsEnabled ()
 
static void setLogsEnabled (bool enabled)
 
static uint32_t getClassIdFromName (const char *name)
 
static const char * getClassNameFromId (const uint32_t id)
 
static CommandHandlergetHandlerFromHandlerId (const uint16_t cmdhandlerID)
 
static CommandHandlergetHandlerFromId (const uint16_t id, const uint8_t instance=0xFF)
 
static CommandHandlergetHandlerFromClassName (const char *name, const uint8_t instance=0xFF)
 
static std::vector< CommandHandler * > getHandlersFromClassName (const char *name)
 
static std::vector< CommandHandler * > getHandlersFromId (const uint16_t id)
 
static bool isInHandlerList (CommandHandler *handler)
 
static std::string getAllHelpstrings ()
 
static std::vector< CommandHandler * > & getCommandHandlers ()
 
template<typename TVal >
static CommandStatus handleGetSet (const ParsedCommand &cmd, std::vector< CommandReply > &replies, TVal &value)
 
template<typename TVal , class cls , class cls1 >
static CommandStatus handleGetSetFunc (const ParsedCommand &cmd, std::vector< CommandReply > &replies, TVal &value, void(cls1::*setfunc)(TVal), cls *obj)
 
template<typename TVal , class cls , class cls1 , class cls2 >
static CommandStatus handleGetFuncSetFunc (const ParsedCommand &cmd, std::vector< CommandReply > &replies, TVal(cls1::*getfunc)(), void(cls2::*setfunc)(TVal), cls *obj)
 
template<typename TVal , class cls , class cls1 >
static CommandStatus handleGetFuncSet (const ParsedCommand &cmd, std::vector< CommandReply > &replies, TVal &value, TVal(cls1::*getfunc)(), cls *obj)
 
- Static Public Member Functions inherited from cpp_freertos::Thread
static void Yield ()
 
static void StartScheduler ()
 
static void EndScheduler ()
 

Public Attributes

TMC4671MainConfig conf
 
bool emergency = false
 
bool estopTriggered = false
 
int16_t nextFlux = 0
 
int16_t idleFlux = 0
 
uint16_t maxOffsetFlux = 0
 
int16_t bangInitPower = 5000
 
const float fluxDissipationLimit = 1000
 
TMC4671PIDConf curPids
 
TMC4671Limits curLimits
 
TMC4671PidPrecision pidPrecision
 
TMC4671ABNConf abnconf
 
TMC4671HALLConf hallconf
 
TMC4671AENCConf aencconf
 
bool flagCheckInProgress = false
 
StatusFlags statusFlags = {0}
 
StatusFlags statusMask = {0}
 
TMC4671FlashAddrs flashAddrs
 
bool allowSlowSPI = true
 

Static Public Attributes

static ClassIdentifier info
 
- Static Public Attributes inherited from MotorDriver
static ClassIdentifier info ={.name = "None" , .id=CLSID_MOT_NONE, .visibility = ClassVisibility::visible}
 
static const std::vector< class_entry< MotorDriver > > all_drivers
 
- Static Public Attributes inherited from ChoosableClass
static ClassIdentifier info
 
- Static Public Attributes inherited from Encoder
static ClassIdentifier info ={.name = "None" , .id=CLSID_ENCODER_NONE, .visibility = ClassVisibility::visible}
 
static const std::vector< class_entry< Encoder > > all_encoders
 
- Static Public Attributes inherited from CommandHandler
static bool logEnabled = true
 
- Static Public Attributes inherited from ExtiHandler
static std::vector< ExtiHandler * > extiHandlers
 

Private Types

enum class  TMC4671_commands : uint32_t {
  cpr , mtype , encsrc , tmcHwType ,
  encalign , poles , acttrq , pwmlim ,
  torqueP , torqueI , fluxP , fluxI ,
  velocityP , velocityI , posP , posI ,
  tmctype , pidPrec , phiesrc , fluxoffset ,
  seqpi , tmcIscale , encdir , temp ,
  reg , svpwm , fullCalibration , calibrated ,
  abnindexenabled , findIndex , getState , encpol ,
  combineEncoder , invertForce , vmTmc , extphie ,
  torqueFilter_mode , torqueFilter_f , torqueFilter_q , pidautotune ,
  fluxbrake , pwmfreq
}
 

Private Member Functions

void initAdc (uint16_t mdecA, uint16_t mdecB, uint32_t mclkA, uint32_t mclkB)
 
void setPwm (uint8_t val, uint16_t maxcnt, uint8_t bbmL, uint8_t bbmH)
 
void setPwm (TMC_PwmMode val)
 
void setPwmMaxCnt (uint16_t maxcnt)
 
void setSvPwm (bool enable)
 
void encInit ()
 
void encoderIndexHit ()
 
void saveAdcParams ()
 
void calibFailCb ()
 
void encoderInit ()
 
void errorCallback (const Error &error, bool cleared)
 
bool pidAutoTune ()
 
void setUpExtEncTimer ()
 

Private Attributes

OutputPin enablePin = OutputPin(*DRV_ENABLE_GPIO_Port,DRV_ENABLE_Pin)
 
const Error indexNotHitError = Error(ErrorCode::encoderIndexMissed,ErrorType::critical,"Encoder index missed")
 
const Error lowVoltageError = Error(ErrorCode::undervoltage,ErrorType::warning,"Low motor voltage")
 
const Error communicationError = Error(ErrorCode::tmcCommunicationError, ErrorType::warning, "TMC not responding")
 
const Error estopError = Error(ErrorCode::emergencyStop, ErrorType::critical, "TMC emergency stop triggered")
 
TMC_ControlState state = TMC_ControlState::uninitialized
 
TMC_ControlState laststate = TMC_ControlState::uninitialized
 
TMC_ControlState requestedState = TMC_ControlState::Shutdown
 
MotionMode curMotionMode = MotionMode::stop
 
MotionMode lastMotionMode = MotionMode::stop
 
MotionMode nextMotionMode = MotionMode::stop
 
TMC_StartupType startupType = TMC_StartupType::NONE
 
bool ES_TMCdetected = false
 
bool encoderAligned = false
 
bool initialized = false
 
bool powerInitialized = false
 
bool adcCalibrated = false
 
bool adcSettingsStored = false
 
bool motorEnabledRequested = false
 
volatile bool encoderIndexHitFlag = false
 
bool zeroEncoderOnIndexHit = false
 
bool fullCalibrationInProgress = false
 
bool phiErestored = false
 
bool encHallRestored = false
 
uint8_t calibrationFailCount = 2
 
int16_t externalEncoderPhieOffset = 0
 
bool allowExternalEncoder = false
 
bool allowStateChange = false
 
bool recalibrationRequired = false
 
uint8_t enc_retry = 0
 
uint8_t enc_retry_max = 3
 
uint32_t lastStatTime = 0
 
uint8_t spi_buf [5] = {0}
 
uint32_t initTime = 0
 
bool manualEncAlign = false
 
bool spiActive = false
 
TMC4671Biquad_conf torqueFilterConf
 
TMC4671BiquadFilters curFilters
 
const float fluxFilterFreq = 350.0
 
TIM_HandleTypeDef * externalEncoderTimer = &TIM_TMC
 
std::unique_ptr< TMC_ExternalEncoderUpdateThreadextEncUpdater = nullptr
 

Friends

class TMCDebugBridge
 

Additional Inherited Members

- Protected Member Functions inherited from CommandHandler
void setInstance (uint8_t instance)
 
virtual void addCommandHandler ()
 
virtual void removeCommandHandler ()
 
- Protected Member Functions inherited from SPIDevice
virtual void setSpiConfig (SPIConfig config)
 
- Protected Member Functions inherited from cpp_freertos::Thread
virtual void Cleanup ()
 
void Delay (const TickType_t Delay)
 
void DelayUntil (const TickType_t Period)
 
void ResetDelayUntil ()
 
bool Wait (ConditionVariable &Cv, Mutex &CvLock, TickType_t Timeout=portMAX_DELAY)
 
- Static Protected Member Functions inherited from CommandHandler
static std::vector< uint16_t > & getCommandHandlerIds ()
 
- Protected Attributes inherited from MotorDriver
std::shared_ptr< EncoderdrvEncoder = std::make_shared<Encoder>()
 
- Protected Attributes inherited from ChoosableClass
uint16_t selectionId
 Should only be written by ClassChooser during creation. More...
 
- Protected Attributes inherited from PersistentStorage
bool restoreDelayedFlag = false
 
- Protected Attributes inherited from Encoder
uint32_t cpr = 0
 
- Protected Attributes inherited from CommandHandler
bool commandsEnabled = true
 
std::vector< CmdHandlerCommanddefregisteredCommands
 
CmdHandlerInfo cmdHandlerInfo
 
- Protected Attributes inherited from SPIDevice
SPIPortspiPort
 
SPIConfig spiConfig
 
- Static Protected Attributes inherited from PersistentStorage
static bool startupComplete = false
 

Detailed Description

Definition at line 317 of file TMC4671.h.

Member Enumeration Documentation

◆ TMC4671_commands

enum class TMC4671::TMC4671_commands : uint32_t
strongprivate
Enumerator
cpr 
mtype 
encsrc 
tmcHwType 
encalign 
poles 
acttrq 
pwmlim 
torqueP 
torqueI 
fluxP 
fluxI 
velocityP 
velocityI 
posP 
posI 
tmctype 
pidPrec 
phiesrc 
fluxoffset 
seqpi 
tmcIscale 
encdir 
temp 
reg 
svpwm 
fullCalibration 
calibrated 
abnindexenabled 
findIndex 
getState 
encpol 
combineEncoder 
invertForce 
vmTmc 
extphie 
torqueFilter_mode 
torqueFilter_f 
torqueFilter_q 
pidautotune 
fluxbrake 
pwmfreq 

Definition at line 325 of file TMC4671.h.

Constructor & Destructor Documentation

◆ TMC4671()

TMC4671::TMC4671 ( SPIPort spiport,
OutputPin  cspin,
uint8_t  address = 1 
)

Definition at line 49 of file TMC4671.cpp.

◆ ~TMC4671()

TMC4671::~TMC4671 ( )
virtual

Definition at line 81 of file TMC4671.cpp.

Member Function Documentation

◆ autohome()

bool TMC4671::autohome ( )

Definition at line 762 of file TMC4671.cpp.

◆ bangInitEnc()

void TMC4671::bangInitEnc ( int16_t  power)

Aligns ABN encoders by forcing an angle with high current and calculating the offset Will start at the current phiE to minimize any extra movements (useful if motor was turned in openloop mode before already)

Parameters
powerMaximum current reached during flux ramp

Definition at line 957 of file TMC4671.cpp.

◆ beginSpiTransfer()

void TMC4671::beginSpiTransfer ( SPIPort port)
virtual

Reimplemented from SPIDevice.

Definition at line 2537 of file TMC4671.cpp.

◆ calibFailCb()

void TMC4671::calibFailCb ( )
private

Definition at line 1420 of file TMC4671.cpp.

◆ calibrateAdcOffset()

bool TMC4671::calibrateAdcOffset ( uint16_t  time = 500)

Calibrates the ADC by disabling the power stage and sampling a mean value. Takes time!

Definition at line 1359 of file TMC4671.cpp.

◆ calibrateAenc()

void TMC4671::calibrateAenc ( )

Moves the motor to find out analog encoder scalings and offsets

Definition at line 1046 of file TMC4671.cpp.

◆ calibrateEncoder()

void TMC4671::calibrateEncoder ( )

Definition at line 648 of file TMC4671.cpp.

◆ changeState()

void TMC4671::changeState ( TMC_ControlState  newState,
bool  force = false 
)
inline

Definition at line 780 of file TMC4671.cpp.

◆ checkAdc()

bool TMC4671::checkAdc ( )

Samples the adc and checks if it returns a neutral value

Definition at line 374 of file TMC4671.cpp.

◆ checkEncoder()

bool TMC4671::checkEncoder ( )

Steps the motor a few times to check if the encoder follows correctly

Definition at line 1167 of file TMC4671.cpp.

◆ command()

CommandStatus TMC4671::command ( const ParsedCommand cmd,
std::vector< CommandReply > &  replies 
)
virtual
Parameters
[in]cmdThe parsed command to be executed.
[out]repliesA vector to return one or multiple reply objects into. Replies to the interface will be generated based on the reply objects. A string reply may not contain start, end and separation markers: [,],| Other characters are allowed.

Reimplemented from CommandHandler.

Definition at line 2890 of file TMC4671.cpp.

◆ controlFluxDissipate()

int16_t TMC4671::controlFluxDissipate ( )

Calculates a flux value based on the internal and external voltage difference to dissipate energy without a brake resistor

Definition at line 1710 of file TMC4671.cpp.

◆ decodeMotFromInt()

TMC4671MotConf TMC4671::decodeMotFromInt ( uint16_t  val)
static

Definition at line 2614 of file TMC4671.cpp.

◆ emergencyStop()

void TMC4671::emergencyStop ( bool  reset)
virtual

Request an emergency stop if something critical happened or the emergency button is triggered Should stop the motor immediately in a safe way.

Reimplemented from MotorDriver.

Definition at line 1680 of file TMC4671.cpp.

◆ encInit()

void TMC4671::encInit ( )
private

◆ encodeEncHallMisc()

uint16_t TMC4671::encodeEncHallMisc ( )

Definition at line 2631 of file TMC4671.cpp.

◆ encodeMotToInt()

uint16_t TMC4671::encodeMotToInt ( TMC4671MotConf  mconf)
static

Definition at line 2623 of file TMC4671.cpp.

◆ encoderIndexHit()

void TMC4671::encoderIndexHit ( )
private

Definition at line 2605 of file TMC4671.cpp.

◆ encoderInit()

void TMC4671::encoderInit ( )
private

Definition at line 1429 of file TMC4671.cpp.

◆ encToPos()

uint32_t TMC4671::encToPos ( uint32_t  enc)

Converts encoder counts to phiM

Definition at line 1935 of file TMC4671.cpp.

◆ endSpiTransfer()

void TMC4671::endSpiTransfer ( SPIPort port)
virtual

Reimplemented from SPIDevice.

Definition at line 2540 of file TMC4671.cpp.

◆ errorCallback()

void TMC4671::errorCallback ( const Error error,
bool  cleared 
)
private

Definition at line 3252 of file TMC4671.cpp.

◆ estimateABNparams()

void TMC4671::estimateABNparams ( )

Moves the rotor and estimates polarity and direction of the encoder Polarity is found by measuring the n pulse. If polarity was found to be reversed during the test direction will be reversed again to account for that

Definition at line 2277 of file TMC4671.cpp.

◆ estimateExtEnc()

void TMC4671::estimateExtEnc ( )

Similar to the ABN calibration this moved the motor and measures the encoder direction

Definition at line 2330 of file TMC4671.cpp.

◆ externalEncoderAllowed()

bool TMC4671::externalEncoderAllowed ( )

Definition at line 2006 of file TMC4671.cpp.

◆ exti()

void TMC4671::exti ( uint16_t  GPIO_Pin)
virtual

Reimplemented from ExtiHandler.

Definition at line 2599 of file TMC4671.cpp.

◆ findEncoderIndex()

bool TMC4671::findEncoderIndex ( int32_t  speed = 10,
uint16_t  power = 2500,
bool  offsetPhiM = false,
bool  zeroCount = false 
)

Rotates motor until the ABN index is found

Definition at line 823 of file TMC4671.cpp.

◆ getActualFlux()

int32_t TMC4671::getActualFlux ( )

Returns measured flux

Definition at line 2471 of file TMC4671.cpp.

◆ getActualTorque()

int32_t TMC4671::getActualTorque ( )

Returns measured torque

Definition at line 2480 of file TMC4671.cpp.

◆ getActualTorqueFlux()

std::pair< int32_t, int32_t > TMC4671::getActualTorqueFlux ( )

Returns measured flux and torque as a pair Flux is first, torque second item

Definition at line 2461 of file TMC4671.cpp.

◆ getClassType()

const ClassType TMC4671::getClassType ( )
inlineoverridevirtual

Type of this class. Mainclass, motordriver... Should be implemented by the parent class so it is not in the info struct

Reimplemented from CommandHandler.

Definition at line 341 of file TMC4671.h.

◆ getCpr()

uint32_t TMC4671::getCpr ( )
virtual

Gets the amount of counts per full rotation of the encoder

Reimplemented from Encoder.

Definition at line 1909 of file TMC4671.cpp.

◆ getEncCpr()

uint32_t TMC4671::getEncCpr ( )

Definition at line 1573 of file TMC4671.cpp.

◆ getEncoder()

Encoder * TMC4671::getEncoder ( )
overridevirtual

Returns the encoder of this motor driver. Either the integrated encoder or an external encoder assigned to this motor driver passed externally

Reimplemented from MotorDriver.

Definition at line 1840 of file TMC4671.cpp.

◆ getEncoderType()

EncoderType TMC4671::getEncoderType ( )
overridevirtual

Returns the type of the encoder. Must override this and NOT return NONE in other classes

Reimplemented from Encoder.

Definition at line 1942 of file TMC4671.cpp.

◆ getFlux()

int16_t TMC4671::getFlux ( )

Definition at line 2046 of file TMC4671.cpp.

◆ getGpioPins()

uint8_t TMC4671::getGpioPins ( )

Reads the state of the 8 gpio pins

Definition at line 1800 of file TMC4671.cpp.

◆ getHelpstring()

virtual std::string TMC4671::getHelpstring ( )
inlinevirtual

Returns a description of this class

Reimplemented from CommandHandler.

Definition at line 559 of file TMC4671.h.

◆ getInfo()

const ClassIdentifier TMC4671::getInfo ( )
virtual

Command handlers always have class infos. Works well with ChoosableClass.

Implements CommandHandler.

Definition at line 87 of file TMC4671.cpp.

◆ getLimits()

TMC4671Limits TMC4671::getLimits ( )

Definition at line 2137 of file TMC4671.cpp.

◆ getMotionMode()

MotionMode TMC4671::getMotionMode ( )

Definition at line 1614 of file TMC4671.cpp.

◆ getPhiE()

int16_t TMC4671::getPhiE ( )

Definition at line 946 of file TMC4671.cpp.

◆ getPhiE_Enc()

int16_t TMC4671::getPhiE_Enc ( )

Reads phiE directly from the encoder selection instead of the current phiE selection

Definition at line 1150 of file TMC4671.cpp.

◆ getPhiEfromExternalEncoder()

int16_t TMC4671::getPhiEfromExternalEncoder ( )

Definition at line 934 of file TMC4671.cpp.

◆ getPhiEtype()

PhiE TMC4671::getPhiEtype ( )

Definition at line 1595 of file TMC4671.cpp.

◆ getPids()

TMC4671PIDConf TMC4671::getPids ( )

Definition at line 2089 of file TMC4671.cpp.

◆ getPos()

int32_t TMC4671::getPos ( )
overridevirtual

Returns the encoder position as raw counts

Reimplemented from Encoder.

Definition at line 1887 of file TMC4671.cpp.

◆ getPosAbs()

int32_t TMC4671::getPosAbs ( )
overridevirtual

Returns absolute positions without offsets for absolute encoders. Otherwise it returns getPos

Reimplemented from Encoder.

Definition at line 1893 of file TMC4671.cpp.

◆ getPwmFreq()

float TMC4671::getPwmFreq ( )

Returns the PWM loop frequency in Hz Depends on hardware clock and pwm counter setting. Default 25kHz

Definition at line 2416 of file TMC4671.cpp.

◆ getSpiAddr()

uint8_t TMC4671::getSpiAddr ( )

◆ getState()

TMC_ControlState TMC4671::getState ( )

Definition at line 776 of file TMC4671.cpp.

◆ getTargetPos()

int32_t TMC4671::getTargetPos ( )

Definition at line 903 of file TMC4671.cpp.

◆ getTargetVelocity()

int32_t TMC4671::getTargetVelocity ( )

Definition at line 919 of file TMC4671.cpp.

◆ getTemp()

float TMC4671::getTemp ( )

Reads a temperature from a thermistor connected to AGPI_B Not calibrated perfectly!

Definition at line 349 of file TMC4671.cpp.

◆ getTmcType()

std::pair< uint32_t, std::string > TMC4671::getTmcType ( )

Returns a string with the name and version of the chip

Definition at line 1817 of file TMC4671.cpp.

◆ getTmcVM()

int32_t TMC4671::getTmcVM ( )

Returns estimated VM in mV measured by TMC

Definition at line 231 of file TMC4671.cpp.

◆ getTorque()

int16_t TMC4671::getTorque ( )

Definition at line 2036 of file TMC4671.cpp.

◆ getVelocity()

int32_t TMC4671::getVelocity ( )

Definition at line 922 of file TMC4671.cpp.

◆ hasIntegratedEncoder()

bool TMC4671::hasIntegratedEncoder ( )
overridevirtual

If returned true it signals that this motor driver contains its own encoder and does not require an external encoder

Reimplemented from MotorDriver.

Definition at line 1856 of file TMC4671.cpp.

◆ hasPower()

bool TMC4671::hasPower ( )

Definition at line 192 of file TMC4671.cpp.

◆ initAdc()

void TMC4671::initAdc ( uint16_t  mdecA,
uint16_t  mdecB,
uint32_t  mclkA,
uint32_t  mclkB 
)
private

Definition at line 2444 of file TMC4671.cpp.

◆ initialize()

bool TMC4671::initialize ( )

Sets all parameters of the driver at startup. Only has to be called once when the driver is detected restoreFlash() should be called before this to restore settings!

Definition at line 244 of file TMC4671.cpp.

◆ initializeWithPower()

void TMC4671::initializeWithPower ( )

Definition at line 385 of file TMC4671.cpp.

◆ isSetUp()

bool TMC4671::isSetUp ( )

Definition at line 198 of file TMC4671.cpp.

◆ motorReady()

bool TMC4671::motorReady ( )
virtual

Reimplemented from MotorDriver.

Definition at line 423 of file TMC4671.cpp.

◆ pidAutoTune()

bool TMC4671::pidAutoTune ( )
private

Iterative tuning function for tuning the torque mode PI values

Enter phieExt & torque mode Zero I, default P Ramp up flux P until 50% of target, then lower increments until targetflux_p is reached Increase I until oscillation is found. Back off a bit

Definition at line 666 of file TMC4671.cpp.

◆ pingDriver()

bool TMC4671::pingDriver ( )

Check if driver is responding

Definition at line 223 of file TMC4671.cpp.

◆ posToEnc()

uint32_t TMC4671::posToEnc ( uint32_t  pos)

Definition at line 1938 of file TMC4671.cpp.

◆ rampFlux()

void TMC4671::rampFlux ( uint16_t  target,
uint16_t  time_ms 
)

Ramps flux from current value to a target value over a specified duration

Definition at line 2066 of file TMC4671.cpp.

◆ reachedPosition()

bool TMC4671::reachedPosition ( uint16_t  tolerance)

Definition at line 792 of file TMC4671.cpp.

◆ readFlags()

StatusFlags TMC4671::readFlags ( bool  maskedOnly = true)

Reads status flags

Parameters
maskedOnlyMasks flags by previously set flag mask that would trigger an interrupt. False to read all flags

Definition at line 2549 of file TMC4671.cpp.

◆ readReg()

uint32_t TMC4671::readReg ( uint8_t  reg)

Definition at line 2488 of file TMC4671.cpp.

◆ registerCommands()

void TMC4671::registerCommands ( )

Definition at line 2842 of file TMC4671.cpp.

◆ restoreEncHallMisc()

void TMC4671::restoreEncHallMisc ( uint16_t  val)

Definition at line 2657 of file TMC4671.cpp.

◆ restoreFlash()

void TMC4671::restoreFlash ( )
overridevirtual

Restores saved parameters Call initialize() to apply some of the settings

Reimplemented from PersistentStorage.

Definition at line 145 of file TMC4671.cpp.

◆ Run()

void TMC4671::Run ( )
virtual

Implementation of your actual thread code. You must override this function.

Note
If INCLUDE_vTaskDelete is defined, then you may return from your Run method. This will cause the task to be deleted from FreeRTOS, however you are still responsible to delete the task object. If this is not defined, then retuning from your Run() method will result in an assert.

Implements cpp_freertos::Thread.

Definition at line 427 of file TMC4671.cpp.

◆ runOpenLoop()

void TMC4671::runOpenLoop ( uint16_t  ud,
uint16_t  uq,
int32_t  speed,
int32_t  accel,
bool  torqueMode = false 
)

Definition at line 1625 of file TMC4671.cpp.

◆ saveAdcParams()

void TMC4671::saveAdcParams ( )
private

Writes ADC offsets into flash

Definition at line 135 of file TMC4671.cpp.

◆ saveFlash()

void TMC4671::saveFlash ( )
overridevirtual

Called when the user uses the "save" command and presses the save button in the configurator Automatically called by the command parser thread for every class that inherits from PersistentStorage

Reimplemented from PersistentStorage.

Definition at line 107 of file TMC4671.cpp.

◆ setAdcOffset()

void TMC4671::setAdcOffset ( uint32_t  adc_I0_offset,
uint32_t  adc_I1_offset 
)

Definition at line 1951 of file TMC4671.cpp.

◆ setAdcScale()

void TMC4671::setAdcScale ( uint32_t  adc_I0_scale,
uint32_t  adc_I1_scale 
)

Definition at line 1959 of file TMC4671.cpp.

◆ setAddress()

void TMC4671::setAddress ( uint8_t  address)

Definition at line 93 of file TMC4671.cpp.

◆ setBBM()

void TMC4671::setBBM ( uint8_t  bbml,
uint8_t  bbmh 
)

Definition at line 2385 of file TMC4671.cpp.

◆ setBiquadFlux()

void TMC4671::setBiquadFlux ( const TMC4671Biquad filter)

Applies a biquad filter to the flux target Set nullptr to disable

Definition at line 2152 of file TMC4671.cpp.

◆ setBiquadPos()

void TMC4671::setBiquadPos ( const TMC4671Biquad filter)

Applies a biquad filter to the pos target Set nullptr to disable

Definition at line 2173 of file TMC4671.cpp.

◆ setBiquadTorque()

void TMC4671::setBiquadTorque ( const TMC4671Biquad filter)

Applies a biquad filter to the torque target Set nullptr to disable

Definition at line 2215 of file TMC4671.cpp.

◆ setBiquadVel()

void TMC4671::setBiquadVel ( const TMC4671Biquad filter)

Applies a biquad filter to the actual measured velocity Set nullptr to disable

Definition at line 2194 of file TMC4671.cpp.

◆ setBrakeLimits()

void TMC4671::setBrakeLimits ( uint16_t  low,
uint16_t  high 
)

Sets the raw brake resistor limits. Centered at 0x7fff Set both 0 to deactivate

Definition at line 2267 of file TMC4671.cpp.

◆ setCpr()

void TMC4671::setCpr ( uint32_t  cpr)

Definition at line 1920 of file TMC4671.cpp.

◆ setEncoder()

void TMC4671::setEncoder ( std::shared_ptr< Encoder > &  encoder)
overridevirtual

Can pass an external encoder if driver has no integrated encoder This allows a driver to get an external encoder assigned if it requires one and has the capability of using external encoders

Reimplemented from MotorDriver.

Definition at line 1848 of file TMC4671.cpp.

◆ setEncoderIndexFlagEnabled()

void TMC4671::setEncoderIndexFlagEnabled ( bool  enabled,
bool  zeroEncoder = false 
)

Enables or disables the encoder index interruption on the flag pin depending on the selected encoder

Definition at line 877 of file TMC4671.cpp.

◆ setEncoderType()

void TMC4671::setEncoderType ( EncoderType_TMC  type)

Changes the encoder type and calls init methods for the encoder types. Setup the specific parameters (abnconf, aencconf...) first.

Definition at line 1513 of file TMC4671.cpp.

◆ setExternalEncoderAllowed()

void TMC4671::setExternalEncoderAllowed ( bool  allow)

Definition at line 1993 of file TMC4671.cpp.

◆ setFFMode()

void TMC4671::setFFMode ( FFMode  mode)

Definition at line 1980 of file TMC4671.cpp.

◆ setFlux()

void TMC4671::setFlux ( int16_t  flux)

Definition at line 2040 of file TMC4671.cpp.

◆ setFluxTorque()

void TMC4671::setFluxTorque ( int16_t  flux,
int16_t  torque 
)

Definition at line 2049 of file TMC4671.cpp.

◆ setFluxTorqueFF()

void TMC4671::setFluxTorqueFF ( int16_t  flux,
int16_t  torque 
)

Definition at line 2056 of file TMC4671.cpp.

◆ setGpioMode()

void TMC4671::setGpioMode ( TMC_GpioMode  mode)

Changes the mode of the 8 GPIO pins Banks A and B can be mapped independently to inputs or outputs, as a DS adc interface or by default as a secondary debug SPI port

Definition at line 1774 of file TMC4671.cpp.

◆ setGpioPins()

void TMC4671::setGpioPins ( uint8_t  pins)

Changes the state of gpio pins that are mapped as output lower 4 bits bank A, upper 4 bits bank B

Definition at line 1808 of file TMC4671.cpp.

◆ setHwType()

void TMC4671::setHwType ( TMC_HW_Ver  type)

Sets some constants and features depending on the hardware version of the driver

Definition at line 2692 of file TMC4671.cpp.

◆ setLimits()

void TMC4671::setLimits ( TMC4671Limits  limits)

Definition at line 2126 of file TMC4671.cpp.

◆ setMotionMode()

void TMC4671::setMotionMode ( MotionMode  mode,
bool  force = false 
)

Definition at line 1603 of file TMC4671.cpp.

◆ setMotorType()

void TMC4671::setMotorType ( MotorType  motor,
uint16_t  poles 
)

Definition at line 2014 of file TMC4671.cpp.

◆ setOpenLoopSpeedAccel()

void TMC4671::setOpenLoopSpeedAccel ( int32_t  speed,
uint32_t  accel 
)

Definition at line 1619 of file TMC4671.cpp.

◆ setPhiE_ext()

void TMC4671::setPhiE_ext ( int16_t  phiE)

Definition at line 930 of file TMC4671.cpp.

◆ setPhiEtype()

void TMC4671::setPhiEtype ( PhiE  type)

Definition at line 1585 of file TMC4671.cpp.

◆ setPidPrecision()

void TMC4671::setPidPrecision ( TMC4671PidPrecision  setting)

Definition at line 2113 of file TMC4671.cpp.

◆ setPids()

void TMC4671::setPids ( TMC4671PIDConf  pids)

Definition at line 2080 of file TMC4671.cpp.

◆ setPos()

void TMC4671::setPos ( int32_t  pos)
overridevirtual

Changes position using offset from index

Reimplemented from Encoder.

Definition at line 1864 of file TMC4671.cpp.

◆ setPositionExt()

void TMC4671::setPositionExt ( int32_t  pos)

Definition at line 926 of file TMC4671.cpp.

◆ setPosSel()

void TMC4671::setPosSel ( PosSelection  psel)

Changes the position sensor source

Definition at line 1755 of file TMC4671.cpp.

◆ setPwm() [1/2]

void TMC4671::setPwm ( TMC_PwmMode  val)
private

Sets pwm mode:
0 = pwm off
1 = pwm off, HS low, LS high
2 = pwm off, HS high, LS low
3 = pwm off
4 = pwm off
5 = pwm LS only
6 = pwm HS only
7 = pwm on centered, FOC mode

Definition at line 2381 of file TMC4671.cpp.

◆ setPwm() [2/2]

void TMC4671::setPwm ( uint8_t  val,
uint16_t  maxcnt,
uint8_t  bbmL,
uint8_t  bbmH 
)
private

Definition at line 2392 of file TMC4671.cpp.

◆ setPwmFreq()

void TMC4671::setPwmFreq ( float  freq)

Changes the PWM frequency to a desired frequency Possible values depend on the hwclock. At 25MHz the lowest possible frequency is 24.1kHz

Definition at line 2436 of file TMC4671.cpp.

◆ setPwmMaxCnt()

void TMC4671::setPwmMaxCnt ( uint16_t  maxcnt)
private

Changes PWM frequency Max value 4095, minimum 255

Definition at line 2425 of file TMC4671.cpp.

◆ setSequentialPI()

void TMC4671::setSequentialPI ( bool  sequential)

Definition at line 1988 of file TMC4671.cpp.

◆ setSpiAddr()

bool TMC4671::setSpiAddr ( uint8_t  chan)

◆ setStatusFlags() [1/2]

void TMC4671::setStatusFlags ( StatusFlags  flags)

Definition at line 2570 of file TMC4671.cpp.

◆ setStatusFlags() [2/2]

void TMC4671::setStatusFlags ( uint32_t  flags)

Definition at line 2566 of file TMC4671.cpp.

◆ setStatusMask() [1/2]

void TMC4671::setStatusMask ( StatusFlags  mask)

Definition at line 2558 of file TMC4671.cpp.

◆ setStatusMask() [2/2]

void TMC4671::setStatusMask ( uint32_t  mask)

Definition at line 2562 of file TMC4671.cpp.

◆ setSvPwm()

void TMC4671::setSvPwm ( bool  enable)
private

Enable or disable space vector pwm for 3 phase motors Normally active but should be disabled if the motor has no isolated star point

Definition at line 2403 of file TMC4671.cpp.

◆ setTargetPos()

void TMC4671::setTargetPos ( int32_t  pos)

Enables position mode and sets a target position

Definition at line 896 of file TMC4671.cpp.

◆ setTargetVelocity()

void TMC4671::setTargetVelocity ( int32_t  vel)

Enables velocity mode and sets a velocity target

Definition at line 912 of file TMC4671.cpp.

◆ setTmcPos()

void TMC4671::setTmcPos ( int32_t  pos)

Changes position in tmc register

Definition at line 1882 of file TMC4671.cpp.

◆ setTorque()

void TMC4671::setTorque ( int16_t  torque)

Definition at line 2030 of file TMC4671.cpp.

◆ setTorqueFilter()

void TMC4671::setTorqueFilter ( TMC4671Biquad_conf conf)

Changes the torque biquad filter

Definition at line 2236 of file TMC4671.cpp.

◆ setTorqueLimit()

void TMC4671::setTorqueLimit ( uint16_t  limit)

Definition at line 2107 of file TMC4671.cpp.

◆ setUdUq()

void TMC4671::setUdUq ( int16_t  ud,
int16_t  uq 
)

Definition at line 1646 of file TMC4671.cpp.

◆ setup_ABN_Enc()

void TMC4671::setup_ABN_Enc ( TMC4671ABNConf  encconf)

Definition at line 1289 of file TMC4671.cpp.

◆ setup_AENC()

void TMC4671::setup_AENC ( TMC4671AENCConf  encconf)

Definition at line 1313 of file TMC4671.cpp.

◆ setup_HALL()

void TMC4671::setup_HALL ( TMC4671HALLConf  hallconf)

Definition at line 1330 of file TMC4671.cpp.

◆ setUpExtEncTimer()

void TMC4671::setUpExtEncTimer ( )
private

Definition at line 3218 of file TMC4671.cpp.

◆ setupFeedForwardTorque()

void TMC4671::setupFeedForwardTorque ( int32_t  gain,
int32_t  constant 
)

Definition at line 1967 of file TMC4671.cpp.

◆ setupFeedForwardVelocity()

void TMC4671::setupFeedForwardVelocity ( int32_t  gain,
int32_t  constant 
)

Definition at line 1973 of file TMC4671.cpp.

◆ setUqUdLimit()

void TMC4671::setUqUdLimit ( uint16_t  limit)

Limits the PWM value

Definition at line 2102 of file TMC4671.cpp.

◆ setVelSel()

void TMC4671::setVelSel ( VelSelection  vsel,
uint8_t  mode = 0 
)

Changes the velocity sensor source (RPM if PhiM source used)

Parameters
mode0 = fixed frequency sampling (~4369.067Hz), 1 = PWM sync time difference measurement

Definition at line 1764 of file TMC4671.cpp.

◆ startMotor()

void TMC4671::startMotor ( )
virtual

Enable the motor driver

Reimplemented from MotorDriver.

Definition at line 1661 of file TMC4671.cpp.

◆ statusCheck()

void TMC4671::statusCheck ( )

Reads and resets all status flags and executes depending on status flags

Definition at line 2577 of file TMC4671.cpp.

◆ stopMotor()

void TMC4671::stopMotor ( )
virtual

Disable the motor driver

Reimplemented from MotorDriver.

Definition at line 1650 of file TMC4671.cpp.

◆ timerElapsed()

void TMC4671::timerElapsed ( TIM_HandleTypeDef *  htim)

Definition at line 3205 of file TMC4671.cpp.

◆ turn()

void TMC4671::turn ( int16_t  power)
virtual

Sets a torque in positive or negative direction For ADC linearity reasons under 25000 is recommended

Reimplemented from MotorDriver.

Definition at line 1724 of file TMC4671.cpp.

◆ updateReg()

void TMC4671::updateReg ( uint8_t  reg,
uint32_t  dat,
uint32_t  mask,
uint8_t  shift 
)

Definition at line 2530 of file TMC4671.cpp.

◆ usingExternalEncoder()

bool TMC4671::usingExternalEncoder ( )
inline

Definition at line 513 of file TMC4671.h.

◆ writeReg()

void TMC4671::writeReg ( uint8_t  reg,
uint32_t  dat 
)

Definition at line 2502 of file TMC4671.cpp.

◆ writeRegAsync()

void TMC4671::writeRegAsync ( uint8_t  reg,
uint32_t  dat 
)

Definition at line 2514 of file TMC4671.cpp.

◆ zeroAbnUsingPhiM()

void TMC4671::zeroAbnUsingPhiM ( bool  offsetPhiE = false)

Definition at line 802 of file TMC4671.cpp.

Friends And Related Function Documentation

◆ TMCDebugBridge

friend class TMCDebugBridge
friend

Definition at line 334 of file TMC4671.h.

Member Data Documentation

◆ abnconf

TMC4671ABNConf TMC4671::abnconf

Definition at line 505 of file TMC4671.h.

◆ adcCalibrated

bool TMC4671::adcCalibrated = false
private

Definition at line 595 of file TMC4671.h.

◆ adcSettingsStored

bool TMC4671::adcSettingsStored = false
private

Definition at line 596 of file TMC4671.h.

◆ aencconf

TMC4671AENCConf TMC4671::aencconf

Definition at line 507 of file TMC4671.h.

◆ allowExternalEncoder

bool TMC4671::allowExternalEncoder = false
private

Definition at line 607 of file TMC4671.h.

◆ allowSlowSPI

bool TMC4671::allowSlowSPI = true

Definition at line 550 of file TMC4671.h.

◆ allowStateChange

bool TMC4671::allowStateChange = false
private

Definition at line 609 of file TMC4671.h.

◆ bangInitPower

int16_t TMC4671::bangInitPower = 5000

Definition at line 440 of file TMC4671.h.

◆ calibrationFailCount

uint8_t TMC4671::calibrationFailCount = 2
private

Definition at line 604 of file TMC4671.h.

◆ communicationError

const Error TMC4671::communicationError = Error(ErrorCode::tmcCommunicationError, ErrorType::warning, "TMC not responding")
private

Definition at line 577 of file TMC4671.h.

◆ conf

TMC4671MainConfig TMC4671::conf

Definition at line 357 of file TMC4671.h.

◆ curFilters

TMC4671BiquadFilters TMC4671::curFilters
private

Definition at line 644 of file TMC4671.h.

◆ curLimits

TMC4671Limits TMC4671::curLimits

Definition at line 495 of file TMC4671.h.

◆ curMotionMode

MotionMode TMC4671::curMotionMode = MotionMode::stop
private

Definition at line 583 of file TMC4671.h.

◆ curPids

TMC4671PIDConf TMC4671::curPids

Definition at line 493 of file TMC4671.h.

◆ emergency

bool TMC4671::emergency = false

Definition at line 433 of file TMC4671.h.

◆ enablePin

OutputPin TMC4671::enablePin = OutputPin(*DRV_ENABLE_GPIO_Port,DRV_ENABLE_Pin)
private

Definition at line 574 of file TMC4671.h.

◆ enc_retry

uint8_t TMC4671::enc_retry = 0
private

Definition at line 612 of file TMC4671.h.

◆ enc_retry_max

uint8_t TMC4671::enc_retry_max = 3
private

Definition at line 613 of file TMC4671.h.

◆ encHallRestored

bool TMC4671::encHallRestored = false
private

Definition at line 602 of file TMC4671.h.

◆ encoderAligned

bool TMC4671::encoderAligned = false
private

Definition at line 591 of file TMC4671.h.

◆ encoderIndexHitFlag

volatile bool TMC4671::encoderIndexHitFlag = false
private

Definition at line 598 of file TMC4671.h.

◆ ES_TMCdetected

bool TMC4671::ES_TMCdetected = false
private

Definition at line 589 of file TMC4671.h.

◆ estopError

const Error TMC4671::estopError = Error(ErrorCode::emergencyStop, ErrorType::critical, "TMC emergency stop triggered")
private

Definition at line 578 of file TMC4671.h.

◆ estopTriggered

bool TMC4671::estopTriggered = false

Definition at line 434 of file TMC4671.h.

◆ extEncUpdater

std::unique_ptr<TMC_ExternalEncoderUpdateThread> TMC4671::extEncUpdater = nullptr
private

Definition at line 651 of file TMC4671.h.

◆ externalEncoderPhieOffset

int16_t TMC4671::externalEncoderPhieOffset = 0
private

Definition at line 606 of file TMC4671.h.

◆ externalEncoderTimer

TIM_HandleTypeDef * TMC4671::externalEncoderTimer = &TIM_TMC
private

Definition at line 650 of file TMC4671.h.

◆ flagCheckInProgress

bool TMC4671::flagCheckInProgress = false

Definition at line 539 of file TMC4671.h.

◆ flashAddrs

TMC4671FlashAddrs TMC4671::flashAddrs

Definition at line 545 of file TMC4671.h.

◆ fluxDissipationLimit

const float TMC4671::fluxDissipationLimit = 1000

Definition at line 443 of file TMC4671.h.

◆ fluxFilterFreq

const float TMC4671::fluxFilterFreq = 350.0
private

Definition at line 645 of file TMC4671.h.

◆ fullCalibrationInProgress

bool TMC4671::fullCalibrationInProgress = false
private

Definition at line 600 of file TMC4671.h.

◆ hallconf

TMC4671HALLConf TMC4671::hallconf

Definition at line 506 of file TMC4671.h.

◆ idleFlux

int16_t TMC4671::idleFlux = 0

Definition at line 437 of file TMC4671.h.

◆ indexNotHitError

const Error TMC4671::indexNotHitError = Error(ErrorCode::encoderIndexMissed,ErrorType::critical,"Encoder index missed")
private

Definition at line 575 of file TMC4671.h.

◆ info

ClassIdentifier TMC4671::info
static
Initial value:
= {
.name = "TMC4671" ,
.id=CLSID_MOT_TMC0,
}

Definition at line 339 of file TMC4671.h.

◆ initialized

bool TMC4671::initialized = false
private

Definition at line 593 of file TMC4671.h.

◆ initTime

uint32_t TMC4671::initTime = 0
private

Definition at line 638 of file TMC4671.h.

◆ lastMotionMode

MotionMode TMC4671::lastMotionMode = MotionMode::stop
private

Definition at line 584 of file TMC4671.h.

◆ laststate

TMC_ControlState TMC4671::laststate = TMC_ControlState::uninitialized
private

Definition at line 581 of file TMC4671.h.

◆ lastStatTime

uint32_t TMC4671::lastStatTime = 0
private

Definition at line 615 of file TMC4671.h.

◆ lowVoltageError

const Error TMC4671::lowVoltageError = Error(ErrorCode::undervoltage,ErrorType::warning,"Low motor voltage")
private

Definition at line 576 of file TMC4671.h.

◆ manualEncAlign

bool TMC4671::manualEncAlign = false
private

Definition at line 639 of file TMC4671.h.

◆ maxOffsetFlux

uint16_t TMC4671::maxOffsetFlux = 0

Definition at line 438 of file TMC4671.h.

◆ motorEnabledRequested

bool TMC4671::motorEnabledRequested = false
private

Definition at line 597 of file TMC4671.h.

◆ nextFlux

int16_t TMC4671::nextFlux = 0

Definition at line 436 of file TMC4671.h.

◆ nextMotionMode

MotionMode TMC4671::nextMotionMode = MotionMode::stop
private

Definition at line 585 of file TMC4671.h.

◆ phiErestored

bool TMC4671::phiErestored = false
private

Definition at line 601 of file TMC4671.h.

◆ pidPrecision

TMC4671PidPrecision TMC4671::pidPrecision

Definition at line 503 of file TMC4671.h.

◆ powerInitialized

bool TMC4671::powerInitialized = false
private

Definition at line 594 of file TMC4671.h.

◆ recalibrationRequired

bool TMC4671::recalibrationRequired = false
private

Definition at line 610 of file TMC4671.h.

◆ requestedState

TMC_ControlState TMC4671::requestedState = TMC_ControlState::Shutdown
private

Definition at line 582 of file TMC4671.h.

◆ spi_buf

uint8_t TMC4671::spi_buf[5] = {0}
private

Definition at line 617 of file TMC4671.h.

◆ spiActive

bool TMC4671::spiActive = false
private

Definition at line 640 of file TMC4671.h.

◆ startupType

TMC_StartupType TMC4671::startupType = TMC_StartupType::NONE
private

Definition at line 587 of file TMC4671.h.

◆ state

Definition at line 580 of file TMC4671.h.

◆ statusFlags

StatusFlags TMC4671::statusFlags = {0}

Definition at line 540 of file TMC4671.h.

◆ statusMask

StatusFlags TMC4671::statusMask = {0}

Definition at line 541 of file TMC4671.h.

◆ torqueFilterConf

TMC4671Biquad_conf TMC4671::torqueFilterConf
private

Definition at line 643 of file TMC4671.h.

◆ zeroEncoderOnIndexHit

bool TMC4671::zeroEncoderOnIndexHit = false
private

Definition at line 599 of file TMC4671.h.


The documentation for this class was generated from the following files: