![]() |
Bioscara
DALSA's DIY SCARA Robot Arm.
|
Generic base class to control a single joint. More...
#include <mBaseJoint.h>
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. | |
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.
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.
| bioscara_hardware_drivers::BaseJoint::BaseJoint | ( | const std::string | name | ) |
| bioscara_hardware_drivers::BaseJoint::~BaseJoint | ( | void | ) |
|
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.
| velocity | signed velocity in rad/s or m/s. Must be between 1.0 < RAD2DEG(JOINT2ACTUATOR(velocity, reduction, 0)) / 6 < 250.0 |
| sensitivity | Encoder pid error threshold 0 to 255. |
| current | homing current, determines how easy it is to stop the motor and thereby provoke a stall |
Implemented in bioscara_hardware_drivers::MockJoint, and bioscara_hardware_drivers::Joint.
|
virtual |
Calls the checkOrientation method of the motor. Checks in which direction the motor is turning.
| angle | degrees how much the motor should turn. A few degrees is sufficient. |
Reimplemented in bioscara_hardware_drivers::Joint, and bioscara_hardware_drivers::MockJoint.
|
virtual |
Denitialize the joint communication.
Reimplemented in bioscara_hardware_drivers::Joint.
|
virtual |
disenganges the joint
invokes stop(), sets hold and drive current to 0 and sets the the joint brake mode to freewheeling
Reimplemented in bioscara_hardware_drivers::MockJoint.
|
virtual |
Reimplemented in bioscara_hardware_drivers::Joint.
|
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)
| driveCurrent | drive current in 0-100 % of 2.5A output (check uStepper doc.) |
| holdCurrent | hold current in 0-100 % of 2.5A output (check uStepper doc.) |
Reimplemented in bioscara_hardware_drivers::Joint, and bioscara_hardware_drivers::MockJoint.
|
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().
| sensitivity | value of threshold. 0 - 255 where lower is more sensitive. |
Reimplemented in bioscara_hardware_drivers::Joint.
|
virtual |
get the currently active blocking command
|
virtual |
|
virtual |
Overload of getFlags(u_int8_t &flags)
Reimplemented in bioscara_hardware_drivers::Joint, and bioscara_hardware_drivers::MockJoint.
|
pure virtual |
get the current joint position in radians or m for cylindrical and prismatic joints respectively.
pos will be 0.0.| pos | the current joint position in rad or m. |
Implemented in bioscara_hardware_drivers::Joint, and bioscara_hardware_drivers::MockJoint.
|
pure virtual |
get the current joint velocity in radians/s or m/s for cylindrical and prismatic joints respectively.
| vel | the current joint velocity in rad/s or m/s. |
Implemented in bioscara_hardware_drivers::Joint, and bioscara_hardware_drivers::MockJoint.
|
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.
|
virtual |
Initialize the joint communication.
Reimplemented in bioscara_hardware_drivers::Joint.
|
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.
|
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().
|
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.
Reimplemented in bioscara_hardware_drivers::MockJoint.
|
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.
|
virtual |
Move full steps.
This function can be called even when not homed.
| steps | number of full steps |
Reimplemented in bioscara_hardware_drivers::Joint.
|
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.
Reimplemented in bioscara_hardware_drivers::Joint.
|
virtual |
Set Brake Mode.
| mode | Freewheel: 0, Coolbrake: 1, Hardbrake: 2 |
Reimplemented in bioscara_hardware_drivers::Joint.
|
virtual |
Set the Drive Current.
| current | 0% - 100% of driver current |
Reimplemented in bioscara_hardware_drivers::Joint.
|
virtual |
Set the Hold Current.
| current | 0% - 100% of driver current |
Reimplemented in bioscara_hardware_drivers::Joint.
|
virtual |
Set the maximum permitted joint acceleration (and deceleration) in rad/s^2 or m/s^2 for cylindrical and prismatic joints respectively.
| maxAccel | maximum joint acceleration. |
Reimplemented in bioscara_hardware_drivers::Joint.
|
virtual |
Set the maximum permitted joint velocity in rad/s or m/s for cylindrical and prismatic joints respectively.
| maxVel | maximum joint velocity. |
Reimplemented in bioscara_hardware_drivers::Joint.
|
virtual |
get the current joint position in radians or m for cylindrical and prismatic joints respectively.
| pos | the commanded joint position in rad or m. |
Reimplemented in bioscara_hardware_drivers::Joint, and bioscara_hardware_drivers::MockJoint.
|
virtual |
Set the current joint velocity in radians/s or m/s for cylindrical and prismatic joints respectively.
| vel | the commanded joint velocity in rad/s or m/s. |
Reimplemented in bioscara_hardware_drivers::Joint, and bioscara_hardware_drivers::MockJoint.
|
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
|
virtual |
Stops the motor.
Stops the motor by setting the maximum velocity to zero and the position setpoint to the current position
Reimplemented in bioscara_hardware_drivers::Joint, and bioscara_hardware_drivers::MockJoint.
|
protectedvirtual |
Blocking loop waiting for BUSY flag to reset.
| period_ms | time in ms between polls. |
Keeps track if a blocking command is being executed.
|
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()
| std::string bioscara_hardware_drivers::BaseJoint::name |
Joint name for logging.