ToolPlugin¶
- class ToolPluginClient¶
- Canonical
kortex_api.autogen.client_stubs.ToolPluginClientRpc
- __init__(router, namespace)¶
Constructs a ToolPluginClient with an initialized
RouterClient
and a namespace.- Parameters
router (RouterClient) –
RouterClient
used for the communicationnamespace (string) – Namespace on which to initialize the ToolPluginClient
- 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
- Jog(jogmessage, deviceId=0, options=RouterClientSendOptions())¶
- The
OPERATE
permission is necessary to call this RPC.Sends a jog command.The jog_value must be between -100 and 100, or else an error ERROR_DEVICE, METHOD_FAILED is thrown.- Parameters
jogmessage (JogMessage) –
deviceId (int) – Device’s Id called by rpc (optional)
options (RouterClientSendOptions) – Router options for sending the message
- GetToolInformation(toolhandle, deviceId=0, options=RouterClientSendOptions())¶
- The
READ_ONLY
permission is necessary to call this RPC.Gets the tool information.If the tool information is empty, an error ERROR_DEVICE, METHOD_FAILED is raised.If the ToolHandle is not one from an existing tool, 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
- Return type
- GetToolsInformation(deviceId = 0, options = RouterClientSendOptions())¶
- The
READ_ONLY
permission is necessary to call this RPC.Gets the list of tool information.- Parameters
deviceId (int) – Device’s Id called by rpc (optional)
options (RouterClientSendOptions) – Router options for sending the message
- Return type
- GetToolFeedback(toolhandle, deviceId=0, options=RouterClientSendOptions())¶
- The
READ_ONLY
permission is necessary to call this RPC.Gets the tool feedback.The identifier of the targeted tool needs to match one from an existing tool, 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
- Return type
- OnNotificationToolInformationTopic(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.ToolPlugin.ToolInformationNotification
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
- MoveRelative(movemessage, deviceId=0, options=RouterClientSendOptions())¶
- The
OPERATE
permission is necessary to call this RPC.Sends a move command that is relative to the current position.The target_position value must be between -100 and 100 or else an error ERROR_DEVICE, METHOD_FAILED is thrown.The target_position value must not contain decimal numbers.The identifier of the targeted tool needs to match one from an existing tool.- Parameters
movemessage (MoveMessage) –
deviceId (int) – Device’s Id called by rpc (optional)
options (RouterClientSendOptions) – Router options for sending the message