HerkuleXLib  1.2
Arduino library to drive HerkuleX DRS-0101 and DRS-0201
Public Member Functions | Private Attributes | List of all members
HkxSetup Class Reference

Class to setup the servos. More...

#include <HkxSetup.h>

Public Member Functions

 HkxSetup (HkxCommunication &herkXCom, HkxPrint &print)
 Constructor. More...
 
uint8_t getServoInfo (uint8_t ID, HkxMaybe< uint16_t > model, HkxMaybe< uint16_t > version)
 Get model and firmware. More...
 
uint8_t getBaudRate (uint8_t ID, hkxBaudrate *baudRate)
 Get the baud rate. More...
 
uint8_t setAllBaudRate (const hkxBaudrate &baudrate)
 Set the baud rate for all. More...
 
uint8_t setID (uint8_t ID, uint8_t newID)
 Set ID. More...
 
uint8_t getPolicies (uint8_t ID, HkxMaybe< uint8_t > newAlarmLEDPolicy, HkxMaybe< uint8_t > newTorquePolicy)
 Get Policies. More...
 
uint8_t setOnePolicies (uint8_t ID, uint8_t newAlarmLEDPolicy, uint8_t newTorquePolicy)
 Set policies. More...
 
uint8_t setAllPolicies (uint8_t newAlarmLEDPolicy, uint8_t newTorquePolicy)
 Set policies for all. More...
 
uint8_t getTemperatureVoltage (uint8_t ID, HkxMaybe< int16_t > maxTemp, HkxMaybe< uint16_t > minVoltage, HkxMaybe< uint16_t > maxVoltage)
 Get temperature and voltage. More...
 
uint8_t setOneTemperatureVoltage (uint8_t ID, int16_t newMaxTemp, uint16_t newMinVoltage, uint16_t newMaxVoltage)
 Set temperature and voltage. More...
 
uint8_t setAllTemperatureVoltage (int16_t newMaxTemp, int16_t newMinVoltage, int16_t newMaxVoltage)
 Set temperature and voltage for all. More...
 
uint8_t getAcceleration (uint8_t ID, HkxMaybe< uint8_t > accelerationRatio, HkxMaybe< uint16_t > maxAccelerationTime)
 Get Acceleration. More...
 
uint8_t setOneAcceleration (uint8_t ID, uint8_t newAccelerationRatio, uint16_t newMaxAccelerationTime)
 Set Acceleration. More...
 
uint8_t setAllAcceleration (uint8_t newAccelerationRatio, uint16_t newMaxAccelerationTime)
 Set Acceleration for all. More...
 
uint8_t getLoadControl (uint8_t ID, HkxMaybe< uint16_t > deadZone, HkxMaybe< uint8_t > saturatorOffSet, HkxMaybe< uint32_t > saturatorSlope, HkxMaybe< int8_t > PWMoffset, HkxMaybe< uint8_t > minPWM, HkxMaybe< uint16_t > maxPWM)
 Get load control. More...
 
uint8_t setOneLoadControl (uint8_t ID, uint16_t newDeadZone, uint8_t newSaturatorOffset, const uint32_t &newSaturatorSlope, int8_t newPWMOffset, uint8_t newMinPWM, uint16_t newMaxPWM)
 Set load control parameters. More...
 
uint8_t setAllLoadControl (uint16_t newDeadZone, uint8_t newSaturatorOffset, const uint32_t &newSaturatorSlope, int8_t newPWMOffset, uint8_t newMinPWM, uint16_t newMaxPWM)
 Set load control parameters for all. More...
 
uint8_t getPWMPositionLimits (uint8_t ID, HkxMaybe< uint16_t > overlaodPWMThreshold, HkxMaybe< int16_t > minPosition, HkxMaybe< int16_t > maxPosition)
 Get PWM and position limits. More...
 
uint8_t setOnePWMPositionLimits (uint8_t ID, uint16_t newOverlaodPWMThreshold, int16_t newMinPosition, int16_t newMaxPosition)
 Set PWM and position limits. More...
 
uint8_t setAllPWMPositionLimits (uint16_t newOverlaodPWMThreshold, int16_t newMinPosition, int16_t newMaxPosition)
 Set PWM and position limits for all. More...
 
uint8_t getControlSystem (uint8_t ID, HkxMaybe< uint16_t > kProportionnal, HkxMaybe< uint16_t > kDerivative, HkxMaybe< uint16_t > kInteger, HkxMaybe< uint16_t > feedforwardGain1, HkxMaybe< uint16_t > feedforwardGain2)
 Get Control System. More...
 
uint8_t setOneControlSystem (uint8_t ID, uint16_t kProportionnal, uint16_t kDerivative, uint16_t kInteger, uint16_t feedforwardGain1, uint16_t feedforwardGain2)
 Set Control System. More...
 
uint8_t setAllControlSystem (uint16_t kProportionnal, uint16_t kDerivative, uint16_t kInteger, uint16_t feedforwardGain1, uint16_t feedforwardGain2)
 Set Control System for all. More...
 
uint8_t getErrorsCheckPeriod (uint8_t ID, HkxMaybe< uint16_t > LEDBlink, HkxMaybe< uint16_t > ADCFault, HkxMaybe< uint16_t > packetGarbage, HkxMaybe< uint16_t > stopDetection, HkxMaybe< uint16_t > overloadDetection)
 Get check periods. More...
 
uint8_t setOneErrorsCheckPeriod (uint8_t ID, uint16_t LEDBlink, uint16_t ADCFault, uint16_t packetGarbage, uint16_t stopDetection, uint16_t overloadDetection)
 Set check periods. More...
 
uint8_t setAllErrorsCheckPeriod (uint16_t LEDBlink, uint16_t ADCFault, uint16_t packetGarbage, uint16_t stopDetection, uint16_t overloadDetection)
 Set check periods for all. More...
 
uint8_t getInPositionCriteria (uint8_t ID, HkxMaybe< uint16_t > stopThreshold, HkxMaybe< uint16_t > inPositionMargin)
 Get in position criteria. More...
 
uint8_t setOneInPositionCriteria (uint8_t ID, uint16_t stopThreshold, uint16_t inPositionMargin)
 Set in position criteria. More...
 
uint8_t setAllInPositionCriteria (uint16_t stopThreshold, uint16_t inPositionMargin)
 Set in position criteria for all. More...
 
uint8_t getTorqueLEDControl (uint8_t ID, HkxMaybe< hkxTorqueControl > torqueControl, HkxMaybe< hkxLEDControl > LEDControl)
 Get torque actuation and LED colour. More...
 
uint8_t setOneTorqueLEDControl (uint8_t ID, hkxTorqueControl newTorqueControl, hkxLEDControl newLEDControl)
 Set torque actuation and LED colour. More...
 
uint8_t setAllTorqueLEDControl (hkxTorqueControl newTorqueControl, hkxLEDControl newLEDControl)
 Set torque actuation and LED colour for all. More...
 
uint8_t getBehaviour (uint8_t ID, HkxMaybe< uint16_t > voltage, HkxMaybe< uint16_t > temperature, HkxMaybe< hkxControlMode > controlMode, HkxMaybe< uint16_t > tick, HkxMaybe< int16_t > absolutePosition, HkxMaybe< int16_t > velocity, HkxMaybe< int16_t > PWM, HkxMaybe< int16_t > absoluteGoalPosition, HkxMaybe< int16_t > absoluteDesiredTrajectoryPosition, HkxMaybe< int16_t > desiredVelocity)
 Get behaviour. More...
 
uint8_t getStatus (uint8_t ID, HkxStatus &statusED)
 Get status. More...
 
uint8_t clearOneStatus (uint8_t ID)
 Clear status. More...
 
uint8_t clearAllStatus ()
 Clear status for all. More...
 
void scanIDs (boolean IDs[])
 Scan IDs. More...
 
uint8_t factoryResetOne (uint8_t ID, boolean IDskip, boolean baudrateSkip)
 Factory reset. More...
 
uint8_t factoryResetAll (boolean IDskip, boolean baudrateSkip)
 Factory reset for all. More...
 
uint8_t rebootOne (uint8_t ID)
 Reboot. More...
 
void rebootAll ()
 Reboot. More...
 

Private Attributes

HkxCommunication_herkXCom
 
HkxPrint_print
 

Detailed Description

Class to setup the servos.

This class allows to setup the servos.

Constructor & Destructor Documentation

HkxSetup::HkxSetup ( HkxCommunication herkXCom,
HkxPrint print 
)
inline

Constructor.

The constructor of HkxSetup.

Parameters
[in]herkXCom: Communication with the servos.
[in]print: Communication to print messages.

Member Function Documentation

uint8_t HkxSetup::clearAllStatus ( )
inline

Clear status for all.

Clear the status of the servo to leave the "error state" and stop the LED blink and torque deactivation.

Returns
0 = OK
1 = Input not correct
uint8_t HkxSetup::clearOneStatus ( uint8_t  ID)
inline

Clear status.

Clear the status of the servo to leave the "error state" and stop the LED blink and torque deactivation.

Parameters
[in]ID: ID of the servo to address the request. The value shall be [0 ; 254] (254 means all servos).
Returns
0 = OK
1 = Input not correct
uint8_t HkxSetup::factoryResetAll ( boolean  IDskip,
boolean  baudrateSkip 
)
inline

Factory reset for all.

Reset all the parameters to factory default values.

Parameters
[in]IDskip: If true, the ID is NOT reset. If false, the ID is reset.
[in]baudrateSkip: If true, the baud rate is NOT reset. If false, the baud rate is reset.
Returns
0 = OK
1 = Input not correct
uint8_t HkxSetup::factoryResetOne ( uint8_t  ID,
boolean  IDskip,
boolean  baudrateSkip 
)
inline

Factory reset.

Reset all the parameters to factory default values.

Parameters
[in]ID: ID of the servo to address the request. The value shall be [0 ; 253].
[in]IDskip: If true, the ID is NOT reset. If false, the ID is reset.
[in]baudrateSkip: If true, the baud rate is NOT reset. If false, the baud rate is reset.
Returns
0 = OK
1 = Input not correct
uint8_t HkxSetup::getAcceleration ( uint8_t  ID,
HkxMaybe< uint8_t >  accelerationRatio,
HkxMaybe< uint16_t >  maxAccelerationTime 
)

Get Acceleration.

Get the current acceleration parameters of the servo in the RAM. The servo generates a trapezoidal velocity trajectory profile (see figure below) according to play time given by the user (see for instance HkxPosControl.movePosition()) where: acceleration time = deceleration time = min (playtime x accelerationRatio / 100, maxAccelerationTime).

if (playtime x accelerationRatio / 100) < maxAccelerationTime   if (playtime x accelerationRatio / 100) > maxAccelerationTime
            V |                                                        V |          ______________                   
            e |         /*\                                            e |         /*            *\                      
            l |        / * \                                           l |        / *            * \                 
            o |       /  *  \                                          o |       /  *            *  \                
            c |      /   *   \                                         c |      /   *            *   \                   
            i |     /    *    \                                        i |     /    *            *    \                  
            t |    /     *     \                                       t |    /     *            *     \                 
            y |   /      *      \                                      y |   /      *            *      \                
              |  /       *       \                                       |  /       *            *       \               
              | /        *        \                                      | /        *            *        \              
              |/_________*_________\________ Time                        |/_________*____________*_________\________ Time
              < Acc time> <Dec time >                                    < Acc time >            < Dec time >            
              <----- Play time ----->                                    <----------- Play time ------------>            
Parameters
[in]ID: id of the servo to address the request. The value shall be [0 ; 253].
[out]accelerationRatio: Acceleration ratio considered to generate velocity trajectory. Its value is given in percent (%). This parameter is optional, either set the address of uint8_t (or byte) variable, or set HKX_NO_VALUE to ignore it.
[out]maxAccelerationTime: Maximum acceleration time to generate velocity trajectory. Its value is given in milliseconds. This parameter is optional, either set the address of uint16_t (or unsigned int) variable, or set HKX_NO_VALUE to ignore it.
Returns
0 = OK
1 = Input not correct
2 = Servo not connected
3 = Data not consistent
uint8_t HkxSetup::getBaudRate ( uint8_t  ID,
hkxBaudrate baudRate 
)

Get the baud rate.

Get the baud rate from the servo settings from EEP memory.

Parameters
[in]ID: id of the servo to address the request. The value shall be [0 ; 253].
[out]baudRate: Baud rate setup in the servo. This parameter is a point, then set the address of hkxBaudrate variable.
Returns
0 = OK
1 = Input not correct
2 = Servo not connected
3 = Data not consistent
uint8_t HkxSetup::getBehaviour ( uint8_t  ID,
HkxMaybe< uint16_t >  voltage,
HkxMaybe< uint16_t >  temperature,
HkxMaybe< hkxControlMode controlMode,
HkxMaybe< uint16_t >  tick,
HkxMaybe< int16_t >  absolutePosition,
HkxMaybe< int16_t >  velocity,
HkxMaybe< int16_t >  PWM,
HkxMaybe< int16_t >  absoluteGoalPosition,
HkxMaybe< int16_t >  absoluteDesiredTrajectoryPosition,
HkxMaybe< int16_t >  desiredVelocity 
)

Get behaviour.

Get the current behaviour of the servo.

Parameters
[in]ID: ID of the servo to address the request. The value shall be [0 ; 253].
[out]voltage: Current servo input voltage. Its value is given in millivolts. This parameter is optional, either set the address of a uint16_t (or unsigned int) variable to return the value, or set HKX_NO_VALUE to ignore it.
[out]temperature: Current temperature of the servo. Its value is given in 10^-2 °C (degree Celsius). This parameter is optional, either set the address of a uint16_t (or unsigned int) variable to return the value, or set HKX_NO_VALUE to ignore it.
[out]controlMode: Control mode of the current move, can be position control (HKX_CTRL_POSITION), or continuous rotation (HKX_CTRL_ROTATION). This parameter is optional, either set the address of a hkxControlMode variable to return the value, or set HKX_NO_VALUE to ignore it.
[out]tick: Current operating time of the servo. Its value is given in milliseconds). This parameter is optional, either set the address of a uint16_t (or unsigned int) variable to return the value, or set HKX_NO_VALUE to ignore it.
[out]absolutePosition: Current angle position of the servo. Its value is given in 10^-1 degrees. This parameter is optional, either set the address of a uint16_t (or unsigned int) variable to return the value, or set HKX_NO_VALUE to ignore it.
[out]velocity: Current angle velocity of the servo. Its value is given in degree / second. This parameter is optional, either set the address of a uint16_t (or unsigned int) variable to return the value, or set HKX_NO_VALUE to ignore it.
[out]PWM: Current PWM (load) of the servo. Its value is given in PWM (raw). This parameter is optional, either set the address of a int16_t (or int) variable to return the value, or set HKX_NO_VALUE to ignore it.
[out]absoluteGoalPosition: Goal position of the current move of the servo. Its value is given in 10^-1 degrees. This parameter is optional, either set the address of a uint16_t (or unsigned int) variable to return the value, or set HKX_NO_VALUE to ignore it.
[out]absoluteDesiredTrajectoryPosition: Current trajectory position - desired position at a given time according the trajectory - of the servo. Its value is given in 10^-1 degrees. This parameter is optional, either set the address of a uint16_t (or unsigned int) variable to return the value, or set HKX_NO_VALUE to ignore it.
[out]desiredVelocity: Current trajectory velocity - desired velocity at a given time according the trajectory - of the servo. Its value is given in degree / second. This parameter is optional, either set the address of a uint16_t (or unsigned int) variable to return the value, or set HKX_NO_VALUE to ignore it.
Returns
0 = OK
1 = Input not correct
2 = Servo not connected
3 = Data not consistent
uint8_t HkxSetup::getControlSystem ( uint8_t  ID,
HkxMaybe< uint16_t >  kProportionnal,
HkxMaybe< uint16_t >  kDerivative,
HkxMaybe< uint16_t >  kInteger,
HkxMaybe< uint16_t >  feedforwardGain1,
HkxMaybe< uint16_t >  feedforwardGain2 
)

Get Control System.

Get the current control system of the servo in the RAM.

Parameters
[in]ID: ID of the servo to address the request. The value shall be [0 ; 253].
[out]kProportionnal: Proportional gain, when its value increase, the response time decreases but may lead to over response (vibration, overshoot). Its value is given with no unit. This parameter is optional, either set the address of uint16_t (or unsigned int) variable, or set HKX_NO_VALUE to ignore it.
[out]kDerivative: Derivative gain, when its value increase, the over response is attenuated but may lead to instability. Its value is given with no unit. This parameter is optional, either set the address of uint16_t (or unsigned int) variable, or set HKX_NO_VALUE to ignore it.
[out]kInteger: Integral gain, when its value increase, reduce the position offset error in steady state but may lead response lag. Its value is given with no unit. This parameter is optional, either set the address of uint16_t (or unsigned int) variable, or set HKX_NO_VALUE to ignore it.
[out]feedforwardGain1: Position feed forward 1st gain, when its value increase, the response time decreases. Its value is given with no unit. This parameter is optional, either set the address of uint16_t (or unsigned int) variable, or set HKX_NO_VALUE to ignore it.
[out]feedforwardGain2: Position feed forward 2nd gain, when its value increase, the response time decreases. Its value is given with no unit. This parameter is optional, either set the address of uint16_t (or unsigned int) variable, or set HKX_NO_VALUE to ignore it.
Returns
0 = OK
1 = Input not correct
2 = Servo not connected
3 = Data not consistent
uint8_t HkxSetup::getErrorsCheckPeriod ( uint8_t  ID,
HkxMaybe< uint16_t >  LEDBlink,
HkxMaybe< uint16_t >  ADCFault,
HkxMaybe< uint16_t >  packetGarbage,
HkxMaybe< uint16_t >  stopDetection,
HkxMaybe< uint16_t >  overloadDetection 
)

Get check periods.

Get the current check periods for de different errors of the servo in the RAM.

Parameters
[in]ID: ID of the servo to address the request. The value shall be [0 ; 253].
[out]LEDBlink: Check period for the alarm LED policy to activate LED blinking. Its value is given in milliseconds. This parameter is optional, either set the address of uint16_t (or unsigned int) variable, or set HKX_NO_VALUE to ignore it.
[out]ADCFault: Check period for temperature and input voltage error (when temperature > max temperature or voltage < min voltage or voltage > max voltage). Its value is given in milliseconds. This parameter is optional, either set the address of uint16_t (or unsigned int) variable, or set HKX_NO_VALUE to ignore it.
[out]packetGarbage: Check period for incomplete packet error. Its value is given in milliseconds. This parameter is optional, either set the address of uint16_t (or unsigned int) variable, or set HKX_NO_VALUE to ignore it.
[out]stopDetection: Check period for the servo stoppage. Its value is given in milliseconds. This parameter is optional, either set the address of uint16_t (or unsigned int) variable, or set HKX_NO_VALUE to ignore it.
[out]overloadDetection: Check period for the overload PWM threshold. Its value is given in milliseconds. This parameter is optional, either set the address of uint16_t (or unsigned int) variable, or set HKX_NO_VALUE to ignore it.
Returns
0 = OK
1 = Input not correct
2 = Servo not connected
3 = Data not consistent
uint8_t HkxSetup::getInPositionCriteria ( uint8_t  ID,
HkxMaybe< uint16_t >  stopThreshold,
HkxMaybe< uint16_t >  inPositionMargin 
)

Get in position criteria.

Get the current in position criteria of the servo in the RAM.

Parameters
[in]ID: ID of the servo to address the request. The value shall be [0 ; 253].
[out]stopThreshold: Under this angle displacement, the servo is seen as not moving. Its value is given in 10^-1 degrees. This parameter is optional, either set the address of uint16_t (or unsigned int) variable, or set HKX_NO_VALUE to ignore it.
[out]inPositionMargin: Minimum angle distance to determine the goal position reached. Its value is given in 10^-1 degrees. This parameter is optional, either set the address of uint16_t (or unsigned int) variable, or set HKX_NO_VALUE to ignore it.
Returns
0 = OK
1 = Input not correct
2 = Servo not connected
3 = Data not consistent
uint8_t HkxSetup::getLoadControl ( uint8_t  ID,
HkxMaybe< uint16_t >  deadZone,
HkxMaybe< uint8_t >  saturatorOffSet,
HkxMaybe< uint32_t >  saturatorSlope,
HkxMaybe< int8_t >  PWMoffset,
HkxMaybe< uint8_t >  minPWM,
HkxMaybe< uint16_t >  maxPWM 
)

Get load control.

Get the current load control parameters of the servo in the RAM. The load control parameters define the saturation curve according to the figure below.

         PWM+
          |  ___________........................................ PWM max
          |             \
          |              \ Saturator slope
          |               \..................................... Saturator offset
          |                |<dead zone> <dead zone>
          |                |___________ ........................ PWM min
          |                            |
          |  --------------------------|------------------------ PWM offset
          |                            |__________
Position- |____________________________*__________|_____________ Position+
          |                          goal         |
          |                        position        \
          |                                         \__________
          |
         PWM- 
Parameters
[in]ID: ID of the servo to address the request. The value shall be [0 ; 253].
[out]deadZone: The dead zone is the angle error before the servo applies a load compensation to maintain its position (see the figure above). Its value is given in 10^-1 degrees. This parameter is optional, either set the address of uint16_t (or unsigned int) variable, or set HKX_NO_VALUE to ignore it.
[out]saturatorOffSet: The saturator offset is the step PWM value of the saturator once deadzone the position goes out of the dead zone (see the figure above). Its value is given set in PWM. This parameter is optional, either set the address of uint8_t (or byte) variable, or set HKX_NO_VALUE to ignore it.
[out]saturatorSlope: The saturator slop is a gradient of the saturator, going from the saturator offset and increasing gradually the PWM with the error position to the goal (see the above figure). It provides a flexible and elastic response of the servo to external forces. Its value is given in 10^-2 PWM / degree. This parameter is optional, either set the address of uint32_t (or unsigned long) variable, or set HKX_NO_VALUE to ignore it.
[out]PWMoffset: The PWM offset allows compensating permanent load (e.g. gravity) by shifting the saturator by the same value (see the above figure). Its value is given in PWM. This parameter is optional, either set the address of uint8_t (or byte) variable, or set HKX_NO_VALUE to ignore it.
[out]minPWM: The min PWM is the minimum PWM that is applied by the servo (see the above figure). As specified in the user manual p.37, this may lead to unstable system. The value is given in PWM. This parameter is optional, either set the address of uint8_t (or byte) variable, or set HKX_NO_VALUE to ignore it.
[out]maxPWM: The max PWM is the maximum PWM that is applied by the servo (see the above figure). It could be used to limit the load of the servo, to avoid damages or injuries for instance. The value is given in PWM. This parameter is optional, either set the address of uint16_t (or unsigned int) variable, or set HKX_NO_VALUE to ignore it.
Returns
0 = OK
1 = Input not correct
2 = Servo not connected
3 = Data not consistent
uint8_t HkxSetup::getPolicies ( uint8_t  ID,
HkxMaybe< uint8_t >  newAlarmLEDPolicy,
HkxMaybe< uint8_t >  newTorquePolicy 
)

Get Policies.

Get the current Alarm LED policy and Torque policy of the servo in the RAM.

Parameters
[in]ID: current id of the servo to address the request. The value shall be [0 ; 253].
[out]newAlarmLEDPolicy: Alarm LED policy. See the user manual p.33 for more details. This parameter is optional, either set the address of uint8_t (or byte) variable, or set HKX_NO_VALUE to ignore it.
[out]newTorquePolicy: Torque policy. See the user manual p.33 for more details. This parameter is optional, either set the address of uint8_t (or byte) variable, or set HKX_NO_VALUE to ignore it.
Returns
0 = OK
1 = Input not correct
2 = Servo not connected
3 = Data not consistent
uint8_t HkxSetup::getPWMPositionLimits ( uint8_t  ID,
HkxMaybe< uint16_t >  overlaodPWMThreshold,
HkxMaybe< int16_t >  minPosition,
HkxMaybe< int16_t >  maxPosition 
)

Get PWM and position limits.

Get the current PWM and position limits of the servo in the RAM. Over these defined limits, the servo is switching to error mode.

Parameters
[in]ID: ID of the servo to address the request. The value shall be [0 ; 253].
[out]overlaodPWMThreshold: The overload PWM threshold is the limits off PWM load from which the servo switches to error mode. Its value is given in PWM. This parameter is optional, either set the address of uint16_t (or unsigned int) variable, or set HKX_NO_VALUE to ignore it.
[out]minPosition: The min position is the lower limit position (given compare to the neutral position = 512 raw) the servo is allowed to move before switching to error mode. It can be used to avoid collisions for instance. Its value is given set in 10^-1 degrees. This parameter is optional, either set the address of uint16_t (or unsigned int) variable, or set HKX_NO_VALUE to ignore it.
[out]maxPosition: The max position is the upper limit position (given compare to the neutral position = 512 raw) the servo is allowed to move before switching to error mode. It can be used to avoid collisions for instance. Its value is given set in 10^-1 degrees. This parameter is optional, either set the address of uint16_t (or unsigned int) variable, or set HKX_NO_VALUE to ignore it.
Returns
0 = OK
1 = Input not correct
2 = Servo not connected
3 = Data not consistent
uint8_t HkxSetup::getServoInfo ( uint8_t  ID,
HkxMaybe< uint16_t >  model,
HkxMaybe< uint16_t >  version 
)

Get model and firmware.

Get the model and the firmware version of the servo from EEP memory.

Parameters
[in]ID: id of the servo to address the request. The value shall be [0 ; 253].
[out]model: Model of the servo (DRS-0101 returns 0x0101, DRS-0201 returns 0x0201). This parameter is optional, either set the address of uint16_t (or unsigned int) variable, or set HKX_NO_VALUE to ignore it.
[out]version: Version of the firmware. This parameter is optional, either set the address of uint16_t (or unsigned int) variable, or set HKX_NO_VALUE to ignore it.
Returns
0 = OK
1 = Input not correct
2 = Servo not connected
3 = Data not consistent
uint8_t HkxSetup::getStatus ( uint8_t  ID,
HkxStatus statusED 
)

Get status.

Get the status of the servo.

Parameters
[in]ID: id of the servo to address the request. The value shall be [0 ; 253].
[out]statusED: Current status of the servo.
Returns
0 = OK
1 = bad input parameter
2 = no data received
3 = received data are not consistent
uint8_t HkxSetup::getTemperatureVoltage ( uint8_t  ID,
HkxMaybe< int16_t >  maxTemp,
HkxMaybe< uint16_t >  minVoltage,
HkxMaybe< uint16_t >  maxVoltage 
)

Get temperature and voltage.

Get the current max temperature, and min and max voltages of the servo in the RAM.

Parameters
[in]ID: current id of the servo to address the request. The value shall be [0 ; 253].
[out]maxTemp: Maximum allowed temperature. Exceeding this temperature switch the servo to error. The value shall is in 10^-2 degree. This parameter is optional, either set the address of uint16_t (or unsigned int) variable, or set HKX_NO_VALUE to ignore it.
[out]minVoltage: Minimum allowed voltage value. Under this input voltage, the servo switches to error. The value is in millivolts. This parameter is optional, either set the address of uint16_t (or unsigned int) variable, or set HKX_NO_VALUE to ignore it.
[out]maxVoltage: Maximum allowed voltage value. Over this input voltage, the servo switches to error. The value is in millivolts. This parameter is optional, either set the address of uint16_t (or unsigned int) variable, or set HKX_NO_VALUE to ignore it.
Returns
0 = OK
1 = Input not correct
2 = Servo not connected
3 = Data not consistent
uint8_t HkxSetup::getTorqueLEDControl ( uint8_t  ID,
HkxMaybe< hkxTorqueControl torqueControl,
HkxMaybe< hkxLEDControl LEDControl 
)

Get torque actuation and LED colour.

Get the current torque actuation and LED colour of the servo in the RAM.

Parameters
[in]ID: ID of the servo to address the request. The value shall be [0 ; 253].
[out]torqueControl: Torque actuator. This parameter is optional, either set the address of hkxTorqueControl variable, or set HKX_NO_VALUE to ignore it.
[out]LEDControl: LED colour. This parameter is optional, either set the address of hkxLEDControl variable, or set HKX_NO_VALUE to ignore it.
Returns
0 = OK
1 = Input not correct
2 = Servo not connected
3 = Data not consistent
void HkxSetup::rebootAll ( )
inline

Reboot.

Reboot all the servo.

uint8_t HkxSetup::rebootOne ( uint8_t  ID)
inline

Reboot.

Reboot the servo.

Parameters
[in]ID: ID of the servo to address the request. The value shall be [0 ; 253].
Returns
0 = OK
1 = Input not correct
void HkxSetup::scanIDs ( boolean  IDs[])

Scan IDs.

Scan all the IDs to check witch servos are connected and their ID.

Parameters
[out]IDs[]: Array of 254 booleans. When IDs[i] = true, the servo with ID = i is connected. When false, the servo is NOT connected.
Returns
0 = OK
1 = Input not correct
2 = no data received
3 = received data are not consistent
uint8_t HkxSetup::setAllAcceleration ( uint8_t  newAccelerationRatio,
uint16_t  newMaxAccelerationTime 
)
inline

Set Acceleration for all.

Modify the acceleration parameters of the servo in both EEP and RAM. The servo generates a trapezoidal velocity trajectory profile (see figure below) according to play time given by the user (see for instance HkxPosControl.movePosition()) where: acceleration time = deceleration time = min (playtime x accelerationRatio / 100, maxAccelerationTime).

if (playtime x accelerationRatio / 100) < maxAccelerationTime   if (playtime x accelerationRatio / 100) > maxAccelerationTime
            V |                                                        V |          ______________                   
            e |         /*\                                            e |         /*            *\                      
            l |        / * \                                           l |        / *            * \                 
            o |       /  *  \                                          o |       /  *            *  \                
            c |      /   *   \                                         c |      /   *            *   \                   
            i |     /    *    \                                        i |     /    *            *    \                  
            t |    /     *     \                                       t |    /     *            *     \                 
            y |   /      *      \                                      y |   /      *            *      \                
              |  /       *       \                                       |  /       *            *       \               
              | /        *        \                                      | /        *            *        \              
              |/_________*_________\________ Time                        |/_________*____________*_________\________ Time
              < Acc time> <Dec time >                                    < Acc time >            < Dec time >            
              <----- Play time ----->                                    <----------- Play time ------------>            
Parameters
[in]newAccelerationRatio: Acceleration ratio considered to generate velocity trajectory. Its value shall be set in percent (%) within the range [0 ; 50%].
[in]newMaxAccelerationTime: Maximum acceleration time to generate velocity trajectory. Its value shall be set in milliseconds within the range [0 ; 2845ms].
Returns
0 = OK
1 = Input not correct
uint8_t HkxSetup::setAllBaudRate ( const hkxBaudrate baudrate)

Set the baud rate for all.

Modify the baud rate for all the servos in EEP memory. A reboot of all the servos is performed at the same time the communication serial port is restarted with the new baud rate.

Warning
From experience, the baud rate 57600 does NOT work properly. Please avoid using it.
Parameters
[in]baudrate: Baud rate to apply to the servos and the communication port. The possible values are:
  • HKX_57600 : 57600 bps
  • HKX_115200 : 115200 bps
  • HKX_200000 : 200000 bps
  • HKX_250000 : 250000 bps
  • HKX_400000 : 400000 bps
  • HKX_500000 : 500000 bps
  • HKX_666666 : 666666 bps
Returns
0 = OK
1 = Input not correct
uint8_t HkxSetup::setAllControlSystem ( uint16_t  kProportionnal,
uint16_t  kDerivative,
uint16_t  kInteger,
uint16_t  feedforwardGain1,
uint16_t  feedforwardGain2 
)
inline

Set Control System for all.

Modify the control system of the servo in both EEP and RAM.

Parameters
[in]kProportionnal: Proportional gain, when its value increase, the response time decreases but may lead to over response (vibration, overshoot). Its value shall be set with no unit within the range [0 ; 32767]. This parameter is optional, either set the address of uint16_t (or unsigned int) variable, or set HKX_NO_VALUE to ignore it.
[in]kDerivative: Derivative gain, when its value increase, the over response is attenuated but may lead to instability. Its value shall be set with no unit within the range [0 ; 32767]. This parameter is optional, either set the address of uint16_t (or unsigned int) variable, or set HKX_NO_VALUE to ignore it.
[in]kInteger: Integral gain, when its value increase, reduce the position offset error in steady state but may lead response lag. Its value shall be set with no unit within the range [0 ; 32767]. This parameter is optional, either set the address of uint16_t (or unsigned int) variable, or set HKX_NO_VALUE to ignore it.
[in]feedforwardGain1: Position feed forward 1st gain, when its value increase, the response time decreases. Its value shall be set with no unit within the range [0 ; 32767]. This parameter is optional, either set the address of uint16_t (or unsigned int) variable, or set HKX_NO_VALUE to ignore it.
[in]feedforwardGain2: Position feed forward 2nd gain, when its value increase, the response time decreases. Its value shall be set with no unit within the range [0 ; 32767]. This parameter is optional, either set the address of uint16_t (or unsigned int) variable, or set HKX_NO_VALUE to ignore it.
Returns
0 = OK
1 = Input not correct
uint8_t HkxSetup::setAllErrorsCheckPeriod ( uint16_t  LEDBlink,
uint16_t  ADCFault,
uint16_t  packetGarbage,
uint16_t  stopDetection,
uint16_t  overloadDetection 
)
inline

Set check periods for all.

Modify the check periods for de different errors of the servo in both EEP and RAM.

Parameters
[in]LEDBlink: Check period for the alarm LED policy to activate LED blinking. Its value shall be set in milliseconds within the range [0 ; 2845ms].
[in]ADCFault: Check period for temperature and input voltage error (when temperature > max temperature or voltage < min voltage or voltage > max voltage). Its value shall be set in milliseconds within the range [0 ; 2845ms].
[in]packetGarbage: Check period for incomplete packet error. Its value shall be set in milliseconds within the range [0 ; 2845ms].
[out]stopDetection: Check period for the servo stoppage. Its value shall be set in milliseconds within the range [0 ; 2845ms].
[in]overloadDetection: Check period for the overload PWM threshold. Its value shall be set in milliseconds within the range [0 ; 2845ms].
Returns
0 = OK
1 = Input not correct
uint8_t HkxSetup::setAllInPositionCriteria ( uint16_t  stopThreshold,
uint16_t  inPositionMargin 
)
inline

Set in position criteria for all.

Modify the in position criteria of the servo in both EEP and RAM.

Parameters
[in]stopThreshold: Under this angle displacement, the servo is seen as not moving. Its value shall be set in 10^-1 degrees within the range [0 ; 82.8°]. This parameter is optional, either set the address of uint16_t (or unsigned int) variable, or set HKX_NO_VALUE to ignore it.
[in]inPositionMargin: Minimum angle distance to determine the goal position reached. Its value shall be set in 10^-1 degrees within the range [0 ; 82.8°]. This parameter is optional, either set the address of uint16_t (or unsigned int) variable, or set HKX_NO_VALUE to ignore it.
Returns
0 = OK
1 = Input not correct
uint8_t HkxSetup::setAllLoadControl ( uint16_t  newDeadZone,
uint8_t  newSaturatorOffset,
const uint32_t &  newSaturatorSlope,
int8_t  newPWMOffset,
uint8_t  newMinPWM,
uint16_t  newMaxPWM 
)
inline

Set load control parameters for all.

Modify the load control parameters of the servo in both EEP and RAM. The load control parameters define the saturation curve according to the figure below.

         PWM+
          |  ___________........................................ PWM max
          |             \
          |              \ Saturator slope
          |               \..................................... Saturator offset
          |                |<dead zone> <dead zone>
          |                |___________ ........................ PWM min
          |                            |
          |  --------------------------|------------------------ PWM offset
          |                            |__________
Position- |____________________________*__________|_____________ Position+
          |                          goal         |
          |                        position        \
          |                                         \__________
          |
         PWM- 
Parameters
[in]newDeadZone: The dead zone is the angle error before the servo applies a load compensation to maintain its position (see the above figure). Its value shall be set in 10^-1 degrees within the range [0 ; 82.8°].
[in]newSaturatorOffset: The saturator offset is the step PWM value of the saturator once dead zone the position goes out of the dead zone (see the above figure). Its value shall be set in PWM within the range [0 ; 254].
[in]newSaturatorSlope: The saturator slop is a gradient of the saturator, going from the saturator offset and increasing gradually the PWM with the error position to the goal (see the above figure). It provides a flexible and elastic response of the servo to external forces. Its value shall be set in 10^-2 PWM / degree within the range [0 ; 393 PWM/degree].
[in]newPWMOffset: The PWM offset allows compensating permanent load (e.g. gravity) by shifting the saturator by the same value (see the above figure). Its value shall be set in PWM within the range [-128 ; 127].
[in]newMinPWM: The min PWM is the minimum PWM that is applied by the servo (see the above figure). As specified in the user manual p.37, this may lead to unstable system. Use 0 as default value. The value shall be set in PWM within the range [0 ; 254].
[in]newMaxPWM: The max PWM is the maximum PWM that is applied by the servo (see the above figure). It could be used to limit the load of the servo, to avoid damages or injuries or instance. The value shall be set in PWM within the range [0 ; 1023].
Returns
0 = OK
1 = Input not correct
uint8_t HkxSetup::setAllPolicies ( uint8_t  newAlarmLEDPolicy,
uint8_t  newTorquePolicy 
)
inline

Set policies for all.

Modify the current Alarm LED policy and Torque policy of all servos in both EEP and RAM. For easier definition the following constants can be used.

  • HKX_STAT_VOLTAGE : Exceed Input Voltage limit
  • HKX_STAT_POSITION : Exceed allowed POT limit
  • HKX_STAT_TEMPERATURE : Exceed Temperature limit
  • HKX_STAT_PACKET : Invalid Packet
  • HKX_STAT_OVERLOAD : Overload detected
  • HKX_STAT_DRIVER : Driver fault detected
  • HKX_STAT_ROM_DISTORTED : EEP REG distorted
  • HKX_STAT_ALL : all the list
    Parameters
    [in]newAlarmLEDPolicy: Alarm LED policy. See the user manual p.33 for more details.
    It can be easily setup thanks the below constants. For instance, the setting HKX_STAT_VOLTAGE & HKX_STAT_POSITION to start the LED alarm for any of this two errors.
    [in]newTorquePolicy: Torque policy. See the user manual p.33 for more details.
    It can be easily setup thanks the below constants. For instance, the setting HKX_STAT_TEMPERATURE & HKX_STAT_OVERLOAD & HKX_STAT_DRIVER to start the torque alarm for any of this three errors.
    Returns
    0 = OK
    1 = Input not correct
uint8_t HkxSetup::setAllPWMPositionLimits ( uint16_t  newOverlaodPWMThreshold,
int16_t  newMinPosition,
int16_t  newMaxPosition 
)
inline

Set PWM and position limits for all.

Modify the PWM and position limits of the servo both EEP and RAM. Over these defined limits, the servo is switching to error mode.

Parameters
[out]newOverlaodPWMThreshold: The overload PWM threshold is the limits off PWM load from which the servo switches to error mode. Its value is given in PWM within the range [0 ; 1023 PWM]. This parameter is optional, either set the address of uint16_t (or unsigned int) variable, or set HKX_NO_VALUE to ignore it.
[out]newMinPosition: The min position is the lower limit position (given compare to the neutral position = 512 raw) the servo is allowed to move before switching to error mode. It can be used to avoid collisions for instance. Its value is given in 10^-1 degrees within the range [-166.7° ; 166.7°]. This parameter is optional, either set the address of uint16_t (or unsigned int) variable, or set HKX_NO_VALUE to ignore it.
[out]newMaxPosition: The max position is the upper limit position (given compare to the neutral position = 512 raw) the servo is allowed to move before switching to error mode. It can be used to avoid collisions for instance. Its value is given in 10^-1 degrees within the range [-166.7° ; 166.7°]. This parameter is optional, either set the address of uint16_t (or unsigned int) variable, or set HKX_NO_VALUE to ignore it.
Returns
0 = OK
1 = Input not correct
uint8_t HkxSetup::setAllTemperatureVoltage ( int16_t  newMaxTemp,
int16_t  newMinVoltage,
int16_t  newMaxVoltage 
)
inline

Set temperature and voltage for all.

Modify the max temperature, and min and max voltages of all servos in both EEP and RAM.

Parameters
[in]newMaxTemp: Maximum allowed temperature. Exceeding this temperature switch the servo to error. The value shall be set in 10^-2 degree within the range [-79.47° ; 300.91°].
[in]newMinVoltage: Minimum allowed voltage value. Under this input voltage, the servo switches to error. The value shall be set in millivolts within the range [0 ; 18.889V].
[in]newMaxVoltage: Maximum allowed voltage value. Over this input voltage, the servo switches to error. The value shall be set in millivolts within the range [0 ; 18.889V].
Returns
0 = OK
1 = Input not correct
uint8_t HkxSetup::setAllTorqueLEDControl ( hkxTorqueControl  newTorqueControl,
hkxLEDControl  newLEDControl 
)
inline

Set torque actuation and LED colour for all.

Modify the torque actuation and LED colour of the servo in both EEP and RAM.

Parameters
[in]newTorqueControl: Torque actuator to apply. Possible values are:
  • HKX_TORQUE_FREE: no resistance to the movements (or let say mechanical resistance only)
  • HKX_TORQUE_BREAK: the motor resists but allows the movements
  • HKX_TORQUE_ON: the motor maintain its position (don't allow movements)
[in]newLEDControl: LED colour to set. Possible values are:
  • HKX_LED_OFF,
  • HKX_LED_GREEN,
  • HKX_LED_BLUE,
  • HKX_LED_RED,
  • HKX_LED_CYAN,
  • HKX_LED_YELLOW,
  • HKX_LED_PINK,
  • HKX_LED_WHITE,
Returns
0 = OK
1 = Input not correct
uint8_t HkxSetup::setID ( uint8_t  ID,
uint8_t  newID 
)

Set ID.

Modify the ID of the servo in both EEP and RAM. A check that no other servo already has the newID is performed before applying the modification.

Parameters
[in]ID: current id of the servo to address the request. The value shall be [0 ; 253].
[in]newID: new id of the servo. The value shall be [0 ; 253].
Returns
0 = OK
1 = Input not correct
4 = newID already used
uint8_t HkxSetup::setOneAcceleration ( uint8_t  ID,
uint8_t  newAccelerationRatio,
uint16_t  newMaxAccelerationTime 
)
inline

Set Acceleration.

Modify the acceleration parameters of the servo in both EEP and RAM. The servo generates a trapezoidal velocity trajectory profile (see figure below) according to play time given by the user (see for instance HkxPosControl.movePosition()) where: acceleration time = deceleration time = min (playtime x accelerationRatio / 100, maxAccelerationTime).

if (playtime x accelerationRatio / 100) < maxAccelerationTime   if (playtime x accelerationRatio / 100) > maxAccelerationTime
            V |                                                        V |          ______________                   
            e |         /*\                                            e |         /*            *\                      
            l |        / * \                                           l |        / *            * \                 
            o |       /  *  \                                          o |       /  *            *  \                
            c |      /   *   \                                         c |      /   *            *   \                   
            i |     /    *    \                                        i |     /    *            *    \                  
            t |    /     *     \                                       t |    /     *            *     \                 
            y |   /      *      \                                      y |   /      *            *      \                
              |  /       *       \                                       |  /       *            *       \               
              | /        *        \                                      | /        *            *        \              
              |/_________*_________\________ Time                        |/_________*____________*_________\________ Time
              < Acc time> <Dec time >                                    < Acc time >            < Dec time >            
              <----- Play time ----->                                    <----------- Play time ------------>            
Parameters
[in]ID: id of the servo to address the request. The value shall be [0 ; 253].
[in]newAccelerationRatio: Acceleration ratio considered to generate velocity trajectory. Its value shall be set in percent (%) within the range [0 ; 50%].
[in]newMaxAccelerationTime: Maximum acceleration time to generate velocity trajectory. Its value shall be set in milliseconds within the range [0 ; 2845ms].
Returns
0 = OK
1 = Input not correct
2 = Servo not connected
3 = Data not consistent
uint8_t HkxSetup::setOneControlSystem ( uint8_t  ID,
uint16_t  kProportionnal,
uint16_t  kDerivative,
uint16_t  kInteger,
uint16_t  feedforwardGain1,
uint16_t  feedforwardGain2 
)
inline

Set Control System.

Modify the control system of the servo in both EEP and RAM.

Parameters
[in]ID: ID of the servo to address the request. The value shall be [0 ; 253].
[in]kProportionnal: Proportional gain, when its value increase, the response time decreases but may lead to over response (vibration, overshoot). Its value shall be set with no unit within the range [0 ; 32767]. This parameter is optional, either set the address of uint16_t (or unsigned int) variable, or set HKX_NO_VALUE to ignore it.
[in]kDerivative: Derivative gain, when its value increase, the over response is attenuated but may lead to instability. Its value shall be set with no unit within the range [0 ; 32767]. This parameter is optional, either set the address of uint16_t (or unsigned int) variable, or set HKX_NO_VALUE to ignore it.
[in]kInteger: Integral gain, when its value increase, reduce the position offset error in steady state but may lead response lag. Its value shall be set with no unit within the range [0 ; 32767]. This parameter is optional, either set the address of uint16_t (or unsigned int) variable, or set HKX_NO_VALUE to ignore it.
[in]feedforwardGain1: Position feed forward 1st gain, when its value increase, the response time decreases. Its value shall be set with no unit within the range [0 ; 32767]. This parameter is optional, either set the address of uint16_t (or unsigned int) variable, or set HKX_NO_VALUE to ignore it.
[in]feedforwardGain2: Position feed forward 2nd gain, when its value increase, the response time decreases. Its value shall be set with no unit within the range [0 ; 32767]. This parameter is optional, either set the address of uint16_t (or unsigned int) variable, or set HKX_NO_VALUE to ignore it.
Returns
0 = OK
1 = Input not correct
uint8_t HkxSetup::setOneErrorsCheckPeriod ( uint8_t  ID,
uint16_t  LEDBlink,
uint16_t  ADCFault,
uint16_t  packetGarbage,
uint16_t  stopDetection,
uint16_t  overloadDetection 
)
inline

Set check periods.

Modify the check periods for de different errors of the servo in both EEP and RAM.

Parameters
[in]ID: ID of the servo to address the request. The value shall be [0 ; 253].
[in]LEDBlink: Check period for the alarm LED policy to activate LED blinking. Its value shall be set in milliseconds within the range [0 ; 2845ms].
[in]ADCFault: Check period for temperature and input voltage error (when temperature > max temperature or voltage < min voltage or voltage > max voltage). Its value shall be set in milliseconds within the range [0 ; 2845ms].
[in]packetGarbage: Check period for incomplete packet error. Its value shall be set in milliseconds within the range [0 ; 2845ms].
[out]stopDetection: Check period for the servo stoppage. Its value shall be set in milliseconds within the range [0 ; 2845ms].
[in]overloadDetection: Check period for the overload PWM threshold. Its value shall be set in milliseconds within the range [0 ; 2845ms].
Returns
0 = OK
1 = Input not correct
uint8_t HkxSetup::setOneInPositionCriteria ( uint8_t  ID,
uint16_t  stopThreshold,
uint16_t  inPositionMargin 
)
inline

Set in position criteria.

Modify the in position criteria of the servo in both EEP and RAM.

Parameters
[in]ID: ID of the servo to address the request. The value shall be [0 ; 253].
[out]stopThreshold: Under this angle displacement, the servo is seen as not moving. Its value shall be set in 10^-1 degrees within the range [0 ; 82.8°]. This parameter is optional, either set the address of uint16_t (or unsigned int) variable, or set HKX_NO_VALUE to ignore it.
[out]inPositionMargin: Minimum angle distance to determine the goal position reached. Its value shall be set in 10^-1 degrees within the range [0 ; 82.8°]. This parameter is optional, either set the address of uint16_t (or unsigned int) variable, or set HKX_NO_VALUE to ignore it.
Returns
0 = OK
1 = Input not correct
uint8_t HkxSetup::setOneLoadControl ( uint8_t  ID,
uint16_t  newDeadZone,
uint8_t  newSaturatorOffset,
const uint32_t &  newSaturatorSlope,
int8_t  newPWMOffset,
uint8_t  newMinPWM,
uint16_t  newMaxPWM 
)
inline

Set load control parameters.

Modify the load control parameters of the servo in both EEP and RAM. The load control parameters define the saturation curve according to the figure below.

         PWM+
          |  ___________........................................ PWM max
          |             \
          |              \ Saturator slope
          |               \..................................... Saturator offset
          |                |<dead zone> <dead zone>
          |                |___________ ........................ PWM min
          |                            |
          |  --------------------------|------------------------ PWM offset
          |                            |__________
Position- |____________________________*__________|_____________ Position+
          |                          goal         |
          |                        position        \
          |                                         \__________
          |
         PWM- 
Parameters
[in]ID: ID of the servo to address the request. The value shall be [0 ; 253].
[in]newDeadZone: The dead zone is the angle error before the servo applies a load compensation to maintain its position (see the above figure). Its value shall be set in 10^-1 degrees within the range [0 ; 82.8°].
[in]newSaturatorOffset: The saturator offset is the step PWM value of the saturator once deadzone the position goes out of the dead zone (see the above figure). Its value shall be set in PWM within the range [0 ; 254].
[in]newSaturatorSlope: The saturator slop is a gradient of the saturator, going from the saturator offset and increasing gradually the PWM with the error position to the goal (see the above figure). It provides a flexible and elastic response of the servo to external forces. Its value shall be set in 10^-2 PWM / degree within the range [0 ; 393 PWM/degree].
[in]newPWMOffset: The PWM offset allows compensating permanent load (e.g. gravity) by shifting the saturator by the same value (see the above figure). Its value shall be set in PWM within the range [-128 ; 127].
[in]newMinPWM: The min PWM is the minimum PWM that is applied by the servo (see the above figure). As specified in the user manual p.37, this may lead to unstable system. Use 0 as default value. The value shall be set in PWM within the range [0 ; 254].
[in]newMaxPWM: The max PWM is the maximum PWM that is applied by the servo (see the above figure). It could be used to limit the load of the servo, to avoid damages or injuries or instance. The value shall be set in PWM within the range [0 ; 1023].
Returns
0 = OK
1 = Input not correct
uint8_t HkxSetup::setOnePolicies ( uint8_t  ID,
uint8_t  newAlarmLEDPolicy,
uint8_t  newTorquePolicy 
)
inline

Set policies.

Modify the current Alarm LED policy and Torque policy of the servo in both EEP and RAM. For easier definition the following constants can be used.

  • HKX_STAT_VOLTAGE : Exceed Input Voltage limit
  • HKX_STAT_POSITION : Exceed allowed POT limit
  • HKX_STAT_TEMPERATURE : Exceed Temperature limit
  • HKX_STAT_PACKET : Invalid Packet
  • HKX_STAT_OVERLOAD : Overload detected
  • HKX_STAT_DRIVER : Driver fault detected
  • HKX_STAT_ROM_DISTORTED : EEP REG distorted
  • HKX_STAT_ALL : all the list
    Parameters
    [in]ID: current id of the servo to address the request. The value shall be [0 ; 253].
    [in]newAlarmLEDPolicy: Alarm LED policy. See the user manual p.33 for more details.
    It can be easily setup thanks the below constants. For instance, the setting HKX_STAT_VOLTAGE & HKX_STAT_POSITION to start the LED alarm for any of this two errors.
    [in]newTorquePolicy: Torque policy. See the user manual p.33 for more details.
    It can be easily setup thanks the below constants. For instance, the setting HKX_STAT_TEMPERATURE & HKX_STAT_OVERLOAD & HKX_STAT_DRIVER to start the torque alarm for any of this three errors.
    Returns
    0 = OK
    1 = Input not correct
uint8_t HkxSetup::setOnePWMPositionLimits ( uint8_t  ID,
uint16_t  newOverlaodPWMThreshold,
int16_t  newMinPosition,
int16_t  newMaxPosition 
)
inline

Set PWM and position limits.

Modify the PWM and position limits of the servo both EEP and RAM. Over these defined limits, the servo is switching to error mode.

Parameters
[in]ID: ID of the servo to address the request. The value shall be [0 ; 253].
[out]newOverlaodPWMThreshold: The overload PWM threshold is the limits off PWM load from which the servo switches to error mode. Its value is given in PWM within the range [0 ; 1023 PWM]. This parameter is optional, either set the address of uint16_t (or unsigned int) variable, or set HKX_NO_VALUE to ignore it.
[out]newMinPosition: The min position is the lower limit position (given compare to the neutral position = 512 raw) the servo is allowed to move before switching to error mode. It can be used to avoid collisions for instance. Its value is given set in 10^-1 degrees within the range [-166.7° ; 166.7°]. This parameter is optional, either set the address of uint16_t (or unsigned int) variable, or set HKX_NO_VALUE to ignore it.
[out]newMaxPosition: The max position is the upper limit position (given compare to the neutral position = 512 raw) the servo is allowed to move before switching to error mode. It can be used to avoid collisions for instance. Its value is given set in 10^-1 degrees within the range [-166.7° ; 166.7°]. This parameter is optional, either set the address of uint16_t (or unsigned int) variable, or set HKX_NO_VALUE to ignore it.
Returns
0 = OK
1 = Input not correct
uint8_t HkxSetup::setOneTemperatureVoltage ( uint8_t  ID,
int16_t  newMaxTemp,
uint16_t  newMinVoltage,
uint16_t  newMaxVoltage 
)
inline

Set temperature and voltage.

Modify the max temperature, and min and max voltages of the servo in both EEP and RAM.

Parameters
[in]ID: current id of the servo to address the request. The value shall be [0 ; 253].
[in]newMaxTemp: Maximum allowed temperature. Exceeding this temperature switch the servo to error. The value shall be set in 10^-2 degree within the range [-79.47° ; 300.91°].
[in]newMinVoltage: Minimum allowed voltage value. Under this input voltage, the servo switches to error. The value shall be set in millivolts within the range [0 ; 18.889V].
[in]newMaxVoltage: Maximum allowed voltage value. Over this input voltage, the servo switches to error. The value shall be set in millivolts within the range [0 ; 18.889V].
Returns
0 = OK
1 = Input not correct
uint8_t HkxSetup::setOneTorqueLEDControl ( uint8_t  ID,
hkxTorqueControl  newTorqueControl,
hkxLEDControl  newLEDControl 
)
inline

Set torque actuation and LED colour.

Modify the torque actuation and LED colour of the servo in both EEP and RAM.

Parameters
[in]ID: ID of the servo to address the request. The value shall be [0 ; 253].
[in]newTorqueControl: Torque actuator to apply. Possible values are:
  • HKX_TORQUE_FREE: no resistance to the movements (or let say mechanical resistance only)
  • HKX_TORQUE_BREAK: the motor resists but allows the movements
  • HKX_TORQUE_ON: the motor maintain its position (don't allow movements)
[in]newLEDControl: LED colour to set. Possible values are:
  • HKX_LED_OFF,
  • HKX_LED_GREEN,
  • HKX_LED_BLUE,
  • HKX_LED_RED,
  • HKX_LED_CYAN,
  • HKX_LED_YELLOW,
  • HKX_LED_PINK,
  • HKX_LED_WHITE,
Returns
0 = OK
1 = Input not correct

Member Data Documentation

HkxCommunication& HkxSetup::_herkXCom
private

Communication with servos

HkxPrint& HkxSetup::_print
private

Communication to print messages


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