Public Member Functions | Static Public Member Functions | Protected Member Functions | Protected Attributes
C3mxl Class Reference

#include <3mxl.h>

Inheritance diagram for C3mxl:
Inheritance graph
[legend]

List of all members.

Public Member Functions

 C3mxl ()
virtual int changeID (const int newID)
 Change hardware motor ID.
virtual int get3MxlMode ()
 Read behavioral mode of the 3mxl.
virtual int getAcceleration ()
 Read acceleration from hardware.
virtual int getBusVoltage ()
 Read bus voltage from hardware.
virtual int getCurrent ()
 Read current from hardware.
int getID ()
 Get motor ID.
virtual int getLinearAcceleration ()
 Read linear acceleration from hardware.
virtual int getLinearPos ()
 Read linear position from hardware.
virtual int getLog ()
 Read logfile from hardware.
virtual int getPIDCurrent (double &p, double &d, double &i, double &i_limit)
 Get PID gains for current control mode.
virtual int getPIDEnergy (double &p, double &d, double &i, double &i_limit)
 Get PID gains for energy control mode.
virtual int getPIDPosition (double &p, double &d, double &i, double &i_limit)
 Get PID gains for position control mode.
virtual int getPIDSpeed (double &p, double &d, double &i, double &i_limit)
 Get PID gains for speed control mode.
virtual int getPIDTorque (double &p, double &d, double &i, double &i_limit)
 Get PID gains for torque control mode.
virtual int getPos ()
 Read position from hardware.
virtual int getPosAndSpeed ()
 Read position and speed from hardware.
virtual int getSensorVoltages ()
 Read analog sensor voltages from hardware.
virtual int getState ()
 Read entire state from hardware.
virtual int getStatus ()
 Read status from hardware.
virtual int getTorque ()
 Read torque from hardware.
virtual int getTorquePosSpeed ()
 Read torque, position and speed from hardware.
virtual int getVoltage ()
 Read motor voltage from hardware.
virtual int init (bool sendConfigToMotor=true)
 Initialize this Dynamixel.
int interpretControlData (BYTE address, BYTE length, BYTE *data)
 Interpret data read from control table.
virtual BYTE present3MxlMode ()
 Get behavioral mode of the 3mxl.
virtual double presentAcceleration ()
 Get cached acceleration.
virtual double presentAnalog1Voltage ()
 Get cached analog sensor 1 voltage.
virtual double presentAnalog2Voltage ()
 Get cached analog sensor 2 voltage.
virtual double presentAnalog3Voltage ()
 Get cached analog sensor 3 voltage.
virtual double presentAnalog4Voltage ()
 Get cached analog sensor 4 voltage.
double presentAngleLowerLimit ()
 Get cached lower angle limit.
double presentAngleUpperLimit ()
 Get cached upper angle limit.
virtual double presentBusVoltage ()
 Get cached bus voltage.
WORD presentCCWAngleLimit ()
 Get cached counter-clockwise angle limit.
virtual double presentCurrent ()
 Get cached current.
virtual double presentCurrentADCVoltage ()
 Get cached motor current ADC voltage.
WORD presentCWAngleLimit ()
 Get cached clockwise angle limit.
virtual double presentLinearAcceleration ()
 Get cached linear acceleration.
virtual double presentLinearPos ()
 Get cached linear position.
virtual double presentLoad ()
 Get cached load value.
virtual TMxlLog presentLog ()
 Get cached log string/file.
virtual bool presentMotorInitState ()
 Get motor initialization state.
virtual double presentPos ()
 Get cached position.
virtual double presentSpeed ()
 Get cached speed.
virtual int presentStatus ()
 Get cached status.
virtual double presentTemp ()
 Get cached temperature.
virtual double presentTorque ()
 Get cached torque.
virtual double presentVoltage ()
 Get cached motor voltage.
int printReport (FILE *fOut)
 Report on this Dynamixel.
virtual int set3MxlMode (BYTE mxlMode, bool shouldSyncWrite=false)
 Set behaviour of the 3mxl.
virtual int setAcceleration (double acceleration, bool shouldSyncWrite=false)
 Set acceleration for trajectory generation.
virtual int setAngleLimits (double lowerLimit, double upperLimit)
 Set angle limits.
virtual int setAngleLowerLimit (double limit)
 Set lower angle limit.
virtual int setAngleUpperLimit (double limit)
 Set upper angle limit.
virtual int setBaudRate (const int baudRate)
 Set baud rate in bits/s.
virtual void setConfig (CDxlConfig *config)
 Set motor configuration.
virtual int setCurrent (double current, bool shouldSyncWrite=false)
 Set reference current.
virtual int setEncoderCountJoint (WORD encodercount)
 Joint encoder counts per revolution.
virtual int setEncoderCountMotor (WORD encodercount)
 Motor encoder counts per revolution.
virtual int setEncoderIndexLevelMotor (BYTE level)
 Set motor encoder index pulse signal level.
virtual int setGearboxRatioJoint (float gearboxratio)
 Ratio between joint and joint encoder.
virtual int setGearboxRatioMotor (float gearboxratio)
 Ratio between motor and joint.
virtual int setInitialTorqueLimit (double absMaxTorque)
 Set initial torque limit (EEPROM).
virtual int setJointOffset (double offset)
 Set joint null angle offset.
virtual int setLinearAcceleration (double acceleration, bool shouldSyncWrite=false)
 Set linear acceleration for trajectory generation.
virtual int setLinearPos (double pos, bool shouldSyncWrite=false)
 Set linear reference position.
virtual int setLinearPos (double pos, double absSpeed, bool shouldSyncWrite=false)
 Set linear reference position and velocity.
virtual int setLinearPos (double pos, double absSpeed, double acceleration, bool shouldSyncWrite=false)
 Set linear reference position, velocity and acceleration.
virtual int setLinearSpeed (double speed, bool shouldSyncWrite=false)
 Set linear reference speed.
virtual int setLogInterval (BYTE interval)
 Set logging interval.
virtual int setMaxContinuousMotorCurrent (double current)
 Set maximum motor continuous current.
virtual int setMaxPeakMotorCurrent (double current)
 Set maximum motor peak current.
virtual int setMotorConstant (WORD motorconstant)
 Set motor constant.
virtual int setMotorOffset (double offset)
 Set motor null angle offset.
virtual int setMotorWindingTimeConstant (double time)
 Set motor winding time constant.
virtual int setPIDCurrent (double p, double d, double i, double i_limit, bool shouldSyncWrite=false)
 Set PID for current control mode.
virtual int setPIDEnergy (double p, double d, double i, double i_limit, bool shouldSyncWrite=false)
 Set PID for energy control mode.
virtual int setPIDPosition (double p, double d, double i, double i_limit, bool shouldSyncWrite=false)
 Set PID for position control mode.
virtual int setPIDSpeed (double p, double d, double i, double i_limit, bool shouldSyncWrite=false)
 Set PID for speed control mode.
virtual int setPIDTorque (double p, double d, double i, double i_limit, bool shouldSyncWrite=false)
 Set PID for torque control mode.
virtual int setPos (double pos, bool shouldSyncWrite=false)
 Set reference position.
virtual int setPos (double pos, double absSpeed, bool shouldSyncWrite=false)
 Set reference position and velocity.
virtual int setPos (double pos, double absSpeed, double acceleration, bool shouldSyncWrite=false)
 Set reference position, velocity and acceleration.
virtual void setPositiveDirection (bool clockwiseIsPositive)
 Set direction convention.
virtual int setPositiveDirectionJoint (bool clockwiseIsPositive)
 Set joint direction convention.
virtual int setPositiveDirectionMotor (bool clockwiseIsPositive)
 Set motor direction convention.
virtual int setPosSpeedTorquePPosDPos (double pos, double speed, double torque, int pPos, int dPos, bool shouldSyncWrite=false)
 Set many references simultaneously.
virtual int setPWM (double pwm, bool shouldSyncWrite=false)
 Set pulse width modulation duty cycle.
virtual int setReferenceEnergy (double energy)
 Set reference energy for energy control.
virtual int setRetlevel (const int returnlevel)
 Set status return level.
virtual int setReturnDelayTime (const int microsecondsReturnDelay)
 Set return delay.
virtual void setSerialPort (LxSerial *serialPort)
 Set serial port.
virtual int setSineAmplitude (double amplitude, bool shouldSyncWrite=false)
 Set sine amplitude.
virtual int setSineFrequency (double frequency, bool shouldSyncWrite=false)
 Set sine frequency.
virtual int setSinePhase (double phase, bool shouldSyncWrite=false)
 Set sine phase angle.
virtual int setSpeed (double speed, bool shouldSyncWrite=false)
 Set reference speed.
virtual int setSpringStiffness (double stiffness)
 Set spring stiffness for series elastic actuation.
virtual int setSyncReadIndex (BYTE index)
 Set index in sync read chain.
virtual int setTorque (double torque, bool shouldSyncWrite=false)
 Set reference torque.
virtual int setTorqueLimit (double absMaxTorque)
 Set operational torque limit (RAM).
virtual int setWatchdogMode (BYTE watchdogmode)
 What to do if watchdog triggers.
virtual int setWatchdogMultiplier (BYTE watchdogmultiplier)
 Set watchdog interval (multiplier)
virtual int setWatchdogTime (BYTE watchdogtime)
 Set watchdog interval (time)
virtual int setWheelDiameter (double diameter)
 Set wheel diameter.
virtual int setZeroLengthSpring (double parameterInRad)
 Set zero length of the spring for series elastic actuation.
virtual ~C3mxl ()

Static Public Member Functions

static const char * translateErrorCode (int errorCode)

Protected Member Functions

int clip (const int value, const int min, const int max)
int clipToMaxDWord (int value)
int clipToMaxWord (int value)
WORD internalAccelerationToMxlAcceleration (double acceleration)
WORD internalAmplitudeToMxlAmplitude (double amplitude)
WORD internalCurrentToMxlCurrent (double current)
WORD internalFreqToMxlFreq (double frequency)
WORD internalLinearAccelerationToMxlLinearAcceleration (double acceleration)
DWORD internalLinearPosToMxlLinearPos (double pos)
WORD internalLinearSpeedToMxlLinearSpeed (double speed)
WORD internalPhaseToMxlPhase (double phase)
WORD internalPosToMxlPos (double pos)
WORD internalPWMToMxlPWM (double current)
WORD internalSpeedToMxlSpeed (double speed)
WORD internalTorqueToMxlTorque (double torque)
WORD internalVoltageToMxlVoltage (double voltage)
double mxlAccelerationToInternalAcceleration (WORD acceleration)
double mxlCurrentToInternalCurrent (WORD current)
double mxlLinearAccelerationToInternalLinearAcceleration (WORD acceleration)
double mxlLinearPosToInternalLinearPos (DWORD pos)
double mxlLinearSpeedToInternalLinearSpeed (WORD speed)
double mxlPosToInternalPos (WORD pos)
double mxlPWMToInternalPWM (WORD current)
double mxlSpeedToInternalSpeed (WORD speed)
double mxlTorqueToInternalTorque (WORD torque)
double mxlVoltageToInternalVoltage (WORD voltage)
int round (double val)

Protected Attributes

double mAcceleration
double mAnalog1Voltage
double mAnalog2Voltage
double mAnalog3Voltage
double mAnalog4Voltage
double mBusVoltage
CDxlConfig mConfig
double mCurrent
double mCurrentADCVoltage
double mLinearAcceleration
double mLinearPosition
CLog2 mLog
unsigned char mMotorInitialized
TMxlLog mMxlLog
BYTE mMxlMode
double mPosition
double mSpeed
unsigned char mStatus
double mTorque
double mVoltage

Detailed Description

This class interfaces a 3mxl all settings are directly given to the 3mxl if possible. Status information is cached in this object

Definition at line 84 of file 3mxl.h.


Constructor & Destructor Documentation

Definition at line 25 of file 3mxl.cpp.

C3mxl::~C3mxl ( ) [virtual]

Definition at line 36 of file 3mxl.cpp.


Member Function Documentation

int C3mxl::changeID ( const int  newID) [virtual]

Change hardware motor ID.

Actually sets the new ID in the hardware.

Parameters:
newIDNew ID.

Reimplemented from CDxlGeneric.

Definition at line 815 of file 3mxl.cpp.

int C3mxl::clip ( const int  value,
const int  min,
const int  max 
) [inline, protected]

Definition at line 149 of file 3mxl.h.

int C3mxl::clipToMaxDWord ( int  value) [protected]

Definition at line 218 of file 3mxl.cpp.

int C3mxl::clipToMaxWord ( int  value) [protected]

Definition at line 203 of file 3mxl.cpp.

int C3mxl::get3MxlMode ( ) [virtual]

Read behavioral mode of the 3mxl.

Reimplemented from CDxlGeneric.

Definition at line 469 of file 3mxl.cpp.

int C3mxl::getAcceleration ( ) [virtual]

Read acceleration from hardware.

See also:
presentAcceleration().

Reimplemented from CDxlGeneric.

Definition at line 481 of file 3mxl.cpp.

int C3mxl::getBusVoltage ( ) [virtual]

Read bus voltage from hardware.

See also:
presentBusVoltage().

Reimplemented from CDxlGeneric.

Definition at line 986 of file 3mxl.cpp.

int C3mxl::getCurrent ( ) [virtual]

Read current from hardware.

See also:
presentCurrent().

Reimplemented from CDxlGeneric.

Definition at line 1023 of file 3mxl.cpp.

int C3mxl::getID ( ) [inline, 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.

Implements CDxlGeneric.

Definition at line 198 of file 3mxl.h.

int C3mxl::getLinearAcceleration ( ) [virtual]

Read linear acceleration from hardware.

See also:
presentLinearAcceleration().

Reimplemented from CDxlGeneric.

Definition at line 497 of file 3mxl.cpp.

int C3mxl::getLinearPos ( ) [virtual]

Read linear position from hardware.

See also:
presentLinearPos().

Reimplemented from CDxlGeneric.

Definition at line 909 of file 3mxl.cpp.

int C3mxl::getLog ( ) [virtual]

Read logfile from hardware.

logfile from hardware to memory. Get a pointer to this array with presentLog().

Reimplemented from CDxlGeneric.

Definition at line 1067 of file 3mxl.cpp.

int C3mxl::getPIDCurrent ( double &  p,
double &  d,
double &  i,
double &  i_limit 
) [virtual]

Get PID gains for current control mode.

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

Reimplemented from CDxlGeneric.

Definition at line 1408 of file 3mxl.cpp.

int C3mxl::getPIDEnergy ( double &  p,
double &  d,
double &  i,
double &  i_limit 
) [virtual]

Get PID gains for energy control mode.

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

Reimplemented from CDxlGeneric.

Definition at line 1492 of file 3mxl.cpp.

int C3mxl::getPIDPosition ( double &  p,
double &  d,
double &  i,
double &  i_limit 
) [virtual]

Get PID gains for position control mode.

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

Reimplemented from CDxlGeneric.

Definition at line 1429 of file 3mxl.cpp.

int C3mxl::getPIDSpeed ( double &  p,
double &  d,
double &  i,
double &  i_limit 
) [virtual]

Get PID gains for speed control mode.

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

Reimplemented from CDxlGeneric.

Definition at line 1450 of file 3mxl.cpp.

int C3mxl::getPIDTorque ( double &  p,
double &  d,
double &  i,
double &  i_limit 
) [virtual]

Get PID gains for torque control mode.

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

Reimplemented from CDxlGeneric.

Definition at line 1471 of file 3mxl.cpp.

int C3mxl::getPos ( ) [virtual]

Read position from hardware.

See also:
presentPos().

Reimplemented from CDxlGeneric.

Definition at line 892 of file 3mxl.cpp.

int C3mxl::getPosAndSpeed ( ) [virtual]

Read position and speed from hardware.

See also:
presentPos(), presentSpeed().

Reimplemented from CDxlGeneric.

Definition at line 948 of file 3mxl.cpp.

int C3mxl::getSensorVoltages ( ) [virtual]

Read analog sensor voltages from hardware.

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

Reimplemented from CDxlGeneric.

Definition at line 1001 of file 3mxl.cpp.

int C3mxl::getState ( ) [virtual]

Read entire state from hardware.

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

Reimplemented from CDxlGeneric.

Definition at line 842 of file 3mxl.cpp.

int C3mxl::getStatus ( ) [virtual]

Read status from hardware.

Reimplemented from CDxlGeneric.

Definition at line 1052 of file 3mxl.cpp.

int C3mxl::getTorque ( ) [virtual]

Read torque from hardware.

See also:
presentTorque().

Reimplemented from CDxlGeneric.

Definition at line 1038 of file 3mxl.cpp.

int C3mxl::getTorquePosSpeed ( ) [virtual]

Read torque, position and speed from hardware.

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

Reimplemented from CDxlGeneric.

Definition at line 926 of file 3mxl.cpp.

int C3mxl::getVoltage ( ) [virtual]

Read motor voltage from hardware.

See also:
presentVoltage().

Reimplemented from CDxlGeneric.

Definition at line 971 of file 3mxl.cpp.

int C3mxl::init ( bool  sendConfigToMotor = true) [virtual]

Initialize this Dynamixel.

Warning:
Make sure you call setConfig() before calling init()!
Parameters:
sendConfigToMotorSend configuration to motor

Reimplemented from CDxlGeneric.

Definition at line 742 of file 3mxl.cpp.

WORD C3mxl::internalAccelerationToMxlAcceleration ( double  acceleration) [protected]

Definition at line 120 of file 3mxl.cpp.

WORD C3mxl::internalAmplitudeToMxlAmplitude ( double  amplitude) [protected]

Definition at line 180 of file 3mxl.cpp.

WORD C3mxl::internalCurrentToMxlCurrent ( double  current) [protected]

Definition at line 72 of file 3mxl.cpp.

WORD C3mxl::internalFreqToMxlFreq ( double  frequency) [protected]

Definition at line 174 of file 3mxl.cpp.

WORD C3mxl::internalLinearAccelerationToMxlLinearAcceleration ( double  acceleration) [protected]

Definition at line 156 of file 3mxl.cpp.

DWORD C3mxl::internalLinearPosToMxlLinearPos ( double  pos) [protected]

Definition at line 132 of file 3mxl.cpp.

WORD C3mxl::internalLinearSpeedToMxlLinearSpeed ( double  speed) [protected]

Definition at line 144 of file 3mxl.cpp.

WORD C3mxl::internalPhaseToMxlPhase ( double  phase) [protected]

Definition at line 186 of file 3mxl.cpp.

WORD C3mxl::internalPosToMxlPos ( double  pos) [protected]

Definition at line 96 of file 3mxl.cpp.

WORD C3mxl::internalPWMToMxlPWM ( double  current) [protected]

Definition at line 198 of file 3mxl.cpp.

WORD C3mxl::internalSpeedToMxlSpeed ( double  speed) [protected]

Definition at line 108 of file 3mxl.cpp.

WORD C3mxl::internalTorqueToMxlTorque ( double  torque) [protected]

Definition at line 168 of file 3mxl.cpp.

WORD C3mxl::internalVoltageToMxlVoltage ( double  voltage) [protected]

Definition at line 84 of file 3mxl.cpp.

int C3mxl::interpretControlData ( BYTE  address,
BYTE  length,
BYTE *  data 
) [virtual]

Interpret data read from control table.

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

Reimplemented from CDxlGeneric.

Definition at line 1547 of file 3mxl.cpp.

double C3mxl::mxlAccelerationToInternalAcceleration ( WORD  acceleration) [protected]

Definition at line 114 of file 3mxl.cpp.

double C3mxl::mxlCurrentToInternalCurrent ( WORD  current) [protected]

Definition at line 66 of file 3mxl.cpp.

double C3mxl::mxlLinearAccelerationToInternalLinearAcceleration ( WORD  acceleration) [protected]

Definition at line 150 of file 3mxl.cpp.

double C3mxl::mxlLinearPosToInternalLinearPos ( DWORD  pos) [protected]

Definition at line 126 of file 3mxl.cpp.

double C3mxl::mxlLinearSpeedToInternalLinearSpeed ( WORD  speed) [protected]

Definition at line 138 of file 3mxl.cpp.

double C3mxl::mxlPosToInternalPos ( WORD  pos) [protected]

Definition at line 90 of file 3mxl.cpp.

double C3mxl::mxlPWMToInternalPWM ( WORD  current) [protected]

Definition at line 192 of file 3mxl.cpp.

double C3mxl::mxlSpeedToInternalSpeed ( WORD  speed) [protected]

Definition at line 102 of file 3mxl.cpp.

double C3mxl::mxlTorqueToInternalTorque ( WORD  torque) [protected]

Definition at line 162 of file 3mxl.cpp.

double C3mxl::mxlVoltageToInternalVoltage ( WORD  voltage) [protected]

Definition at line 78 of file 3mxl.cpp.

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

Get behavioral mode of the 3mxl.

See also:
3mxl control modes for address M3XL_CONTROL_MODE.

Reimplemented from CDxlGeneric.

Definition at line 308 of file 3mxl.h.

virtual double C3mxl::presentAcceleration ( ) [inline, virtual]

Get cached acceleration.

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

Implements CDxlGeneric.

Definition at line 286 of file 3mxl.h.

virtual double C3mxl::presentAnalog1Voltage ( ) [inline, virtual]

Get cached analog sensor 1 voltage.

Returns:
Sensor voltage in [V].

Implements CDxlGeneric.

Definition at line 292 of file 3mxl.h.

virtual double C3mxl::presentAnalog2Voltage ( ) [inline, virtual]

Get cached analog sensor 2 voltage.

Returns:
Sensor voltage in [V].

Implements CDxlGeneric.

Definition at line 293 of file 3mxl.h.

virtual double C3mxl::presentAnalog3Voltage ( ) [inline, virtual]

Get cached analog sensor 3 voltage.

Returns:
Sensor voltage in [V].

Implements CDxlGeneric.

Definition at line 294 of file 3mxl.h.

virtual double C3mxl::presentAnalog4Voltage ( ) [inline, virtual]

Get cached analog sensor 4 voltage.

Returns:
Sensor voltage in [V].

Implements CDxlGeneric.

Definition at line 295 of file 3mxl.h.

double C3mxl::presentAngleLowerLimit ( ) [inline, virtual]

Get cached lower angle limit.

Returns:
Lower angle limit in [rad].

Implements CDxlGeneric.

Definition at line 304 of file 3mxl.h.

double C3mxl::presentAngleUpperLimit ( ) [inline, virtual]

Get cached upper angle limit.

Returns:
Upper angle limit in [rad].

Implements CDxlGeneric.

Definition at line 305 of file 3mxl.h.

virtual double C3mxl::presentBusVoltage ( ) [inline, virtual]

Get cached bus voltage.

Returns:
Bus voltage in [V].

Implements CDxlGeneric.

Definition at line 290 of file 3mxl.h.

WORD C3mxl::presentCCWAngleLimit ( ) [inline, virtual]

Get cached counter-clockwise angle limit.

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

Implements CDxlGeneric.

Definition at line 303 of file 3mxl.h.

virtual double C3mxl::presentCurrent ( ) [inline, virtual]

Get cached current.

Returns:
Current in [A].

Implements CDxlGeneric.

Definition at line 297 of file 3mxl.h.

virtual double C3mxl::presentCurrentADCVoltage ( ) [inline, virtual]

Get cached motor current ADC voltage.

Returns:
ADC voltage in [V].

Implements CDxlGeneric.

Definition at line 291 of file 3mxl.h.

WORD C3mxl::presentCWAngleLimit ( ) [inline, virtual]

Get cached clockwise angle limit.

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

Implements CDxlGeneric.

Definition at line 302 of file 3mxl.h.

virtual double C3mxl::presentLinearAcceleration ( ) [inline, virtual]

Get cached linear acceleration.

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

Implements CDxlGeneric.

Definition at line 287 of file 3mxl.h.

virtual double C3mxl::presentLinearPos ( ) [inline, virtual]

Get cached linear position.

Returns:
Position in [m].

Implements CDxlGeneric.

Definition at line 284 of file 3mxl.h.

virtual double C3mxl::presentLoad ( ) [inline, virtual]

Get cached load value.

Returns:
Load in [Nm].

Implements CDxlGeneric.

Definition at line 288 of file 3mxl.h.

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

Get cached log string/file.

Returns:
a vector of log entries.

Reimplemented from CDxlGeneric.

Definition at line 307 of file 3mxl.h.

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

Get motor initialization state.

Returns:
Whether the motor executed the initialization procedure.

Reimplemented from CDxlGeneric.

Definition at line 300 of file 3mxl.h.

virtual double C3mxl::presentPos ( ) [inline, virtual]

Get cached position.

Returns:
Position in [rad].

Implements CDxlGeneric.

Definition at line 283 of file 3mxl.h.

virtual double C3mxl::presentSpeed ( ) [inline, virtual]

Get cached speed.

Returns:
Speed in [rad/s].

Implements CDxlGeneric.

Definition at line 285 of file 3mxl.h.

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

Get cached status.

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

Reimplemented from CDxlGeneric.

Definition at line 299 of file 3mxl.h.

virtual double C3mxl::presentTemp ( ) [inline, virtual]

Get cached temperature.

Returns:
Temperature in [deg. C].

Implements CDxlGeneric.

Definition at line 296 of file 3mxl.h.

virtual double C3mxl::presentTorque ( ) [inline, virtual]

Get cached torque.

Returns:
Torque in [Nm].

Implements CDxlGeneric.

Definition at line 298 of file 3mxl.h.

virtual double C3mxl::presentVoltage ( ) [inline, virtual]

Get cached motor voltage.

Returns:
Motor voltage in [V].

Implements CDxlGeneric.

Definition at line 289 of file 3mxl.h.

int C3mxl::printReport ( FILE *  fOut) [virtual]

Report on this Dynamixel.

Reads out the motor's complete control table.

Parameters:
fOutOutput file.

Reimplemented from CDxlGeneric.

Definition at line 1520 of file 3mxl.cpp.

int C3mxl::round ( double  val) [inline, protected]

Definition at line 159 of file 3mxl.h.

int C3mxl::set3MxlMode ( BYTE  mxlMode,
bool  shouldSyncWrite = false 
) [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 from CDxlGeneric.

Definition at line 454 of file 3mxl.cpp.

int C3mxl::setAcceleration ( double  acceleration,
bool  shouldSyncWrite = false 
) [virtual]

Set acceleration for trajectory generation.

Parameters:
accelerationAcceleration in [rad/s^2].
shouldSyncWriteAccumulate data instead of sending immediately.

Reimplemented from CDxlGeneric.

Definition at line 1212 of file 3mxl.cpp.

int C3mxl::setAngleLimits ( double  lowerLimit,
double  upperLimit 
) [virtual]

Set angle limits.

Parameters:
lowerLimitLower angle limit in [rad].
upperLimitUpper angle limit in [rad].

Reimplemented from CDxlGeneric.

Definition at line 663 of file 3mxl.cpp.

int C3mxl::setAngleLowerLimit ( double  limit) [virtual]

Set lower angle limit.

Parameters:
limitLower angle limit in [rad].

Reimplemented from CDxlGeneric.

Definition at line 623 of file 3mxl.cpp.

int C3mxl::setAngleUpperLimit ( double  limit) [virtual]

Set upper angle limit.

Parameters:
limitUpper angle limit in [rad].

Reimplemented from CDxlGeneric.

Definition at line 634 of file 3mxl.cpp.

int C3mxl::setBaudRate ( const int  baudRate) [virtual]

Set baud rate in bits/s.

Parameters:
baudRateBaudrate in [bit/s].

Reimplemented from CDxlGeneric.

Definition at line 577 of file 3mxl.cpp.

void C3mxl::setConfig ( CDxlConfig config) [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 from CDxlGeneric.

Definition at line 233 of file 3mxl.cpp.

int C3mxl::setCurrent ( double  current,
bool  shouldSyncWrite = false 
) [virtual]

Set reference current.

Parameters:
currentCurrent in [A]
shouldSyncWriteAccumulate data instead of sending immediately.

Reimplemented from CDxlGeneric.

Definition at line 1247 of file 3mxl.cpp.

int C3mxl::setEncoderCountJoint ( WORD  encodercount) [virtual]

Joint encoder counts per revolution.

Parameters:
encodercountCounts per revolution

Reimplemented from CDxlGeneric.

Definition at line 347 of file 3mxl.cpp.

int C3mxl::setEncoderCountMotor ( WORD  encodercount) [virtual]

Motor encoder counts per revolution.

Parameters:
encodercountCounts per revolution

Reimplemented from CDxlGeneric.

Definition at line 337 of file 3mxl.cpp.

int C3mxl::setEncoderIndexLevelMotor ( BYTE  level) [virtual]

Set motor encoder index pulse signal level.

Parameters:
levelLow (0) or high (1) index pulse signal.

Reimplemented from CDxlGeneric.

Definition at line 400 of file 3mxl.cpp.

int C3mxl::setGearboxRatioJoint ( float  gearboxratiojoint) [virtual]

Ratio between joint and joint encoder.

Parameters:
gearboxratiojointturns of encoder for one joint revolution.

Reimplemented from CDxlGeneric.

Definition at line 438 of file 3mxl.cpp.

int C3mxl::setGearboxRatioMotor ( float  gearboxratiomotor) [virtual]

Ratio between motor and joint.

Parameters:
gearboxratiomotorturns of motor for one joint revolution.

Reimplemented from CDxlGeneric.

Definition at line 422 of file 3mxl.cpp.

int C3mxl::setInitialTorqueLimit ( double  absMaxTorque) [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 from CDxlGeneric.

Definition at line 601 of file 3mxl.cpp.

int C3mxl::setJointOffset ( double  offset) [virtual]

Set joint null angle offset.

Parameters:
offsetOffset in [rad].

Reimplemented from CDxlGeneric.

Definition at line 326 of file 3mxl.cpp.

int C3mxl::setLinearAcceleration ( double  acceleration,
bool  shouldSyncWrite = false 
) [virtual]

Set linear acceleration for trajectory generation.

Parameters:
accelerationAcceleration in [m/s^2].
shouldSyncWriteAccumulate data instead of sending immediately.

Reimplemented from CDxlGeneric.

Definition at line 1224 of file 3mxl.cpp.

int C3mxl::setLinearPos ( double  pos,
bool  shouldSyncWrite = false 
) [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 from CDxlGeneric.

Definition at line 1106 of file 3mxl.cpp.

int C3mxl::setLinearPos ( double  pos,
double  absSpeed,
bool  shouldSyncWrite = false 
) [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 from CDxlGeneric.

Definition at line 1134 of file 3mxl.cpp.

int C3mxl::setLinearPos ( double  pos,
double  absSpeed,
double  acceleration,
bool  shouldSyncWrite = false 
) [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 from CDxlGeneric.

Definition at line 1169 of file 3mxl.cpp.

int C3mxl::setLinearSpeed ( double  speed,
bool  shouldSyncWrite = false 
) [virtual]

Set linear reference speed.

Parameters:
speedSpeed in [m/s]. Speed can be positive or negative.
shouldSyncWriteAccumulate data instead of sending immediately.

Reimplemented from CDxlGeneric.

Definition at line 1200 of file 3mxl.cpp.

int C3mxl::setLogInterval ( BYTE  interval) [virtual]

Set logging interval.

Note:
Call this to make sure you're logging for the right motor.
Parameters:
intervallogging interval in [ms].

Reimplemented from CDxlGeneric.

Definition at line 868 of file 3mxl.cpp.

int C3mxl::setMaxContinuousMotorCurrent ( double  current) [virtual]

Set maximum motor continuous current.

Parameters:
currentMaxmimum continuous current in [A].

Reimplemented from CDxlGeneric.

Definition at line 378 of file 3mxl.cpp.

int C3mxl::setMaxPeakMotorCurrent ( double  current) [virtual]

Set maximum motor peak current.

Parameters:
currentMaxmimum peak current in [A].

Reimplemented from CDxlGeneric.

Definition at line 367 of file 3mxl.cpp.

int C3mxl::setMotorConstant ( WORD  motorconstant) [virtual]

Set motor constant.

Parameters:
motorconstantMotor constant in [10^-4 Nm/A].

Reimplemented from CDxlGeneric.

Definition at line 357 of file 3mxl.cpp.

int C3mxl::setMotorOffset ( double  offset) [virtual]

Set motor null angle offset.

Parameters:
offsetOffset in [rad].

Reimplemented from CDxlGeneric.

Definition at line 316 of file 3mxl.cpp.

int C3mxl::setMotorWindingTimeConstant ( double  time) [virtual]

Set motor winding time constant.

Parameters:
timeMotor winding temperature time constant in [s].

Reimplemented from CDxlGeneric.

Definition at line 389 of file 3mxl.cpp.

int C3mxl::setPIDCurrent ( double  p,
double  d,
double  i,
double  i_limit,
bool  shouldSyncWrite = false 
) [virtual]

Set PID for current control mode.

The error is in SI units ([A]), and the output range of the control equation is [-1, 1].

Parameters:
pProportional gain
dDerivative gain
iIntegral gain
i_limitIntegration limit
shouldSyncWriteAccumulate data instead of sending immediately.

Reimplemented from CDxlGeneric.

Definition at line 1327 of file 3mxl.cpp.

int C3mxl::setPIDEnergy ( double  p,
double  d,
double  i,
double  i_limit,
bool  shouldSyncWrite = false 
) [virtual]

Set PID for energy control mode.

The error is in SI units ([J]), and the output range of the control equation is [-1, 1].

Parameters:
pProportional gain
dDerivative gain
iIntegral gain
i_limitIntegration limit
shouldSyncWriteAccumulate data instead of sending immediately.

Reimplemented from CDxlGeneric.

Definition at line 1392 of file 3mxl.cpp.

int C3mxl::setPIDPosition ( double  p,
double  d,
double  i,
double  i_limit,
bool  shouldSyncWrite = false 
) [virtual]

Set PID for position control mode.

The error is in SI units ([rad]), and the output range of the control equation is [-1, 1].

Parameters:
pProportional gain
dDerivative gain
iIntegral gain
i_limitIntegration limit
shouldSyncWriteAccumulate data instead of sending immediately.

Reimplemented from CDxlGeneric.

Definition at line 1344 of file 3mxl.cpp.

int C3mxl::setPIDSpeed ( double  p,
double  d,
double  i,
double  i_limit,
bool  shouldSyncWrite = false 
) [virtual]

Set PID for speed control mode.

The error is in SI units ([rad/s]), and the output range of the control equation is [-1, 1].

Parameters:
pProportional gain
dDerivative gain
iIntegral gain
i_limitIntegration limit
shouldSyncWriteAccumulate data instead of sending immediately.

Reimplemented from CDxlGeneric.

Definition at line 1360 of file 3mxl.cpp.

int C3mxl::setPIDTorque ( double  p,
double  d,
double  i,
double  i_limit,
bool  shouldSyncWrite = false 
) [virtual]

Set PID for torque control mode.

The error is in SI units ([Nm]), and the output range of the control equation is [-1, 1].

Parameters:
pProportional gain
dDerivative gain
iIntegral gain
i_limitIntegration limit
shouldSyncWriteAccumulate data instead of sending immediately.

Reimplemented from CDxlGeneric.

Definition at line 1376 of file 3mxl.cpp.

int C3mxl::setPos ( double  pos,
bool  shouldSyncWrite = false 
) [virtual]

Set reference position.

Parameters:
posPosition in [rad]
shouldSyncWriteAccumulate data instead of sending immediately.

Reimplemented from CDxlGeneric.

Definition at line 1094 of file 3mxl.cpp.

int C3mxl::setPos ( double  pos,
double  absSpeed,
bool  shouldSyncWrite = false 
) [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 from CDxlGeneric.

Definition at line 1118 of file 3mxl.cpp.

int C3mxl::setPos ( double  pos,
double  absSpeed,
double  acceleration,
bool  shouldSyncWrite = false 
) [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 from CDxlGeneric.

Definition at line 1151 of file 3mxl.cpp.

void C3mxl::setPositiveDirection ( bool  clockwiseIsPositive) [virtual]

Set direction convention.

Parameters:
clockwiseIsPositiveTrue if clockwise direction is positive

Reimplemented from CDxlGeneric.

Definition at line 280 of file 3mxl.cpp.

int C3mxl::setPositiveDirectionJoint ( bool  clockwiseIsPositive) [virtual]

Set joint direction convention.

Parameters:
clockwiseIsPositiveTrue if clockwise direction is positive

Reimplemented from CDxlGeneric.

Definition at line 301 of file 3mxl.cpp.

int C3mxl::setPositiveDirectionMotor ( bool  clockwiseIsPositive) [virtual]

Set motor direction convention.

Parameters:
clockwiseIsPositiveTrue if clockwise direction is positive

Reimplemented from CDxlGeneric.

Definition at line 285 of file 3mxl.cpp.

int C3mxl::setPosSpeedTorquePPosDPos ( double  pos,
double  speed,
double  torque,
int  pPos,
int  dPos,
bool  shouldSyncWrite = false 
) [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 from CDxlGeneric.

Definition at line 1305 of file 3mxl.cpp.

int C3mxl::setPWM ( double  pwm,
bool  shouldSyncWrite = false 
) [virtual]

Set pulse width modulation duty cycle.

Parameters:
pwmPWM duty cycle, between -1 and 1.
shouldSyncWriteAccumulate data instead of sending immediately.

Reimplemented from CDxlGeneric.

Definition at line 1258 of file 3mxl.cpp.

int C3mxl::setReferenceEnergy ( double  energy) [virtual]

Set reference energy for energy control.

Parameters:
energyReference energy in [J]

Reimplemented from CDxlGeneric.

Definition at line 704 of file 3mxl.cpp.

int C3mxl::setRetlevel ( const int  returnlevel) [virtual]

Set status return level.

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

Reimplemented from CDxlGeneric.

Definition at line 564 of file 3mxl.cpp.

int C3mxl::setReturnDelayTime ( const int  microsecondsReturnDelay) [virtual]

Set return delay.

Delay between transmission of Instruction Packet until the return of Status Packet.

Parameters:
microsecondsReturnDelayReturn delay in [us].

Reimplemented from CDxlGeneric.

Definition at line 588 of file 3mxl.cpp.

void C3mxl::setSerialPort ( LxSerial serialPort) [virtual]

Set serial port.

serialPort Serial port.

Reimplemented from CDxlGeneric.

Definition at line 273 of file 3mxl.cpp.

int C3mxl::setSineAmplitude ( double  amplitude,
bool  shouldSyncWrite = false 
) [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 from CDxlGeneric.

Definition at line 1281 of file 3mxl.cpp.

int C3mxl::setSineFrequency ( double  frequency,
bool  shouldSyncWrite = false 
) [virtual]

Set sine frequency.

Note:
Starts the motor.
Parameters:
frequencyFrequency in [Hz]
shouldSyncWriteAccumulate data instead of sending immediately.

Reimplemented from CDxlGeneric.

Definition at line 1269 of file 3mxl.cpp.

int C3mxl::setSinePhase ( double  phase,
bool  shouldSyncWrite = false 
) [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 from CDxlGeneric.

Definition at line 1293 of file 3mxl.cpp.

int C3mxl::setSpeed ( double  speed,
bool  shouldSyncWrite = false 
) [virtual]

Set reference speed.

Parameters:
speedSpeed in [rad/s]. Speed can be positive or negative.
shouldSyncWriteAccumulate data instead of sending immediately.

Reimplemented from CDxlGeneric.

Definition at line 1187 of file 3mxl.cpp.

int C3mxl::setSpringStiffness ( double  stiffness) [virtual]

Set spring stiffness for series elastic actuation.

Parameters:
stiffnessSpring stiffness in [Nm/rad]

Reimplemented from CDxlGeneric.

Definition at line 691 of file 3mxl.cpp.

int C3mxl::setSyncReadIndex ( BYTE  index) [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 from CDxlGeneric.

Definition at line 882 of file 3mxl.cpp.

int C3mxl::setTorque ( double  torque,
bool  shouldSyncWrite = false 
) [virtual]

Set reference torque.

Parameters:
torqueTorque in [Nm]
shouldSyncWriteAccumulate data instead of sending immediately.

Reimplemented from CDxlGeneric.

Definition at line 1236 of file 3mxl.cpp.

int C3mxl::setTorqueLimit ( double  absMaxTorque) [virtual]

Set operational torque limit (RAM).

Parameters:
absMaxTorqueTorque limit as fraction of maximum possible torque.

Reimplemented from CDxlGeneric.

Definition at line 612 of file 3mxl.cpp.

int C3mxl::setWatchdogMode ( BYTE  watchdogmode) [virtual]

What to do if watchdog triggers.

Parameters:
watchdogmodeUnused

Reimplemented from CDxlGeneric.

Definition at line 513 of file 3mxl.cpp.

int C3mxl::setWatchdogMultiplier ( BYTE  watchdogmultiplier) [virtual]

Set watchdog interval (multiplier)

Parameters:
watchdogmultiplierWatchdog interval = time * multiplier.

Reimplemented from CDxlGeneric.

Definition at line 533 of file 3mxl.cpp.

int C3mxl::setWatchdogTime ( BYTE  watchdogtime) [virtual]

Set watchdog interval (time)

Parameters:
watchdogtimeWatchdog interval = time * multiplier.

Reimplemented from CDxlGeneric.

Definition at line 523 of file 3mxl.cpp.

int C3mxl::setWheelDiameter ( double  diameter) [virtual]

Set wheel diameter.

Parameters:
diameterWheel diameter in [m].

Reimplemented from CDxlGeneric.

Definition at line 410 of file 3mxl.cpp.

int C3mxl::setZeroLengthSpring ( double  parameterInRad) [virtual]

Set zero length of the spring for series elastic actuation.

Parameters:
parameterInRadZero length in [rad].

Reimplemented from CDxlGeneric.

Definition at line 680 of file 3mxl.cpp.

const char * C3mxl::translateErrorCode ( int  errorCode) [static]
Returns:
Human-readable error code

Reimplemented from CDxlCom.

Definition at line 40 of file 3mxl.cpp.


Member Data Documentation

double C3mxl::mAcceleration [protected]

Definition at line 104 of file 3mxl.h.

double C3mxl::mAnalog1Voltage [protected]

Definition at line 95 of file 3mxl.h.

double C3mxl::mAnalog2Voltage [protected]

Definition at line 96 of file 3mxl.h.

double C3mxl::mAnalog3Voltage [protected]

Definition at line 97 of file 3mxl.h.

double C3mxl::mAnalog4Voltage [protected]

Definition at line 98 of file 3mxl.h.

double C3mxl::mBusVoltage [protected]

Definition at line 93 of file 3mxl.h.

Definition at line 89 of file 3mxl.h.

double C3mxl::mCurrent [protected]

Definition at line 99 of file 3mxl.h.

double C3mxl::mCurrentADCVoltage [protected]

Definition at line 94 of file 3mxl.h.

double C3mxl::mLinearAcceleration [protected]

Definition at line 105 of file 3mxl.h.

double C3mxl::mLinearPosition [protected]

Definition at line 102 of file 3mxl.h.

CLog2 C3mxl::mLog [protected]

Reimplemented from CDxlGeneric.

Definition at line 90 of file 3mxl.h.

unsigned char C3mxl::mMotorInitialized [protected]

Definition at line 107 of file 3mxl.h.

TMxlLog C3mxl::mMxlLog [protected]

Definition at line 109 of file 3mxl.h.

BYTE C3mxl::mMxlMode [protected]

Definition at line 110 of file 3mxl.h.

double C3mxl::mPosition [protected]

Definition at line 101 of file 3mxl.h.

double C3mxl::mSpeed [protected]

Definition at line 103 of file 3mxl.h.

unsigned char C3mxl::mStatus [protected]

Definition at line 106 of file 3mxl.h.

double C3mxl::mTorque [protected]

Definition at line 100 of file 3mxl.h.

double C3mxl::mVoltage [protected]

Definition at line 92 of file 3mxl.h.


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


threemxl
Author(s):
autogenerated on Fri Aug 28 2015 13:21:08