#include <3mxl.h>

Public Member Functions | |
| C3mxl () | |
| virtual int | changeID (const int newID) |
| Change hardware motor ID. | |
| virtual int | get3MxlMode () |
| Read behavioral mode of the 3mxl. | |
| virtual int | getAcceleration () |
| Read acceleration from hardware. | |
| virtual int | getBusVoltage () |
| Read bus voltage from hardware. | |
| virtual int | getCurrent () |
| Read current from hardware. | |
| int | getID () |
| Get motor ID. | |
| virtual int | getLinearAcceleration () |
| Read linear acceleration from hardware. | |
| virtual int | getLinearPos () |
| Read linear position from hardware. | |
| virtual int | getLog () |
| Read logfile from hardware. | |
| virtual int | getPIDCurrent (double &p, double &d, double &i, double &i_limit) |
| Get PID gains for current control mode. | |
| virtual int | getPIDEnergy (double &p, double &d, double &i, double &i_limit) |
| Get PID gains for energy control mode. | |
| virtual int | getPIDPosition (double &p, double &d, double &i, double &i_limit) |
| Get PID gains for position control mode. | |
| virtual int | getPIDSpeed (double &p, double &d, double &i, double &i_limit) |
| Get PID gains for speed control mode. | |
| virtual int | getPIDTorque (double &p, double &d, double &i, double &i_limit) |
| Get PID gains for torque control mode. | |
| virtual int | getPos () |
| Read position from hardware. | |
| virtual int | getPosAndSpeed () |
| Read position and speed from hardware. | |
| virtual int | getSensorVoltages () |
| Read analog sensor voltages from hardware. | |
| virtual int | getState () |
| Read entire state from hardware. | |
| virtual int | getStatus () |
| Read status from hardware. | |
| virtual int | getTorque () |
| Read torque from hardware. | |
| virtual int | getTorquePosSpeed () |
| Read torque, position and speed from hardware. | |
| virtual int | getVoltage () |
| Read motor voltage from hardware. | |
| virtual int | init (bool sendConfigToMotor=true) |
| Initialize this Dynamixel. | |
| int | interpretControlData (BYTE address, BYTE length, BYTE *data) |
| Interpret data read from control table. | |
| virtual BYTE | present3MxlMode () |
| Get behavioral mode of the 3mxl. | |
| virtual double | presentAcceleration () |
| Get cached acceleration. | |
| virtual double | presentAnalog1Voltage () |
| Get cached analog sensor 1 voltage. | |
| virtual double | presentAnalog2Voltage () |
| Get cached analog sensor 2 voltage. | |
| virtual double | presentAnalog3Voltage () |
| Get cached analog sensor 3 voltage. | |
| virtual double | presentAnalog4Voltage () |
| Get cached analog sensor 4 voltage. | |
| double | presentAngleLowerLimit () |
| Get cached lower angle limit. | |
| double | presentAngleUpperLimit () |
| Get cached upper angle limit. | |
| virtual double | presentBusVoltage () |
| Get cached bus voltage. | |
| WORD | presentCCWAngleLimit () |
| Get cached counter-clockwise angle limit. | |
| virtual double | presentCurrent () |
| Get cached current. | |
| virtual double | presentCurrentADCVoltage () |
| Get cached motor current ADC voltage. | |
| WORD | presentCWAngleLimit () |
| Get cached clockwise angle limit. | |
| virtual double | presentLinearAcceleration () |
| Get cached linear acceleration. | |
| virtual double | presentLinearPos () |
| Get cached linear position. | |
| virtual double | presentLoad () |
| Get cached load value. | |
| virtual TMxlLog | presentLog () |
| Get cached log string/file. | |
| virtual bool | presentMotorInitState () |
| Get motor initialization state. | |
| virtual double | presentPos () |
| Get cached position. | |
| virtual double | presentSpeed () |
| Get cached speed. | |
| virtual int | presentStatus () |
| Get cached status. | |
| virtual double | presentTemp () |
| Get cached temperature. | |
| virtual double | presentTorque () |
| Get cached torque. | |
| virtual double | presentVoltage () |
| Get cached motor voltage. | |
| int | printReport (FILE *fOut) |
| Report on this Dynamixel. | |
| virtual int | set3MxlMode (BYTE mxlMode, bool shouldSyncWrite=false) |
| Set behaviour of the 3mxl. | |
| virtual int | setAcceleration (double acceleration, bool shouldSyncWrite=false) |
| Set acceleration for trajectory generation. | |
| virtual int | setAngleLimits (double lowerLimit, double upperLimit) |
| Set angle limits. | |
| virtual int | setAngleLowerLimit (double limit) |
| Set lower angle limit. | |
| virtual int | setAngleUpperLimit (double limit) |
| Set upper angle limit. | |
| virtual int | setBaudRate (const int baudRate) |
| Set baud rate in bits/s. | |
| virtual void | setConfig (CDxlConfig *config) |
| Set motor configuration. | |
| virtual int | setCurrent (double current, bool shouldSyncWrite=false) |
| Set reference current. | |
| virtual int | setEncoderCountJoint (WORD encodercount) |
| Joint encoder counts per revolution. | |
| virtual int | setEncoderCountMotor (WORD encodercount) |
| Motor encoder counts per revolution. | |
| virtual int | setEncoderIndexLevelMotor (BYTE level) |
| Set motor encoder index pulse signal level. | |
| virtual int | setGearboxRatioJoint (float gearboxratio) |
| Ratio between joint and joint encoder. | |
| virtual int | setGearboxRatioMotor (float gearboxratio) |
| Ratio between motor and joint. | |
| virtual int | setInitialTorqueLimit (double absMaxTorque) |
| Set initial torque limit (EEPROM). | |
| virtual int | setJointOffset (double offset) |
| Set joint null angle offset. | |
| virtual int | setLinearAcceleration (double acceleration, bool shouldSyncWrite=false) |
| Set linear acceleration for trajectory generation. | |
| virtual int | setLinearPos (double pos, bool shouldSyncWrite=false) |
| Set linear reference position. | |
| virtual int | setLinearPos (double pos, double absSpeed, bool shouldSyncWrite=false) |
| Set linear reference position and velocity. | |
| virtual int | setLinearPos (double pos, double absSpeed, double acceleration, bool shouldSyncWrite=false) |
| Set linear reference position, velocity and acceleration. | |
| virtual int | setLinearSpeed (double speed, bool shouldSyncWrite=false) |
| Set linear reference speed. | |
| virtual int | setLogInterval (BYTE interval) |
| Set logging interval. | |
| virtual int | setMaxContinuousMotorCurrent (double current) |
| Set maximum motor continuous current. | |
| virtual int | setMaxPeakMotorCurrent (double current) |
| Set maximum motor peak current. | |
| virtual int | setMotorConstant (WORD motorconstant) |
| Set motor constant. | |
| virtual int | setMotorOffset (double offset) |
| Set motor null angle offset. | |
| virtual int | setMotorWindingTimeConstant (double time) |
| Set motor winding time constant. | |
| virtual int | setPIDCurrent (double p, double d, double i, double i_limit, bool shouldSyncWrite=false) |
| Set PID for current control mode. | |
| virtual int | setPIDEnergy (double p, double d, double i, double i_limit, bool shouldSyncWrite=false) |
| Set PID for energy control mode. | |
| virtual int | setPIDPosition (double p, double d, double i, double i_limit, bool shouldSyncWrite=false) |
| Set PID for position control mode. | |
| virtual int | setPIDSpeed (double p, double d, double i, double i_limit, bool shouldSyncWrite=false) |
| Set PID for speed control mode. | |
| virtual int | setPIDTorque (double p, double d, double i, double i_limit, bool shouldSyncWrite=false) |
| Set PID for torque control mode. | |
| virtual int | setPos (double pos, bool shouldSyncWrite=false) |
| Set reference position. | |
| virtual int | setPos (double pos, double absSpeed, bool shouldSyncWrite=false) |
| Set reference position and velocity. | |
| virtual int | setPos (double pos, double absSpeed, double acceleration, bool shouldSyncWrite=false) |
| Set reference position, velocity and acceleration. | |
| virtual void | setPositiveDirection (bool clockwiseIsPositive) |
| Set direction convention. | |
| virtual int | setPositiveDirectionJoint (bool clockwiseIsPositive) |
| Set joint direction convention. | |
| virtual int | setPositiveDirectionMotor (bool clockwiseIsPositive) |
| Set motor direction convention. | |
| virtual int | setPosSpeedTorquePPosDPos (double pos, double speed, double torque, int pPos, int dPos, bool shouldSyncWrite=false) |
| Set many references simultaneously. | |
| virtual int | setPWM (double pwm, bool shouldSyncWrite=false) |
| Set pulse width modulation duty cycle. | |
| virtual int | setReferenceEnergy (double energy) |
| Set reference energy for energy control. | |
| virtual int | setRetlevel (const int returnlevel) |
| Set status return level. | |
| virtual int | setReturnDelayTime (const int microsecondsReturnDelay) |
| Set return delay. | |
| virtual void | setSerialPort (LxSerial *serialPort) |
| Set serial port. | |
| virtual int | setSineAmplitude (double amplitude, bool shouldSyncWrite=false) |
| Set sine amplitude. | |
| virtual int | setSineFrequency (double frequency, bool shouldSyncWrite=false) |
| Set sine frequency. | |
| virtual int | setSinePhase (double phase, bool shouldSyncWrite=false) |
| Set sine phase angle. | |
| virtual int | setSpeed (double speed, bool shouldSyncWrite=false) |
| Set reference speed. | |
| virtual int | setSpringStiffness (double stiffness) |
| Set spring stiffness for series elastic actuation. | |
| virtual int | setSyncReadIndex (BYTE index) |
| Set index in sync read chain. | |
| virtual int | setTorque (double torque, bool shouldSyncWrite=false) |
| Set reference torque. | |
| virtual int | setTorqueLimit (double absMaxTorque) |
| Set operational torque limit (RAM). | |
| virtual int | setWatchdogMode (BYTE watchdogmode) |
| What to do if watchdog triggers. | |
| virtual int | setWatchdogMultiplier (BYTE watchdogmultiplier) |
| Set watchdog interval (multiplier) | |
| virtual int | setWatchdogTime (BYTE watchdogtime) |
| Set watchdog interval (time) | |
| virtual int | setWheelDiameter (double diameter) |
| Set wheel diameter. | |
| virtual int | setZeroLengthSpring (double parameterInRad) |
| Set zero length of the spring for series elastic actuation. | |
| virtual | ~C3mxl () |
Static Public Member Functions | |
| static const char * | translateErrorCode (int errorCode) |
Protected Member Functions | |
| int | clip (const int value, const int min, const int max) |
| int | clipToMaxDWord (int value) |
| int | clipToMaxWord (int value) |
| WORD | internalAccelerationToMxlAcceleration (double acceleration) |
| WORD | internalAmplitudeToMxlAmplitude (double amplitude) |
| WORD | internalCurrentToMxlCurrent (double current) |
| WORD | internalFreqToMxlFreq (double frequency) |
| WORD | internalLinearAccelerationToMxlLinearAcceleration (double acceleration) |
| DWORD | internalLinearPosToMxlLinearPos (double pos) |
| WORD | internalLinearSpeedToMxlLinearSpeed (double speed) |
| WORD | internalPhaseToMxlPhase (double phase) |
| WORD | internalPosToMxlPos (double pos) |
| WORD | internalPWMToMxlPWM (double current) |
| WORD | internalSpeedToMxlSpeed (double speed) |
| WORD | internalTorqueToMxlTorque (double torque) |
| WORD | internalVoltageToMxlVoltage (double voltage) |
| double | mxlAccelerationToInternalAcceleration (WORD acceleration) |
| double | mxlCurrentToInternalCurrent (WORD current) |
| double | mxlLinearAccelerationToInternalLinearAcceleration (WORD acceleration) |
| double | mxlLinearPosToInternalLinearPos (DWORD pos) |
| double | mxlLinearSpeedToInternalLinearSpeed (WORD speed) |
| double | mxlPosToInternalPos (WORD pos) |
| double | mxlPWMToInternalPWM (WORD current) |
| double | mxlSpeedToInternalSpeed (WORD speed) |
| double | mxlTorqueToInternalTorque (WORD torque) |
| double | mxlVoltageToInternalVoltage (WORD voltage) |
| int | round (double val) |
Protected Attributes | |
| double | mAcceleration |
| double | mAnalog1Voltage |
| double | mAnalog2Voltage |
| double | mAnalog3Voltage |
| double | mAnalog4Voltage |
| double | mBusVoltage |
| CDxlConfig | mConfig |
| double | mCurrent |
| double | mCurrentADCVoltage |
| double | mLinearAcceleration |
| double | mLinearPosition |
| CLog2 | mLog |
| unsigned char | mMotorInitialized |
| TMxlLog | mMxlLog |
| BYTE | mMxlMode |
| double | mPosition |
| double | mSpeed |
| unsigned char | mStatus |
| double | mTorque |
| double | mVoltage |
This class interfaces a 3mxl all settings are directly given to the 3mxl if possible. Status information is cached in this object
| C3mxl::C3mxl | ( | ) |
| C3mxl::~C3mxl | ( | ) | [virtual] |
| int C3mxl::changeID | ( | const int | newID | ) | [virtual] |
Change hardware motor ID.
Actually sets the new ID in the hardware.
| newID | New ID. |
Reimplemented from CDxlGeneric.
| int C3mxl::clip | ( | const int | value, |
| const int | min, | ||
| const int | max | ||
| ) | [inline, protected] |
| int C3mxl::clipToMaxDWord | ( | int | value | ) | [protected] |
| int C3mxl::clipToMaxWord | ( | int | value | ) | [protected] |
| int C3mxl::get3MxlMode | ( | ) | [virtual] |
Read behavioral mode of the 3mxl.
Reimplemented from CDxlGeneric.
| int C3mxl::getAcceleration | ( | ) | [virtual] |
| int C3mxl::getBusVoltage | ( | ) | [virtual] |
| int C3mxl::getCurrent | ( | ) | [virtual] |
| int C3mxl::getID | ( | ) | [inline, virtual] |
Get motor ID.
Implements CDxlGeneric.
| int C3mxl::getLinearAcceleration | ( | ) | [virtual] |
Read linear acceleration from hardware.
Reimplemented from CDxlGeneric.
| int C3mxl::getLinearPos | ( | ) | [virtual] |
| int C3mxl::getLog | ( | ) | [virtual] |
Read logfile from hardware.
logfile from hardware to memory. Get a pointer to this array with presentLog().
Reimplemented from CDxlGeneric.
| int C3mxl::getPIDCurrent | ( | double & | p, |
| double & | d, | ||
| double & | i, | ||
| double & | i_limit | ||
| ) | [virtual] |
Get PID gains for current control mode.
| p | Proportional gain |
| d | Derivative gain |
| i | Integral gain |
| i_limit | Integration limit |
Reimplemented from CDxlGeneric.
| int C3mxl::getPIDEnergy | ( | double & | p, |
| double & | d, | ||
| double & | i, | ||
| double & | i_limit | ||
| ) | [virtual] |
Get PID gains for energy control mode.
| p | Proportional gain |
| d | Derivative gain |
| i | Integral gain |
| i_limit | Integration limit |
Reimplemented from CDxlGeneric.
| int C3mxl::getPIDPosition | ( | double & | p, |
| double & | d, | ||
| double & | i, | ||
| double & | i_limit | ||
| ) | [virtual] |
Get PID gains for position control mode.
| p | Proportional gain |
| d | Derivative gain |
| i | Integral gain |
| i_limit | Integration limit |
Reimplemented from CDxlGeneric.
| int C3mxl::getPIDSpeed | ( | double & | p, |
| double & | d, | ||
| double & | i, | ||
| double & | i_limit | ||
| ) | [virtual] |
Get PID gains for speed control mode.
| p | Proportional gain |
| d | Derivative gain |
| i | Integral gain |
| i_limit | Integration limit |
Reimplemented from CDxlGeneric.
| int C3mxl::getPIDTorque | ( | double & | p, |
| double & | d, | ||
| double & | i, | ||
| double & | i_limit | ||
| ) | [virtual] |
Get PID gains for torque control mode.
| p | Proportional gain |
| d | Derivative gain |
| i | Integral gain |
| i_limit | Integration limit |
Reimplemented from CDxlGeneric.
| int C3mxl::getPos | ( | ) | [virtual] |
| int C3mxl::getPosAndSpeed | ( | ) | [virtual] |
Read position and speed from hardware.
Reimplemented from CDxlGeneric.
| int C3mxl::getSensorVoltages | ( | ) | [virtual] |
Read analog sensor voltages from hardware.
Reimplemented from CDxlGeneric.
| int C3mxl::getState | ( | ) | [virtual] |
Read entire state from hardware.
Reimplemented from CDxlGeneric.
| int C3mxl::getStatus | ( | ) | [virtual] |
Read status from hardware.
Reimplemented from CDxlGeneric.
| int C3mxl::getTorque | ( | ) | [virtual] |
| int C3mxl::getTorquePosSpeed | ( | ) | [virtual] |
Read torque, position and speed from hardware.
Reimplemented from CDxlGeneric.
| int C3mxl::getVoltage | ( | ) | [virtual] |
| int C3mxl::init | ( | bool | sendConfigToMotor = true | ) | [virtual] |
Initialize this Dynamixel.
| sendConfigToMotor | Send configuration to motor |
Reimplemented from CDxlGeneric.
| WORD C3mxl::internalAccelerationToMxlAcceleration | ( | double | acceleration | ) | [protected] |
| WORD C3mxl::internalAmplitudeToMxlAmplitude | ( | double | amplitude | ) | [protected] |
| WORD C3mxl::internalCurrentToMxlCurrent | ( | double | current | ) | [protected] |
| WORD C3mxl::internalFreqToMxlFreq | ( | double | frequency | ) | [protected] |
| WORD C3mxl::internalLinearAccelerationToMxlLinearAcceleration | ( | double | acceleration | ) | [protected] |
| DWORD C3mxl::internalLinearPosToMxlLinearPos | ( | double | pos | ) | [protected] |
| WORD C3mxl::internalLinearSpeedToMxlLinearSpeed | ( | double | speed | ) | [protected] |
| WORD C3mxl::internalPhaseToMxlPhase | ( | double | phase | ) | [protected] |
| WORD C3mxl::internalPosToMxlPos | ( | double | pos | ) | [protected] |
| WORD C3mxl::internalPWMToMxlPWM | ( | double | current | ) | [protected] |
| WORD C3mxl::internalSpeedToMxlSpeed | ( | double | speed | ) | [protected] |
| WORD C3mxl::internalTorqueToMxlTorque | ( | double | torque | ) | [protected] |
| WORD C3mxl::internalVoltageToMxlVoltage | ( | double | voltage | ) | [protected] |
| int C3mxl::interpretControlData | ( | BYTE | address, |
| BYTE | length, | ||
| BYTE * | data | ||
| ) | [virtual] |
Interpret data read from control table.
| address | starting address. |
| length | number of bytes read. |
| data | control data. |
Reimplemented from CDxlGeneric.
| double C3mxl::mxlAccelerationToInternalAcceleration | ( | WORD | acceleration | ) | [protected] |
| double C3mxl::mxlCurrentToInternalCurrent | ( | WORD | current | ) | [protected] |
| double C3mxl::mxlLinearAccelerationToInternalLinearAcceleration | ( | WORD | acceleration | ) | [protected] |
| double C3mxl::mxlLinearPosToInternalLinearPos | ( | DWORD | pos | ) | [protected] |
| double C3mxl::mxlLinearSpeedToInternalLinearSpeed | ( | WORD | speed | ) | [protected] |
| double C3mxl::mxlPosToInternalPos | ( | WORD | pos | ) | [protected] |
| double C3mxl::mxlPWMToInternalPWM | ( | WORD | current | ) | [protected] |
| double C3mxl::mxlSpeedToInternalSpeed | ( | WORD | speed | ) | [protected] |
| double C3mxl::mxlTorqueToInternalTorque | ( | WORD | torque | ) | [protected] |
| double C3mxl::mxlVoltageToInternalVoltage | ( | WORD | voltage | ) | [protected] |
| virtual BYTE C3mxl::present3MxlMode | ( | ) | [inline, virtual] |
Get behavioral mode of the 3mxl.
Reimplemented from CDxlGeneric.
| virtual double C3mxl::presentAcceleration | ( | ) | [inline, virtual] |
| virtual double C3mxl::presentAnalog1Voltage | ( | ) | [inline, virtual] |
| virtual double C3mxl::presentAnalog2Voltage | ( | ) | [inline, virtual] |
| virtual double C3mxl::presentAnalog3Voltage | ( | ) | [inline, virtual] |
| virtual double C3mxl::presentAnalog4Voltage | ( | ) | [inline, virtual] |
| double C3mxl::presentAngleLowerLimit | ( | ) | [inline, virtual] |
| double C3mxl::presentAngleUpperLimit | ( | ) | [inline, virtual] |
| virtual double C3mxl::presentBusVoltage | ( | ) | [inline, virtual] |
| WORD C3mxl::presentCCWAngleLimit | ( | ) | [inline, virtual] |
Get cached counter-clockwise angle limit.
Implements CDxlGeneric.
| virtual double C3mxl::presentCurrent | ( | ) | [inline, virtual] |
| virtual double C3mxl::presentCurrentADCVoltage | ( | ) | [inline, virtual] |
| WORD C3mxl::presentCWAngleLimit | ( | ) | [inline, virtual] |
Get cached clockwise angle limit.
Implements CDxlGeneric.
| virtual double C3mxl::presentLinearAcceleration | ( | ) | [inline, virtual] |
| virtual double C3mxl::presentLinearPos | ( | ) | [inline, virtual] |
| virtual double C3mxl::presentLoad | ( | ) | [inline, virtual] |
| virtual TMxlLog C3mxl::presentLog | ( | ) | [inline, virtual] |
| virtual bool C3mxl::presentMotorInitState | ( | ) | [inline, virtual] |
Get motor initialization state.
Reimplemented from CDxlGeneric.
| virtual double C3mxl::presentPos | ( | ) | [inline, virtual] |
| virtual double C3mxl::presentSpeed | ( | ) | [inline, virtual] |
| virtual int C3mxl::presentStatus | ( | ) | [inline, virtual] |
| virtual double C3mxl::presentTemp | ( | ) | [inline, virtual] |
| virtual double C3mxl::presentTorque | ( | ) | [inline, virtual] |
| virtual double C3mxl::presentVoltage | ( | ) | [inline, virtual] |
| int C3mxl::printReport | ( | FILE * | fOut | ) | [virtual] |
Report on this Dynamixel.
Reads out the motor's complete control table.
| fOut | Output file. |
Reimplemented from CDxlGeneric.
| int C3mxl::round | ( | double | val | ) | [inline, protected] |
| int C3mxl::set3MxlMode | ( | BYTE | mxlMode, |
| bool | shouldSyncWrite = false |
||
| ) | [virtual] |
Set behaviour of the 3mxl.
| mxlMode | Control mode. |
| shouldSyncWrite | Accumulate data instead of sending immediately. |
Reimplemented from CDxlGeneric.
| int C3mxl::setAcceleration | ( | double | acceleration, |
| bool | shouldSyncWrite = false |
||
| ) | [virtual] |
Set acceleration for trajectory generation.
| acceleration | Acceleration in [rad/s^2]. |
| shouldSyncWrite | Accumulate data instead of sending immediately. |
Reimplemented from CDxlGeneric.
| int C3mxl::setAngleLimits | ( | double | lowerLimit, |
| double | upperLimit | ||
| ) | [virtual] |
Set angle limits.
| lowerLimit | Lower angle limit in [rad]. |
| upperLimit | Upper angle limit in [rad]. |
Reimplemented from CDxlGeneric.
| int C3mxl::setAngleLowerLimit | ( | double | limit | ) | [virtual] |
| int C3mxl::setAngleUpperLimit | ( | double | limit | ) | [virtual] |
| int C3mxl::setBaudRate | ( | const int | baudRate | ) | [virtual] |
| void C3mxl::setConfig | ( | CDxlConfig * | config | ) | [virtual] |
Set motor configuration.
The configuration is written to the motor during init().
Reimplemented from CDxlGeneric.
| int C3mxl::setCurrent | ( | double | current, |
| bool | shouldSyncWrite = false |
||
| ) | [virtual] |
Set reference current.
| current | Current in [A] |
| shouldSyncWrite | Accumulate data instead of sending immediately. |
Reimplemented from CDxlGeneric.
| int C3mxl::setEncoderCountJoint | ( | WORD | encodercount | ) | [virtual] |
Joint encoder counts per revolution.
| encodercount | Counts per revolution |
Reimplemented from CDxlGeneric.
| int C3mxl::setEncoderCountMotor | ( | WORD | encodercount | ) | [virtual] |
Motor encoder counts per revolution.
| encodercount | Counts per revolution |
Reimplemented from CDxlGeneric.
| int C3mxl::setEncoderIndexLevelMotor | ( | BYTE | level | ) | [virtual] |
Set motor encoder index pulse signal level.
| level | Low (0) or high (1) index pulse signal. |
Reimplemented from CDxlGeneric.
| int C3mxl::setGearboxRatioJoint | ( | float | gearboxratiojoint | ) | [virtual] |
Ratio between joint and joint encoder.
| gearboxratiojoint | turns of encoder for one joint revolution. |
Reimplemented from CDxlGeneric.
| int C3mxl::setGearboxRatioMotor | ( | float | gearboxratiomotor | ) | [virtual] |
Ratio between motor and joint.
| gearboxratiomotor | turns of motor for one joint revolution. |
Reimplemented from CDxlGeneric.
| int C3mxl::setInitialTorqueLimit | ( | double | absMaxTorque | ) | [virtual] |
Set initial torque limit (EEPROM).
This value is copied to ram during power-on.
| absMaxTorque | Torque limi as fraction of maximum possible torque. |
Reimplemented from CDxlGeneric.
| int C3mxl::setJointOffset | ( | double | offset | ) | [virtual] |
| int C3mxl::setLinearAcceleration | ( | double | acceleration, |
| bool | shouldSyncWrite = false |
||
| ) | [virtual] |
Set linear acceleration for trajectory generation.
| acceleration | Acceleration in [m/s^2]. |
| shouldSyncWrite | Accumulate data instead of sending immediately. |
Reimplemented from CDxlGeneric.
| int C3mxl::setLinearPos | ( | double | pos, |
| bool | shouldSyncWrite = false |
||
| ) | [virtual] |
Set linear reference position.
| pos | Position in [m] |
| absSpeed | Speed in [m/s]. Speed is absolute (positive in either direction). 0 speed means slowest. Negative speed means: MAXIMUM speed. |
| shouldSyncWrite | Accumulate data instead of sending immediately. |
Reimplemented from CDxlGeneric.
| int C3mxl::setLinearPos | ( | double | pos, |
| double | absSpeed, | ||
| bool | shouldSyncWrite = false |
||
| ) | [virtual] |
Set linear reference position and velocity.
| pos | Position in [m] |
| absSpeed | Speed in [m/s]. Speed is absolute (positive in either direction). 0 speed means slowest. Negative speed means: MAXIMUM speed. |
| shouldSyncWrite | Accumulate data instead of sending immediately. |
Reimplemented from CDxlGeneric.
| int C3mxl::setLinearPos | ( | double | pos, |
| double | absSpeed, | ||
| double | acceleration, | ||
| bool | shouldSyncWrite = false |
||
| ) | [virtual] |
Set linear reference position, velocity and acceleration.
| pos | Position in [m] |
| absSpeed | Speed in [m/s]. Speed is absolute (positive in either direction). 0 speed means slowest. Negative speed means: MAXIMUM speed. |
| acceleration | Acceleration in [m/s^2]. |
| shouldSyncWrite | Accumulate data instead of sending immediately. |
Reimplemented from CDxlGeneric.
| int C3mxl::setLinearSpeed | ( | double | speed, |
| bool | shouldSyncWrite = false |
||
| ) | [virtual] |
Set linear reference speed.
| speed | Speed in [m/s]. Speed can be positive or negative. |
| shouldSyncWrite | Accumulate data instead of sending immediately. |
Reimplemented from CDxlGeneric.
| int C3mxl::setLogInterval | ( | BYTE | interval | ) | [virtual] |
Set logging interval.
| interval | logging interval in [ms]. |
Reimplemented from CDxlGeneric.
| int C3mxl::setMaxContinuousMotorCurrent | ( | double | current | ) | [virtual] |
Set maximum motor continuous current.
| current | Maxmimum continuous current in [A]. |
Reimplemented from CDxlGeneric.
| int C3mxl::setMaxPeakMotorCurrent | ( | double | current | ) | [virtual] |
Set maximum motor peak current.
| current | Maxmimum peak current in [A]. |
Reimplemented from CDxlGeneric.
| int C3mxl::setMotorConstant | ( | WORD | motorconstant | ) | [virtual] |
Set motor constant.
| motorconstant | Motor constant in [10^-4 Nm/A]. |
Reimplemented from CDxlGeneric.
| int C3mxl::setMotorOffset | ( | double | offset | ) | [virtual] |
| int C3mxl::setMotorWindingTimeConstant | ( | double | time | ) | [virtual] |
Set motor winding time constant.
| time | Motor winding temperature time constant in [s]. |
Reimplemented from CDxlGeneric.
| int C3mxl::setPIDCurrent | ( | double | p, |
| double | d, | ||
| double | i, | ||
| double | i_limit, | ||
| bool | shouldSyncWrite = false |
||
| ) | [virtual] |
Set PID for current control mode.
The error is in SI units ([A]), and the output range of the control equation is [-1, 1].
| p | Proportional gain |
| d | Derivative gain |
| i | Integral gain |
| i_limit | Integration limit |
| shouldSyncWrite | Accumulate data instead of sending immediately. |
Reimplemented from CDxlGeneric.
| int C3mxl::setPIDEnergy | ( | double | p, |
| double | d, | ||
| double | i, | ||
| double | i_limit, | ||
| bool | shouldSyncWrite = false |
||
| ) | [virtual] |
Set PID for energy control mode.
The error is in SI units ([J]), and the output range of the control equation is [-1, 1].
| p | Proportional gain |
| d | Derivative gain |
| i | Integral gain |
| i_limit | Integration limit |
| shouldSyncWrite | Accumulate data instead of sending immediately. |
Reimplemented from CDxlGeneric.
| int C3mxl::setPIDPosition | ( | double | p, |
| double | d, | ||
| double | i, | ||
| double | i_limit, | ||
| bool | shouldSyncWrite = false |
||
| ) | [virtual] |
Set PID for position control mode.
The error is in SI units ([rad]), and the output range of the control equation is [-1, 1].
| p | Proportional gain |
| d | Derivative gain |
| i | Integral gain |
| i_limit | Integration limit |
| shouldSyncWrite | Accumulate data instead of sending immediately. |
Reimplemented from CDxlGeneric.
| int C3mxl::setPIDSpeed | ( | double | p, |
| double | d, | ||
| double | i, | ||
| double | i_limit, | ||
| bool | shouldSyncWrite = false |
||
| ) | [virtual] |
Set PID for speed control mode.
The error is in SI units ([rad/s]), and the output range of the control equation is [-1, 1].
| p | Proportional gain |
| d | Derivative gain |
| i | Integral gain |
| i_limit | Integration limit |
| shouldSyncWrite | Accumulate data instead of sending immediately. |
Reimplemented from CDxlGeneric.
| int C3mxl::setPIDTorque | ( | double | p, |
| double | d, | ||
| double | i, | ||
| double | i_limit, | ||
| bool | shouldSyncWrite = false |
||
| ) | [virtual] |
Set PID for torque control mode.
The error is in SI units ([Nm]), and the output range of the control equation is [-1, 1].
| p | Proportional gain |
| d | Derivative gain |
| i | Integral gain |
| i_limit | Integration limit |
| shouldSyncWrite | Accumulate data instead of sending immediately. |
Reimplemented from CDxlGeneric.
| int C3mxl::setPos | ( | double | pos, |
| bool | shouldSyncWrite = false |
||
| ) | [virtual] |
Set reference position.
| pos | Position in [rad] |
| shouldSyncWrite | Accumulate data instead of sending immediately. |
Reimplemented from CDxlGeneric.
| int C3mxl::setPos | ( | double | pos, |
| double | absSpeed, | ||
| bool | shouldSyncWrite = false |
||
| ) | [virtual] |
Set reference position and velocity.
| pos | Position in [rad] |
| absSpeed | Speed in [rad/s]. Speed is absolute (positive in either direction). 0 speed means slowest. Negative speed means: MAXIMUM speed. |
| shouldSyncWrite | Accumulate data instead of sending immediately. |
Reimplemented from CDxlGeneric.
| int C3mxl::setPos | ( | double | pos, |
| double | absSpeed, | ||
| double | acceleration, | ||
| bool | shouldSyncWrite = false |
||
| ) | [virtual] |
Set reference position, velocity and acceleration.
| pos | Position in [rad] |
| absSpeed | Speed in [rad/s]. Speed is absolute (positive in either direction). 0 speed means slowest. Negative speed means: MAXIMUM speed. |
| acceleration | Acceleration in [rad/s^2]. |
| shouldSyncWrite | Accumulate data instead of sending immediately. |
Reimplemented from CDxlGeneric.
| void C3mxl::setPositiveDirection | ( | bool | clockwiseIsPositive | ) | [virtual] |
Set direction convention.
| clockwiseIsPositive | True if clockwise direction is positive |
Reimplemented from CDxlGeneric.
| int C3mxl::setPositiveDirectionJoint | ( | bool | clockwiseIsPositive | ) | [virtual] |
Set joint direction convention.
| clockwiseIsPositive | True if clockwise direction is positive |
Reimplemented from CDxlGeneric.
| int C3mxl::setPositiveDirectionMotor | ( | bool | clockwiseIsPositive | ) | [virtual] |
Set motor direction convention.
| clockwiseIsPositive | True if clockwise direction is positive |
Reimplemented from CDxlGeneric.
| int C3mxl::setPosSpeedTorquePPosDPos | ( | double | pos, |
| double | speed, | ||
| double | torque, | ||
| int | pPos, | ||
| int | dPos, | ||
| bool | shouldSyncWrite = false |
||
| ) | [virtual] |
Set many references simultaneously.
| pos | Position in [rad] |
| speed | Speed in [rad/s] |
| torque | Torque in [Nm] |
| pPos | Position controller P gain |
| dPos | Position controller D gain |
| shouldSyncWrite | Accumulate data instead of sending immediately. |
Reimplemented from CDxlGeneric.
| int C3mxl::setPWM | ( | double | pwm, |
| bool | shouldSyncWrite = false |
||
| ) | [virtual] |
Set pulse width modulation duty cycle.
| pwm | PWM duty cycle, between -1 and 1. |
| shouldSyncWrite | Accumulate data instead of sending immediately. |
Reimplemented from CDxlGeneric.
| int C3mxl::setReferenceEnergy | ( | double | energy | ) | [virtual] |
Set reference energy for energy control.
| energy | Reference energy in [J] |
Reimplemented from CDxlGeneric.
| int C3mxl::setRetlevel | ( | const int | returnlevel | ) | [virtual] |
Set status return level.
| returnlevel | Return status packet on
|
Reimplemented from CDxlGeneric.
| int C3mxl::setReturnDelayTime | ( | const int | microsecondsReturnDelay | ) | [virtual] |
Set return delay.
Delay between transmission of Instruction Packet until the return of Status Packet.
| microsecondsReturnDelay | Return delay in [us]. |
Reimplemented from CDxlGeneric.
| void C3mxl::setSerialPort | ( | LxSerial * | serialPort | ) | [virtual] |
| int C3mxl::setSineAmplitude | ( | double | amplitude, |
| bool | shouldSyncWrite = false |
||
| ) | [virtual] |
Set sine amplitude.
| amplitude | Amplitude in [rad] |
| shouldSyncWrite | Accumulate data instead of sending immediately. |
Reimplemented from CDxlGeneric.
| int C3mxl::setSineFrequency | ( | double | frequency, |
| bool | shouldSyncWrite = false |
||
| ) | [virtual] |
Set sine frequency.
| frequency | Frequency in [Hz] |
| shouldSyncWrite | Accumulate data instead of sending immediately. |
Reimplemented from CDxlGeneric.
| int C3mxl::setSinePhase | ( | double | phase, |
| bool | shouldSyncWrite = false |
||
| ) | [virtual] |
Set sine phase angle.
| phase | Phase in [rad] |
| shouldSyncWrite | Accumulate data instead of sending immediately. |
Reimplemented from CDxlGeneric.
| int C3mxl::setSpeed | ( | double | speed, |
| bool | shouldSyncWrite = false |
||
| ) | [virtual] |
Set reference speed.
| speed | Speed in [rad/s]. Speed can be positive or negative. |
| shouldSyncWrite | Accumulate data instead of sending immediately. |
Reimplemented from CDxlGeneric.
| int C3mxl::setSpringStiffness | ( | double | stiffness | ) | [virtual] |
Set spring stiffness for series elastic actuation.
| stiffness | Spring stiffness in [Nm/rad] |
Reimplemented from CDxlGeneric.
| int C3mxl::setSyncReadIndex | ( | BYTE | index | ) | [virtual] |
Set index in sync read chain.
| index | index. 0 means this motor does not participate in the chain. |
Reimplemented from CDxlGeneric.
| int C3mxl::setTorque | ( | double | torque, |
| bool | shouldSyncWrite = false |
||
| ) | [virtual] |
Set reference torque.
| torque | Torque in [Nm] |
| shouldSyncWrite | Accumulate data instead of sending immediately. |
Reimplemented from CDxlGeneric.
| int C3mxl::setTorqueLimit | ( | double | absMaxTorque | ) | [virtual] |
Set operational torque limit (RAM).
| absMaxTorque | Torque limit as fraction of maximum possible torque. |
Reimplemented from CDxlGeneric.
| int C3mxl::setWatchdogMode | ( | BYTE | watchdogmode | ) | [virtual] |
| int C3mxl::setWatchdogMultiplier | ( | BYTE | watchdogmultiplier | ) | [virtual] |
Set watchdog interval (multiplier)
| watchdogmultiplier | Watchdog interval = time * multiplier. |
Reimplemented from CDxlGeneric.
| int C3mxl::setWatchdogTime | ( | BYTE | watchdogtime | ) | [virtual] |
Set watchdog interval (time)
| watchdogtime | Watchdog interval = time * multiplier. |
Reimplemented from CDxlGeneric.
| int C3mxl::setWheelDiameter | ( | double | diameter | ) | [virtual] |
| int C3mxl::setZeroLengthSpring | ( | double | parameterInRad | ) | [virtual] |
Set zero length of the spring for series elastic actuation.
| parameterInRad | Zero length in [rad]. |
Reimplemented from CDxlGeneric.
| const char * C3mxl::translateErrorCode | ( | int | errorCode | ) | [static] |
double C3mxl::mAcceleration [protected] |
double C3mxl::mAnalog1Voltage [protected] |
double C3mxl::mAnalog2Voltage [protected] |
double C3mxl::mAnalog3Voltage [protected] |
double C3mxl::mAnalog4Voltage [protected] |
double C3mxl::mBusVoltage [protected] |
CDxlConfig C3mxl::mConfig [protected] |
double C3mxl::mCurrent [protected] |
double C3mxl::mCurrentADCVoltage [protected] |
double C3mxl::mLinearAcceleration [protected] |
double C3mxl::mLinearPosition [protected] |
CLog2 C3mxl::mLog [protected] |
Reimplemented from CDxlGeneric.
unsigned char C3mxl::mMotorInitialized [protected] |
TMxlLog C3mxl::mMxlLog [protected] |
BYTE C3mxl::mMxlMode [protected] |
double C3mxl::mPosition [protected] |
double C3mxl::mSpeed [protected] |
unsigned char C3mxl::mStatus [protected] |
double C3mxl::mTorque [protected] |
double C3mxl::mVoltage [protected] |