Base¶
- class BaseClient¶
- Canonical
kortex_api.autogen.client_stubs.BaseClientRpc
- __init__(router, namespace=None)¶
Constructs a BaseClient with an initialized
RouterClient
and an optional namespace.- Parameters
router (RouterClient) –
RouterClient
used for the communicationnamespace (string) – Optional namespace on which to initialize the BaseClient (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
- CreateUserProfile(fulluserprofile, deviceId=0, options=RouterClientSendOptions())¶
- The
CONFIGURE
permission is necessary to call this RPC.Creates a user profile and returns a handle to the profile.The created user profile will always have the “Operator” role, who has the READ_ONLY and OPERATE user permissions.The handle.permission field is a bitmask of Common.Permission values. A permission of 7 should always be used.The username cannot be empty.The username, first name and last name cannot exceed 50 characters in length.The password cannot exceed 103 characters in length.There cannot be more than 107 user profiles created.Two user profiles cannot have the same username.- Parameters
fulluserprofile (FullUserProfile) –
deviceId (int) – Device’s Id called by rpc (optional)
options (RouterClientSendOptions) – Router options for sending the message
- Return type
- UpdateUserProfile(userprofile, deviceId=0, options=RouterClientSendOptions())¶
- The
CONFIGURE
permission is necessary to call this RPC.Updates an existing user profile.The handle.identifier parameter must be set to a valid identifier.The username cannot already be in use by another user profile.The same username, password, first name and last name length constraints as CreateUserProfile apply for this RPC.- Parameters
userprofile (UserProfile) –
deviceId (int) – Device’s Id called by rpc (optional)
options (RouterClientSendOptions) – Router options for sending the message
- ReadUserProfile(userprofilehandle, deviceId=0, options=RouterClientSendOptions())¶
- The
CONFIGURE
permission is necessary to call this RPC.Retrieves an existing user profile- Parameters
userprofilehandle (UserProfileHandle) –
deviceId (int) – Device’s Id called by rpc (optional)
options (RouterClientSendOptions) – Router options for sending the message
- Return type
- DeleteUserProfile(userprofilehandle, deviceId=0, options=RouterClientSendOptions())¶
- The
CONFIGURE
permission is necessary to call this RPC.Deletes an existing user profile.The handle.identifier parameter must be set to a valid identifier.The handle.permission of the user profile to delete must include the DELETE_PERMISSION.- Parameters
userprofilehandle (UserProfileHandle) –
deviceId (int) – Device’s Id called by rpc (optional)
options (RouterClientSendOptions) – Router options for sending the message
- ReadAllUserProfiles(deviceId = 0, options = RouterClientSendOptions())¶
- The
OPERATE
permission is necessary to call this RPC.Retrieves all user profiles- Parameters
deviceId (int) – Device’s Id called by rpc (optional)
options (RouterClientSendOptions) – Router options for sending the message
- Return type
- ReadAllUsers(deviceId = 0, options = RouterClientSendOptions())¶
- The
CONFIGURE
permission is necessary to call this RPC.Retrieves the list of all user profile handles- Parameters
deviceId (int) – Device’s Id called by rpc (optional)
options (RouterClientSendOptions) – Router options for sending the message
- Return type
- ChangePassword(passwordchange, deviceId=0, options=RouterClientSendOptions())¶
- The
CONFIGURE
permission is necessary to call this RPC.Changes the password of an existing user.The handle.identifier parameter must be set to a valid identifier.The old_password parameter must match the user’s current password.- Parameters
passwordchange (PasswordChange) –
deviceId (int) – Device’s Id called by rpc (optional)
options (RouterClientSendOptions) – Router options for sending the message
- ExecuteAction(action, deviceId=0, options=RouterClientSendOptions())¶
- The
OPERATE
permission is necessary to call this RPC.Commands the robot to execute the specified action.This RPC cannot be called when the operating mode is OPERATING_MODE_JOG_MANUAL.This RPC will be ignored if it is called when the operating mode is OPERATING_MODE_MONITORED_STOP.A ROBOT_NOT_MOVING exception “Failed to execute action: The Enabling device must be pressed for the arm to move” is thrown if the operating mode is OPERATING_MODE_HOLD_TO_RUN and the enabling device is not pressed when the action starts running.A DEVICE_DISCONNECTED exception “Stopping motion failed for Session ID <session ID>: No Arm Detected” is thrown if the arm is not powered on.Most of the action types are no longer supported. All action types that are not detailed below will return an UNSUPPORTED_ACTION exception “Unsupported action type: <type ID of action> in action “<name of action>””.send_twist_command:- If the input twist is higher than the set arm limits, the command does not return an error or warning but the twists do not exceed the set limits.- If the arm is given a twist command in a direction it can’t move in, it will try to move which can induce movement in other directions as well.- If the twist is too high, the induced acceleration may cause the arm to falsely detect a collision.- The action will not stop after the time specified in the duration parameter of the TwistCommand object.send_joint_speeds:- The JointSpeed objects’ input parameter “identifier” should be an integer between 0 and 5, defining the index of the joint to control.- If not all 6 joint speeds have been defined, then the undefined ones are set as 0.execute_waypoint_list:has to be an integer- A METHOD_FAILED exception “The waypoint list is empty” will be thrown if the list of waypoints is empty or no argument has been passed to the WaypointList object.- If a waypoint is out of reach, the robot will not execute the waypoint list and it will send a warning message “Invalid Waypoint - Out of Robot Workspace”.- The action will not stop after the time specified in the duration parameter of the WaypointList object.change_payload_parameters:- The input parameter mass of ChangePayloadParameters has to be between 0 and 9 kg.- The input parameter center_of_mass should have values between -1 and 1.- The input parameter inertia should have diagonal values (I xx,I yy,I zz) between 0 and 1, and cross-product element values (I xy,I xz,I yz) between -1 and 1.- If any value is outside its range, the action will be ignored and no value will be changed.switch_control_mapping:- This action type is not to be used.play_pre_computed_trajectory:- This action type is to be deprecated.- The elements of the list of PreComputedJointTRajectoryElement objects should be spaced by 1ms increments.- The action will be ignored if the trajectory elements do not form a coherent path, given the time spacing of 1ms.execute_action:- This action type is deprecated.- Parameters
action (Action) –
deviceId (int) – Device’s Id called by rpc (optional)
options (RouterClientSendOptions) – Router options for sending the message
- PauseAction(deviceId = 0, options = RouterClientSendOptions())¶
- The
OPERATE
permission is necessary to call this RPC.Pauses the currently executed action. ResumeAction can be invoked afterwards.Pausing an action sets the operating the operating mode to OPERATING_MODE_MONITORED_STOP.A ROBOT_NOT_MOVING exception “Failed to pause action: The Enabling device must be pressed for the arm to move” is thrown when the operating mode is OPERATING_MODE_HOLD_TO_RUN and the enabling device is not pressed.A DEVICE_DISCONNECTED exception “Failed to pause action: No Arm Detected” is thrown if the arm is not powered on.- Parameters
deviceId (int) – Device’s Id called by rpc (optional)
options (RouterClientSendOptions) – Router options for sending the message
- StopAction(deviceId = 0, options = RouterClientSendOptions())¶
- The
OPERATE
permission is necessary to call this RPC.Stops the currently executed action. ResumeAction cannot be invoked afterwards.An INVALID_PARAM exception “Failed to stop action: Argument Invalid” is thrown if the operating mode is OPERATING_MODE_MONITORED_STOP.A ROBOT_NOT_MOVING exception “Failed to stop action: The Enabling device must be pressed for the arm to move” is thrown when the operating mode is OPERATING_MODE_HOLD_TO_RUN and the enabling device is not pressed.A ROBOT_NOT_MOVING exception “Failed to stop action: Trying to stop, pause or resume an action that is not started” is thrown if no action is started before the RPC is called.A DEVICE_DISCONNECTED exception “Failed to stop action: No Arm Detected” is thrown if the arm is not powered on.- Parameters
deviceId (int) – Device’s Id called by rpc (optional)
options (RouterClientSendOptions) – Router options for sending the message
- ResumeAction(deviceId = 0, options = RouterClientSendOptions())¶
- The
OPERATE
permission is necessary to call this RPC.Resumes execution of the currently paused action.This RPC can only be called when the operating mode is OPERATING_MODE_AUTO.An INVALID_PARAM exception “Failed to resume action: Argument Invalid” is thrown if the operating mode is OPERATING_MODE_MONITORED_STOP.A METHOD_FAILED exception “Failed to resume action: Action failed” is thrown if the operating mode is OPERATING_MODE_HOLD_TO_RUN.A DEVICE_DISCONNECTED exception “Failed to resume action: No Arm Detected” is thrown if the arm is not powered on.- Parameters
deviceId (int) – Device’s Id called by rpc (optional)
options (RouterClientSendOptions) – Router options for sending the message
- GetIPv4Configuration(networkhandle, deviceId=0, options=RouterClientSendOptions())¶
- The
READ_ONLY
permission is necessary to call this RPC.Retrieves the IPv4 network configuration for the specified network adapter- Parameters
networkhandle (NetworkHandle) –
deviceId (int) – Device’s Id called by rpc (optional)
options (RouterClientSendOptions) – Router options for sending the message
- Return type
- SetIPv4Configuration(fullipv4configuration, deviceId=0, options=RouterClientSendOptions())¶
- The
CONFIGURE
permission is necessary to call this RPC.Modifies the IPv4 network configuration for the specified network adapter- Parameters
fullipv4configuration (FullIPv4Configuration) –
deviceId (int) – Device’s Id called by rpc (optional)
options (RouterClientSendOptions) – Router options for sending the message
- 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
- OnNotificationConfigurationChangeTopic(callback, notificationoptions)¶
- The
READ_ONLY
permission is necessary to call this RPC.Subscribes to configuration change topic for notifications- Parameters
callback (function) – Function callback taking a
ConfigurationChangeNotification
as only argument, and returningNone
.notificationoptions (NotificationOptions) – Notification options
- Return type
- OnNotificationOperatingModeTopic(callback, notificationoptions)¶
- The
READ_ONLY
permission is necessary to call this RPC.Subscribes to operating mode topic for notifications- Parameters
callback (function) – Function callback taking a
OperatingModeNotification
as only argument, and returningNone
.notificationoptions (NotificationOptions) – Notification options
- Return type
- OnNotificationControllerTopic(callback, notificationoptions)¶
- The
READ_ONLY
permission is necessary to call this RPC.Subscribes to controller topic for notifications- Parameters
callback (function) – Function callback taking a
ControllerNotification
as only argument, and returningNone
.notificationoptions (NotificationOptions) – Notification options
- Return type
- OnNotificationActionTopic(callback, notificationoptions)¶
- The
READ_ONLY
permission is necessary to call this RPC.Subscribes to action topic for notifications- Parameters
callback (function) – Function callback taking a
ActionNotification
as only argument, and returningNone
.notificationoptions (NotificationOptions) – Notification options
- Return type
- OnNotificationRobotEventTopic(callback, notificationoptions)¶
- The
READ_ONLY
permission is necessary to call this RPC.Subscribes to robot event topic for notifications- Parameters
callback (function) – Function callback taking a
RobotEventNotification
as only argument, and returningNone
.notificationoptions (NotificationOptions) – Notification options
- Return type
- Stop(deviceId = 0, options = RouterClientSendOptions())¶
- The
OPERATE
permission is necessary to call this RPC.Stops robot movement- Parameters
deviceId (int) – Device’s Id called by rpc (optional)
options (RouterClientSendOptions) – Router options for sending the message
- GetMeasuredCartesianPose(deviceId = 0, options = RouterClientSendOptions())¶
- The
READ_ONLY
permission is necessary to call this RPC.Retrieves the current computed tool pose (position and orientation) for the robot- Parameters
deviceId (int) – Device’s Id called by rpc (optional)
options (RouterClientSendOptions) – Router options for sending the message
- Return type
- SendTwistJoystickCommand(twistcommand, deviceId=0, options=RouterClientSendOptions())¶
- The
OPERATE
permission is necessary to call this RPC.Sends a twist (screw consisting of linear and angular velocity) joystick command to be applied to the tool.The twist values sent to this call are expected to be a ratio of the maximum value (between -1.0/+1.0).This RPC can only be sent while the robot is in Jog Manual.A ROBOT_NOT_MOVING error will be thrown if the Enabling Device is not pressed.- Parameters
twistcommand (TwistCommand) –
deviceId (int) – Device’s Id called by rpc (optional)
options (RouterClientSendOptions) – Router options for sending the message
- SendTwistCommand(twistcommand, deviceId=0, options=RouterClientSendOptions())¶
- The
OPERATE
permission is necessary to call this RPC.Sends a twist (screw consisting of linear and angular velocity) command to be applied to the tool.This RPC can only be sent while the robot is in Jog Manual.A ROBOT_NOT_MOVING error will be thrown if the Enabling Device is not pressed.- Parameters
twistcommand (TwistCommand) –
deviceId (int) – Device’s Id called by rpc (optional)
options (RouterClientSendOptions) – Router options for sending the message
- GetMeasuredJointAngles(deviceId = 0, options = RouterClientSendOptions())¶
- The
READ_ONLY
permission is necessary to call this RPC.Retrieves the currently measured joint angles for each joint- Parameters
deviceId (int) – Device’s Id called by rpc (optional)
options (RouterClientSendOptions) – Router options for sending the message
- Return type
- SendJointSpeedsCommand(jointspeeds, deviceId=0, options=RouterClientSendOptions())¶
- The
OPERATE
permission is necessary to call this RPC.Sends a set of joint speed commands to all joints with one command. Joint speed commmands must be sent to all joints.If you do not want to move some of the joints, simply send a speed value of 0 degrees / second for that joint.This RPC can only be sent while the robot is in Jog Manual.A ROBOT_NOT_MOVING error will be thrown if the Enabling Device is not pressed.- Parameters
jointspeeds (JointSpeeds) –
deviceId (int) – Device’s Id called by rpc (optional)
options (RouterClientSendOptions) – Router options for sending the message
- SendSelectedJointSpeedCommand(jointspeed, deviceId=0, options=RouterClientSendOptions())¶
- The
OPERATE
permission is necessary to call this RPC.Sends a speed command for a specific joint.This RPC can only be sent while the robot is in Jog Manual.A ROBOT_NOT_MOVING error will be thrown if the Enabling Device is not pressed.- Parameters
jointspeed (JointSpeed) –
deviceId (int) – Device’s Id called by rpc (optional)
options (RouterClientSendOptions) – Router options for sending the message
- ApplyQuickStop(deviceId = 0, options = RouterClientSendOptions())¶
- The
OPERATE
permission is necessary to call this RPC.Applies a category 2 stop to the robot and puts it back in Monitored Stop state.- Parameters
deviceId (int) – Device’s Id called by rpc (optional)
options (RouterClientSendOptions) – Router options for sending the message
- ClearFaults(deviceId = 0, options = RouterClientSendOptions())¶
- The
OPERATE
permission is necessary to call this RPC.Clears robot fault state. Robot is permitted to move again.- Parameters
deviceId (int) – Device’s Id called by rpc (optional)
options (RouterClientSendOptions) – Router options for sending the message
- GetServoingMode(deviceId = 0, options = RouterClientSendOptions())¶
- The
READ_ONLY
permission is necessary to call this RPC.Retrieves current servoing mode- Parameters
deviceId (int) – Device’s Id called by rpc (optional)
options (RouterClientSendOptions) – Router options for sending the message
- Return type
- OnNotificationServoingModeTopic(callback, notificationoptions)¶
- The
READ_ONLY
permission is necessary to call this RPC.Subscribes to servoing mode topic for notifications- Parameters
callback (function) – Function callback taking a
ServoingModeNotification
as only argument, and returningNone
.notificationoptions (NotificationOptions) – Notification options
- Return type
- RestoreFactorySettings(deviceId = 0, options = RouterClientSendOptions())¶
- The
CONFIGURE
permission is necessary to call this RPC.Deletes all configurations and reverts settings to their factory defaults (except network settings)- Parameters
deviceId (int) – Device’s Id called by rpc (optional)
options (RouterClientSendOptions) – Router options for sending the message
- Reboot(deviceId = 0, options = RouterClientSendOptions())¶
- The
OPERATE
permission is necessary to call this RPC.Reboots the controller- Parameters
deviceId (int) – Device’s Id called by rpc (optional)
options (RouterClientSendOptions) – Router options for sending the message
- OnNotificationFactoryTopic(callback, notificationoptions)¶
- The
READ_ONLY
permission is necessary to call this RPC.Subscribes to factory topic for notifications- Parameters
callback (function) – Function callback taking a
FactoryNotification
as only argument, and returningNone
.notificationoptions (NotificationOptions) – Notification options
- Return type
- GetActuatorCount(deviceId = 0, options = RouterClientSendOptions())¶
- The
READ_ONLY
permission is necessary to call this RPC.Retrieves the number of actuators in the robot- Parameters
deviceId (int) – Device’s Id called by rpc (optional)
options (RouterClientSendOptions) – Router options for sending the message
- Return type
- GetArmState(deviceId = 0, options = RouterClientSendOptions())¶
- The
READ_ONLY
permission is necessary to call this RPC.Retrieves current robot arm state- Parameters
deviceId (int) – Device’s Id called by rpc (optional)
options (RouterClientSendOptions) – Router options for sending the message
- Return type
- OnNotificationArmStateTopic(callback, notificationoptions)¶
- The
READ_ONLY
permission is necessary to call this RPC.Subscribes to robot arm state notifications- Parameters
callback (function) – Function callback taking a
ArmStateNotification
as only argument, and returningNone
.notificationoptions (NotificationOptions) – Notification options
- Return type
- GetIPv4Information(networkhandle, deviceId=0, options=RouterClientSendOptions())¶
- The
READ_ONLY
permission is necessary to call this RPC.Retrieves the IPv4 network information for the specified network adapter- Parameters
networkhandle (NetworkHandle) –
deviceId (int) – Device’s Id called by rpc (optional)
options (RouterClientSendOptions) – Router options for sending the message
- Return type
- SendJointSpeedsJoystickCommand(jointspeeds, deviceId=0, options=RouterClientSendOptions())¶
- The
OPERATE
permission is necessary to call this RPC.Sends the desired joystick speeds to all joints with one command.The speed values sent to this call are expected to be a ratio of the maximum value (between -1.0/+1.0)Speeds must be sent to all joints. If you don’t want to move some of the joints, send a value of 0.This RPC can only be sent while the robot is in Jog Manual.A ROBOT_NOT_MOVING error will be thrown if the Enabling Device is not pressed.- Parameters
jointspeeds (JointSpeeds) –
deviceId (int) – Device’s Id called by rpc (optional)
options (RouterClientSendOptions) – Router options for sending the message
- SendSelectedJointSpeedJoystickCommand(jointspeed, deviceId=0, options=RouterClientSendOptions())¶
- The
OPERATE
permission is necessary to call this RPC.Sends a joystick speed for a specific joint.The speed value sent to this call is expected to be a ratio of the maximum value (between -1.0/+1.0)This RPC can only be sent while the robot is in Jog Manual.A ROBOT_NOT_MOVING error will be thrown if the Enabling Device is not pressed.- Parameters
jointspeed (JointSpeed) –
deviceId (int) – Device’s Id called by rpc (optional)
options (RouterClientSendOptions) – Router options for sending the message
- PlayPreComputedJointTrajectory(precomputedjointtrajectory, deviceId=0, options=RouterClientSendOptions())¶
- The
OPERATE
permission is necessary to call this RPC.Plays a pre-computed angular trajectory- Parameters
precomputedjointtrajectory (PreComputedJointTrajectory) –
deviceId (int) – Device’s Id called by rpc (optional)
options (RouterClientSendOptions) – Router options for sending the message
- GetProductConfiguration(deviceId = 0, options = RouterClientSendOptions())¶
- The
READ_ONLY
permission is necessary to call this RPC.Retrieves product configuration information- Parameters
deviceId (int) – Device’s Id called by rpc (optional)
options (RouterClientSendOptions) – Router options for sending the message
- Return type
- GetTrajectoryErrorReport(deviceId = 0, options = RouterClientSendOptions())¶
- The
READ_ONLY
permission is necessary to call this RPC.Obtains trajectory error report listing errors for rejected trajectory.Provides some feedback on why the trajectory could not be completed.- Parameters
deviceId (int) – Device’s Id called by rpc (optional)
options (RouterClientSendOptions) – Router options for sending the message
- Return type
- GetFirmwareBundleVersions(deviceId = 0, options = RouterClientSendOptions())¶
- The
READ_ONLY
permission is necessary to call this RPC.Retrieves current firmware bundle versions- Parameters
deviceId (int) – Device’s Id called by rpc (optional)
options (RouterClientSendOptions) – Router options for sending the message
- Return type
- ExecuteWaypointTrajectory(waypointlist, deviceId=0, options=RouterClientSendOptions())¶
- The
OPERATE
permission is necessary to call this RPC.Executes a trajectory defined by a series of waypoints in joint space or in Cartesian space- Parameters
waypointlist (WaypointList) –
deviceId (int) – Device’s Id called by rpc (optional)
options (RouterClientSendOptions) – Router options for sending the message
- ValidateWaypointList(waypointlist, deviceId=0, options=RouterClientSendOptions())¶
- The
OPERATE
permission is necessary to call this RPC.Validate a waypoint list, returns an empty trajectory error report list if the waypoint list is valid.If the use_optimal_blending option is true, a waypoint list with optimal blending will be returned.- Parameters
waypointlist (WaypointList) –
deviceId (int) – Device’s Id called by rpc (optional)
options (RouterClientSendOptions) – Router options for sending the message
- Return type
- ComputeForwardKinematics(jointangles, deviceId=0, options=RouterClientSendOptions())¶
- The
OPERATE
permission is necessary to call this RPC.Get the forward kinematics given specified angular positions of actuators- Parameters
jointangles (JointAngles) –
deviceId (int) – Device’s Id called by rpc (optional)
options (RouterClientSendOptions) – Router options for sending the message
- Return type
- ComputeInverseKinematics(ikdata, deviceId=0, options=RouterClientSendOptions())¶
- The
OPERATE
permission is necessary to call this RPC.Get the inverse kinematics given a specified cartesian pose and guess of joint angles- Parameters
ikdata (IKData) –
deviceId (int) – Device’s Id called by rpc (optional)
options (RouterClientSendOptions) – Router options for sending the message
- Return type
- ActivateRobot(deviceId = 0, options = RouterClientSendOptions())¶
- The
OPERATE
permission is necessary to call this RPC.Activates the robot.This function will return after the command is sent, not after the arm is properly activated.Subscribe to the ArmStateTopic to be notified of the robot’s current activation status.A METHOD_FAILED error will be thrown if the robot was powered off less than 8 seconds ago. Activating the robot can only be done more than 8 seconds after the last power off.A WRONG_MODE error will be thrown if the robot is already activated.- Parameters
deviceId (int) – Device’s Id called by rpc (optional)
options (RouterClientSendOptions) – Router options for sending the message
- OnNotificationUpdatingModeTopic(callback, notificationoptions)¶
- The
READ_ONLY
permission is necessary to call this RPC.Subscribes to updating mode topic for notifications- Parameters
callback (function) – Function callback taking a
UpdatingModeNotification
as only argument, and returningNone
.notificationoptions (NotificationOptions) – Notification options
- Return type
- SetUpdatingMode(updatingmodeinformation, deviceId=0, options=RouterClientSendOptions())¶
- The
CONFIGURE
permission is necessary to call this RPC.Sets a new updating mode. Only Maintenance, Update and Run modes are permitted.- Parameters
updatingmodeinformation (UpdatingModeInformation) –
deviceId (int) – Device’s Id called by rpc (optional)
options (RouterClientSendOptions) – Router options for sending the message
- GetUpdatingMode(deviceId = 0, options = RouterClientSendOptions())¶
- The
READ_ONLY
permission is necessary to call this RPC.Retrieves current updating mode- Parameters
deviceId (int) – Device’s Id called by rpc (optional)
options (RouterClientSendOptions) – Router options for sending the message
- Return type
- SelectOperatingMode(modeselection, deviceId=0, options=RouterClientSendOptions())¶
- The
OPERATE
permission is necessary to call this RPC.Select the operating modeThere is a small transition period (about 1 ms) when switching operating modes where the value of the current operating mode is temporarily set as OPERATING_MODE_MONITORED_STOP.If a call that checks the current operating mode is made from the API shortly after this RPC has been called, it might return OPERATING_MODE_MONITORED_STOP instead of the correct operating mode.When the arm is in ARMSTATE_RECOVERY, no exceptions are thrown but the command is ignoredA DEVICE_DISCONNECTED exception “Stopping motion failed for Session ID <session ID>: No Arm Detected” will be thrown if the arm is powered off.A ROBOT_NOT_READY exception “Stopping motion failed for Session ID <session ID>: Arm Initialization In Progress” if the arm is initializing.A METHOD_FAILED exception “Failed to change the operating mode : Unknown Event” if the arm is in fault (either powered on or off).A WRONG_MODE exception “Failed to change the operating mode : Invalid operating mode” will be thrown if the parameter is OPERATING_MODE_HAND_GUIDING.A WRONG_MODE exception “Failed to change the operating mode : Invalid transition between two operating modes” will be thrown if the parameter is not an admissible mode to transition into from the current operating mode.From the operating mode OPERATING_MODE_MONITORED_STOP, the admissible transitions are to the operating modes:- OPERATING_MODE_MONITORED_STOP- OPERATING_MODE_HOLD_TO_RUN- OPERATING_MODE_AUTO- OPERATING_MODE_JOG_MANUALFrom the operating mode OPERATING_MODE_HOLD_TO_RUN, the admissible transitions are to the operating modes:- OPERATING_MODE_MONITORED_STOP- OPERATING_MODE_AUTO- OPERATING_MODE_JOG_MANUALFrom the operating mode OPERATING_MODE_AUTO, the admissible transitions are to the operating modes:- OPERATING_MODE_MONITORED_STOP- OPERATING_MODE_HOLD_TO_RUNFrom the operating mode OPERATING_MODE_JOG_MANUAL, the admissible transitions are to the operating modes:- OPERATING_MODE_MONITORED_STOP- OPERATING_MODE_HOLD_TO_RUN- OPERATING_MODE_JOG_MANUAL- Parameters
modeselection (ModeSelection) –
deviceId (int) – Device’s Id called by rpc (optional)
options (RouterClientSendOptions) – Router options for sending the message
- ExitRecoveryState(deviceId = 0, options = RouterClientSendOptions())¶
- The
OPERATE
permission is necessary to call this RPC.Exit the recovery state after clearing a faultThis RPC should be called when the Arm State is ARMSTATE_RECOVERY.A WRONG_MODE exception “Arm is not in recovery mode” is thrown if the arm is not in recovery modeA METHOD_FAILED exception “Arm is still in restricted area - can’t exit recovery mode” will be thrown if the arm is not out of the protection zone when the RPC is called- Parameters
deviceId (int) – Device’s Id called by rpc (optional)
options (RouterClientSendOptions) – Router options for sending the message
- DeactivateRobot(deviceId = 0, options = RouterClientSendOptions())¶
- The
OPERATE
permission is necessary to call this RPC.Deactivates the robot.- Parameters
deviceId (int) – Device’s Id called by rpc (optional)
options (RouterClientSendOptions) – Router options for sending the message
- GetCurrentOperatingMode(deviceId = 0, options = RouterClientSendOptions())¶
- The
READ_ONLY
permission is necessary to call this RPC.Retrieves the current robot operating mode- Parameters
deviceId (int) – Device’s Id called by rpc (optional)
options (RouterClientSendOptions) – Router options for sending the message
- Return type
- ReadAllUserRoles(deviceId = 0, options = RouterClientSendOptions())¶
- The
CONFIGURE
permission is necessary to call this RPC.Retrieves the list of existing User Roles- Parameters
deviceId (int) – Device’s Id called by rpc (optional)
options (RouterClientSendOptions) – Router options for sending the message
- Return type
- SetHandGuidingMode(handguiding, deviceId=0, options=RouterClientSendOptions())¶
- The
OPERATE
permission is necessary to call this RPC.Set the Hand-GuidingThis RPC can be called even if the arm is powered offAn INVALID_PARAM exception “Invalid hand-guiding type” is thrown if the hand guiding mode is not CARTESIAN or JOINT.- Parameters
handguiding (HandGuiding) –
deviceId (int) – Device’s Id called by rpc (optional)
options (RouterClientSendOptions) – Router options for sending the message
- GetHandGuidingMode(deviceId = 0, options = RouterClientSendOptions())¶
- The
READ_ONLY
permission is necessary to call this RPC.Get the Hand-Guiding mode that will be active while hand guiding- Parameters
deviceId (int) – Device’s Id called by rpc (optional)
options (RouterClientSendOptions) – Router options for sending the message
- Return type
- OnNotificationHandGuidingModeTopic(callback, notificationoptions)¶
- The
READ_ONLY
permission is necessary to call this RPC.Subscribes to Hand-Guiding mode topic for notifications- Parameters
callback (function) – Function callback taking a
HandGuidingModeNotification
as only argument, and returningNone
.notificationoptions (NotificationOptions) – Notification options
- Return type
- OnNotificationEnablingDeviceTopic(callback, notificationoptions)¶
- The
READ_ONLY
permission is necessary to call this RPC.Subscribes to enabling device topic for notifications- Parameters
callback (function) – Function callback taking a
EnablingDeviceNotification
as only argument, and returningNone
.notificationoptions (NotificationOptions) – Notification options
- Return type
- OnNotificationMotionTopic(callback, notificationoptions)¶
- The
READ_ONLY
permission is necessary to call this RPC.Subscribes to motion topic for notifications- Parameters
callback (function) – Function callback taking a
MotionNotification
as only argument, and returningNone
.notificationoptions (NotificationOptions) – Notification options
- Return type
- GetLastRecordedJointAngles(deviceId = 0, options = RouterClientSendOptions())¶
- The
READ_ONLY
permission is necessary to call this RPC.Gets the last recorded joint angles- Parameters
deviceId (int) – Device’s Id called by rpc (optional)
options (RouterClientSendOptions) – Router options for sending the message
- Return type
- OnNotificationProgramRequestTopic(callback, notificationoptions)¶
- The
READ_ONLY
permission is necessary to call this RPC.Subscribes to program request topic for notifications- Parameters
callback (function) – Function callback taking a
ProgramRequestNotification
as only argument, and returningNone
.notificationoptions (NotificationOptions) – Notification options
- Return type
- GetStorageList(deviceId = 0, options = RouterClientSendOptions())¶
- The
CONFIGURE
permission is necessary to call this RPC.Get available storage mount points- Parameters
deviceId (int) – Device’s Id called by rpc (optional)
options (RouterClientSendOptions) – Router options for sending the message
- Return type
- FileSystemList(fslistargs, deviceId=0, options=RouterClientSendOptions())¶
- The
CONFIGURE
permission is necessary to call this RPC.Perform file system item list (files and directories) from given path.- Parameters
fslistargs (FSListArgs) –
deviceId (int) – Device’s Id called by rpc (optional)
options (RouterClientSendOptions) – Router options for sending the message
- Return type
- FileWrite(fswriteargs, deviceId=0, options=RouterClientSendOptions())¶
- The
CONFIGURE
permission is necessary to call this RPC.Write text data to a file specified by given path. Directories are created if they do not exist.- Parameters
fswriteargs (FSWriteArgs) –
deviceId (int) – Device’s Id called by rpc (optional)
options (RouterClientSendOptions) – Router options for sending the message
- FileRead(fsreadargs, deviceId=0, options=RouterClientSendOptions())¶
- The
CONFIGURE
permission is necessary to call this RPC.Read text data from file specified by given path.- Parameters
fsreadargs (FSReadArgs) –
deviceId (int) – Device’s Id called by rpc (optional)
options (RouterClientSendOptions) – Router options for sending the message
- Return type
- RestoreNeutralArmCalibration(deviceId = 0, options = RouterClientSendOptions())¶
- The
CONFIGURE
permission is necessary to call this RPC.Restores arm calibration to neutral- Parameters
deviceId (int) – Device’s Id called by rpc (optional)
options (RouterClientSendOptions) – Router options for sending the message
- GetArmCalibrationStatus(deviceId = 0, options = RouterClientSendOptions())¶
- The
READ_ONLY
permission is necessary to call this RPC.Gets arm calibration status- Parameters
deviceId (int) – Device’s Id called by rpc (optional)
options (RouterClientSendOptions) – Router options for sending the message
- Return type
- OnNotificationArmCalibrationStatusChangeTopic(callback, notificationoptions)¶
- The
READ_ONLY
permission is necessary to call this RPC.Subscribes to arm calibration status change topic for notifications- Parameters
callback (function) – Function callback taking a
ArmCalibrationStatusChangeNotification
as only argument, and returningNone
.notificationoptions (NotificationOptions) – Notification options
- Return type
- OnNotificationAcknowledgeActionTopic(callback, notificationoptions)¶
- The
READ_ONLY
permission is necessary to call this RPC.Subscribes to acknowledge action topic for notifications- Parameters
callback (function) – Function callback taking a
AcknowledgeActionNotification
as only argument, and returningNone
.notificationoptions (NotificationOptions) – Notification options
- Return type