Generic interface to both CDynamixel and C3mxl. More...
#include <CDxlGeneric.h>
Public Member Functions | |
int | action () |
Execute registered command. | |
CDxlGeneric () | |
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 | get3MxlMode () |
Read behavioral mode of the 3mxl. | |
virtual int | getAcceleration () |
Read acceleration from hardware. | |
virtual int | getAngleLimits () |
Read angle limits from hardware. | |
virtual int | getBusVoltage () |
Read bus voltage from hardware. | |
virtual int | getCurrent () |
Read current from hardware. | |
virtual int | getID ()=0 |
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 | getTemp () |
Read temperature 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. | |
virtual int | interpretControlData (BYTE address, BYTE length, BYTE *data) |
Interpret data read from control table. | |
int | ping () |
Check for motor presence. | |
virtual BYTE | present3MxlMode () |
Get behavioral mode of the 3mxl. | |
virtual double | presentAcceleration ()=0 |
Get cached acceleration. | |
virtual double | presentAnalog1Voltage ()=0 |
Get cached analog sensor 1 voltage. | |
virtual double | presentAnalog2Voltage ()=0 |
Get cached analog sensor 2 voltage. | |
virtual double | presentAnalog3Voltage ()=0 |
Get cached analog sensor 3 voltage. | |
virtual double | presentAnalog4Voltage ()=0 |
Get cached analog sensor 4 voltage. | |
virtual double | presentAngleLowerLimit ()=0 |
Get cached lower angle limit. | |
virtual double | presentAngleUpperLimit ()=0 |
Get cached upper angle limit. | |
virtual double | presentBusVoltage ()=0 |
Get cached bus voltage. | |
virtual WORD | presentCCWAngleLimit ()=0 |
Get cached counter-clockwise angle limit. | |
virtual double | presentCurrent ()=0 |
Get cached current. | |
virtual double | presentCurrentADCVoltage ()=0 |
Get cached motor current ADC voltage. | |
virtual WORD | presentCWAngleLimit ()=0 |
Get cached clockwise angle limit. | |
virtual double | presentLinearAcceleration ()=0 |
Get cached linear acceleration. | |
virtual double | presentLinearPos ()=0 |
Get cached linear position. | |
virtual double | presentLoad ()=0 |
Get cached load value. | |
virtual TMxlLog | presentLog () |
Get cached log string/file. | |
virtual bool | presentMotorInitState () |
Get motor initialization state. | |
virtual double | presentPos ()=0 |
Get cached position. | |
virtual double | presentSpeed ()=0 |
Get cached speed. | |
virtual int | presentStatus () |
Get cached status. | |
virtual double | presentTemp ()=0 |
Get cached temperature. | |
virtual double | presentTorque ()=0 |
Get cached torque. | |
virtual double | presentVoltage ()=0 |
Get cached motor voltage. | |
virtual int | printReport (FILE *fOut) |
Report on this Dynamixel. | |
int | readData (BYTE startingAddress, BYTE dataLength, BYTE *data) |
Read data from hardware. | |
int | reset () |
Reset control table. | |
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 | 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 | 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 | 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 | setGearboxRatioJoint (float gearboxratiojoint) |
Ratio between joint and joint encoder. | |
virtual int | setGearboxRatioMotor (float gearboxratiomotor) |
Ratio between motor and joint. | |
virtual void | setGroup (CDxlGroup *group) |
Set group membership. | |
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 | setMaxMotorCurrent (WORD maxcurrent) |
Unused. | |
virtual int | setMaxPeakMotorCurrent (double current) |
Set maximum motor peak current. | |
virtual int | setMaxUninitializedMotorCurrent (WORD maxcurrent) |
Unused. | |
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 void | setNullAngle (double nullAngle) |
Set null angle convention. | |
virtual int | setOperatingMode (const BYTE mode) |
Undocumented. | |
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 | setPunch (WORD punch) |
Unused. | |
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 | setTemperatureLimit (const int maxTemp) |
Set temperature limit. | |
virtual int | setTorque (double torque, bool shouldSyncWrite=false) |
Set reference torque. | |
virtual int | setTorqueLimit (double absMaxTorque) |
Set operational torque limit (RAM). | |
virtual int | setVoltageLimits (double minVoltage, double maxVoltage) |
Set voltage limits. | |
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. | |
int | writeData (BYTE startingAddress, BYTE dataLength, BYTE *data, bool shouldSyncWrite=false) |
Write data to hardware. | |
virtual | ~CDxlGeneric () |
Protected Attributes | |
int | mID |
CLog2 | mLog |
CDxlGroup * | mpGroup |
int | mRetlevel |
Generic interface to both CDynamixel and C3mxl.
Some of the set* functions can also be used in a SYNC_WRITE packet fashion; use CDxlGroup for that.
get*() functions cannot be used in a SYNC_WRITE packet fashion, since they return data.
Definition at line 55 of file CDxlGeneric.h.
CDxlGeneric::CDxlGeneric | ( | ) | [inline] |
Definition at line 64 of file CDxlGeneric.h.
virtual CDxlGeneric::~CDxlGeneric | ( | ) | [inline, virtual] |
Definition at line 70 of file CDxlGeneric.h.
int CDxlGeneric::action | ( | ) |
Execute registered command.
Definition at line 77 of file CDxlGeneric.cpp.
virtual int CDxlGeneric::changeID | ( | const int | newID | ) | [inline, virtual] |
Change hardware motor ID.
Actually sets the new ID in the hardware.
newID | New ID. |
Reimplemented in C3mxl, and CDynamixel.
Definition at line 445 of file CDxlGeneric.h.
virtual int CDxlGeneric::enableLED | ( | int | state | ) | [inline, virtual] |
Enable LED.
state | 0 to extinguish the LED, 1 to light it. |
Reimplemented in CDynamixel.
Definition at line 449 of file CDxlGeneric.h.
virtual int CDxlGeneric::enableTorque | ( | int | state | ) | [inline, virtual] |
Enable torque.
state | 0 to disable power, 1 to enable it. |
Reimplemented in CDynamixel.
Definition at line 453 of file CDxlGeneric.h.
virtual int CDxlGeneric::get3MxlMode | ( | ) | [inline, virtual] |
Read behavioral mode of the 3mxl.
Reimplemented in C3mxl.
Definition at line 675 of file CDxlGeneric.h.
virtual int CDxlGeneric::getAcceleration | ( | ) | [inline, virtual] |
Read acceleration from hardware.
Reimplemented in C3mxl.
Definition at line 661 of file CDxlGeneric.h.
virtual int CDxlGeneric::getAngleLimits | ( | ) | [inline, virtual] |
Read angle limits from hardware.
Reimplemented in CDynamixel.
Definition at line 633 of file CDxlGeneric.h.
virtual int CDxlGeneric::getBusVoltage | ( | ) | [inline, virtual] |
Read bus voltage from hardware.
Reimplemented in C3mxl.
Definition at line 641 of file CDxlGeneric.h.
virtual int CDxlGeneric::getCurrent | ( | ) | [inline, virtual] |
Read current from hardware.
Reimplemented in C3mxl.
Definition at line 649 of file CDxlGeneric.h.
virtual int CDxlGeneric::getID | ( | ) | [pure virtual] |
Get motor ID.
Implemented in C3mxl, and CDynamixel.
virtual int CDxlGeneric::getLinearAcceleration | ( | ) | [inline, virtual] |
Read linear acceleration from hardware.
Reimplemented in C3mxl.
Definition at line 665 of file CDxlGeneric.h.
virtual int CDxlGeneric::getLinearPos | ( | ) | [inline, virtual] |
Read linear position from hardware.
Reimplemented in C3mxl.
Definition at line 614 of file CDxlGeneric.h.
virtual int CDxlGeneric::getLog | ( | ) | [inline, virtual] |
Read logfile from hardware.
logfile from hardware to memory. Get a pointer to this array with presentLog().
Reimplemented in C3mxl.
Definition at line 672 of file CDxlGeneric.h.
virtual int CDxlGeneric::getPIDCurrent | ( | double & | p, |
double & | d, | ||
double & | i, | ||
double & | i_limit | ||
) | [inline, virtual] |
Get PID gains for current control mode.
p | Proportional gain |
d | Derivative gain |
i | Integral gain |
i_limit | Integration limit |
Reimplemented in C3mxl.
Definition at line 268 of file CDxlGeneric.h.
virtual int CDxlGeneric::getPIDEnergy | ( | double & | p, |
double & | d, | ||
double & | i, | ||
double & | i_limit | ||
) | [inline, virtual] |
Get PID gains for energy control mode.
p | Proportional gain |
d | Derivative gain |
i | Integral gain |
i_limit | Integration limit |
Reimplemented in C3mxl.
Definition at line 356 of file CDxlGeneric.h.
virtual int CDxlGeneric::getPIDPosition | ( | double & | p, |
double & | d, | ||
double & | i, | ||
double & | i_limit | ||
) | [inline, virtual] |
Get PID gains for position control mode.
p | Proportional gain |
d | Derivative gain |
i | Integral gain |
i_limit | Integration limit |
Reimplemented in C3mxl.
Definition at line 290 of file CDxlGeneric.h.
virtual int CDxlGeneric::getPIDSpeed | ( | double & | p, |
double & | d, | ||
double & | i, | ||
double & | i_limit | ||
) | [inline, virtual] |
Get PID gains for speed control mode.
p | Proportional gain |
d | Derivative gain |
i | Integral gain |
i_limit | Integration limit |
Reimplemented in C3mxl.
Definition at line 312 of file CDxlGeneric.h.
virtual int CDxlGeneric::getPIDTorque | ( | double & | p, |
double & | d, | ||
double & | i, | ||
double & | i_limit | ||
) | [inline, virtual] |
Get PID gains for torque control mode.
p | Proportional gain |
d | Derivative gain |
i | Integral gain |
i_limit | Integration limit |
Reimplemented in C3mxl.
Definition at line 334 of file CDxlGeneric.h.
virtual int CDxlGeneric::getPos | ( | ) | [inline, virtual] |
Read position from hardware.
Reimplemented in C3mxl, and CDynamixel.
Definition at line 610 of file CDxlGeneric.h.
virtual int CDxlGeneric::getPosAndSpeed | ( | ) | [inline, virtual] |
Read position and speed from hardware.
Reimplemented in C3mxl, and CDynamixel.
Definition at line 618 of file CDxlGeneric.h.
virtual int CDxlGeneric::getSensorVoltages | ( | ) | [inline, virtual] |
Read analog sensor voltages from hardware.
Reimplemented in C3mxl.
Definition at line 645 of file CDxlGeneric.h.
virtual int CDxlGeneric::getState | ( | ) | [inline, virtual] |
Read entire state from hardware.
Reimplemented in C3mxl, and CDynamixel.
Definition at line 626 of file CDxlGeneric.h.
virtual int CDxlGeneric::getStatus | ( | ) | [inline, virtual] |
virtual int CDxlGeneric::getTemp | ( | ) | [inline, virtual] |
Read temperature from hardware.
Reimplemented in CDynamixel.
Definition at line 622 of file CDxlGeneric.h.
virtual int CDxlGeneric::getTorque | ( | ) | [inline, virtual] |
Read torque from hardware.
Reimplemented in C3mxl.
Definition at line 653 of file CDxlGeneric.h.
virtual int CDxlGeneric::getTorquePosSpeed | ( | ) | [inline, virtual] |
Read torque, position and speed from hardware.
Reimplemented in C3mxl.
Definition at line 657 of file CDxlGeneric.h.
virtual int CDxlGeneric::getVoltage | ( | ) | [inline, virtual] |
Read motor voltage from hardware.
Reimplemented in C3mxl.
Definition at line 637 of file CDxlGeneric.h.
virtual int CDxlGeneric::init | ( | bool | sendConfigToMotor = true | ) | [inline, virtual] |
Initialize this Dynamixel.
sendConfigToMotor | Send configuration to motor |
Reimplemented in C3mxl, and CDynamixel.
Definition at line 129 of file CDxlGeneric.h.
virtual int CDxlGeneric::interpretControlData | ( | BYTE | address, |
BYTE | length, | ||
BYTE * | data | ||
) | [inline, virtual] |
Interpret data read from control table.
address | starting address. |
length | number of bytes read. |
data | control data. |
Reimplemented in C3mxl.
Definition at line 794 of file CDxlGeneric.h.
int CDxlGeneric::ping | ( | ) |
Check for motor presence.
Definition at line 56 of file CDxlGeneric.cpp.
virtual BYTE CDxlGeneric::present3MxlMode | ( | ) | [inline, virtual] |
Get behavioral mode of the 3mxl.
Reimplemented in C3mxl.
Definition at line 780 of file CDxlGeneric.h.
virtual double CDxlGeneric::presentAcceleration | ( | ) | [pure virtual] |
virtual double CDxlGeneric::presentAnalog1Voltage | ( | ) | [pure virtual] |
Get cached analog sensor 1 voltage.
Implemented in C3mxl, and CDynamixel.
virtual double CDxlGeneric::presentAnalog2Voltage | ( | ) | [pure virtual] |
Get cached analog sensor 2 voltage.
Implemented in C3mxl, and CDynamixel.
virtual double CDxlGeneric::presentAnalog3Voltage | ( | ) | [pure virtual] |
Get cached analog sensor 3 voltage.
Implemented in C3mxl, and CDynamixel.
virtual double CDxlGeneric::presentAnalog4Voltage | ( | ) | [pure virtual] |
Get cached analog sensor 4 voltage.
Implemented in C3mxl, and CDynamixel.
virtual double CDxlGeneric::presentAngleLowerLimit | ( | ) | [pure virtual] |
Get cached lower angle limit.
Implemented in C3mxl, and CDynamixel.
virtual double CDxlGeneric::presentAngleUpperLimit | ( | ) | [pure virtual] |
Get cached upper angle limit.
Implemented in C3mxl, and CDynamixel.
virtual double CDxlGeneric::presentBusVoltage | ( | ) | [pure virtual] |
virtual WORD CDxlGeneric::presentCCWAngleLimit | ( | ) | [pure virtual] |
Get cached counter-clockwise angle limit.
Implemented in C3mxl, and CDynamixel.
virtual double CDxlGeneric::presentCurrent | ( | ) | [pure virtual] |
virtual double CDxlGeneric::presentCurrentADCVoltage | ( | ) | [pure virtual] |
Get cached motor current ADC voltage.
Implemented in C3mxl, and CDynamixel.
virtual WORD CDxlGeneric::presentCWAngleLimit | ( | ) | [pure virtual] |
Get cached clockwise angle limit.
Implemented in C3mxl, and CDynamixel.
virtual double CDxlGeneric::presentLinearAcceleration | ( | ) | [pure virtual] |
Get cached linear acceleration.
Implemented in C3mxl, and CDynamixel.
virtual double CDxlGeneric::presentLinearPos | ( | ) | [pure virtual] |
virtual double CDxlGeneric::presentLoad | ( | ) | [pure virtual] |
virtual TMxlLog CDxlGeneric::presentLog | ( | ) | [inline, virtual] |
Get cached log string/file.
Reimplemented in C3mxl.
Definition at line 776 of file CDxlGeneric.h.
virtual bool CDxlGeneric::presentMotorInitState | ( | ) | [inline, virtual] |
Get motor initialization state.
Reimplemented in C3mxl.
Definition at line 750 of file CDxlGeneric.h.
virtual double CDxlGeneric::presentPos | ( | ) | [pure virtual] |
virtual double CDxlGeneric::presentSpeed | ( | ) | [pure virtual] |
virtual int CDxlGeneric::presentStatus | ( | ) | [inline, virtual] |
Get cached status.
Reimplemented in C3mxl.
Definition at line 746 of file CDxlGeneric.h.
virtual double CDxlGeneric::presentTemp | ( | ) | [pure virtual] |
virtual double CDxlGeneric::presentTorque | ( | ) | [pure virtual] |
virtual double CDxlGeneric::presentVoltage | ( | ) | [pure virtual] |
virtual int CDxlGeneric::printReport | ( | FILE * | fOut | ) | [inline, virtual] |
Report on this Dynamixel.
Reads out the motor's complete control table.
fOut | Output file. |
Reimplemented in C3mxl, and CDynamixel.
Definition at line 786 of file CDxlGeneric.h.
int CDxlGeneric::readData | ( | BYTE | startingAddress, |
BYTE | dataLength, | ||
BYTE * | data | ||
) |
Read data from hardware.
startingAddress | Starting address in control table. |
dataLength | Bytes to write. |
data | Buffer of dataLength bytes. |
Definition at line 3 of file CDxlGeneric.cpp.
int CDxlGeneric::reset | ( | ) |
Reset control table.
Definition at line 85 of file CDxlGeneric.cpp.
virtual int CDxlGeneric::set3MxlMode | ( | BYTE | mxlMode, |
bool | shouldSyncWrite = false |
||
) | [inline, virtual] |
Set behaviour of the 3mxl.
mxlMode | Control mode. |
shouldSyncWrite | Accumulate data instead of sending immediately. |
Reimplemented in C3mxl.
Definition at line 478 of file CDxlGeneric.h.
virtual int CDxlGeneric::setAcceleration | ( | double | acceleration, |
bool | shouldSyncWrite = false |
||
) | [inline, virtual] |
Set acceleration for trajectory generation.
acceleration | Acceleration in [rad/s^2]. |
shouldSyncWrite | Accumulate data instead of sending immediately. |
Reimplemented in C3mxl.
Definition at line 207 of file CDxlGeneric.h.
virtual int CDxlGeneric::setAlarmLEDMask | ( | const BYTE | mask | ) | [inline, virtual] |
Set which conditions cause the alarm LED to blink.
mask Condition mask. See Dynamixel documentation.
Reimplemented in CDynamixel.
Definition at line 431 of file CDxlGeneric.h.
virtual int CDxlGeneric::setAlarmShutdownMask | ( | const BYTE | mask | ) | [inline, virtual] |
Set which conditions trigger a shutdown.
mask Condition mask. See Dynamixel documentation.
Reimplemented in CDynamixel.
Definition at line 439 of file CDxlGeneric.h.
virtual int CDxlGeneric::setAngleLimits | ( | double | lowerLimit, |
double | upperLimit | ||
) | [inline, virtual] |
Set angle limits.
lowerLimit | Lower angle limit in [rad]. |
upperLimit | Upper angle limit in [rad]. |
Reimplemented in C3mxl, and CDynamixel.
Definition at line 392 of file CDxlGeneric.h.
virtual int CDxlGeneric::setAngleLowerLimit | ( | double | limit | ) | [inline, virtual] |
Set lower angle limit.
limit | Lower angle limit in [rad]. |
Reimplemented in C3mxl, and CDynamixel.
Definition at line 409 of file CDxlGeneric.h.
virtual int CDxlGeneric::setAngleUpperLimit | ( | double | limit | ) | [inline, virtual] |
Set upper angle limit.
limit | Upper angle limit in [rad]. |
Reimplemented in C3mxl, and CDynamixel.
Definition at line 415 of file CDxlGeneric.h.
virtual int CDxlGeneric::setBaudRate | ( | const int | baudRate | ) | [inline, virtual] |
Set baud rate in bits/s.
baudRate | Baudrate in [bit/s]. |
Reimplemented in C3mxl, and CDynamixel.
Definition at line 368 of file CDxlGeneric.h.
virtual int CDxlGeneric::setBaudRateIndex | ( | const BYTE | baudRateIndex | ) | [inline, virtual] |
Set baud rate in Dynamixel units.
baudRateIndex | Baudrate in Dynamixel BPS unit. [bits/s] = 2000000/(baudRateIndex+1). |
Reimplemented in CDynamixel.
Definition at line 364 of file CDxlGeneric.h.
virtual int CDxlGeneric::setCompliance | ( | BYTE | complianceMargin, |
BYTE | complianceSlope | ||
) | [inline, 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 in CDynamixel.
Definition at line 423 of file CDxlGeneric.h.
virtual void CDxlGeneric::setConfig | ( | CDxlConfig * | config | ) | [inline, virtual] |
Set motor configuration.
The configuration is written to the motor during init().
Reimplemented in C3mxl, and CDynamixel.
Definition at line 118 of file CDxlGeneric.h.
virtual int CDxlGeneric::setCurrent | ( | double | current, |
bool | shouldSyncWrite = false |
||
) | [inline, virtual] |
Set reference current.
current | Current in [A] |
shouldSyncWrite | Accumulate data instead of sending immediately. |
Reimplemented in C3mxl.
Definition at line 228 of file CDxlGeneric.h.
virtual int CDxlGeneric::setEncoderCountJoint | ( | WORD | encodercount | ) | [inline, virtual] |
Joint encoder counts per revolution.
encodercount | Counts per revolution |
Reimplemented in C3mxl.
Definition at line 502 of file CDxlGeneric.h.
virtual int CDxlGeneric::setEncoderCountMotor | ( | WORD | encodercount | ) | [inline, virtual] |
Motor encoder counts per revolution.
encodercount | Counts per revolution |
Reimplemented in C3mxl.
Definition at line 498 of file CDxlGeneric.h.
virtual int CDxlGeneric::setEncoderIndexLevelMotor | ( | BYTE | level | ) | [inline, virtual] |
Set motor encoder index pulse signal level.
level | Low (0) or high (1) index pulse signal. |
Reimplemented in C3mxl.
Definition at line 522 of file CDxlGeneric.h.
virtual int CDxlGeneric::setEndlessTurnMode | ( | bool | enabled, |
bool | shouldSyncWrite = false |
||
) | [inline, virtual] |
Endless turn mode ('wheel mode').
Calling setEndlessTurnMode(false) will restore angle limits.
enabled | State. |
shouldSyncWrite | Accumulate data instead of sending immediately. |
Reimplemented in CDynamixel.
Definition at line 462 of file CDxlGeneric.h.
virtual int CDxlGeneric::setEndlessTurnTorque | ( | double | torqueRatio, |
bool | shouldSyncWrite = false |
||
) | [inline, virtual] |
Torque to apply in endless turn mode.
torqueRatio | Torque as fraction of maximum possible torque. |
shouldSyncWrite | Accumulate data instead of sending immediately. |
Reimplemented in CDynamixel.
Definition at line 469 of file CDxlGeneric.h.
virtual int CDxlGeneric::setGearboxRatioJoint | ( | float | gearboxratiojoint | ) | [inline, virtual] |
Ratio between joint and joint encoder.
gearboxratiojoint | turns of encoder for one joint revolution. |
Reimplemented in C3mxl.
Definition at line 534 of file CDxlGeneric.h.
virtual int CDxlGeneric::setGearboxRatioMotor | ( | float | gearboxratiomotor | ) | [inline, virtual] |
Ratio between motor and joint.
gearboxratiomotor | turns of motor for one joint revolution. |
Reimplemented in C3mxl.
Definition at line 530 of file CDxlGeneric.h.
virtual void CDxlGeneric::setGroup | ( | CDxlGroup * | group | ) | [inline, virtual] |
Set group membership.
group | Group to set membership to. |
Definition at line 111 of file CDxlGeneric.h.
virtual int CDxlGeneric::setInitialTorqueLimit | ( | double | absMaxTorque | ) | [inline, 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 in C3mxl, and CDynamixel.
Definition at line 381 of file CDxlGeneric.h.
virtual int CDxlGeneric::setJointOffset | ( | double | offset | ) | [inline, virtual] |
Set joint null angle offset.
offset | Offset in [rad]. |
Reimplemented in C3mxl.
Definition at line 494 of file CDxlGeneric.h.
virtual int CDxlGeneric::setLinearAcceleration | ( | double | acceleration, |
bool | shouldSyncWrite = false |
||
) | [inline, virtual] |
Set linear acceleration for trajectory generation.
acceleration | Acceleration in [m/s^2]. |
shouldSyncWrite | Accumulate data instead of sending immediately. |
Reimplemented in C3mxl.
Definition at line 214 of file CDxlGeneric.h.
virtual int CDxlGeneric::setLinearPos | ( | double | pos, |
bool | shouldSyncWrite = false |
||
) | [inline, 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 in C3mxl.
Definition at line 169 of file CDxlGeneric.h.
virtual int CDxlGeneric::setLinearPos | ( | double | pos, |
double | absSpeed, | ||
bool | shouldSyncWrite = false |
||
) | [inline, 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 in C3mxl.
Definition at line 177 of file CDxlGeneric.h.
virtual int CDxlGeneric::setLinearPos | ( | double | pos, |
double | absSpeed, | ||
double | acceleration, | ||
bool | shouldSyncWrite = false |
||
) | [inline, 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 in C3mxl.
Definition at line 186 of file CDxlGeneric.h.
virtual int CDxlGeneric::setLinearSpeed | ( | double | speed, |
bool | shouldSyncWrite = false |
||
) | [inline, virtual] |
Set linear reference speed.
speed | Speed in [m/s]. Speed can be positive or negative. |
shouldSyncWrite | Accumulate data instead of sending immediately. |
Reimplemented in C3mxl.
Definition at line 200 of file CDxlGeneric.h.
virtual int CDxlGeneric::setLogInterval | ( | BYTE | interval | ) | [inline, virtual] |
Set logging interval.
interval | logging interval in [ms]. |
Reimplemented in C3mxl.
Definition at line 599 of file CDxlGeneric.h.
virtual int CDxlGeneric::setMaxContinuousMotorCurrent | ( | double | current | ) | [inline, virtual] |
Set maximum motor continuous current.
current | Maxmimum continuous current in [A]. |
Reimplemented in C3mxl.
Definition at line 514 of file CDxlGeneric.h.
virtual int CDxlGeneric::setMaxMotorCurrent | ( | WORD | maxcurrent | ) | [inline, virtual] |
virtual int CDxlGeneric::setMaxPeakMotorCurrent | ( | double | current | ) | [inline, virtual] |
Set maximum motor peak current.
current | Maxmimum peak current in [A]. |
Reimplemented in C3mxl.
Definition at line 510 of file CDxlGeneric.h.
virtual int CDxlGeneric::setMaxUninitializedMotorCurrent | ( | WORD | maxcurrent | ) | [inline, virtual] |
virtual int CDxlGeneric::setMotorConstant | ( | WORD | motorconstant | ) | [inline, virtual] |
Set motor constant.
motorconstant | Motor constant in [10^-4 Nm/A]. |
Reimplemented in C3mxl.
Definition at line 506 of file CDxlGeneric.h.
virtual int CDxlGeneric::setMotorOffset | ( | double | offset | ) | [inline, virtual] |
Set motor null angle offset.
offset | Offset in [rad]. |
Reimplemented in C3mxl.
Definition at line 490 of file CDxlGeneric.h.
virtual int CDxlGeneric::setMotorWindingTimeConstant | ( | double | time | ) | [inline, virtual] |
Set motor winding time constant.
time | Motor winding temperature time constant in [s]. |
Reimplemented in C3mxl.
Definition at line 518 of file CDxlGeneric.h.
virtual void CDxlGeneric::setNullAngle | ( | double | nullAngle | ) | [inline, virtual] |
Set null angle convention.
nullAngle | Null angle in [rad] |
Reimplemented in CDynamixel.
Definition at line 137 of file CDxlGeneric.h.
virtual int CDxlGeneric::setOperatingMode | ( | const BYTE | mode | ) | [inline, virtual] |
Undocumented.
mode Undocumented.
Reimplemented in CDynamixel.
Definition at line 435 of file CDxlGeneric.h.
virtual int CDxlGeneric::setPIDCurrent | ( | double | p, |
double | d, | ||
double | i, | ||
double | i_limit, | ||
bool | shouldSyncWrite = false |
||
) | [inline, 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 in C3mxl.
Definition at line 258 of file CDxlGeneric.h.
virtual int CDxlGeneric::setPIDEnergy | ( | double | p, |
double | d, | ||
double | i, | ||
double | i_limit, | ||
bool | shouldSyncWrite = false |
||
) | [inline, 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 in C3mxl.
Definition at line 346 of file CDxlGeneric.h.
virtual int CDxlGeneric::setPIDPosition | ( | double | p, |
double | d, | ||
double | i, | ||
double | i_limit, | ||
bool | shouldSyncWrite = false |
||
) | [inline, 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 in C3mxl.
Definition at line 280 of file CDxlGeneric.h.
virtual int CDxlGeneric::setPIDSpeed | ( | double | p, |
double | d, | ||
double | i, | ||
double | i_limit, | ||
bool | shouldSyncWrite = false |
||
) | [inline, 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 in C3mxl.
Definition at line 302 of file CDxlGeneric.h.
virtual int CDxlGeneric::setPIDTorque | ( | double | p, |
double | d, | ||
double | i, | ||
double | i_limit, | ||
bool | shouldSyncWrite = false |
||
) | [inline, 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 in C3mxl.
Definition at line 324 of file CDxlGeneric.h.
virtual int CDxlGeneric::setPos | ( | double | pos, |
bool | shouldSyncWrite = false |
||
) | [inline, virtual] |
Set reference position.
pos | Position in [rad] |
shouldSyncWrite | Accumulate data instead of sending immediately. |
Reimplemented in C3mxl.
Definition at line 144 of file CDxlGeneric.h.
virtual int CDxlGeneric::setPos | ( | double | pos, |
double | absSpeed, | ||
bool | shouldSyncWrite = false |
||
) | [inline, 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 in C3mxl, and CDynamixel.
Definition at line 152 of file CDxlGeneric.h.
virtual int CDxlGeneric::setPos | ( | double | pos, |
double | absSpeed, | ||
double | acceleration, | ||
bool | shouldSyncWrite = false |
||
) | [inline, 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 in C3mxl.
Definition at line 161 of file CDxlGeneric.h.
virtual void CDxlGeneric::setPositiveDirection | ( | bool | clockwiseIsPositive | ) | [inline, virtual] |
Set direction convention.
clockwiseIsPositive | True if clockwise direction is positive |
Reimplemented in C3mxl, and CDynamixel.
Definition at line 133 of file CDxlGeneric.h.
virtual int CDxlGeneric::setPositiveDirectionJoint | ( | bool | clockwiseIsPositive | ) | [inline, virtual] |
Set joint direction convention.
clockwiseIsPositive | True if clockwise direction is positive |
Reimplemented in C3mxl.
Definition at line 486 of file CDxlGeneric.h.
virtual int CDxlGeneric::setPositiveDirectionMotor | ( | bool | clockwiseIsPositive | ) | [inline, virtual] |
Set motor direction convention.
clockwiseIsPositive | True if clockwise direction is positive |
Reimplemented in C3mxl.
Definition at line 482 of file CDxlGeneric.h.
virtual int CDxlGeneric::setPosSpeedTorquePPosDPos | ( | double | pos, |
double | speed, | ||
double | torque, | ||
int | pPos, | ||
int | dPos, | ||
bool | shouldSyncWrite = false |
||
) | [inline, 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 in C3mxl.
Definition at line 246 of file CDxlGeneric.h.
virtual int CDxlGeneric::setPunch | ( | WORD | punch | ) | [inline, virtual] |
Unused.
punch | Unused. |
Reimplemented in CDynamixel.
Definition at line 427 of file CDxlGeneric.h.
virtual int CDxlGeneric::setPWM | ( | double | pwm, |
bool | shouldSyncWrite = false |
||
) | [inline, virtual] |
Set pulse width modulation duty cycle.
pwm | PWM duty cycle, between -1 and 1. |
shouldSyncWrite | Accumulate data instead of sending immediately. |
Reimplemented in C3mxl.
Definition at line 235 of file CDxlGeneric.h.
virtual int CDxlGeneric::setReferenceEnergy | ( | double | energy | ) | [inline, virtual] |
Set reference energy for energy control.
energy | Reference energy in [J] |
Reimplemented in C3mxl.
Definition at line 566 of file CDxlGeneric.h.
virtual int CDxlGeneric::setRetlevel | ( | const int | returnlevel | ) | [inline, virtual] |
Set status return level.
returnlevel | Return status packet on
|
Reimplemented in C3mxl, and CDynamixel.
Definition at line 360 of file CDxlGeneric.h.
virtual int CDxlGeneric::setReturnDelayTime | ( | const int | microsecondsReturnDelay | ) | [inline, virtual] |
Set return delay.
Delay between transmission of Instruction Packet until the return of Status Packet.
microsecondsReturnDelay | Return delay in [us]. |
Reimplemented in C3mxl, and CDynamixel.
Definition at line 374 of file CDxlGeneric.h.
virtual void CDxlGeneric::setSerialPort | ( | LxSerial * | serialPort | ) | [inline, virtual] |
Set serial port.
serialPort Serial port.
Reimplemented in C3mxl, and CDynamixel.
Definition at line 122 of file CDxlGeneric.h.
virtual int CDxlGeneric::setSineAmplitude | ( | double | amplitude, |
bool | shouldSyncWrite = false |
||
) | [inline, virtual] |
Set sine amplitude.
amplitude | Amplitude in [rad] |
shouldSyncWrite | Accumulate data instead of sending immediately. |
Reimplemented in C3mxl.
Definition at line 583 of file CDxlGeneric.h.
virtual int CDxlGeneric::setSineFrequency | ( | double | frequency, |
bool | shouldSyncWrite = false |
||
) | [inline, virtual] |
Set sine frequency.
frequency | Frequency in [Hz] |
shouldSyncWrite | Accumulate data instead of sending immediately. |
Reimplemented in C3mxl.
Definition at line 574 of file CDxlGeneric.h.
virtual int CDxlGeneric::setSinePhase | ( | double | phase, |
bool | shouldSyncWrite = false |
||
) | [inline, virtual] |
Set sine phase angle.
phase | Phase in [rad] |
shouldSyncWrite | Accumulate data instead of sending immediately. |
Reimplemented in C3mxl.
Definition at line 592 of file CDxlGeneric.h.
virtual int CDxlGeneric::setSpeed | ( | double | speed, |
bool | shouldSyncWrite = false |
||
) | [inline, virtual] |
Set reference speed.
speed | Speed in [rad/s]. Speed can be positive or negative. |
shouldSyncWrite | Accumulate data instead of sending immediately. |
Reimplemented in C3mxl, and CDynamixel.
Definition at line 193 of file CDxlGeneric.h.
virtual int CDxlGeneric::setSpringStiffness | ( | double | stiffness | ) | [inline, virtual] |
Set spring stiffness for series elastic actuation.
stiffness | Spring stiffness in [Nm/rad] |
Reimplemented in C3mxl.
Definition at line 562 of file CDxlGeneric.h.
virtual int CDxlGeneric::setSyncReadIndex | ( | BYTE | index | ) | [inline, virtual] |
Set index in sync read chain.
index | index. 0 means this motor does not participate in the chain. |
Reimplemented in C3mxl.
Definition at line 606 of file CDxlGeneric.h.
virtual int CDxlGeneric::setTemperatureLimit | ( | const int | maxTemp | ) | [inline, virtual] |
Set temperature limit.
maxTemp | Maximum temperature in [deg. C]. |
Reimplemented in CDynamixel.
Definition at line 403 of file CDxlGeneric.h.
virtual int CDxlGeneric::setTorque | ( | double | torque, |
bool | shouldSyncWrite = false |
||
) | [inline, virtual] |
Set reference torque.
torque | Torque in [Nm] |
shouldSyncWrite | Accumulate data instead of sending immediately. |
Reimplemented in C3mxl.
Definition at line 221 of file CDxlGeneric.h.
virtual int CDxlGeneric::setTorqueLimit | ( | double | absMaxTorque | ) | [inline, virtual] |
Set operational torque limit (RAM).
absMaxTorque | Torque limit as fraction of maximum possible torque. |
Reimplemented in C3mxl, and CDynamixel.
Definition at line 385 of file CDxlGeneric.h.
virtual int CDxlGeneric::setVoltageLimits | ( | double | minVoltage, |
double | maxVoltage | ||
) | [inline, virtual] |
Set voltage limits.
minVoltage | Minimum voltage in [V]. |
maxVoltage | Maximum voltage in [V]. |
Reimplemented in CDynamixel.
Definition at line 399 of file CDxlGeneric.h.
virtual int CDxlGeneric::setWatchdogMode | ( | BYTE | watchdogmode | ) | [inline, virtual] |
What to do if watchdog triggers.
watchdogmode | Unused |
Reimplemented in C3mxl.
Definition at line 538 of file CDxlGeneric.h.
virtual int CDxlGeneric::setWatchdogMultiplier | ( | BYTE | watchdogmultiplier | ) | [inline, virtual] |
Set watchdog interval (multiplier)
watchdogmultiplier | Watchdog interval = time * multiplier . |
Reimplemented in C3mxl.
Definition at line 546 of file CDxlGeneric.h.
virtual int CDxlGeneric::setWatchdogTime | ( | BYTE | watchdogtime | ) | [inline, virtual] |
Set watchdog interval (time)
watchdogtime | Watchdog interval = time * multiplier . |
Reimplemented in C3mxl.
Definition at line 542 of file CDxlGeneric.h.
virtual int CDxlGeneric::setWheelDiameter | ( | double | diameter | ) | [inline, virtual] |
Set wheel diameter.
diameter | Wheel diameter in [m]. |
Reimplemented in C3mxl.
Definition at line 526 of file CDxlGeneric.h.
virtual int CDxlGeneric::setZeroLengthSpring | ( | double | parameterInRad | ) | [inline, virtual] |
Set zero length of the spring for series elastic actuation.
parameterInRad | Zero length in [rad]. |
Reimplemented in C3mxl.
Definition at line 558 of file CDxlGeneric.h.
int CDxlGeneric::writeData | ( | BYTE | startingAddress, |
BYTE | dataLength, | ||
BYTE * | data, | ||
bool | shouldSyncWrite = false |
||
) |
Write data to hardware.
startingAddress | Starting address in control table. |
dataLength | Bytes to write. |
data | Buffer of dataLength bytes. |
shouldSyncWrite | Accumulate data instead of sending immediately. |
Here we have syncWriteLocation as the position to place the data that otherwise would be send directly to the dynamixel
Definition at line 96 of file CDxlGeneric.cpp.
int CDxlGeneric::mID [protected] |
Definition at line 59 of file CDxlGeneric.h.
CLog2 CDxlGeneric::mLog [protected] |
Reimplemented from CDxlCom.
Reimplemented in C3mxl, and CDynamixel.
Definition at line 61 of file CDxlGeneric.h.
CDxlGroup* CDxlGeneric::mpGroup [protected] |
Definition at line 58 of file CDxlGeneric.h.
int CDxlGeneric::mRetlevel [protected] |
Definition at line 60 of file CDxlGeneric.h.