Public Member Functions | Protected Attributes
CDxlGeneric Class Reference

Generic interface to both CDynamixel and C3mxl. More...

#include <CDxlGeneric.h>

Inheritance diagram for CDxlGeneric:
Inheritance graph
[legend]

List of all members.

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
CDxlGroupmpGroup
int mRetlevel

Detailed Description

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.


Constructor & Destructor Documentation

Definition at line 64 of file CDxlGeneric.h.

virtual CDxlGeneric::~CDxlGeneric ( ) [inline, virtual]

Definition at line 70 of file CDxlGeneric.h.


Member Function Documentation

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.

Parameters:
newIDNew ID.

Reimplemented in C3mxl, and CDynamixel.

Definition at line 445 of file CDxlGeneric.h.

virtual int CDxlGeneric::enableLED ( int  state) [inline, virtual]

Enable LED.

Parameters:
state0 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.

Parameters:
state0 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.

See also:
presentAcceleration().

Reimplemented in C3mxl.

Definition at line 661 of file CDxlGeneric.h.

virtual int CDxlGeneric::getAngleLimits ( ) [inline, virtual]

Read angle limits from hardware.

Warning:
May not be called in endless turn mode!
See also:
presentCWAngleLimit() presentCCWAngleLimit() presentAngleLowerLimit() presentAngleUpperLimit().

Reimplemented in CDynamixel.

Definition at line 633 of file CDxlGeneric.h.

virtual int CDxlGeneric::getBusVoltage ( ) [inline, virtual]

Read bus voltage from hardware.

See also:
presentBusVoltage().

Reimplemented in C3mxl.

Definition at line 641 of file CDxlGeneric.h.

virtual int CDxlGeneric::getCurrent ( ) [inline, virtual]

Read current from hardware.

See also:
presentCurrent().

Reimplemented in C3mxl.

Definition at line 649 of file CDxlGeneric.h.

virtual int CDxlGeneric::getID ( ) [pure virtual]

Get motor ID.

Warning:
Merely returns the internally cached ID of the motor and does not request it (how could it, anyway?)
Returns:
Motor ID.

Implemented in C3mxl, and CDynamixel.

virtual int CDxlGeneric::getLinearAcceleration ( ) [inline, virtual]

Read linear acceleration from hardware.

See also:
presentLinearAcceleration().

Reimplemented in C3mxl.

Definition at line 665 of file CDxlGeneric.h.

virtual int CDxlGeneric::getLinearPos ( ) [inline, virtual]

Read linear position from hardware.

See also:
presentLinearPos().

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.

Parameters:
pProportional gain
dDerivative gain
iIntegral gain
i_limitIntegration limit
See also:
setPIDCurrent

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.

Parameters:
pProportional gain
dDerivative gain
iIntegral gain
i_limitIntegration limit
See also:
setPIDTorque

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.

Parameters:
pProportional gain
dDerivative gain
iIntegral gain
i_limitIntegration limit
See also:
setPIDPosition

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.

Parameters:
pProportional gain
dDerivative gain
iIntegral gain
i_limitIntegration limit
See also:
setPIDSpeed

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.

Parameters:
pProportional gain
dDerivative gain
iIntegral gain
i_limitIntegration limit
See also:
setPIDTorque

Reimplemented in C3mxl.

Definition at line 334 of file CDxlGeneric.h.

virtual int CDxlGeneric::getPos ( ) [inline, virtual]

Read position from hardware.

See also:
presentPos().

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.

See also:
presentPos(), presentSpeed().

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.

See also:
presentBusVoltage() presentCurrentADCVoltage() presentAnalog1Voltage() presentAnalog2Voltage().

Reimplemented in C3mxl.

Definition at line 645 of file CDxlGeneric.h.

virtual int CDxlGeneric::getState ( ) [inline, virtual]

Read entire state from hardware.

See also:
presentPos(), presentSpeed(), presentLoad(), presentVoltage(), presentTemp().

Reimplemented in C3mxl, and CDynamixel.

Definition at line 626 of file CDxlGeneric.h.

virtual int CDxlGeneric::getStatus ( ) [inline, virtual]

Read status from hardware.

Reimplemented in C3mxl.

Definition at line 668 of file CDxlGeneric.h.

virtual int CDxlGeneric::getTemp ( ) [inline, virtual]

Read temperature from hardware.

See also:
presentTemp().

Reimplemented in CDynamixel.

Definition at line 622 of file CDxlGeneric.h.

virtual int CDxlGeneric::getTorque ( ) [inline, virtual]

Read torque from hardware.

See also:
presentTorque().

Reimplemented in C3mxl.

Definition at line 653 of file CDxlGeneric.h.

virtual int CDxlGeneric::getTorquePosSpeed ( ) [inline, virtual]

Read torque, position and speed from hardware.

See also:
presentTorque() presentPos() presentSpeed().

Reimplemented in C3mxl.

Definition at line 657 of file CDxlGeneric.h.

virtual int CDxlGeneric::getVoltage ( ) [inline, virtual]

Read motor voltage from hardware.

See also:
presentVoltage().

Reimplemented in C3mxl.

Definition at line 637 of file CDxlGeneric.h.

virtual int CDxlGeneric::init ( bool  sendConfigToMotor = true) [inline, virtual]

Initialize this Dynamixel.

Warning:
Make sure you call setConfig() before calling init()!
Parameters:
sendConfigToMotorSend 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.

Parameters:
addressstarting address.
lengthnumber of bytes read.
datacontrol data.

Reimplemented in C3mxl.

Definition at line 794 of file CDxlGeneric.h.

Check for motor presence.

Returns:
DXL_SUCCESS on success, error otherwise.

Definition at line 56 of file CDxlGeneric.cpp.

virtual BYTE CDxlGeneric::present3MxlMode ( ) [inline, virtual]

Get behavioral mode of the 3mxl.

See also:
3mxl control modes for address M3XL_CONTROL_MODE.

Reimplemented in C3mxl.

Definition at line 780 of file CDxlGeneric.h.

virtual double CDxlGeneric::presentAcceleration ( ) [pure virtual]

Get cached acceleration.

Returns:
Acceleration in [rad/s^2].

Implemented in C3mxl, and CDynamixel.

virtual double CDxlGeneric::presentAnalog1Voltage ( ) [pure virtual]

Get cached analog sensor 1 voltage.

Returns:
Sensor voltage in [V].

Implemented in C3mxl, and CDynamixel.

virtual double CDxlGeneric::presentAnalog2Voltage ( ) [pure virtual]

Get cached analog sensor 2 voltage.

Returns:
Sensor voltage in [V].

Implemented in C3mxl, and CDynamixel.

virtual double CDxlGeneric::presentAnalog3Voltage ( ) [pure virtual]

Get cached analog sensor 3 voltage.

Returns:
Sensor voltage in [V].

Implemented in C3mxl, and CDynamixel.

virtual double CDxlGeneric::presentAnalog4Voltage ( ) [pure virtual]

Get cached analog sensor 4 voltage.

Returns:
Sensor voltage in [V].

Implemented in C3mxl, and CDynamixel.

virtual double CDxlGeneric::presentAngleLowerLimit ( ) [pure virtual]

Get cached lower angle limit.

Returns:
Lower angle limit in [rad].

Implemented in C3mxl, and CDynamixel.

virtual double CDxlGeneric::presentAngleUpperLimit ( ) [pure virtual]

Get cached upper angle limit.

Returns:
Upper angle limit in [rad].

Implemented in C3mxl, and CDynamixel.

virtual double CDxlGeneric::presentBusVoltage ( ) [pure virtual]

Get cached bus voltage.

Returns:
Bus voltage in [V].

Implemented in C3mxl, and CDynamixel.

virtual WORD CDxlGeneric::presentCCWAngleLimit ( ) [pure virtual]

Get cached counter-clockwise angle limit.

Warning:
Ignores the motor's null-angle and direction.
Returns:
Raw counter-clockwise angle limit limit.

Implemented in C3mxl, and CDynamixel.

virtual double CDxlGeneric::presentCurrent ( ) [pure virtual]

Get cached current.

Returns:
Current in [A].

Implemented in C3mxl, and CDynamixel.

virtual double CDxlGeneric::presentCurrentADCVoltage ( ) [pure virtual]

Get cached motor current ADC voltage.

Returns:
ADC voltage in [V].

Implemented in C3mxl, and CDynamixel.

virtual WORD CDxlGeneric::presentCWAngleLimit ( ) [pure virtual]

Get cached clockwise angle limit.

Warning:
Ignores the motor's null-angle and direction.
Returns:
Raw clockwise angle limit limit.

Implemented in C3mxl, and CDynamixel.

virtual double CDxlGeneric::presentLinearAcceleration ( ) [pure virtual]

Get cached linear acceleration.

Returns:
Acceleration in [m/s^2].

Implemented in C3mxl, and CDynamixel.

virtual double CDxlGeneric::presentLinearPos ( ) [pure virtual]

Get cached linear position.

Returns:
Position in [m].

Implemented in C3mxl, and CDynamixel.

virtual double CDxlGeneric::presentLoad ( ) [pure virtual]

Get cached load value.

Returns:
Load in [Nm].

Implemented in C3mxl, and CDynamixel.

virtual TMxlLog CDxlGeneric::presentLog ( ) [inline, virtual]

Get cached log string/file.

Returns:
a vector of log entries.

Reimplemented in C3mxl.

Definition at line 776 of file CDxlGeneric.h.

virtual bool CDxlGeneric::presentMotorInitState ( ) [inline, virtual]

Get motor initialization state.

Returns:
Whether the motor executed the initialization procedure.

Reimplemented in C3mxl.

Definition at line 750 of file CDxlGeneric.h.

virtual double CDxlGeneric::presentPos ( ) [pure virtual]

Get cached position.

Returns:
Position in [rad].

Implemented in C3mxl, and CDynamixel.

virtual double CDxlGeneric::presentSpeed ( ) [pure virtual]

Get cached speed.

Returns:
Speed in [rad/s].

Implemented in C3mxl, and CDynamixel.

virtual int CDxlGeneric::presentStatus ( ) [inline, virtual]

Get cached status.

Returns:
Status.
See also:
3mxl status codes for address M3XL_STATUS.

Reimplemented in C3mxl.

Definition at line 746 of file CDxlGeneric.h.

virtual double CDxlGeneric::presentTemp ( ) [pure virtual]

Get cached temperature.

Returns:
Temperature in [deg. C].

Implemented in C3mxl, and CDynamixel.

virtual double CDxlGeneric::presentTorque ( ) [pure virtual]

Get cached torque.

Returns:
Torque in [Nm].

Implemented in C3mxl, and CDynamixel.

virtual double CDxlGeneric::presentVoltage ( ) [pure virtual]

Get cached motor voltage.

Returns:
Motor voltage in [V].

Implemented in C3mxl, and CDynamixel.

virtual int CDxlGeneric::printReport ( FILE *  fOut) [inline, virtual]

Report on this Dynamixel.

Reads out the motor's complete control table.

Parameters:
fOutOutput 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.

Parameters:
startingAddressStarting address in control table.
dataLengthBytes to write.
dataBuffer of dataLength bytes.

Definition at line 3 of file CDxlGeneric.cpp.

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.

Warning:
Stops the motor.
Parameters:
mxlModeControl mode.
shouldSyncWriteAccumulate data instead of sending immediately.
See also:
3mxl control modes for address M3XL_CONTROL_MODE.

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.

Parameters:
accelerationAcceleration in [rad/s^2].
shouldSyncWriteAccumulate 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.

Parameters:
lowerLimitLower angle limit in [rad].
upperLimitUpper 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.

Parameters:
limitLower 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.

Parameters:
limitUpper 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.

Parameters:
baudRateBaudrate 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.

Parameters:
baudRateIndexBaudrate 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.

Warning:
Uses Dynamixel internal units.
Parameters:
complianceMarginMaximum error between goal position and present position in Dynamixel units.
complianceSlopeLevel 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().

Warning:
After init(), the fields of mConfig are not guaranteed to be up to date anymore!

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.

Parameters:
currentCurrent in [A]
shouldSyncWriteAccumulate 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.

Parameters:
encodercountCounts 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.

Parameters:
encodercountCounts 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.

Parameters:
levelLow (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.

Warning:
In this mode, there is no speed control! For safety, before enabling this mode, set the endlessTurnTorque() to zero first to avoid unwanted movements!
Parameters:
enabledState.
shouldSyncWriteAccumulate 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.

Parameters:
torqueRatioTorque as fraction of maximum possible torque.
shouldSyncWriteAccumulate 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.

Parameters:
gearboxratiojointturns 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.

Parameters:
gearboxratiomotorturns 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.

Warning:
Don't set this manually. Use CDxlGroup::addNewDynamixel.
Parameters:
groupGroup 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.

Parameters:
absMaxTorqueTorque 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.

Parameters:
offsetOffset 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.

Parameters:
accelerationAcceleration in [m/s^2].
shouldSyncWriteAccumulate 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.

Parameters:
posPosition in [m]
absSpeedSpeed in [m/s]. Speed is absolute (positive in either direction). 0 speed means slowest. Negative speed means: MAXIMUM speed.
shouldSyncWriteAccumulate 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.

Parameters:
posPosition in [m]
absSpeedSpeed in [m/s]. Speed is absolute (positive in either direction). 0 speed means slowest. Negative speed means: MAXIMUM speed.
shouldSyncWriteAccumulate 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.

Parameters:
posPosition in [m]
absSpeedSpeed in [m/s]. Speed is absolute (positive in either direction). 0 speed means slowest. Negative speed means: MAXIMUM speed.
accelerationAcceleration in [m/s^2].
shouldSyncWriteAccumulate 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.

Parameters:
speedSpeed in [m/s]. Speed can be positive or negative.
shouldSyncWriteAccumulate 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.

Note:
Call this to make sure you're logging for the right motor.
Parameters:
intervallogging 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.

Parameters:
currentMaxmimum continuous current in [A].

Reimplemented in C3mxl.

Definition at line 514 of file CDxlGeneric.h.

virtual int CDxlGeneric::setMaxMotorCurrent ( WORD  maxcurrent) [inline, virtual]

Unused.

Parameters:
maxcurrentUnused

Definition at line 554 of file CDxlGeneric.h.

virtual int CDxlGeneric::setMaxPeakMotorCurrent ( double  current) [inline, virtual]

Set maximum motor peak current.

Parameters:
currentMaxmimum peak current in [A].

Reimplemented in C3mxl.

Definition at line 510 of file CDxlGeneric.h.

virtual int CDxlGeneric::setMaxUninitializedMotorCurrent ( WORD  maxcurrent) [inline, virtual]

Unused.

Parameters:
maxcurrentUnused

Definition at line 550 of file CDxlGeneric.h.

virtual int CDxlGeneric::setMotorConstant ( WORD  motorconstant) [inline, virtual]

Set motor constant.

Parameters:
motorconstantMotor 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.

Parameters:
offsetOffset 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.

Parameters:
timeMotor 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.

Parameters:
nullAngleNull 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].

Parameters:
pProportional gain
dDerivative gain
iIntegral gain
i_limitIntegration limit
shouldSyncWriteAccumulate 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].

Parameters:
pProportional gain
dDerivative gain
iIntegral gain
i_limitIntegration limit
shouldSyncWriteAccumulate 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].

Parameters:
pProportional gain
dDerivative gain
iIntegral gain
i_limitIntegration limit
shouldSyncWriteAccumulate 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].

Parameters:
pProportional gain
dDerivative gain
iIntegral gain
i_limitIntegration limit
shouldSyncWriteAccumulate 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].

Parameters:
pProportional gain
dDerivative gain
iIntegral gain
i_limitIntegration limit
shouldSyncWriteAccumulate 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.

Parameters:
posPosition in [rad]
shouldSyncWriteAccumulate 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.

Parameters:
posPosition in [rad]
absSpeedSpeed in [rad/s]. Speed is absolute (positive in either direction). 0 speed means slowest. Negative speed means: MAXIMUM speed.
shouldSyncWriteAccumulate 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.

Parameters:
posPosition in [rad]
absSpeedSpeed in [rad/s]. Speed is absolute (positive in either direction). 0 speed means slowest. Negative speed means: MAXIMUM speed.
accelerationAcceleration in [rad/s^2].
shouldSyncWriteAccumulate 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.

Parameters:
clockwiseIsPositiveTrue 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.

Parameters:
clockwiseIsPositiveTrue 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.

Parameters:
clockwiseIsPositiveTrue 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.

Parameters:
posPosition in [rad]
speedSpeed in [rad/s]
torqueTorque in [Nm]
pPosPosition controller P gain
dPosPosition controller D gain
shouldSyncWriteAccumulate 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.

Parameters:
punchUnused.

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.

Parameters:
pwmPWM duty cycle, between -1 and 1.
shouldSyncWriteAccumulate 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.

Parameters:
energyReference 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.

Parameters:
returnlevelReturn status packet on
  • 0 PING
  • 1 PING+READ
  • 2 all commands

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.

Parameters:
microsecondsReturnDelayReturn 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.

Warning:
Does not start the motor. Use setSineFrequency for that.
Parameters:
amplitudeAmplitude in [rad]
shouldSyncWriteAccumulate data instead of sending immediately.
See also:
setSineFrequency

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.

Note:
Starts the motor.
Parameters:
frequencyFrequency in [Hz]
shouldSyncWriteAccumulate 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.

Warning:
Does not start the motor. Use setSineFrequency for that.
Parameters:
phasePhase in [rad]
shouldSyncWriteAccumulate data instead of sending immediately.
See also:
setSineFrequency

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.

Parameters:
speedSpeed in [rad/s]. Speed can be positive or negative.
shouldSyncWriteAccumulate 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.

Parameters:
stiffnessSpring 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.

Note:
Normally called by CDxlGroup.
Parameters:
indexindex. 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.

Parameters:
maxTempMaximum 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.

Parameters:
torqueTorque in [Nm]
shouldSyncWriteAccumulate 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).

Parameters:
absMaxTorqueTorque 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.

Parameters:
minVoltageMinimum voltage in [V].
maxVoltageMaximum 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.

Parameters:
watchdogmodeUnused

Reimplemented in C3mxl.

Definition at line 538 of file CDxlGeneric.h.

virtual int CDxlGeneric::setWatchdogMultiplier ( BYTE  watchdogmultiplier) [inline, virtual]

Set watchdog interval (multiplier)

Parameters:
watchdogmultiplierWatchdog 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)

Parameters:
watchdogtimeWatchdog 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.

Parameters:
diameterWheel 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.

Parameters:
parameterInRadZero 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.

Parameters:
startingAddressStarting address in control table.
dataLengthBytes to write.
dataBuffer of dataLength bytes.
shouldSyncWriteAccumulate 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.


Member Data Documentation

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.

Definition at line 58 of file CDxlGeneric.h.

int CDxlGeneric::mRetlevel [protected]

Definition at line 60 of file CDxlGeneric.h.


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


threemxl
Author(s):
autogenerated on Thu Jun 6 2019 21:10:52