ProgramRunner

class ProgramRunnerClient
Canonical

kortex_api.autogen.client_stubs.ProgramRunnerClientRpc

__init__(router, namespace=None)

Constructs a ProgramRunnerClient 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 ProgramRunnerClient (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

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

Create a program.

If the program is not valid, an INVALID_PARAM error is thrown.

Parameters
  • program (Program) –

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

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

Return type

ProgramHandle

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

Delete a program.

If the program to delete is running, an ERROR_DEVICE error is thrown.

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

Fetch all available plugin actions descriptors.
Parameters
  • deviceId (int) – Device’s Id called by rpc (optional)

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

Return type

ActionList

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

Read all programs.
Parameters
  • deviceId (int) – Device’s Id called by rpc (optional)

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

Return type

ProgramList

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

Read a program.
Parameters
Return type

Program

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

Update an existing program.

If the program is not valid, an INVALID_PARAM error is thrown.

Parameters
  • program (Program) –

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

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

Return type

Program

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

Export a program from Runner.
Parameters
Return type

ProgramJSON

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

Import a program to Runner.
Parameters
Return type

ProgramHandle

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

Returns the current status.
Parameters
  • deviceId (int) – Device’s Id called by rpc (optional)

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

Return type

StatusInformation

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

Pause an ongoing Program or Action.
Parameters
  • deviceId (int) – Device’s Id called by rpc (optional)

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

Resume(runnablehandle, deviceId=0, options=RouterClientSendOptions())
The OPERATE permission is necessary to call this RPC.

Resume a paused Program or Action.
The input argument RunnableHandle is unused, use a default RunnableHandle to make the call.

If runner status is STATUS_PAUSED_AUTOMATIC_RESUME, an ERROR_DEVICE error is thrown.
If the operating mode is different as it was when the program was started, an INVALID_PARAM error is thrown.

Parameters
Start(programstartconfiguration, deviceId=0, options=RouterClientSendOptions())
The OPERATE permission is necessary to call this RPC.

Start a program.
The Arm State must be powered ON.
The Operating Mode must be HOLD_TO_RUN or AUTO.

To avoid the INVALID_PARAM error, the action_handle is not set, the program_handle is set,
the program is valid and the operating mode is HOLD_TO_RUN or AUTO.
If it is AUTO, the program must be validated.

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

Stop an ongoing Program or Action.

If the status is neither paused nor running or if it is stopping or idle, an ERROR_DEVICE error is thrown.

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

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

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

Subscribes to state event notifications
Parameters
  • callback (function) – Function callback taking a Kinova.Api.ProgramRunner.StateChangeNotification as only argument, and returning None.

  • notificationoptions (NotificationOptions) – Notification options

Return type

NotificationHandle

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

Subscribes to status event notifications
Parameters
  • callback (function) – Function callback taking a Kinova.Api.ProgramRunner.StatusChangeNotification as only argument, and returning None.

  • notificationoptions (NotificationOptions) – Notification options

Return type

NotificationHandle

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

Subscribes to Configuration change topic on programs
Parameters
  • callback (function) – Function callback taking a Kinova.Api.ProgramConfig.ConfigurationChangeNotification as only argument, and returning None.

  • notificationoptions (NotificationOptions) – Notification options

Return type

NotificationHandle

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

Subscribes to program execution event notifications
Parameters
  • callback (function) – Function callback taking a Kinova.Api.ProgramRunner.ExecutionEventNotification as only argument, and returning None.

  • notificationoptions (NotificationOptions) – Notification options

Return type

NotificationHandle

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
StartActions(actionsstartconfiguration, deviceId=0, options=RouterClientSendOptions())
The OPERATE permission is necessary to call this RPC.

Start specified actions of a program.

If action_handle or program_handle is not set, the program is not valid or the operating mode is not HOLD_TO_RUN, an INVALID_PARAM error is thrown.

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

Validate a program.
Parameters