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

Representing a single hardware joint connected via I2C. More...

#include <mJoint.h>

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

Public Member Functions

 Joint (const std::string name, const int address, const float reduction, const float min, const float max)
 Create a Joint object.
 
 ~Joint (void)
 Destroy the Joint object.
 
err_type_t init (void) override
 Initialize connection to a joint via I2C.
 
err_type_t deinit (void) override
 Disconnects from a joint.
 
err_type_t enable (u_int8_t driveCurrent, u_int8_t holdCurrent) override
 Engages the joint.
 
err_type_t postHoming (void) override
 perform tasks after a non-blocking homing
 
err_type_t getPosition (float &pos) override
 get the current joint position in radians or m for cylindrical and prismatic joints respectively.
 
err_type_t setPosition (float pos) override
 get the current joint position in radians or m for cylindrical and prismatic joints respectively.
 
err_type_t moveSteps (int32_t steps) override
 Move full steps.
 
err_type_t getVelocity (float &vel) override
 get the current joint velocity in radians/s or m/s for cylindrical and prismatic joints respectively.
 
err_type_t setVelocity (float vel) override
 Set the current joint velocity in radians/s or m/s for cylindrical and prismatic joints respectively.
 
err_type_t checkOrientation (float angle=2.0) override
 Calls the checkOrientation method of the motor. Checks in which direction the motor is turning.
 
err_type_t stop (void) override
 Stops the motor.
 
err_type_t disableCL (void) override
 
err_type_t setDriveCurrent (u_int8_t current) override
 Set the Drive Current.
 
err_type_t setHoldCurrent (u_int8_t current) override
 Set the Hold Current.
 
err_type_t setBrakeMode (u_int8_t mode) override
 Set Brake Mode.
 
err_type_t setMaxAcceleration (float maxAccel) override
 Set the maximum permitted joint acceleration (and deceleration) in rad/s^2 or m/s^2 for cylindrical and prismatic joints respectively.
 
err_type_t setMaxVelocity (float maxVel) override
 Set the maximum permitted joint velocity in rad/s or m/s for cylindrical and prismatic joints respectively.
 
err_type_t enableStallguard (u_int8_t sensitivity) override
 Enable encoder stall detection of the joint.
 
err_type_t getFlags (void) override
 Overload of getFlags(u_int8_t &flags)
 
- Public Member Functions inherited from bioscara_hardware_drivers::BaseJoint
 BaseJoint (const std::string name)
 Create a Joint object.
 
 ~BaseJoint (void)
 Destroy the BaseJoint object.
 
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 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 stp_reg_t getCurrentBCmd (void)
 get the currently active blocking command
 

Protected Member Functions

err_type_t getHomingOffset (float &offset)
 Retrieves the homing position from the last homing.
 
err_type_t setHomingOffset (const float offset)
 Stores the homing position on the joint.
 
err_type_t _home (float velocity, u_int8_t sensitivity, u_int8_t current) override
 Call to start the homing sequence of a joint.
 
err_type_t checkCom (void)
 Check if communication to the joint is established.
 
- Protected Member Functions inherited from bioscara_hardware_drivers::BaseJoint
virtual void wait_while_busy (const float period_ms)
 Blocking loop waiting for BUSY flag to reset.
 

Protected Attributes

float reduction = 1
 Joint to actuator reduction ratio.
 
float offset = 0
 Joint position offset.
 
float min = 0
 Joint lower limit.
 
float max = 0
 Joint upper limit.
 
- Protected Attributes inherited from bioscara_hardware_drivers::BaseJoint
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.
 

Private Member Functions

template<typename T >
int read (const stp_reg_t reg, T &data, u_int8_t &flags)
 Wrapper function to request data from the I2C slave.
 
template<typename T >
int write (const stp_reg_t reg, T data, u_int8_t &flags)
 Wrapper function to send command to the I2C slave.
 

Private Attributes

int address
 I2C adress.
 
int handle = -1
 I2C bus handle.
 

Additional Inherited Members

- Public Types inherited from bioscara_hardware_drivers::BaseJoint
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 Attributes inherited from bioscara_hardware_drivers::BaseJoint
std::string name
 Joint name for logging.
 

Detailed Description

Representing a single hardware joint connected via I2C.

Constructor & Destructor Documentation

◆ Joint()

bioscara_hardware_drivers::Joint::Joint ( const std::string  name,
const int  address,
const float  reduction,
const float  min,
const float  max 
)

Create a Joint object.

The Joint object represents a single joint and its actuator. Each Joint has a transmission with the following relationship:

‍actuator position = (joint position - offset) * reduction
joint position = actuator position / reduction + offset

Parameters
namestring device name for identification
address1-byte I2C device adress (0x11 ... 0x14) for J1 ... J4
reductiongear reduction of the joint. This is used to transform position and velocity values between in joint units and actuator (stepper) units. The sign depends on the direction the motor is mounted and is turning. Adjust such that the joint moves in the positive direction on on positive joint commands. Cable polarity has no effect since the motors automatically adjust to always run in the 'right' direction from their point of view.
J1: 35
J2: -2*pi/0.004 (4 mm linear movement per stepper revolution)
J3: 24
J4: 12
minlower joint limit in joint units.
J1: -3.04647
J2: -0.0016
J3: -2.62672
J4: -3.01069
maxupper joint limit in joint units.
J1: 3.04647
J2: 0.3380
J3: 2.62672
J4: 3.01069

◆ ~Joint()

bioscara_hardware_drivers::Joint::~Joint ( void  )

Destroy the Joint object.

Create a Joint object.

Member Function Documentation

◆ _home()

err_type_t bioscara_hardware_drivers::Joint::_home ( float  velocity,
u_int8_t  sensitivity,
u_int8_t  current 
)
overrideprotectedvirtual

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

Implements bioscara_hardware_drivers::BaseJoint.

◆ checkCom()

err_type_t bioscara_hardware_drivers::Joint::checkCom ( void  )
protected

Check if communication to the joint is established.

Sends a PING to and expects a ACK from the joint.

Returns
err_type_t

◆ checkOrientation()

err_type_t bioscara_hardware_drivers::Joint::checkOrientation ( float  angle = 2.0)
overridevirtual

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 from bioscara_hardware_drivers::BaseJoint.

◆ deinit()

err_type_t bioscara_hardware_drivers::Joint::deinit ( void  )
overridevirtual

Disconnects from a joint.

Removes the joint from the I2C bus by invoking closeI2CDevHandle().

Returns
err_type_t

Reimplemented from bioscara_hardware_drivers::BaseJoint.

◆ disableCL()

err_type_t bioscara_hardware_drivers::Joint::disableCL ( void  )
overridevirtual

◆ enable()

err_type_t bioscara_hardware_drivers::Joint::enable ( u_int8_t  driveCurrent,
u_int8_t  holdCurrent 
)
overridevirtual

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 from bioscara_hardware_drivers::BaseJoint.

◆ enableStallguard()

err_type_t bioscara_hardware_drivers::Joint::enableStallguard ( u_int8_t  sensitivity)
overridevirtual

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 from bioscara_hardware_drivers::BaseJoint.

◆ getFlags()

err_type_t bioscara_hardware_drivers::Joint::getFlags ( void  )
overridevirtual

Overload of getFlags(u_int8_t &flags)

Returns
err_type_t

Reimplemented from bioscara_hardware_drivers::BaseJoint.

◆ getHomingOffset()

err_type_t bioscara_hardware_drivers::Joint::getHomingOffset ( float &  offset)
protected

Retrieves the homing position from the last homing.

The homing position is stored on the joint to make it persistent as long as the joint is powered up.

Returns
err_type_t

◆ getPosition()

err_type_t bioscara_hardware_drivers::Joint::getPosition ( float &  pos)
overridevirtual

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

Implements bioscara_hardware_drivers::BaseJoint.

◆ getVelocity()

err_type_t bioscara_hardware_drivers::Joint::getVelocity ( float &  vel)
overridevirtual

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

Implements bioscara_hardware_drivers::BaseJoint.

◆ init()

err_type_t bioscara_hardware_drivers::Joint::init ( void  )
overridevirtual

Initialize connection to a joint via I2C.

Adds the joint to the I2C bus and tests if is responsive by invoking checkCom(). If the joint is homed, retrieve the homing position stored on the joint by invoking getHomingOffset().

Returns
err_type_t

Reimplemented from bioscara_hardware_drivers::BaseJoint.

◆ moveSteps()

err_type_t bioscara_hardware_drivers::Joint::moveSteps ( int32_t  steps)
overridevirtual

Move full steps.

This function can be called even when not homed.

Parameters
stepsnumber of full steps
Returns
err_type_t

Reimplemented from bioscara_hardware_drivers::BaseJoint.

◆ postHoming()

err_type_t bioscara_hardware_drivers::Joint::postHoming ( void  )
overridevirtual

perform tasks after a non-blocking homing

Invokes BaseJoint::postHoming() and additionally saves the homing offset to the joint controller setHomingOffset()

Returns
err_type_t

Reimplemented from bioscara_hardware_drivers::BaseJoint.

◆ read()

template<typename T >
int bioscara_hardware_drivers::Joint::read ( const stp_reg_t  reg,
T &  data,
u_int8_t &  flags 
)
private

Wrapper function to request data from the I2C slave.

Allocates a buffer of size sizeof(T) + RFLAGS_SIZE. Invokes readFromI2CDev(), and copies the received payload to data and the transmisison flags to flags. See BaseJoint::flags for details.

Template Parameters
TDatatype of value to be transmitted
Parameters
regstp_reg_t register to read
datareference to store payload.
flagsreference to a byte which stores the return flags
Returns
0 on OK, negative on error

◆ setBrakeMode()

err_type_t bioscara_hardware_drivers::Joint::setBrakeMode ( u_int8_t  mode)
overridevirtual

Set Brake Mode.

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

Reimplemented from bioscara_hardware_drivers::BaseJoint.

◆ setDriveCurrent()

err_type_t bioscara_hardware_drivers::Joint::setDriveCurrent ( u_int8_t  current)
overridevirtual

Set the Drive Current.

Parameters
current0% - 100% of driver current
Returns
err_type_t

Reimplemented from bioscara_hardware_drivers::BaseJoint.

◆ setHoldCurrent()

err_type_t bioscara_hardware_drivers::Joint::setHoldCurrent ( u_int8_t  current)
overridevirtual

Set the Hold Current.

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

Reimplemented from bioscara_hardware_drivers::BaseJoint.

◆ setHomingOffset()

err_type_t bioscara_hardware_drivers::Joint::setHomingOffset ( const float  offset)
protected

Stores the homing position on the joint.

The homing position is stored on the joint to make it persistent as long as the joint is powered up.

Returns
err_type_t

◆ setMaxAcceleration()

err_type_t bioscara_hardware_drivers::Joint::setMaxAcceleration ( float  maxAccel)
overridevirtual

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 from bioscara_hardware_drivers::BaseJoint.

◆ setMaxVelocity()

err_type_t bioscara_hardware_drivers::Joint::setMaxVelocity ( float  maxVel)
overridevirtual

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 from bioscara_hardware_drivers::BaseJoint.

◆ setPosition()

err_type_t bioscara_hardware_drivers::Joint::setPosition ( float  pos)
overridevirtual

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 from bioscara_hardware_drivers::BaseJoint.

◆ setVelocity()

err_type_t bioscara_hardware_drivers::Joint::setVelocity ( float  vel)
overridevirtual

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 from bioscara_hardware_drivers::BaseJoint.

◆ stop()

err_type_t bioscara_hardware_drivers::Joint::stop ( void  )
overridevirtual

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 from bioscara_hardware_drivers::BaseJoint.

◆ write()

template<typename T >
int bioscara_hardware_drivers::Joint::write ( const stp_reg_t  reg,
data,
u_int8_t &  flags 
)
private

Wrapper function to send command to the I2C slave.

Allocates a buffer of size sizeof(T) + RFLAGS_SIZE. Copyies data to the buffer and invokes writeToI2CDev(). The flags received from the transaction are copied to flags. The flags are described in Joint::read().

Template Parameters
TDatatype of value to be transmitted
Parameters
regstp_reg_t command to execute
datapayload to transmit. It is the users responsibility to populate the right amount of data for the relevant register
flagsreference to a byte which stores the return flags
Returns
0 on OK, negative on error

Member Data Documentation

◆ address

int bioscara_hardware_drivers::Joint::address
private

I2C adress.

◆ handle

int bioscara_hardware_drivers::Joint::handle = -1
private

I2C bus handle.

◆ max

float bioscara_hardware_drivers::Joint::max = 0
protected

Joint upper limit.

◆ min

float bioscara_hardware_drivers::Joint::min = 0
protected

Joint lower limit.

◆ offset

float bioscara_hardware_drivers::Joint::offset = 0
protected

Joint position offset.

◆ reduction

float bioscara_hardware_drivers::Joint::reduction = 1
protected

Joint to actuator reduction ratio.


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