Bioscara
DALSA's DIY SCARA Robot Arm.
Loading...
Searching...
No Matches
Public Types | Public Member Functions | Public Attributes | Protected Member Functions | Protected Attributes | List of all members
bioscara_hardware_drivers::BaseJoint Class Referenceabstract

Generic base class to control a single joint. More...

#include <mBaseJoint.h>

Inheritance diagram for bioscara_hardware_drivers::BaseJoint:
bioscara_hardware_drivers::Joint bioscara_hardware_drivers::MockJoint

Public Types

enum  stp_reg_t {
  NONE = 0x00 , PING = 0x0f , SETUP = 0x10 , SETRPM = 0x11 ,
  GETDRIVERRPM = 0x12 , MOVESTEPS = 0x13 , MOVEANGLE = 0x14 , MOVETOANGLE = 0x15 ,
  GETMOTORSTATE = 0x16 , RUNCOTINOUS = 0x17 , ANGLEMOVED = 0x18 , SETCURRENT = 0x19 ,
  SETHOLDCURRENT = 0x1A , SETMAXACCELERATION = 0x1B , SETMAXDECELERATION = 0x1C , SETMAXVELOCITY = 0x1D ,
  ENABLESTALLGUARD = 0x1E , DISABLESTALLGUARD = 0x1F , CLEARSTALL = 0x20 , SETBRAKEMODE = 0x22 ,
  ENABLEPID = 0x23 , DISABLEPID = 0x24 , ENABLECLOSEDLOOP = 0x25 , DISABLECLOSEDLOOP = 0x26 ,
  SETCONTROLTHRESHOLD = 0x27 , MOVETOEND = 0x28 , STOP = 0x29 , GETPIDERROR = 0x2A ,
  CHECKORIENTATION = 0x2B , GETENCODERRPM = 0x2C , HOME = 0x2D , HOMEOFFSET = 0x2E
}
 register and command definitions More...
 

Public Member Functions

 BaseJoint (const std::string name)
 Create a Joint object.
 
 ~BaseJoint (void)
 Destroy the BaseJoint object.
 
virtual err_type_t init (void)
 Initialize the joint communication.
 
virtual err_type_t deinit (void)
 Denitialize the joint communication.
 
virtual err_type_t enable (u_int8_t driveCurrent, u_int8_t holdCurrent)
 Engages the joint.
 
virtual err_type_t disable (void)
 disenganges the joint
 
virtual err_type_t home (float velocity, u_int8_t sensitivity, u_int8_t current)
 Blocking implementation to home the joint.
 
virtual err_type_t startHoming (float velocity, u_int8_t sensitivity, u_int8_t current)
 non-blocking implementation to home the joint
 
virtual err_type_t postHoming (void)
 perform tasks after a non-blocking homing
 
virtual err_type_t getPosition (float &pos)=0
 get the current joint position in radians or m for cylindrical and prismatic joints respectively.
 
virtual err_type_t setPosition (float pos)
 get the current joint position in radians or m for cylindrical and prismatic joints respectively.
 
virtual err_type_t moveSteps (int32_t steps)
 Move full steps.
 
virtual err_type_t getVelocity (float &vel)=0
 get the current joint velocity in radians/s or m/s for cylindrical and prismatic joints respectively.
 
virtual err_type_t setVelocity (float vel)
 Set the current joint velocity in radians/s or m/s for cylindrical and prismatic joints respectively.
 
virtual err_type_t checkOrientation (float angle=2.0)
 Calls the checkOrientation method of the motor. Checks in which direction the motor is turning.
 
virtual err_type_t stop (void)
 Stops the motor.
 
virtual err_type_t disableCL (void)
 
virtual err_type_t setDriveCurrent (u_int8_t current)
 Set the Drive Current.
 
virtual err_type_t setHoldCurrent (u_int8_t current)
 Set the Hold Current.
 
virtual err_type_t setBrakeMode (u_int8_t mode)
 Set Brake Mode.
 
virtual err_type_t setMaxAcceleration (float maxAccel)
 Set the maximum permitted joint acceleration (and deceleration) in rad/s^2 or m/s^2 for cylindrical and prismatic joints respectively.
 
virtual err_type_t setMaxVelocity (float maxVel)
 Set the maximum permitted joint velocity in rad/s or m/s for cylindrical and prismatic joints respectively.
 
virtual err_type_t enableStallguard (u_int8_t sensitivity)
 Enable encoder stall detection of the joint.
 
virtual bool isHomed (void)
 Checks the state if the motor is homed.
 
virtual bool isEnabled (void)
 Checks the state if the motor is enabled.
 
virtual bool isStalled (void)
 Checks if the motor is stalled.
 
virtual bool isBusy (void)
 Checks if the joint controller is busy processing a blocking command.
 
virtual err_type_t getFlags (u_int8_t &flags)
 get the latest driver state flags from the joint
 
virtual err_type_t getFlags (void)
 Overload of getFlags(u_int8_t &flags)
 
virtual stp_reg_t getCurrentBCmd (void)
 get the currently active blocking command
 

Public Attributes

std::string name
 Joint name for logging.
 

Protected Member Functions

virtual void wait_while_busy (const float period_ms)
 Blocking loop waiting for BUSY flag to reset.
 
virtual err_type_t _home (float velocity, u_int8_t sensitivity, u_int8_t current)=0
 Call to start the homing sequence of a joint.
 

Protected Attributes

u_int8_t flags = 0b00001100
 State flags transmitted with every I2C transaction.
 
stp_reg_t current_b_cmd = NONE
 Keeps track if a blocking command is being executed.
 

Detailed Description

Generic base class to control a single joint.

This class is a wrapper function to interact with a robot joint either through a MockJoint or hardware Joint object.

Member Enumeration Documentation

◆ stp_reg_t

register and command definitions

a register can be read (R) or written (W), each register has a size in bytes. The payload can be split into multiple values or just be a single value. Note that not all functions are implemented.

Enumerator
NONE 

Used for signalling purposes.

PING 

R; Size: 1; [(char) ACK].

SETUP 

W; Size: 2; [(uint8) holdCurrent, (uint8) driveCurrent].

SETRPM 

W; Size: 4; [(float) RPM].

GETDRIVERRPM 
MOVESTEPS 

W; Size: 4; [(int32) steps].

MOVEANGLE 
MOVETOANGLE 

W; Size: 4; [(float) degrees].

GETMOTORSTATE 
RUNCOTINOUS 
ANGLEMOVED 

R; Size: 4; [(float) degrees].

SETCURRENT 

W; Size: 1; [(uint8) driveCurrent].

SETHOLDCURRENT 

W; Size: 1; [(uint8) holdCurrent].

SETMAXACCELERATION 
SETMAXDECELERATION 
SETMAXVELOCITY 
ENABLESTALLGUARD 

W; Size: 1; [(uint8) threshold].

DISABLESTALLGUARD 
CLEARSTALL 
SETBRAKEMODE 

W; Size: 1; [(uint8) mode].

ENABLEPID 
DISABLEPID 
ENABLECLOSEDLOOP 
DISABLECLOSEDLOOP 

W; Size: 1; [(uint8) 0].

SETCONTROLTHRESHOLD 
MOVETOEND 
STOP 

W; Size: 1; [(uint8) mode].

GETPIDERROR 
CHECKORIENTATION 

W; Size: 4; [(float) degrees].

GETENCODERRPM 

R; Size: 4; [(float) RPM].

HOME 

W; Size: 4; [(uint8) current, (int8) sensitivity, (uint8) speed, (uint8) direction].

HOMEOFFSET 

R/W; Size: 4; [(float) -].

Constructor & Destructor Documentation

◆ BaseJoint()

bioscara_hardware_drivers::BaseJoint::BaseJoint ( const std::string  name)

Create a Joint object.

The Joint object represents a single joint.

Parameters
namestring device name for logging.

◆ ~BaseJoint()

bioscara_hardware_drivers::BaseJoint::~BaseJoint ( void  )

Destroy the BaseJoint object.

Invokes the disable() and deinit() method to clean up.

Member Function Documentation

◆ _home()

virtual err_type_t bioscara_hardware_drivers::BaseJoint::_home ( float  velocity,
u_int8_t  sensitivity,
u_int8_t  current 
)
protectedpure virtual

Call to start the homing sequence of a joint.

The joint will start rotating with the specified speed until a resistance which drives the PID error above the specified threshold is encountered. At this point the stepper stops and zeros the encoder.

Parameters
velocitysigned velocity in rad/s or m/s. Must be between 1.0 < RAD2DEG(JOINT2ACTUATOR(velocity, reduction, 0)) / 6 < 250.0
sensitivityEncoder pid error threshold 0 to 255.
currenthoming current, determines how easy it is to stop the motor and thereby provoke a stall
Returns
err_type_t

Implemented in bioscara_hardware_drivers::MockJoint, and bioscara_hardware_drivers::Joint.

◆ checkOrientation()

err_type_t bioscara_hardware_drivers::BaseJoint::checkOrientation ( float  angle = 2.0)
virtual

Calls the checkOrientation method of the motor. Checks in which direction the motor is turning.

Note
This is a blocking function.
Parameters
angledegrees how much the motor should turn. A few degrees is sufficient.
Returns
err_type_t

Reimplemented in bioscara_hardware_drivers::Joint, and bioscara_hardware_drivers::MockJoint.

◆ deinit()

err_type_t bioscara_hardware_drivers::BaseJoint::deinit ( void  )
virtual

Denitialize the joint communication.

Returns
err_type_t

Reimplemented in bioscara_hardware_drivers::Joint.

◆ disable()

err_type_t bioscara_hardware_drivers::BaseJoint::disable ( void  )
virtual

disenganges the joint

invokes stop(), sets hold and drive current to 0 and sets the the joint brake mode to freewheeling

Returns
err_type_t

Reimplemented in bioscara_hardware_drivers::MockJoint.

◆ disableCL()

err_type_t bioscara_hardware_drivers::BaseJoint::disableCL ( void  )
virtual

◆ enable()

err_type_t bioscara_hardware_drivers::BaseJoint::enable ( u_int8_t  driveCurrent,
u_int8_t  holdCurrent 
)
virtual

Engages the joint.

This function prepares the motor for movement. After successfull execution the joint is ready to accept setPosition() and setVelocity() commands.

The function sets the drive and hold current for the specified joint and engages the motor. The currents are in percent of driver max. output (2.5A, check with TMC5130 datasheet or Ustepper documentation)

Parameters
driveCurrentdrive current in 0-100 % of 2.5A output (check uStepper doc.)
holdCurrenthold current in 0-100 % of 2.5A output (check uStepper doc.)
Returns
err_type_t

Reimplemented in bioscara_hardware_drivers::Joint, and bioscara_hardware_drivers::MockJoint.

◆ enableStallguard()

err_type_t bioscara_hardware_drivers::BaseJoint::enableStallguard ( u_int8_t  sensitivity)
virtual

Enable encoder stall detection of the joint.

If the PID error exceeds the set threshold a stall is triggered and the motor disabled. A detected stall can be reset by homing or reenabling the joint using enable().

Note
If stall detection shall be enabled, invoke this method AFTER enabling the joint with enable().
Parameters
sensitivityvalue of threshold. 0 - 255 where lower is more sensitive.
Returns
err_type_t

Reimplemented in bioscara_hardware_drivers::Joint.

◆ getCurrentBCmd()

BaseJoint::stp_reg_t bioscara_hardware_drivers::BaseJoint::getCurrentBCmd ( void  )
virtual

get the currently active blocking command

Returns
The the command of type stp_reg_t

◆ getFlags() [1/2]

err_type_t bioscara_hardware_drivers::BaseJoint::getFlags ( u_int8_t &  flags)
virtual

get the latest driver state flags from the joint

Parameters
flagsif succesfull, populated with the latest flags
Returns
err_type_t

◆ getFlags() [2/2]

err_type_t bioscara_hardware_drivers::BaseJoint::getFlags ( void  )
virtual

◆ getPosition()

virtual err_type_t bioscara_hardware_drivers::BaseJoint::getPosition ( float &  pos)
pure virtual

get the current joint position in radians or m for cylindrical and prismatic joints respectively.

Warning
If the joint is not homed this method does not return an error. Instead pos will be 0.0.
Parameters
posthe current joint position in rad or m.
Returns
err_type_t

Implemented in bioscara_hardware_drivers::Joint, and bioscara_hardware_drivers::MockJoint.

◆ getVelocity()

virtual err_type_t bioscara_hardware_drivers::BaseJoint::getVelocity ( float &  vel)
pure virtual

get the current joint velocity in radians/s or m/s for cylindrical and prismatic joints respectively.

Parameters
velthe current joint velocity in rad/s or m/s.
Returns
err_type_t

Implemented in bioscara_hardware_drivers::Joint, and bioscara_hardware_drivers::MockJoint.

◆ home()

err_type_t bioscara_hardware_drivers::BaseJoint::home ( float  velocity,
u_int8_t  sensitivity,
u_int8_t  current 
)
virtual

Blocking implementation to home the joint.

Homing the joint is neccessary after its controller has been powered off. The joint can be moved while the encoders are inactive and hence the position at startup is unknow. See _home() for information on implementation and description of the paramters.

This is a blocking implementation which only returns after the the joint is no longer busy. First startHoming() is called, and subsequently waits with wait_while_busy() to finish homing. Lastly postHoming() is called.

Returns
err_type_t

◆ init()

err_type_t bioscara_hardware_drivers::BaseJoint::init ( void  )
virtual

Initialize the joint communication.

Returns
err_type_t

Reimplemented in bioscara_hardware_drivers::Joint.

◆ isBusy()

bool bioscara_hardware_drivers::BaseJoint::isBusy ( void  )
virtual

Checks if the joint controller is busy processing a blocking command.

Reads the internal state flags from the last transmission. If an update is neccessary call getFlags() before invoking this function.

Returns
true if a blocking command is currently executing, false if not.

◆ isEnabled()

bool bioscara_hardware_drivers::BaseJoint::isEnabled ( void  )
virtual

Checks the state if the motor is enabled.

Reads the internal state flags from the last transmission. If an update is neccessary call getFlags() before invoking this function. If the motor actually can move depends on the state of the STALLED flag which can be checked using Joint::isStalled().

Returns
true if the motor is enabled, false if not.

◆ isHomed()

bool bioscara_hardware_drivers::BaseJoint::isHomed ( void  )
virtual

Checks the state if the motor is homed.

Reads the internal state flags from the last transmission. If an update is neccessary call getFlags() before invoking this function.

Returns
true if the motor is homed, false if not.

Reimplemented in bioscara_hardware_drivers::MockJoint.

◆ isStalled()

bool bioscara_hardware_drivers::BaseJoint::isStalled ( void  )
virtual

Checks if the motor is stalled.

Reads the internal state flags from the last transmission. If an update is neccessary call getFlags() before invoking this function.

Returns
true if the motor is stalled, false if not.

◆ moveSteps()

err_type_t bioscara_hardware_drivers::BaseJoint::moveSteps ( int32_t  steps)
virtual

Move full steps.

This function can be called even when not homed.

Parameters
stepsnumber of full steps
Returns
err_type_t

Reimplemented in bioscara_hardware_drivers::Joint.

◆ postHoming()

err_type_t bioscara_hardware_drivers::BaseJoint::postHoming ( void  )
virtual

perform tasks after a non-blocking homing

This method resets the current_b_cmd to stp_reg_t::NONE, checks if the joint is homed, and saves the homing offset to the joint.

Returns
err_type_t

Reimplemented in bioscara_hardware_drivers::Joint.

◆ setBrakeMode()

err_type_t bioscara_hardware_drivers::BaseJoint::setBrakeMode ( u_int8_t  mode)
virtual

Set Brake Mode.

Parameters
modeFreewheel: 0, Coolbrake: 1, Hardbrake: 2
Returns
err_type_t

Reimplemented in bioscara_hardware_drivers::Joint.

◆ setDriveCurrent()

err_type_t bioscara_hardware_drivers::BaseJoint::setDriveCurrent ( u_int8_t  current)
virtual

Set the Drive Current.

Parameters
current0% - 100% of driver current
Returns
err_type_t

Reimplemented in bioscara_hardware_drivers::Joint.

◆ setHoldCurrent()

err_type_t bioscara_hardware_drivers::BaseJoint::setHoldCurrent ( u_int8_t  current)
virtual

Set the Hold Current.

Parameters
current0% - 100% of driver current
Returns
err_type_t -1 on communication error,

Reimplemented in bioscara_hardware_drivers::Joint.

◆ setMaxAcceleration()

err_type_t bioscara_hardware_drivers::BaseJoint::setMaxAcceleration ( float  maxAccel)
virtual

Set the maximum permitted joint acceleration (and deceleration) in rad/s^2 or m/s^2 for cylindrical and prismatic joints respectively.

Parameters
maxAccelmaximum joint acceleration.
Returns
err_type_t

Reimplemented in bioscara_hardware_drivers::Joint.

◆ setMaxVelocity()

err_type_t bioscara_hardware_drivers::BaseJoint::setMaxVelocity ( float  maxVel)
virtual

Set the maximum permitted joint velocity in rad/s or m/s for cylindrical and prismatic joints respectively.

Parameters
maxVelmaximum joint velocity.
Returns
err_type_t

Reimplemented in bioscara_hardware_drivers::Joint.

◆ setPosition()

err_type_t bioscara_hardware_drivers::BaseJoint::setPosition ( float  pos)
virtual

get the current joint position in radians or m for cylindrical and prismatic joints respectively.

Parameters
posthe commanded joint position in rad or m.
Returns
err_type_t

Reimplemented in bioscara_hardware_drivers::Joint, and bioscara_hardware_drivers::MockJoint.

◆ setVelocity()

err_type_t bioscara_hardware_drivers::BaseJoint::setVelocity ( float  vel)
virtual

Set the current joint velocity in radians/s or m/s for cylindrical and prismatic joints respectively.

Parameters
velthe commanded joint velocity in rad/s or m/s.
Returns
err_type_t

Reimplemented in bioscara_hardware_drivers::Joint, and bioscara_hardware_drivers::MockJoint.

◆ startHoming()

err_type_t bioscara_hardware_drivers::BaseJoint::startHoming ( float  velocity,
u_int8_t  sensitivity,
u_int8_t  current 
)
virtual

non-blocking implementation to home the joint

Homing the joint is neccessary after its controller has been powered off. The joint can be moved while the encoders are inactive and hence the position at startup is unknow. See _home() for information on implementation and description of the paramters.

This method returns immediatly after starting the homing sequence and should be used when the blocking implementation is not acceptable, for example in a realtime loop.

This method sets the current_b_cmd flag to stp_reg_t::HOME

Returns
err_type_t

◆ stop()

err_type_t bioscara_hardware_drivers::BaseJoint::stop ( void  )
virtual

Stops the motor.

Stops the motor by setting the maximum velocity to zero and the position setpoint to the current position

Returns
err_type_t

Reimplemented in bioscara_hardware_drivers::Joint, and bioscara_hardware_drivers::MockJoint.

◆ wait_while_busy()

void bioscara_hardware_drivers::BaseJoint::wait_while_busy ( const float  period_ms)
protectedvirtual

Blocking loop waiting for BUSY flag to reset.

Parameters
period_mstime in ms between polls.

Member Data Documentation

◆ current_b_cmd

stp_reg_t bioscara_hardware_drivers::BaseJoint::current_b_cmd = NONE
protected

Keeps track if a blocking command is being executed.

◆ flags

u_int8_t bioscara_hardware_drivers::BaseJoint::flags = 0b00001100
protected

State flags transmitted with every I2C transaction.

The transmission flags purpose are to transmit the joints current state. Note: They can not be used as error indication of the execution of a transmitted write command, since commands are executed after the I2C transaction is completed. The status flags are one byte with following structure:

BIT7 BIT6 BIT5 BIT4 BIT3 BIT2 BIT1 BIT0
reserved reserved reserved reserved NOTENABLED NOTHOMED BUSY STALL

STALL is set if a stall from the stall detection is sensed and the joint is stopped. The flag is cleared when the joint is homed or the Stallguard enabled.
BUSY is set if the slave is busy processing a previous command.
NOTHOMED is cleared if the joint is homed. Movement is only allowed if this flag is clear
NOTENABLED is cleared if the joint is enabled after calling enable()

◆ name

std::string bioscara_hardware_drivers::BaseJoint::name

Joint name for logging.


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