ToolManager¶
- class ToolManagerClient¶
- Canonical
kortex_api.autogen.client_stubs.ToolManagerClientRpc
- __init__(router, namespace=None)¶
Constructs a ToolManagerClient with an initialized
RouterClient
and an optional namespace.- Parameters
router (RouterClient) –
RouterClient
used for the communicationnamespace (string) – Optional namespace on which to initialize the ToolManagerClient (defaults to
None
)
- IsAlive(timeoutMs: int = 1000)¶
Returns
True
if the Service Server is detected online beforetimeoutMs
is expired,False
otherwise.- Parameters
timeoutMs (unsigned int) – The maximum time to wait for an answer from the server
- Return type
bool
- GetAllToolsInformation(deviceId = 0, options = RouterClientSendOptions())¶
- The
READ_ONLY
permission is necessary to call this RPC.Gets information about all the tools- Parameters
deviceId (int) – Device’s Id called by rpc (optional)
options (RouterClientSendOptions) – Router options for sending the message
- Return type
- GetToolInformation(toolhandle, deviceId=0, options=RouterClientSendOptions())¶
- The
READ_ONLY
permission is necessary to call this RPC.Gets information about one specific toolThe handle.identifier of the tool needs to match the identifier from an existing one, or else an ERROR_DEVICE, ENTITY_NOT_FOUND exception is thrown.- Parameters
toolhandle (ToolHandle) –
deviceId (int) – Device’s Id called by rpc (optional)
options (RouterClientSendOptions) – Router options for sending the message
- Return type
- GetActiveToolInformationList(deviceId = 0, options = RouterClientSendOptions())¶
- The
READ_ONLY
permission is necessary to call this RPC.Gets information about the active tool list- Parameters
deviceId (int) – Device’s Id called by rpc (optional)
options (RouterClientSendOptions) – Router options for sending the message
- Return type
- SelectActiveToolList(toolhandlelist, deviceId=0, options=RouterClientSendOptions())¶
- The
CONFIGURE
permission is necessary to call this RPC.Sets the tools from the tool handle list to active. The last tool in the list is the one farthest from the robot flange.The arm must be powered on and in monitored stop, or be powered off, or else an error ERROR_DEVICE, WRONG_MODE is thrown.The identifiers of the tools in the list need to match the identifier from an existing one, or else an ERROR_DEVICE, ENTITY_NOT_FOUND exception is thrown.- Parameters
toolhandlelist (ToolHandleList) –
deviceId (int) – Device’s Id called by rpc (optional)
options (RouterClientSendOptions) – Router options for sending the message
- CreateCustomTool(toolinformation, deviceId=0, options=RouterClientSendOptions())¶
- The
CONFIGURE
permission is necessary to call this RPC.Creates a Custom Tool entryThe tool_plugin_type must be TOOL_TYPE_CUSTOM, or else the error ERROR_DEVICE, INVALID_PARAM is thrown.The friendly name size must be between 1 and 25.The mass must be entered in Kilograms and its value must be between 0 and 9 kg.The range for the cartesian transform must be between -1 and 1 meters for the translation coordinates x, y and z, between -180 and 180 degrees for rotation values theta_x and theta_y and between 0 and 180 degrees for theta_z.The center of mass must be entered in meters and its value must be between -1 and 1.The inertia must be between 0 and 1 kgm² for the diagonal values Ixx, Iyy and Izz and between -1 and 1 kgm² for the cross values Ixy, Ixz and Iyz.- Parameters
toolinformation (ToolInformation) –
deviceId (int) – Device’s Id called by rpc (optional)
options (RouterClientSendOptions) – Router options for sending the message
- Return type
- DeleteCustomTool(toolhandle, deviceId=0, options=RouterClientSendOptions())¶
- The
CONFIGURE
permission is necessary to call this RPC.Deletes a Custom Tool entryThe tool to be deleted needs to exist, or else an error ERROR_DEVICE, ENTITY_NOT_FOUND is thrown.The tool must not be in the active tool list, or else an error ERROR_DEVICE, INVALID_PARAM is thrown.The tool must be a custom tool to be deleted, or else an error ERROR_DEVICE, INVALID_PARAM is thrown.- Parameters
toolhandle (ToolHandle) –
deviceId (int) – Device’s Id called by rpc (optional)
options (RouterClientSendOptions) – Router options for sending the message
- UpdateToolInformation(toolinformation, deviceId=0, options=RouterClientSendOptions())¶
- The
OPERATE
permission is necessary to call this RPC.Updates a Tool’s informationUpdates on the tool information need to follow the same rules as the ones mentioned in CreateCustomTool’s description.The handle.identifier of the tool to be updated needs to match the identifier from an existing tool, or else an ENTITY_NOT_FOUND exception is thrown.- Parameters
toolinformation (ToolInformation) –
deviceId (int) – Device’s Id called by rpc (optional)
options (RouterClientSendOptions) – Router options for sending the message
- OnNotificationActiveToolInformationChangedTopic(callback, notificationoptions)¶
- The
READ_ONLY
permission is necessary to call this RPC.Subscribes to tool information notifications- Parameters
callback (function) – Function callback taking a
Kinova.Api.ToolManager.ActiveToolNotification
as only argument, and returningNone
.notificationoptions (NotificationOptions) – Notification options
- Return type
- OnNotificationToolInformationTopic(callback, notificationoptions)¶
- The
READ_ONLY
permission is necessary to call this RPC.Subscribes to custom tool notifications- Parameters
callback (function) – Function callback taking a
Kinova.Api.ToolManager.ToolNotification
as only argument, and returningNone
.notificationoptions (NotificationOptions) – Notification options
- Return type
- Unsubscribe(notificationhandle, deviceId=0, options=RouterClientSendOptions())¶
- The
READ_ONLY
permission is necessary to call this RPC.Unsubscribes client from receiving notifications for the specified topic- Parameters
notificationhandle (NotificationHandle) –
deviceId (int) – Device’s Id called by rpc (optional)
options (RouterClientSendOptions) – Router options for sending the message