#include <Dynamixel.h>
Public Member Functions | |
CDynamixel () | |
virtual int | changeID (const int newID) |
Change hardware motor ID. | |
virtual int | enableLED (int state) |
Enable LED. | |
virtual int | enableTorque (int state) |
Enable torque. | |
virtual int | getAngleLimits () |
Read angle limits from hardware. | |
virtual int | getID () |
Get motor ID. | |
virtual int | getPos () |
Read position from hardware. | |
virtual int | getPosAndSpeed () |
Read position and speed from hardware. | |
virtual int | getState () |
Read entire state from hardware. | |
virtual int | getTemp () |
Read temperature from hardware. | |
virtual int | init (bool sendConfigToMotor=true) |
Initialize this Dynamixel. | |
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. | |
virtual double | presentAngleLowerLimit () |
Get cached lower angle limit. | |
virtual double | presentAngleUpperLimit () |
Get cached upper angle limit. | |
virtual double | presentBusVoltage () |
Get cached bus voltage. | |
virtual WORD | presentCCWAngleLimit () |
Get cached counter-clockwise angle limit. | |
virtual double | presentCurrent () |
Get cached current. | |
virtual double | presentCurrentADCVoltage () |
Get cached motor current ADC voltage. | |
virtual 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 double | presentPos () |
Get cached position. | |
virtual double | presentSpeed () |
Get cached speed. | |
virtual double | presentTemp () |
Get cached temperature. | |
virtual double | presentTorque () |
Get cached torque. | |
virtual double | presentVoltage () |
Get cached motor voltage. | |
virtual int | printReport (FILE *fOut) |
Report on this Dynamixel. | |
virtual int | setAlarmLEDMask (const BYTE mask) |
Set which conditions cause the alarm LED to blink. | |
virtual int | setAlarmShutdownMask (const BYTE mask) |
Set which conditions trigger a shutdown. | |
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 int | setBaudRateIndex (const BYTE baudRateIndex) |
Set baud rate in Dynamixel units. | |
virtual int | setCompliance (BYTE complianceMargin, BYTE complianceSlope) |
Set control flexibility. | |
virtual void | setConfig (CDxlConfig *config) |
Set motor configuration. | |
virtual int | setEndlessTurnMode (bool enabled, bool shouldSyncWrite=false) |
Endless turn mode ('wheel mode'). | |
virtual int | setEndlessTurnTorque (double torqueRatio, bool shouldSyncWrite=false) |
Torque to apply in endless turn mode. | |
virtual int | setInitialTorqueLimit (double absMaxTorque) |
Set initial torque limit (EEPROM). | |
virtual void | setNullAngle (double nullAngle) |
Set null angle convention. | |
virtual int | setOperatingMode (const BYTE mode) |
Undocumented. | |
virtual int | setPos (double pos, double absSpeed, bool shouldSyncWrite=false) |
Set reference position and velocity. | |
virtual void | setPositiveDirection (bool clockwiseIsPositive) |
Set direction convention. | |
virtual int | setPunch (WORD punch) |
Unused. | |
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 | setSpeed (double speed, bool shouldSyncWrite=false) |
Move to angle limit with reference speed. | |
virtual int | setTemperatureLimit (const int maxTemp) |
Set temperature limit. | |
virtual int | setTorqueLimit (double absMaxTorque) |
Set operational torque limit (RAM). | |
virtual int | setVoltageLimits (double minVoltage, double maxVoltage) |
Set voltage limits. | |
virtual | ~CDynamixel () |
Protected Member Functions | |
int | clip (const int value, const int min, const int max) |
double | dxlPosToInternalPos (WORD pos) |
double | dxlSpeedToInternalSpeed (WORD speed) |
double | dxlTorqueToInternalTorque (WORD torque) |
int | internalPosToDxlPos (double pos) |
int | internalSpeedToDxlSpeed (double speed) |
WORD | internalTorqueToDxlTorque (double torque) |
int | round (double val) |
Protected Attributes | |
double | mAngleLUT [DXL_NUM_POSITIONS] |
WORD | mCCWAngleLimit |
Counter-clockwise angle limit. | |
CDxlConfig | mConfig |
WORD | mCWAngleLimit |
Clockwise angle limit. | |
double | mDirection |
Should be either 1.0 or -1.0 and is used as internal multiplication factor! | |
bool | mEndlessTurnMode |
Virtual state. | |
double | mLoad |
Current load expressed as a ratio of the maximum torque [dimensionless]. | |
CLog2 | mLog |
double | mNullAngle |
Null-angle in SI units AFTER the mDirection sign convention. | |
double | mPosition |
Position [rad] in the range [0 - (10/6)pi] (0-300 degrees) | |
double | mSpeed |
Speed [rad/s]. | |
double | mTemperature |
Temperature [deg. C]. | |
double | mVoltage |
Voltage [V]. |
Definition at line 51 of file Dynamixel.h.
Definition at line 21 of file Dynamixel.cpp.
CDynamixel::~CDynamixel | ( | ) | [virtual] |
Definition at line 43 of file Dynamixel.cpp.
int CDynamixel::changeID | ( | const int | newID | ) | [virtual] |
Change hardware motor ID.
Actually sets the new ID in the hardware.
newID | New ID. |
Reimplemented from CDxlGeneric.
Definition at line 295 of file Dynamixel.cpp.
int CDynamixel::clip | ( | const int | value, |
const int | min, | ||
const int | max | ||
) | [inline, protected] |
Definition at line 82 of file Dynamixel.h.
double CDynamixel::dxlPosToInternalPos | ( | WORD | pos | ) | [protected] |
Definition at line 124 of file Dynamixel.cpp.
double CDynamixel::dxlSpeedToInternalSpeed | ( | WORD | speed | ) | [protected] |
Definition at line 180 of file Dynamixel.cpp.
double CDynamixel::dxlTorqueToInternalTorque | ( | WORD | torque | ) | [protected] |
Definition at line 195 of file Dynamixel.cpp.
int CDynamixel::enableLED | ( | int | state | ) | [virtual] |
Enable LED.
state | 0 to extinguish the LED, 1 to light it. |
Reimplemented from CDxlGeneric.
Definition at line 317 of file Dynamixel.cpp.
int CDynamixel::enableTorque | ( | int | state | ) | [virtual] |
Enable torque.
state | 0 to disable power, 1 to enable it. |
Reimplemented from CDxlGeneric.
Definition at line 488 of file Dynamixel.cpp.
int CDynamixel::getAngleLimits | ( | ) | [virtual] |
Read angle limits from hardware.
Reimplemented from CDxlGeneric.
Definition at line 582 of file Dynamixel.cpp.
virtual int CDynamixel::getID | ( | ) | [inline, virtual] |
Get motor ID.
Implements CDxlGeneric.
Definition at line 109 of file Dynamixel.h.
int CDynamixel::getPos | ( | ) | [virtual] |
Read position from hardware.
Reimplemented from CDxlGeneric.
Definition at line 368 of file Dynamixel.cpp.
int CDynamixel::getPosAndSpeed | ( | ) | [virtual] |
Read position and speed from hardware.
Reimplemented from CDxlGeneric.
Definition at line 382 of file Dynamixel.cpp.
int CDynamixel::getState | ( | ) | [virtual] |
Read entire state from hardware.
Reimplemented from CDxlGeneric.
Definition at line 344 of file Dynamixel.cpp.
int CDynamixel::getTemp | ( | ) | [virtual] |
Read temperature from hardware.
Reimplemented from CDxlGeneric.
Definition at line 401 of file Dynamixel.cpp.
int CDynamixel::init | ( | bool | sendConfigToMotor = true | ) | [virtual] |
Initialize this Dynamixel.
sendConfigToMotor | Send configuration to motor |
Reimplemented from CDxlGeneric.
Definition at line 234 of file Dynamixel.cpp.
int CDynamixel::internalPosToDxlPos | ( | double | pos | ) | [protected] |
Definition at line 133 of file Dynamixel.cpp.
int CDynamixel::internalSpeedToDxlSpeed | ( | double | speed | ) | [protected] |
Definition at line 190 of file Dynamixel.cpp.
WORD CDynamixel::internalTorqueToDxlTorque | ( | double | torque | ) | [protected] |
Definition at line 205 of file Dynamixel.cpp.
virtual double CDynamixel::presentAcceleration | ( | ) | [inline, virtual] |
Get cached acceleration.
Implements CDxlGeneric.
Definition at line 156 of file Dynamixel.h.
virtual double CDynamixel::presentAnalog1Voltage | ( | ) | [inline, virtual] |
Get cached analog sensor 1 voltage.
Implements CDxlGeneric.
Definition at line 162 of file Dynamixel.h.
virtual double CDynamixel::presentAnalog2Voltage | ( | ) | [inline, virtual] |
Get cached analog sensor 2 voltage.
Implements CDxlGeneric.
Definition at line 163 of file Dynamixel.h.
virtual double CDynamixel::presentAnalog3Voltage | ( | ) | [inline, virtual] |
Get cached analog sensor 3 voltage.
Implements CDxlGeneric.
Definition at line 164 of file Dynamixel.h.
virtual double CDynamixel::presentAnalog4Voltage | ( | ) | [inline, virtual] |
Get cached analog sensor 4 voltage.
Implements CDxlGeneric.
Definition at line 165 of file Dynamixel.h.
double CDynamixel::presentAngleLowerLimit | ( | ) | [virtual] |
Get cached lower angle limit.
Implements CDxlGeneric.
Definition at line 218 of file Dynamixel.cpp.
double CDynamixel::presentAngleUpperLimit | ( | ) | [virtual] |
Get cached upper angle limit.
Implements CDxlGeneric.
Definition at line 226 of file Dynamixel.cpp.
virtual double CDynamixel::presentBusVoltage | ( | ) | [inline, virtual] |
Get cached bus voltage.
Implements CDxlGeneric.
Definition at line 160 of file Dynamixel.h.
virtual WORD CDynamixel::presentCCWAngleLimit | ( | ) | [inline, virtual] |
Get cached counter-clockwise angle limit.
Implements CDxlGeneric.
Definition at line 170 of file Dynamixel.h.
virtual double CDynamixel::presentCurrent | ( | ) | [inline, virtual] |
Get cached current.
Implements CDxlGeneric.
Definition at line 167 of file Dynamixel.h.
virtual double CDynamixel::presentCurrentADCVoltage | ( | ) | [inline, virtual] |
Get cached motor current ADC voltage.
Implements CDxlGeneric.
Definition at line 161 of file Dynamixel.h.
virtual WORD CDynamixel::presentCWAngleLimit | ( | ) | [inline, virtual] |
Get cached clockwise angle limit.
Implements CDxlGeneric.
Definition at line 169 of file Dynamixel.h.
virtual double CDynamixel::presentLinearAcceleration | ( | ) | [inline, virtual] |
Get cached linear acceleration.
Implements CDxlGeneric.
Definition at line 157 of file Dynamixel.h.
virtual double CDynamixel::presentLinearPos | ( | ) | [inline, virtual] |
Get cached linear position.
Implements CDxlGeneric.
Definition at line 154 of file Dynamixel.h.
virtual double CDynamixel::presentLoad | ( | ) | [inline, virtual] |
Get cached load value.
Implements CDxlGeneric.
Definition at line 158 of file Dynamixel.h.
virtual double CDynamixel::presentPos | ( | ) | [inline, virtual] |
Get cached position.
Implements CDxlGeneric.
Definition at line 153 of file Dynamixel.h.
virtual double CDynamixel::presentSpeed | ( | ) | [inline, virtual] |
Get cached speed.
Implements CDxlGeneric.
Definition at line 155 of file Dynamixel.h.
virtual double CDynamixel::presentTemp | ( | ) | [inline, virtual] |
Get cached temperature.
Implements CDxlGeneric.
Definition at line 166 of file Dynamixel.h.
virtual double CDynamixel::presentTorque | ( | ) | [inline, virtual] |
Get cached torque.
Implements CDxlGeneric.
Definition at line 168 of file Dynamixel.h.
virtual double CDynamixel::presentVoltage | ( | ) | [inline, virtual] |
Get cached motor voltage.
Implements CDxlGeneric.
Definition at line 159 of file Dynamixel.h.
int CDynamixel::printReport | ( | FILE * | fOut | ) | [virtual] |
Report on this Dynamixel.
Reads out the motor's complete control table.
fOut | Output file. |
Reimplemented from CDxlGeneric.
Definition at line 718 of file Dynamixel.cpp.
int CDynamixel::round | ( | double | val | ) | [inline, protected] |
Definition at line 92 of file Dynamixel.h.
int CDynamixel::setAlarmLEDMask | ( | const BYTE | mask | ) | [virtual] |
Set which conditions cause the alarm LED to blink.
mask Condition mask. See Dynamixel documentation.
Reimplemented from CDxlGeneric.
Definition at line 678 of file Dynamixel.cpp.
int CDynamixel::setAlarmShutdownMask | ( | const BYTE | mask | ) | [virtual] |
Set which conditions trigger a shutdown.
mask Condition mask. See Dynamixel documentation.
Reimplemented from CDxlGeneric.
Definition at line 687 of file Dynamixel.cpp.
int CDynamixel::setAngleLimits | ( | double | lowerLimit, |
double | upperLimit | ||
) | [virtual] |
Set angle limits.
lowerLimit | Lower angle limit in [rad]. |
upperLimit | Upper angle limit in [rad]. |
Reimplemented from CDxlGeneric.
Definition at line 600 of file Dynamixel.cpp.
int CDynamixel::setAngleLowerLimit | ( | double | limit | ) | [virtual] |
Set lower angle limit.
limit | Lower angle limit in [rad]. |
Reimplemented from CDxlGeneric.
Definition at line 532 of file Dynamixel.cpp.
int CDynamixel::setAngleUpperLimit | ( | double | limit | ) | [virtual] |
Set upper angle limit.
limit | Upper angle limit in [rad]. |
Reimplemented from CDxlGeneric.
Definition at line 547 of file Dynamixel.cpp.
int CDynamixel::setBaudRate | ( | const int | baudRate | ) | [virtual] |
Set baud rate in bits/s.
baudRate | Baudrate in [bit/s]. |
Reimplemented from CDxlGeneric.
Definition at line 470 of file Dynamixel.cpp.
int CDynamixel::setBaudRateIndex | ( | const BYTE | baudRateIndex | ) | [virtual] |
Set baud rate in Dynamixel units.
baudRateIndex | Baudrate in Dynamixel BPS unit. [bits/s] = 2000000/(baudRateIndex+1). |
Reimplemented from CDxlGeneric.
Definition at line 461 of file Dynamixel.cpp.
int CDynamixel::setCompliance | ( | BYTE | complianceMargin, |
BYTE | complianceSlope | ||
) | [virtual] |
Set control flexibility.
complianceMargin | Maximum error between goal position and present position in Dynamixel units. |
complianceSlope | Level of Torque near the goal position. Used value = 2^complianceSlope . |
Reimplemented from CDxlGeneric.
Definition at line 696 of file Dynamixel.cpp.
void CDynamixel::setConfig | ( | CDxlConfig * | config | ) | [virtual] |
Set motor configuration.
The configuration is written to the motor during init().
1.0
Reimplemented from CDxlGeneric.
Definition at line 47 of file Dynamixel.cpp.
int CDynamixel::setEndlessTurnMode | ( | bool | enabled, |
bool | shouldSyncWrite = false |
||
) | [virtual] |
Endless turn mode ('wheel mode').
Calling setEndlessTurnMode(false) will restore angle limits.
enabled | State. |
shouldSyncWrite | Accumulate data instead of sending immediately. |
Reimplemented from CDxlGeneric.
Definition at line 623 of file Dynamixel.cpp.
int CDynamixel::setEndlessTurnTorque | ( | double | torqueRatio, |
bool | shouldSyncWrite = false |
||
) | [virtual] |
Torque to apply in endless turn mode.
torqueRatio | Torque as fraction of maximum possible torque. |
shouldSyncWrite | Accumulate data instead of sending immediately. |
Reimplemented from CDxlGeneric.
Definition at line 653 of file Dynamixel.cpp.
int CDynamixel::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.
Definition at line 514 of file Dynamixel.cpp.
void CDynamixel::setNullAngle | ( | double | nullAngle | ) | [virtual] |
Set null angle convention.
nullAngle | Null angle in [rad] |
Reimplemented from CDxlGeneric.
Definition at line 119 of file Dynamixel.cpp.
int CDynamixel::setOperatingMode | ( | const BYTE | mode | ) | [virtual] |
Undocumented.
mode Undocumented.
Reimplemented from CDxlGeneric.
Definition at line 669 of file Dynamixel.cpp.
int CDynamixel::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.
Definition at line 415 of file Dynamixel.cpp.
void CDynamixel::setPositiveDirection | ( | bool | clockwiseIsPositive | ) | [virtual] |
Set direction convention.
clockwiseIsPositive | True if clockwise direction is positive |
Reimplemented from CDxlGeneric.
Definition at line 111 of file Dynamixel.cpp.
int CDynamixel::setPunch | ( | WORD | punch | ) | [virtual] |
Unused.
punch | Unused. |
Reimplemented from CDxlGeneric.
Definition at line 709 of file Dynamixel.cpp.
int CDynamixel::setRetlevel | ( | const int | returnlevel | ) | [virtual] |
Set status return level.
returnlevel | Return status packet on
|
Reimplemented from CDxlGeneric.
Definition at line 450 of file Dynamixel.cpp.
int CDynamixel::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.
Definition at line 479 of file Dynamixel.cpp.
void CDynamixel::setSerialPort | ( | LxSerial * | serialPort | ) | [virtual] |
Set serial port.
serialPort Serial port.
Reimplemented from CDxlGeneric.
Definition at line 106 of file Dynamixel.cpp.
int CDynamixel::setSpeed | ( | double | speed, |
bool | shouldSyncWrite = false |
||
) | [virtual] |
Move to angle limit with reference speed.
speed | Speed in [rad/s]. Speed can be positive or negative. |
shouldSyncWrite | Accumulate data instead of sending immediately. |
Reimplemented from CDxlGeneric.
Definition at line 429 of file Dynamixel.cpp.
int CDynamixel::setTemperatureLimit | ( | const int | maxTemp | ) | [virtual] |
Set temperature limit.
maxTemp | Maximum temperature in [deg. C]. |
Reimplemented from CDxlGeneric.
Definition at line 562 of file Dynamixel.cpp.
int CDynamixel::setTorqueLimit | ( | double | absMaxTorque | ) | [virtual] |
Set operational torque limit (RAM).
absMaxTorque | Torque limit as fraction of maximum possible torque. |
Reimplemented from CDxlGeneric.
Definition at line 523 of file Dynamixel.cpp.
int CDynamixel::setVoltageLimits | ( | double | minVoltage, |
double | maxVoltage | ||
) | [virtual] |
Set voltage limits.
minVoltage | Minimum voltage in [V]. |
maxVoltage | Maximum voltage in [V]. |
Reimplemented from CDxlGeneric.
Definition at line 571 of file Dynamixel.cpp.
double CDynamixel::mAngleLUT[DXL_NUM_POSITIONS] [protected] |
Definition at line 58 of file Dynamixel.h.
WORD CDynamixel::mCCWAngleLimit [protected] |
CDxlConfig CDynamixel::mConfig [protected] |
Definition at line 57 of file Dynamixel.h.
WORD CDynamixel::mCWAngleLimit [protected] |
Clockwise angle limit.
Angle limits are NOT saved in SI units but as Dynamixel WORD values, because we want to use the exact CWAngleLimit and CCWAngleLimit in setSpeed() as they are present in the control table of the Dynamixel (also as WORD values). Otherwise, we may set a slightly larger or smaller goal position in setSpeed() and encounter an angle limit error. Then setSpeed() would fail completely.
Definition at line 77 of file Dynamixel.h.
double CDynamixel::mDirection [protected] |
Should be either 1.0 or -1.0 and is used as internal multiplication factor!
Definition at line 59 of file Dynamixel.h.
bool CDynamixel::mEndlessTurnMode [protected] |
Virtual state.
Definition at line 80 of file Dynamixel.h.
double CDynamixel::mLoad [protected] |
Current load expressed as a ratio of the maximum torque [dimensionless].
Definition at line 65 of file Dynamixel.h.
CLog2 CDynamixel::mLog [protected] |
Reimplemented from CDxlGeneric.
Definition at line 54 of file Dynamixel.h.
double CDynamixel::mNullAngle [protected] |
Null-angle in SI units AFTER the mDirection sign convention.
Definition at line 60 of file Dynamixel.h.
double CDynamixel::mPosition [protected] |
Position [rad] in the range [0 - (10/6)pi] (0-300 degrees)
Definition at line 63 of file Dynamixel.h.
double CDynamixel::mSpeed [protected] |
Speed [rad/s].
Definition at line 64 of file Dynamixel.h.
double CDynamixel::mTemperature [protected] |
Temperature [deg. C].
Definition at line 67 of file Dynamixel.h.
double CDynamixel::mVoltage [protected] |
Voltage [V].
Definition at line 66 of file Dynamixel.h.