Skip to main content
Version: latest

Inverse3

Haply::HardwareAPI::Devices::Inverse3

Encapsulates the logic required to interact with an Inverse3 device.

An instance of the SerialStream class representing the serial port of the Inverse3 is required as a parameter to the constructor. Once constructed, the DeviceWakeup command will wakeup the device and allow enable the send methods. All send methods must be followed by their respective receive methods to process the device's response.

This class uses the term end-effector to refer to the device's cursor.

All methods within this class will block until their IO operations are completed. An Inverse3 device can operate frequencies of up to 8kHz where a recommended minimum of 1kHz is required to ensure a smooth haptic experience. If multiple devices are managed by the same thread, the overall processing frequency will cap at the lowest frequency of all the device. Mixing handles and Inverse3 within the same thread is therefore not recommended.

Index

Classes

Members

NameTypeDescription
NUM_JOINTSstatic constexpr uint8_tNumber of motors/joints in an inverse3 device.
LEFT_HANDEDstatic constexpr uint8_tConstant for a left-handed device to be used in conjunction ...
RIGHT_HANDEDstatic constexpr uint8_tConstant for a right-handed device to be used in ...

Methods

NameTypeDescription
Inverse3(...)Constructs an Inverse3 object from ...
DeviceWakeupDeviceInfoResponse(...)Wakeup a device to allow for additional commands.
SendDeviceWakeupvoid()Wakeup a device to allow for additional commands.
ReceiveDeviceInfoint()Receive the response from ...
ReceiveDeviceInfoint(uint16_t *, uint8_t *, uint8_t *, ...)Receive the response from ...
DeviceIdExtQueryDeviceIdExtResponse(...)Query the UUID of the device.
SendDeviceIdExtQueryvoid()Query the UUID of the device.
ReceiveDeviceIdExtint()Receive the response from ...
ReceiveDeviceIdExtint(UUID *)Receive the response from ...
FirmwareVersionExtQueryFirmwareVersionExtResponse(...)Query the device for its extended firmware version.
SendFirmwareVersionExtQueryvoid()Query the device for its extended firmware version.
ReceiveFirmwareVersionExtint()Receive the response from ...
ReceiveFirmwareVersionExtint(UUID *)Receive the response from ...
JointTorquesJointStatesResponse(...)Apply the provided torque to the device's motors.
SendJointTorquesvoid()Halts the generation of torque by the device's motors.
SendJointTorquesvoid(const float)Apply the provided torque to the device's motors.
JointAnglesJointStatesResponse(...)Set the angle for the device's joints.
SendJointAnglesvoid()Halts the generation of torque by the device's motors.
SendJointAnglesvoid(const float)Set the angle for the device's joints.
ReceiveJointStatesint()Receive the response from ...
ReceiveJointStatesint(float *, float *)Receive the response from ...
EndEffectorForceEndEffectorStateResponse(...)Apply the provided force to the device's cursor.
SendEndEffectorForcevoid()Halts the generation of forces to the device's cursor.
SendEndEffectorForcevoid(const float)Apply the provided force to the device's cursor.
EndEffectorPositionEndEffectorStateResponse(...)Set the position of the device's cursor.
SendEndEffectorPositionvoid()Halts the generation of forces to the device's cursor.
SendEndEffectorPositionvoid(const float)Set the position of the device's cursor.
ReceiveEndEffectorStateint()Receive the response from ...
ReceiveEndEffectorStateint(float *, float *)Receive the response from ...
DeviceOrientationQueryDeviceOrientationResponse(...)Query the orientation of the device's body.
SendDeviceOrientationQueryvoid()Query the orientation of the device's body.
ReceiveDeviceOrientationint()Receive the response from ...
ReceiveDeviceOrientationint(float)Receive the response from ...
DevicePowerQueryDevicePowerResponse(...)Query the powered state of the device.
SendDevicePowerQueryvoid()Query the powered state of the device.
ReceiveDevicePowerint()Receive the response from ...
ReceiveDevicePowerint(bool *)Receive the response from ...
DeviceTemperatureQueryDeviceTemperatureResponse(...)Query the device's temperature.
SendDeviceTemperatureQueryvoid()Query the device's temperature.
ReceiveDeviceTemperatureint()Receive the response from ...
ReceiveDeviceTemperatureint(float *)Receive the response from ...
MotorCurrentsQueryMotorCurrentsResponse(...)Query the current being applied to the device's motors.
SendMotorCurrentsQueryvoid()Query the current being applied to the device's motors.
ReceiveMotorCurrentsint()Receive the response from ...
ReceiveMotorCurrentsint(float *)Receive the response from ...
GetDeviceHandednessDeviceHandednessPayload(...)Query the device's handedness.
SendGetDeviceHandednessvoid()Query the device's handedness.
SetDeviceHandednessDeviceHandednessPayload(...)Set the device's handedness.
SendSetDeviceHandednessvoid(const uint8_t &)Set the device's handedness.
ReceiveDeviceHandednessint()Receive the response from ...
ReceiveDeviceHandednessint(uint8_t *)Receive the response from ...
GetTorqueScalingTorqueScalingPayload(...)Query the device's torque scaling state.
SendGetTorqueScalingvoid()Query the device's torque scaling state.
SetTorqueScalingTorqueScalingPayload(...)Set the device's torque scaling state to the provided ...
SendSetTorqueScalingvoid(const bool &)Set the device's torque scaling state to the provided ...
ReceiveTorqueScalingint()Receive the response from ...
ReceiveTorqueScalingint(bool *)Receive the response from ...
GetGravityCompensationGravityCompensationPayload(...)Query the device's gravity compensation state.
SendGetGravityCompensationvoid()Query the device's gravity compensation state.
SetGravityCompensationGravityCompensationPayload(...)Set the device's gravity compensation state to the provided ...
SendSetGravityCompensationvoid(const bool &, const float &)Set the device's gravity compensation state to the provided ...
ReceiveGravityCompensationint()Receive the response from ...
ReceiveGravityCompensationint(bool *, float *)Receive the response from ...
SaveConfigSaveConfigResponse(...)Permanently persists any modified configuration parameter.
SendSaveConfigvoid()Permanently persists any modified configuration parameter.
ReceiveSaveConfigint(uint8_t *)Receive the response from ...

Members

NUM_JOINTS

static constexpr uint8_t NUM_JOINTS = 3

Number of motors/joints in an inverse3 device.

LEFT_HANDED

static constexpr uint8_t LEFT_HANDED = 0x00

Constant for a left-handed device to be used in conjunction with DeviceHandednessPayload.

RIGHT_HANDED

static constexpr uint8_t RIGHT_HANDED = 0x01

Constant for a right-handed device to be used in conjunction with DeviceHandednessPayload.

Methods

Inverse3

Inverse3(         Haply::HardwareAPI::IO::SerialStream * stream,         float timeout)

Constructs an Inverse3 object from the provided stream.

Parameters

  • stream The stream object representing the serial port associated with the device. The lifetime of the stream must match or exceed the lifetime of the Inverse3 object. We recommend constructing this stream using the SerialStream class.

  • timeout The maximum amount of time to wait for a response from the device. If the device fails to respond within this time, the operation will fail and an error will be printed to stderr.

The default timeout is 5 seconds, a negative value will disable the timeout.

DeviceWakeup

DeviceInfoResponse DeviceWakeup()

Wakeup a device to allow for additional commands.

This command is required to be sent to the device before any other commands can be sent. This command also has the side-effect of resetting the internal state of the device (i.e. simulation mode).

Will block until a message is received from the device or an error is encountered. If an error occurred then an error will be printed to stderr and may return false.

Functionally equivalent to SendDeviceWakeup but provides no error handling mechanism.

Returns

Basic information about the device.

SendDeviceWakeup

void SendDeviceWakeup()

Wakeup a device to allow for additional commands.

This command is required to be sent to the device before any other commands can be sent. This command also has the side-effect of resetting the internal state of the device (i.e. simulation mode). Must be followed by a call to ReceiveDeviceInfo to process the device's response.

Functionally equivalent to DeviceWakeup but provides a basic error handling mechanism.

ReceiveDeviceInfo

int ReceiveDeviceInfo()

Receive the response from SendDeviceWakeup discarding the results.

Will block until a message is received from the device or an error is encountered.

Returns

Returns 0 if the operation completed successfully. If an error occurred while communicating with the device via the stream then the method will return a negative value, an error will be printed to stderr and may return false.

ReceiveDeviceInfo

int ReceiveDeviceInfo(         uint16_t * device_id,         uint8_t * device_model_number,         uint8_t * hardware_version,         uint8_t * firmware_version,         UUID * device_id_ext)

Receive the response from SendDeviceWakeup storing the result in the provided arguments.

Will block until a message is received from the device or an error is encountered.

Returns

Returns 0 if the operation completed successfully. If an error occurred while communicating with the device via the stream then the method will return a negative value, an error will be printed to stderr and may return false.

See Also

DeviceInfoResponse for a description of the parameters.

DeviceIdExtQuery

DeviceIdExtResponse DeviceIdExtQuery()

Query the UUID of the device.

Returns the same UUID as provided in the response to the DeviceWakeup method.

Will block until a message is received from the device or an error is encountered. If an error occurred then an error will be printed to stderr and may return false.

Functionally equivalent to SendDeviceIdExtQuery but provides no error handling mechanism.

Returns

The UUID of the device.

SendDeviceIdExtQuery

void SendDeviceIdExtQuery()

Query the UUID of the device.

Returns the same UUID as provided in the response to the DeviceWakeup method. Must be followed by a call to ReceiveDeviceIdExt to process the device's response.

Functionally equivalent to DeviceIdExtQuery but provides a basic error handling mechanism.

ReceiveDeviceIdExt

int ReceiveDeviceIdExt()

Receive the response from SendDeviceIdExtQuery discarding the results.

Will block until a message is received from the device or an error is encountered.

Returns

Returns 0 if the operation completed successfully. If an error occurred while communicating with the device via the stream then the method will return a negative value, an error will be printed to stderr and may return false.

ReceiveDeviceIdExt

int ReceiveDeviceIdExt(UUID * device_id)

Receive the response from SendDeviceIdExtQuery storing the result in the provided argument.

Will block until a message is received from the device or an error is encountered.

Returns

Returns 0 if the operation completed successfully. If an error occurred while communicating with the device via the stream then the method will return a negative value, an error will be printed to stderr and may return false.

See Also

DeviceIdExtResponse for a description of the parameters.

FirmwareVersionExtQuery

FirmwareVersionExtResponse FirmwareVersionExtQuery()

Query the device for its extended firmware version.

WARNING This command is still under review and its behaviour should not be relied upon.

Will block until a message is received from the device or an error is encountered. If an error occurred then an error will be printed to stderr and may return false.

Functionally equivalent to SendFirmwareVersionExtQuery but provides no error handling mechanism.

Returns

The firmware version of the device.

SendFirmwareVersionExtQuery

void SendFirmwareVersionExtQuery()

Query the device for its extended firmware version.

Must be followed by a call to ReceiveFirmwareVersionExt to process the device's response.

Functionally equivalent to FirmwareVersionExtResponse but provides a basic error handling mechanism.

ReceiveFirmwareVersionExt

int ReceiveFirmwareVersionExt()

Receive the response from SendFirmwareVersionExtQuery discarding the results.

Will block until a message is received from the device or an error is encountered.

Returns

Returns 0 if the operation completed successfully. If an error occurred while communicating with the device via the stream then the method will return a negative value, an error will be printed to stderr and may return false.

ReceiveFirmwareVersionExt

int ReceiveFirmwareVersionExt(UUID * firmware_version_id)

Receive the response from SendFirmwareVersionExtQuery storing the result in the provided arguments.

Will block until a message is received from the device or an error is encountered.

Returns

Returns 0 if the operation completed successfully. If an error occurred while communicating with the device via the stream then the method will return a negative value, an error will be printed to stderr and may return false.

See Also

FirmwareVersionExtResponse for a description the parameters.

JointTorques

JointStatesResponse JointTorques(const JointTorquesRequest & request)

Apply the provided torque to the device's motors.

This command will switch the device to the joints simulation mode and will maintain the provided torque until overridden by a new torque value or a new simulation mode.

Will block until a message is received from the device or an error is encountered. If an error occurred then an error will be printed to stderr and may return false.

Functionally equivalent to SendJointTorques but provides no error handling mechanism.

Parameters

  • request The torque to apply to the motors.

Returns

The current state of the device's joints.

SendJointTorques

void SendJointTorques()

Halts the generation of torque by the device's motors.

SendJointTorques

void SendJointTorques(const float torques)

Apply the provided torque to the device's motors.

This command will switch the device to the joints simulation mode and will maintain the provided torque until overridden by a new torque value or a new simulation mode.

Must be followed by a call to ReceiveJointStates to process the device's response.

Functionally equivalent to JointTorques but provides a basic error handling mechanism.

JointAngles

JointStatesResponse JointAngles(const JointAnglesRequest & request)

Set the angle for the device's joints.

This command will switch the device to the joints simulation mode and will maintain the provided angles until overridden by new angles or a new simulation mode.

Will block until a message is received from the device or an error is encountered. If an error occurred then an error will be printed to stderr and may return false.

Functionally equivalent to SendJointAngles but provides no error handling mechanism.

Parameters

  • request The angles to apply to the motors.

Returns

The current state of the device's joints.

SendJointAngles

void SendJointAngles()

Halts the generation of torque by the device's motors.

SendJointAngles

void SendJointAngles(const float angles)

Set the angle for the device's joints.

This command will switch the device to the joints simulation mode and will maintain the provided angles until overridden by new angles or a new simulation mode.

Must be followed by a call to ReceiveJointStates to process the device's response.

Functionally equivalent to JointAngles but provides a basic error handling mechanism.

ReceiveJointStates

int ReceiveJointStates()

Receive the response from SendJointTorques or SendJointAngles discarding the results.

Will block until a message is received from the device or an error is encountered.

Returns

Returns 0 if the operation completed successfully. If an error occurred while communicating with the device via the stream then the method will return a negative value, an error will be printed to stderr and may return false.

ReceiveJointStates

int ReceiveJointStates(         float * angles,         float * angularVelocities)

Receive the response from SendJointTorques or SendJointAngles storing the results in the provided parameters.

Will block until a message is received from the device or an error is encountered.

Returns

Returns 0 if the operation completed successfully. If an error occurred while communicating with the device via the stream then the method will return a negative value, an error will be printed to stderr and may return false.

See Also

JointStatesResponse for a description of the parameters.

EndEffectorForce

EndEffectorStateResponse EndEffectorForce(const EndEffectorForceRequest & request)

Apply the provided force to the device's cursor.

This command will switch the device to the cursor simulation mode and will maintain the provided force until overridden by a new force or a new simulation mode.

Will block until a message is received from the device or an error is encountered. If an error occurred then an error will be printed to stderr and may return false.

Functionally equivalent to xSendEndEffectorForce but provides no error handling mechanism.

Parameters

  • request The force to apply to the cursor.

Returns

The current state of the device's cursor.

SendEndEffectorForce

void SendEndEffectorForce()

Halts the generation of forces to the device's cursor.

SendEndEffectorForce

void SendEndEffectorForce(const float force)

Apply the provided force to the device's cursor.

This command will switch the device to the cursor simulation mode and will maintain the provided force until overridden by a new force or a new simulation mode.

Must be followed by a call to ReceiveEndEffectorState to process the device's response.

Functionally equivalent to EndEffectorForce but provides a basic error handling mechanism.

EndEffectorPosition

EndEffectorStateResponse EndEffectorPosition(const EndEffectorPositionRequest & request)

Set the position of the device's cursor.

This command will switch the device to the cursor simulation mode and will maintain the provided position until overridden by a new position or a new simulation mode.

Will block until a message is received from the device or an error is encountered. If an error occurred then an error will be printed to stderr and may return false.

Functionally equivalent to xSendEndEffectorPosition but provides no error handling mechanism.

Parameters

  • request The desired position for the cursor.

Returns

The current state of the device's cursor.

SendEndEffectorPosition

void SendEndEffectorPosition()

Halts the generation of forces to the device's cursor.

SendEndEffectorPosition

void SendEndEffectorPosition(const float position)

Set the position of the device's cursor.

This command will switch the device to the cursor simulation mode and will maintain the provided position until overridden by a new position or a new simulation mode.

Must be followed by a call to ReceiveEndEffectorState to process the device's response.

Functionally equivalent to EndEffectorPosition but provides a basic error handling mechanism.

ReceiveEndEffectorState

int ReceiveEndEffectorState()

Receive the response from SendEndEffectorForce or SendEndEffectorPosition discarding the results.

Will block until a message is received from the device or an error is encountered.

Returns

Returns 0 if the operation completed successfully. If an error occurred while communicating with the device via the stream then the method will return a negative value, an error will be printed to stderr and may return false.

ReceiveEndEffectorState

int ReceiveEndEffectorState(         float * position,         float * velocity)

Receive the response from SendEndEffectorForce or SendEndEffectorPosition storing the results in the provided arguments.

Will block until a message is received from the device or an error is encountered.

Returns

Returns 0 if the operation completed successfully. If an error occurred while communicating with the device via the stream then the method will return a negative value, an error will be printed to stderr and may return false.

See Also

EndEffetorStatesResponse for a description of the parameters.

DeviceOrientationQuery

DeviceOrientationResponse DeviceOrientationQuery()

Query the orientation of the device's body.

Will block until a message is received from the device or an error is encountered. If an error occurred then an error will be printed to stderr and may return false.

Functionally equivalent to SendDeviceOrientationQuery but provides no error handling mechanism.

Returns

The orientation of the device's body.

SendDeviceOrientationQuery

void SendDeviceOrientationQuery()

Query the orientation of the device's body.

Must be followed by a call to ReceiveDeviceOrientation to process the device's response.

Functionally equivalent to DeviceOrientationQuery but provides a basic error handling mechanism.

ReceiveDeviceOrientation

int ReceiveDeviceOrientation()

Receive the response from SendDeviceOrientationQuery discarding the results.

Will block until a message is received from the device or an error is encountered.

Returns

Returns 0 if the operation completed successfully. If an error occurred while communicating with the device via the stream then the method will return a negative value, an error will be printed to stderr and may return false.

ReceiveDeviceOrientation

int ReceiveDeviceOrientation(float quaternion)

Receive the response from SendDeviceOrientationQuery storing the result in the provided arguments.

Will block until a message is received from the device or an error is encountered.

Returns

Returns 0 if the operation completed successfully. If an error occurred while communicating with the device via the stream then the method will return a negative value, an error will be printed to stderr and may return false.

See Also

DeviceOrientationResponse for a description the parameters.

DevicePowerQuery

DevicePowerResponse DevicePowerQuery()

Query the powered state of the device.

Will block until a message is received from the device or an error is encountered. If an error occurred then an error will be printed to stderr and may return false.

Functionally equivalent to SendDevicePowerQuery but provides no error handling mechanism.

Returns

The powered state of the device.

SendDevicePowerQuery

void SendDevicePowerQuery()

Query the powered state of the device.

Must be followed by a call to ReceiveDevicePower to process the device's response.

Functionally equivalent to DevicePowerQuery but provides a basic error handling mechanism.

ReceiveDevicePower

int ReceiveDevicePower()

Receive the response from SendDevicePowerQuery discarding the results.

Will block until a message is received from the device or an error is encountered.

Returns

Returns 0 if the operation completed successfully. If an error occurred while communicating with the device via the stream then the method will return a negative value, an error will be printed to stderr and may return false.

ReceiveDevicePower

int ReceiveDevicePower(bool * powered)

Receive the response from SendDevicePowerQuery storing the result in the provided arguments.

Will block until a message is received from the device or an error is encountered.

Returns

Returns 0 if the operation completed successfully. If an error occurred while communicating with the device via the stream then the method will return a negative value, an error will be printed to stderr and may return false.

See Also

DevicePowerResponse for a description the parameters.

DeviceTemperatureQuery

DeviceTemperatureResponse DeviceTemperatureQuery()

Query the device's temperature.

Will block until a message is received from the device or an error is encountered. If an error occurred while then an error will be printed to stderr and may return false.

Functionally equivalent to SendDeviceTemperatureQuery but provides no error handling mechanism.

Returns

The temperature of the device.

SendDeviceTemperatureQuery

void SendDeviceTemperatureQuery()

Query the device's temperature.

Must be followed by a call to ReceiveDeviceTemperature to process the device's response.

Functionally equivalent to DeviceTemperatureQuery but provides a basic error handling mechanism.

ReceiveDeviceTemperature

int ReceiveDeviceTemperature()

Receive the response from SendDeviceTemperatureQuery discarding the results.

Will block until a message is received from the device or an error is encountered.

Returns

Returns 0 if the operation completed successfully. If an error occurred while communicating with the device via the stream then the method will return a negative value, an error will be printed to stderr and may return false.

ReceiveDeviceTemperature

int ReceiveDeviceTemperature(float * temperature)

Receive the response from SendDeviceTemperatureQuery storing the result in the provided arguments.

Will block until a message is received from the device or an error is encountered.

Returns

Returns 0 if the operation completed successfully. If an error occurred while communicating with the device via the stream then the method will return a negative value, an error will be printed to stderr and may return false.

See Also

DeviceTemperatureResponse for a description the parameters.

MotorCurrentsQuery

MotorCurrentsResponse MotorCurrentsQuery()

Query the current being applied to the device's motors.

Will block until a message is received from the device or an error is encountered. If an error occurred then an error will be printed to stderr and may return false.

Functionally equivalent to SendMotorCurrentsQuery but provides no error handling mechanism.

Returns

The current for each of the device's motors.

SendMotorCurrentsQuery

void SendMotorCurrentsQuery()

Query the current being applied to the device's motors.

Must be followed by a call to ReceiveMotorCurrents to process the device's response.

Functionally equivalent to MotorCurrentsQuery but provides a basic error handling mechanism.

ReceiveMotorCurrents

int ReceiveMotorCurrents()

Receive the response from SendMotorCurrentsQuery discarding the results.

Will block until a message is received from the device or an error is encountered.

Returns

Returns 0 if the operation completed successfully. If an error occurred while communicating with the device via the stream then the method will return a negative value, an error will be printed to stderr and may return false.

ReceiveMotorCurrents

int ReceiveMotorCurrents(float * currents)

Receive the response from SendMotorCurrentsQuery storing the result in the provided arguments.

Will block until a message is received from the device or an error is encountered.

Returns

Returns 0 if the operation completed successfully. If an error occurred while communicating with the device via the stream then the method will return a negative value, an error will be printed to stderr and may return false.

See Also

MotorCurrentsResponse for a description the parameters.

GetDeviceHandedness

DeviceHandednessPayload GetDeviceHandedness()

Query the device's handedness.

Will block until a message is received from the device or an error is encountered. If an error occurred then an error will be printed to stderr and may return false.

Functionally equivalent to SendGetDeviceHandedness but provides no error handling mechanism.

Returns

The handedness of the device.

SendGetDeviceHandedness

void SendGetDeviceHandedness()

Query the device's handedness.

Must be followed by a call to ReceiveDeviceHandedness to process the device's response.

Functionally equivalent to GetDeviceHandedness but provides a basic error handling mechanism.

SetDeviceHandedness

DeviceHandednessPayload SetDeviceHandedness(const DeviceHandednessPayload & payload)

Set the device's handedness.

Changing the handedness will cause a device to change it's frame of reference and reset its internal state. This include the device's calibration, torque/angle/force/position values and simulation mode. Any changes to the handedness will also necessitate a physical change to the device's arms. Consult the Haply documentation hub to find a guide on how to effect this change.

The change made by this method will only persist until the next power-cycle of the device. SaveConfig can be used to persist the change permanently.

Will block until a message is received from the device or an error is encountered. If an error occurred then an error will be printed to stderr and may return false.

Functionally equivalent to SendSetDeviceHandedness but provides no error handling mechanism.

Returns

The handedness of the device.

SendSetDeviceHandedness

void SendSetDeviceHandedness(const uint8_t & handedness)

Set the device's handedness.

Changing the handedness will cause a device to change it's frame of reference and reset its internal state. This include the device's calibration, torque/angle/force/position values and simulation mode. Any changes to the handedness will also necessitate a physical change to the device's arms. Consult the Haply documentation hub to find a guide on how to effect this change.

The change made by this method will only persist until the next power-cycle of the device. SaveConfig can be used to persist the change permanently.

The change made by this method will only persist until the next power-cycle of the device. SaveConfig can be used to persist the change permanently.

Must be followed by a call to ReceiveDeviceHandedness to process the device's response.

Functionally equivalent to SetDeviceHandedness but provides a basic error handling mechanism.

ReceiveDeviceHandedness

int ReceiveDeviceHandedness()

Receive the response from SendGetDeviceHandedness or SendSetDeviceHandedness discarding the results.

Will block until a message is received from the device or an error is encountered.

Returns

Returns 0 if the operation completed successfully. If an error occurred while communicating with the device via the stream then the method will return a negative value, an error will be printed to stderr and may return false.

ReceiveDeviceHandedness

int ReceiveDeviceHandedness(uint8_t * handedness)

Receive the response from SendGetDeviceHandedness or SendSetDeviceHandedness storing the result in the provided arguments.

Will block until a message is received from the device or an error is encountered.

Returns

Returns 0 if the operation completed successfully. If an error occurred while communicating with the device via the stream then the method will return a negative value, an error will be printed to stderr and may return false.

See Also

DeviceHandednessResponse for a description the parameters.

GetTorqueScaling

TorqueScalingPayload GetTorqueScaling()

Query the device's torque scaling state.

Will block until a message is received from the device or an error is encountered. If an error occurred then an error will be printed to stderr and may return false.

Functionally equivalent to SendGetTorqueScaling but provides no error handling mechanism.

Returns

The torque scaling state of the device.

SendGetTorqueScaling

void SendGetTorqueScaling()

Query the device's torque scaling state.

Must be followed by a call to ReceiveTorqueScaling to process the device's response.

Functionally equivalent to GetTorqueScaling but provides a basic error handling mechanism.

SetTorqueScaling

TorqueScalingPayload SetTorqueScaling(const TorqueScalingPayload & payload)

Set the device's torque scaling state to the provided value.

The change made by this method will only persist until the next power-cycle of the device. SaveConfig can be used to persist the change permanently.

Will block until a message is received from the device or an error is encountered. If an error occurred then an error will be printed to stderr and may return false.

Functionally equivalent to SendGetTorqueScaling but provides no error handling mechanism.

Returns

The torque scaling state of the device.

SendSetTorqueScaling

void SendSetTorqueScaling(const bool & enabled)

Set the device's torque scaling state to the provided value.

The change made by this method will only persist until the next power-cycle of the device. SaveConfig can be used to persist the change permanently.

Must be followed by a call to ReceiveTorqueScaling to process the device's response.

Functionally equivalent to SetTorqueScaling but provides a basic error handling mechanism.

ReceiveTorqueScaling

int ReceiveTorqueScaling()

Receive the response from SendGetTorqueScaling or SendSetTorqueScaling discarding the results.

Will block until a message is received from the device or an error is encountered.

Returns

Returns 0 if the operation completed successfully. If an error occurred while communicating with the device via the stream then the method will return a negative value, an error will be printed to stderr and may return false.

ReceiveTorqueScaling

int ReceiveTorqueScaling(bool * enabled)

Receive the response from SendGetTorqueScaling or SendSetTorqueScaling storing the result in the provided arguments.

Will block until a message is received from the device or an error is encountered.

Returns

Returns 0 if the operation completed successfully. If an error occurred while communicating with the device via the stream then the method will return a negative value, an error will be printed to stderr and may return false.

See Also

TorqueScalingPayload for a description the parameters.

GetGravityCompensation

GravityCompensationPayload GetGravityCompensation()

Query the device's gravity compensation state.

Will block until a message is received from the device or an error is encountered. If an error occurred then an error will be printed to stderr and may return false.

Functionally equivalent to SendGetGravityCompensation but provides no error handling mechanism.

Returns

The device's gravity compensation state.

SendGetGravityCompensation

void SendGetGravityCompensation()

Query the device's gravity compensation state.

Must be followed by a call to ReceiveGravityCompensation to process the device's response.

Functionally equivalent to GetGravityCompensation but provides a basic error handling mechanism.

SetGravityCompensation

GravityCompensationPayload SetGravityCompensation(const GravityCompensationPayload & payload)

Set the device's gravity compensation state to the provided value.

The change made by this method will only persist until the next power-cycle of the device. SaveConfig can be used to persist the change permanently.

Will block until a message is received from the device or an error is encountered. If an error occurred then an error will be printed to stderr and may return false.

Functionally equivalent to SendSetGravityCompensation but provides no error handling mechanism.

Returns

The gravity compensation state of the device.

SendSetGravityCompensation

void SendSetGravityCompensation(         const bool & enabled,         const float & gravity_scale_factor)

Set the device's gravity compensation state to the provided value.

The change made by this method will only persist until the next power-cycle of the device. SaveConfig can be used to persist the change permanently.

Must be followed by a call to ReceiveGravityCompensation to process the device's response.

Functionally equivalent to GetGravityCompensation but provides a basic error handling mechanism.

ReceiveGravityCompensation

int ReceiveGravityCompensation()

Receive the response from SendGetGravityCompensation or SendSetGravityCompensation discarding the results.

Will block until a message is received from the device or an error is encountered.

Returns

Returns 0 if the operation completed successfully. If an error occurred while communicating with the device via the stream then the method will return a negative value, an error will be printed to stderr and may return false.

ReceiveGravityCompensation

int ReceiveGravityCompensation(         bool * enabled,         float * gravity_scale_factor)

Receive the response from SendGetGravityCompensation or SendSetGravityCompensation storing the result in the provided arguments.

Will block until a message is received from the device or an error is encountered.

Returns

Returns 0 if the operation completed successfully. If an error occurred while communicating with the device via the stream then the method will return a negative value, an error will be printed to stderr and may return false.

See Also

GravityCompensationPayload for a description the parameters.

SaveConfig

SaveConfigResponse SaveConfig()

Permanently persists any modified configuration parameter.

The device's persistent storage has a write limit which is consumed with every invocation of this method. As a result, this method should only be used seldomly.

Will block until a message is received from the device or an error is encountered. If an error occurred then an error will be printed to stderr and may return false.

Functionally equivalent to SendSaveConfig but provides no error handling mechanism.

Returns

The result of the command.

SendSaveConfig

void SendSaveConfig()

Permanently persists any modified configuration parameter.

The device's persistent storage has a write limit which is consumed with every invocation of this method. As a result, this method should only be used seldomly.

Must be followed by a call to ReceiveSaveConfig to process the device's response.

Functionally equivalent to SaveConfig but provides a basic error handling mechanism.

ReceiveSaveConfig

int ReceiveSaveConfig(uint8_t * parameters_updated)

Receive the response from SendSaveConfig storing the results in the provided argument.

Will block until a message is received from the device or an error is encountered.

Returns

Returns 0 if the operation completed successfully. If an error occurred while communicating with the device via the stream then the method will return a negative value, an error will be printed to stderr and may return false.

See Also

SaveConfigResponse for a description of the parameters.