ControlConfig

class ControlConfigClient
Canonical

kortex_api.autogen.client_stubs.ControlConfigClientRpc

__init__(router, namespace=None)

Constructs a ControlConfigClient with an initialized RouterClient and an optional namespace.

Parameters
  • router (RouterClient) – RouterClient used for the communication

  • namespace (string) – Optional namespace on which to initialize the ControlConfigClient (defaults to None)

IsAlive(timeoutMs: int = 1000)

Returns True if the Service Server is detected online before timeoutMs is expired, False otherwise.

Parameters

timeoutMs (unsigned int) – The maximum time to wait for an answer from the server

Return type

bool

SetGravityVector(gravityvector, deviceId=0, options=RouterClientSendOptions())
The CONFIGURE permission is necessary to call this RPC.

Sets global gravity vector in terms of base reference frame.
The arm must be powered off and not be in an Unrecoverable Fault state, or powered on and be in Monitored Stop state to set the gravity vector.
This needs to be configured to enable control of the robot in wall or ceiling mounting.

Parameters
GetGravityVector(deviceId = 0, options = RouterClientSendOptions())
The READ_ONLY permission is necessary to call this RPC.

Retrieves global gravity vector
Parameters
  • deviceId (int) – Device’s Id called by rpc (optional)

  • options (RouterClientSendOptions) – Router options for sending the message

Return type

GravityVector

SetPayloadInformation(payloadinformation, deviceId=0, options=RouterClientSendOptions())
The CONFIGURE permission is necessary to call this RPC.

Sets payload information.
This needs to be configured so that the controller can take into account the presence of the payload while computing the kinematics of the robot.
The arm must not be in an Unrecoverable Fault state to set the payload information.
This RPC will also error with a WRONG_MODE error if a program is playing when it’s called.

Parameters
GetPayloadInformation(deviceId = 0, options = RouterClientSendOptions())
The READ_ONLY permission is necessary to call this RPC.

Retrieves payload information
Parameters
  • deviceId (int) – Device’s Id called by rpc (optional)

  • options (RouterClientSendOptions) – Router options for sending the message

Return type

PayloadInformation

GetToolConfiguration(deviceId = 0, options = RouterClientSendOptions())
The READ_ONLY permission is necessary to call this RPC.

Retrieves the tool configuration
Parameters
  • deviceId (int) – Device’s Id called by rpc (optional)

  • options (RouterClientSendOptions) – Router options for sending the message

Return type

ToolConfiguration

OnNotificationControlConfigurationTopic(callback, notificationoptions)
The READ_ONLY permission is necessary to call this RPC.

Subscribes to control configuration notifications
Parameters
Return type

NotificationHandle

Unsubscribe(notificationhandle, deviceId=0, options=RouterClientSendOptions())
The CONFIGURE permission is necessary to call this RPC.

Unsubscribes client from receiving specified type of notifications
Parameters
SetCartesianReferenceFrame(cartesianreferenceframeinfo, deviceId=0, options=RouterClientSendOptions())
The CONFIGURE permission is necessary to call this RPC.

Defines the reference frame to use with twist commands
The arm must be powered on to set the reference frame.

Parameters
GetCartesianReferenceFrame(deviceId = 0, options = RouterClientSendOptions())
The READ_ONLY permission is necessary to call this RPC.

Retrieves the current reference frame used by the twist commands
Parameters
  • deviceId (int) – Device’s Id called by rpc (optional)

  • options (RouterClientSendOptions) – Router options for sending the message

Return type

CartesianReferenceFrameInfo

SetLockedCartesianAxes(axislockconfig, deviceId=0, options=RouterClientSendOptions())
The CONFIGURE permission is necessary to call this RPC.

Apply or remove a lock on some axis.
control_mode must be CARTESIAN_HAND_GUIDING.
translation.reference_frame must be CARTESIAN_REFERENCE_FRAME_TOOL or CARTESIAN_REFERENCE_FRAME_BASE.
orientation.reference_frame must be CARTESIAN_REFERENCE_FRAME_TOOL or CARTESIAN_REFERENCE_FRAME_BASE.
Both the translation and the orientation reference frames must be supplied and valid.
translation.axes must contain 0 to 3 vectors. If more than one vector is provided, they must all be perpendicular.
orientation.axes must contain 0 to 3 vectors. If more than one vector is provided, they must all be perpendicular.

Parameters
GetLockedCartesianAxes(controlmodeinformation, deviceId=0, options=RouterClientSendOptions())
The READ_ONLY permission is necessary to call this RPC.

Retrieves the locked axis status.
control_mode must be CARTESIAN_HAND_GUIDING.

Parameters
Return type

AxisLockConfig

GetControlMode(deviceId = 0, options = RouterClientSendOptions())
The READ_ONLY permission is necessary to call this RPC.

Retrieves current control mode
Parameters
  • deviceId (int) – Device’s Id called by rpc (optional)

  • options (RouterClientSendOptions) – Router options for sending the message

Return type

ControlModeInformation

SetJointSpeedSoftLimits(jointspeedsoftlimits, deviceId=0, options=RouterClientSendOptions())
The ```` permission is necessary to call this RPC.

Set the software joint speed limits.
Parameters
SetTwistLinearSoftLimit(twistlinearsoftlimit, deviceId=0, options=RouterClientSendOptions())
The ```` permission is necessary to call this RPC.

Set the software twist linear limit.
Parameters
SetTwistAngularSoftLimit(twistangularsoftlimit, deviceId=0, options=RouterClientSendOptions())
The ```` permission is necessary to call this RPC.

Set the software twist angular limit.
Parameters
SetJointAccelerationSoftLimits(jointaccelerationsoftlimits, deviceId=0, options=RouterClientSendOptions())
The ```` permission is necessary to call this RPC.

Set the software joint acceleration limits.
Parameters
GetKinematicHardLimits(deviceId = 0, options = RouterClientSendOptions())
The READ_ONLY permission is necessary to call this RPC.

Retrieves angular and twist hard limits.
Parameters
  • deviceId (int) – Device’s Id called by rpc (optional)

  • options (RouterClientSendOptions) – Router options for sending the message

Return type

KinematicLimits

SetDesiredLinearTwist(lineartwist, deviceId=0, options=RouterClientSendOptions())
The CONFIGURE permission is necessary to call this RPC.

Sets the desired linear twist when jogging the robot
A VALUE_ABOVE_MAXIMUM error will be raised if the twist value is above 1.6 m/s.

Parameters
SetDesiredAngularTwist(angulartwist, deviceId=0, options=RouterClientSendOptions())
The CONFIGURE permission is necessary to call this RPC.

Sets the desired angular twist when jogging the robot
A VALUE_ABOVE_MAXIMUM error will be raised if the twist value is above 142.5 deg/s.

Parameters
SetDesiredJointSpeeds(jointspeeds, deviceId=0, options=RouterClientSendOptions())
The CONFIGURE permission is necessary to call this RPC.

Sets the desired joint speeds when jogging in angular mode.
A VALUE_ABOVE_MAXIMUM error will be raised if any of the joint speeds is above its limit.
The size of the joint_speed parameter must be equal to the number of actuators.

Parameters
GetDesiredSpeeds(deviceId = 0, options = RouterClientSendOptions())
The READ_ONLY permission is necessary to call this RPC.

Retrieves the desired joystick speeds
Parameters
  • deviceId (int) – Device’s Id called by rpc (optional)

  • options (RouterClientSendOptions) – Router options for sending the message

Return type

DesiredSpeeds

ResetGravityVector(deviceId = 0, options = RouterClientSendOptions())
The CONFIGURE permission is necessary to call this RPC.

Resets gravity vector to default values.
The arm must be powered off and not be in an Unrecoverable Fault state, or powered on and be in Monitored Stop state to set the gravity vector.
The default values are (x = 0, y = 0, z = -9.81).

Parameters
  • deviceId (int) – Device’s Id called by rpc (optional)

  • options (RouterClientSendOptions) – Router options for sending the message

Return type

GravityVector

ResetPayloadInformation(deviceId = 0, options = RouterClientSendOptions())
The CONFIGURE permission is necessary to call this RPC.

Resets payload information to default values.
This needs to be configured so that the controller can take into account the presence of the payload in computing the dynamics of the robot.
The arm must not be in an Unrecoverable Fault state to set the payload information.
This RPC will also error with a WRONG_MODE error if a program is playing when it’s called.

Parameters
  • deviceId (int) – Device’s Id called by rpc (optional)

  • options (RouterClientSendOptions) – Router options for sending the message

Return type

PayloadInformation

ResetJointSpeedSoftLimits(controlmodeinformation, deviceId=0, options=RouterClientSendOptions())
The ```` permission is necessary to call this RPC.

Resets joint speed soft limits to default values
Parameters
Return type

JointSpeedSoftLimits

ResetTwistLinearSoftLimit(controlmodeinformation, deviceId=0, options=RouterClientSendOptions())
The ```` permission is necessary to call this RPC.

Resets twist linear soft limit to default value
Parameters
Return type

TwistLinearSoftLimit

ResetTwistAngularSoftLimit(controlmodeinformation, deviceId=0, options=RouterClientSendOptions())
The ```` permission is necessary to call this RPC.

Resets twist angular soft limit to default value
Parameters
Return type

TwistAngularSoftLimit

ResetJointAccelerationSoftLimits(controlmodeinformation, deviceId=0, options=RouterClientSendOptions())
The ```` permission is necessary to call this RPC.

Resets joint acceleration soft limits to default values
Parameters
Return type

JointAccelerationSoftLimits

OnNotificationControlModeTopic(callback, notificationoptions)
The READ_ONLY permission is necessary to call this RPC.

Subscribes to control mode topic for notifications
Parameters
Return type

NotificationHandle

SetJointPositionSoftLimits(jointpositionsoftlimits, deviceId=0, options=RouterClientSendOptions())
The ```` permission is necessary to call this RPC.

Set the software joint position limits.
Parameters
ResetJointPositionSoftLimits(controlmodeinformation, deviceId=0, options=RouterClientSendOptions())
The ```` permission is necessary to call this RPC.

Resets joint position soft limits to default values
Parameters
Return type

JointPositionSoftLimits

ZeroExternalWrenchFromFTSensor(deviceId = 0, options = RouterClientSendOptions())
The CONFIGURE permission is necessary to call this RPC.

Adds a persistent offset to the force torque sensor measurements of external efforts to make them equal to zero.
This allows to compensate for small measurement errors (for example drift due to temperature).
The arm must be powered on to set the zero external wrench.

Parameters
  • deviceId (int) – Device’s Id called by rpc (optional)

  • options (RouterClientSendOptions) – Router options for sending the message

ResetExternalWrenchFromFTSensor(deviceId = 0, options = RouterClientSendOptions())
The CONFIGURE permission is necessary to call this RPC.

Resets external wrench from force torque sensor.
The arm must be powered on to set the zero external wrench.

Parameters
  • deviceId (int) – Device’s Id called by rpc (optional)

  • options (RouterClientSendOptions) – Router options for sending the message

GetTcpTranslationSpeedSaturation(deviceId = 0, options = RouterClientSendOptions())
The READ_ONLY permission is necessary to call this RPC.

Gets the tcp translation speed saturation
Parameters
  • deviceId (int) – Device’s Id called by rpc (optional)

  • options (RouterClientSendOptions) – Router options for sending the message

Return type

LinearTwist

GetCollisionDetectionRangesList(deviceId = 0, options = RouterClientSendOptions())
The READ_ONLY permission is necessary to call this RPC.

Retrieves collision detection limits range
Parameters
  • deviceId (int) – Device’s Id called by rpc (optional)

  • options (RouterClientSendOptions) – Router options for sending the message

Return type

CollisionDetectionRangesList

SetAllCollisionDetectionLimits(collisiondetectionlimitslist, deviceId=0, options=RouterClientSendOptions())
The CONFIGURE permission is necessary to call this RPC.

Sets all collision detection limits and activation mode statuses.
The arm must be powered off and not be in an Unrecoverable Fault state, or powered on and be in Monitored Stop state to set the limits.

Parameters
GetAllCollisionDetectionLimits(deviceId = 0, options = RouterClientSendOptions())
The READ_ONLY permission is necessary to call this RPC.

Gets all collision detection limits and activation mode statuses
Parameters
  • deviceId (int) – Device’s Id called by rpc (optional)

  • options (RouterClientSendOptions) – Router options for sending the message

Return type

CollisionDetectionLimitsList

GetEnergyLimitsRangesList(deviceId = 0, options = RouterClientSendOptions())
The READ_ONLY permission is necessary to call this RPC.

Retrieves energy limitation ranges
Parameters
  • deviceId (int) – Device’s Id called by rpc (optional)

  • options (RouterClientSendOptions) – Router options for sending the message

Return type

EnergyLimitsRangesList

SetAllEnergyLimits(energylimitslist, deviceId=0, options=RouterClientSendOptions())
The CONFIGURE permission is necessary to call this RPC.

Sets all energy limits and activation mode statuses.
The arm must be powered off and not be in an Unrecoverable Fault state, or powered on and be in Monitored Stop state to set the limits.

Parameters
GetAllEnergyLimits(deviceId = 0, options = RouterClientSendOptions())
The READ_ONLY permission is necessary to call this RPC.

Gets all energy limits and activation mode statuses
Parameters
  • deviceId (int) – Device’s Id called by rpc (optional)

  • options (RouterClientSendOptions) – Router options for sending the message

Return type

EnergyLimitsList