Skip to content

Latest commit

 

History

History
400 lines (387 loc) · 52.6 KB

File metadata and controls

400 lines (387 loc) · 52.6 KB

Base (C++)

This page describes the C++ Base API.

RPC reference

This section describes the existing RPCs used in this API.

Base service. Broadly useful service. Provides functions for configuring a range of base-related functionalities and for enabling high-level control for the robot.

BaseClient RPCs

Function name Return type Input type Description
CreateUserProfile UserProfileHandle FullUserProfile Creates a user profile and returns a handle to the profile
UpdateUserProfile Empty UserProfile Updates an existing user profile
ReadUserProfile UserProfile UserProfileHandle Retrieves an existing user profile
DeleteUserProfile Empty UserProfileHandle Deletes an existing user profile
ReadAllUserProfiles UserProfileList Empty Retrieves all user profiles
ReadAllUsers UserList Empty Retrieves the list of all user profile handles
ChangePassword Empty PasswordChange Changes the password of an existing user
CreateSequence SequenceHandle Sequence Creates a new sequence and returns a handle to the sequence
UpdateSequence Empty Sequence Updates an existing sequence
ReadSequence Sequence SequenceHandle Retrieves an existing sequence
DeleteSequence Empty SequenceHandle Deletes an existing sequence
ReadAllSequences SequenceList Empty Retrieves the list of all existing sequences
PlaySequence Empty SequenceHandle Plays an existing sequence
PlayAdvancedSequence Empty AdvancedSequenceHandle Plays an existing sequence with options
StopSequence Empty Empty Stops execution of currently playing sequence
PauseSequence Empty Empty Pauses execution of currently playing sequence
ResumeSequence Empty Empty Resumes execution of currently paused sequence
CreateProtectionZone ProtectionZoneHandle ProtectionZone Creates a new protection zone and returns a handle to the protection zone
UpdateProtectionZone Empty ProtectionZone Updates an existing protection zone
ReadProtectionZone ProtectionZone ProtectionZoneHandle Retrieves an existing protection zone
DeleteProtectionZone Empty ProtectionZoneHandle Deletes an existing protection zone
ReadAllProtectionZones ProtectionZoneList Empty Retrieves a list of all protection zones
CreateMapping MappingHandle Mapping Creates a new mapping
ReadMapping Mapping MappingHandle Retrieves an existing mapping
UpdateMapping Empty Mapping Updates an existing mapping
DeleteMapping Empty MappingHandle Deletes an existing mapping
ReadAllMappings MappingList Empty Retrieves a list of all mappings
CreateMap MapHandle Map Creates a new map
ReadMap Map MapHandle Retrieves an existing map
UpdateMap Empty Map Updates an existing map
DeleteMap Empty MapHandle Deletes an existing map
ReadAllMaps MapList MappingHandle Retrieves a list of all maps associated to the specified mapping
ActivateMap Empty ActivateMapHandle Activates the specified map within the specified map group and mapping
CreateAction ActionHandle Action Creates a new action
ReadAction Action ActionHandle Retrieves an existing action
ReadAllActions ActionList RequestedActionType Retrieves a list of all existing actions
DeleteAction Empty ActionHandle Deletes an existing action
UpdateAction Empty Action Updates an existing action
ExecuteActionFromReference Empty ActionHandle Commands the robot to execute the specified existing action
ExecuteAction Empty Action Commands the robot to execute the specified action
PauseAction Empty Empty Pauses the currently executed action. ResumeAction can be invoked afterwards
StopAction Empty Empty Stops the currently executed action. ResumeAction cannot be invoked afterwards
ResumeAction Empty Empty Resumes execution of the currently paused action
GetIPv4Configuration IPv4Configuration NetworkHandle Retrieves the IPv4 network configuration for the specified network adapter
SetIPv4Configuration Empty FullIPv4Configuration Modifies the IPv4 network configuration for the specified network adapter
SetCommunicationInterfaceEnable Empty CommunicationInterfaceConfiguration Enables (or disables) the specified communication interface
IsCommunicationInterfaceEnable CommunicationInterfaceConfiguration NetworkHandle Determines if the specified communication interface is enabled (or disabled)
GetAvailableWifi WifiInformationList Empty Retrieves the list of available Wi-Fi networks
GetWifiInformation WifiInformation Ssid Retrieves information about a specific Wi-Fi network
AddWifiConfiguration Empty WifiConfiguration Configures a specific Wi-Fi network
DeleteWifiConfiguration Empty Ssid Deletes a specific Wi-Fi network
GetAllConfiguredWifis WifiConfigurationList Empty Retrieves the list of configured Wi-Fi networks
ConnectWifi Empty Ssid Connects robot to specified Wi-Fi network
DisconnectWifi Empty Empty Disconnects the robot from the currently connected Wi-Fi network
GetConnectedWifiInformation WifiInformation Empty Retrieves information about the connected Wi-Fi network
Unsubscribe Empty NotificationHandle Unsubscribes client from receiving notifications for the specified topic
OnNotificationConfigurationChangeTopic NotificationHandle NotificationOptions Subscribes to configuration change topic for notifications
OnNotificationMappingInfoTopic NotificationHandle NotificationOptions Subscribes to mapping information topic for notifications
OnNotificationControlModeTopic NotificationHandle NotificationOptions Subscribes to control mode topic for notifications. This function may be removed in a future release. It has been moved to ControlConfig service.
OnNotificationOperatingModeTopic NotificationHandle NotificationOptions Subscribes to operating mode topic for notifications
OnNotificationSequenceInfoTopic NotificationHandle NotificationOptions Subscribes to sequence information topic for notifications
OnNotificationProtectionZoneTopic NotificationHandle NotificationOptions Subscribes to protection zone topic for notifications
OnNotificationUserTopic NotificationHandle NotificationOptions Subscribes to user topic for notifications
OnNotificationControllerTopic NotificationHandle NotificationOptions Subscribes to controller topic for notifications
OnNotificationActionTopic NotificationHandle NotificationOptions Subscribes to action topic for notifications
OnNotificationRobotEventTopic NotificationHandle NotificationOptions Subscribes to robot event topic for notifications
PlayCartesianTrajectory Empty ConstrainedPose Moves robot to the specifed tool pose (position and orientation) while imposing specified constraints. This RPC will be deprecated in a future version and will be replaced by ExecuteWaypointTrajectory.. This function will be removed in a future release.
PlayCartesianTrajectoryPosition Empty ConstrainedPosition Moves robot to the specifed position while imposing specified constraints. This RPC will be deprecated in a future version and will be replaced by ExecuteWaypointTrajectory.. This function will be removed in a future release.
PlayCartesianTrajectoryOrientation Empty ConstrainedOrientation Moves to the specifed orientation while imposing specified constraints. This RPC will be deprecated in a future version and will be replaced by ExecuteWaypointTrajectory.. This function will be removed in a future release.
Stop Empty Empty Stops robot movement
GetMeasuredCartesianPose Pose Empty Retrieves the current computed tool pose (position and orientation) for the robot
SendWrenchCommand Empty WrenchCommand Sends a wrench command (screw consisting of force and torque) to be applied to the tool. This method is EXPERIMENTAL.
SendWrenchJoystickCommand Empty WrenchCommand Sends a wrench (screw consisting of force and torque) joystick command to be applied to the tool. The wrench values sent to this call are expected to be a ratio of maximum value (between -1.0/+1.0). This method is EXPERIMENTAL.
SendTwistJoystickCommand Empty TwistCommand 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).
SendTwistCommand Empty TwistCommand Sends a twist (screw consisting of linear and angular velocity) command to be applied to the tool
PlayJointTrajectory Empty ConstrainedJointAngles Moves joints to the specified joint angles while imposing specified constraints. This RPC will be deprecated in a future version and will be replaced by ExecuteWaypointTrajectory.. This function will be removed in a future release.
PlaySelectedJointTrajectory Empty ConstrainedJointAngle Moves specifed joint to the specifed joint angle while imposing specified constraints. This RPC will be deprecated in a future version and will be replaced by ExecuteWaypointTrajectory.. This function will be removed in a future release.
GetMeasuredJointAngles JointAngles Empty Retrieves the currently measured joint angles for each joint
SendJointSpeedsCommand Empty JointSpeeds 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.
SendSelectedJointSpeedCommand Empty JointSpeed Sends a speed command for a specific joint
SendGripperCommand Empty GripperCommand Sends a command to move the gripper
GetMeasuredGripperMovement Gripper GripperRequest Retrieves the current gripper movement, that is the current gripper position, force or speed
SetAdmittance Empty Admittance Sets the robot in the chosen admittance mode
SetOperatingMode Empty OperatingModeInformation Sets a new operating mode. Only Maintenance, Update and Run modes are permitted.
ApplyEmergencyStop Empty Empty Stops robot movement and activates emergency stop state. You will not be able to move the robot. Use ClearFaults() to clear the stop.
ClearFaults Empty Empty Clears robot stop. Robot is permitted to move again.
GetControlMode ControlModeInformation Empty Retrieves current control mode. This function may be removed in a future release. It has been moved to ControlConfig service.
GetOperatingMode OperatingModeInformation Empty Retrieves current operating mode
SetServoingMode Empty ServoingModeInformation Sets the servoing mode
GetServoingMode ServoingModeInformation Empty Retrieves current servoing mode
OnNotificationServoingModeTopic NotificationHandle NotificationOptions Subscribes to servoing mode topic for notifications
RestoreFactorySettings Empty Empty Deletes all configurations and reverts settings to their factory defaults (except network settings)
Reboot Empty Empty Reboots the robot
OnNotificationFactoryTopic NotificationHandle NotificationOptions Subscribes to factory topic for notifications
GetAllConnectedControllers ControllerList Empty Retrieves the list of all connected controllers
GetControllerState ControllerState ControllerHandle Retrieves the state of a specified controller
GetActuatorCount ActuatorInformation Empty Retrieves the number of actuators in the robot
StartWifiScan Empty Empty Initiates Wi-Fi scanning
GetConfiguredWifi WifiConfiguration Ssid Retrieves a configured Wi-Fi network
OnNotificationNetworkTopic NotificationHandle NotificationOptions Subscribes to network event notifications
GetArmState ArmStateInformation Empty Retrieves current robot arm state
OnNotificationArmStateTopic NotificationHandle NotificationOptions Subscribes to robot arm state notifications
GetIPv4Information IPv4Information NetworkHandle Retrieves the IPv4 network information for the specified network adapter
SetWifiCountryCode Empty CountryCode Sets the Wi-Fi country code
GetWifiCountryCode CountryCode Empty Retrieves the Wi-Fi country code
SetCapSenseConfig Empty CapSenseConfig Configures capacitive sensor on the gripper or wrist
GetCapSenseConfig CapSenseConfig Empty Retrieves configuration of capacitive sensor on the gripper or wrist
GetAllJointsSpeedHardLimitation JointsLimitationsList Empty Retrieves speed hard limits for all joints. This function will be removed in a future release. Use GetKinematicHardLimits from the ControlConfig service instead.
GetAllJointsTorqueHardLimitation JointsLimitationsList Empty Retrieves torque hard limits for all joints. This function will be removed in a future release.
GetTwistHardLimitation TwistLimitation Empty Retrieves twist hard limitations. This function will be removed in a future release. Use GetKinematicHardLimits from the ControlConfig service instead.
GetWrenchHardLimitation WrenchLimitation Empty Retrieves wrench hard limitations. This function will be removed in a future release.
SendJointSpeedsJoystickCommand Empty JointSpeeds 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.
SendSelectedJointSpeedJoystickCommand Empty JointSpeed 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)
EnableBridge BridgeResult BridgeConfig Enables TCP bridge to hardware device
DisableBridge BridgeResult BridgeIdentifier Disables specified TCP bridge
GetBridgeList BridgeList Empty Retrieves list of created bridges
GetBridgeConfig BridgeConfig BridgeIdentifier Retrieves configuration for specified bridge
PlayPreComputedJointTrajectory Empty PreComputedJointTrajectory Plays a pre-computed angular trajectory
GetProductConfiguration CompleteProductConfiguration Empty Retrieves product configuration information
UpdateEndEffectorTypeConfiguration Empty ProductConfigurationEndEffectorType Set new end-effector type in product configuration (Identification Number)
RestoreFactoryProductConfiguration Empty Empty Restores product configuration to factory product configuration
GetTrajectoryErrorReport TrajectoryErrorReport Empty Obtains trajectory error report listing errors for rejected trajectory. Provides some feedback on why the trajectory could not be completed.
GetAllJointsSpeedSoftLimitation JointsLimitationsList Empty Retrieves list of soft speed limits for all joints. This function will be removed in a future release. Use GetKinematicSoftLimits from the ControlConfig service instead.
GetAllJointsTorqueSoftLimitation JointsLimitationsList Empty Retrieves list of soft torque limits for all joints. This function will be removed in a future release.
GetTwistSoftLimitation TwistLimitation Empty Retrieves all twist soft limitations. This function will be removed in a future release. Use GetKinematicSoftLimits from the ControlConfig service instead.
GetWrenchSoftLimitation WrenchLimitation Empty Retrieves all wrench soft limitations. This function will be removed in a future release.
SetControllerConfigurationMode Empty ControllerConfigurationMode Sets controller configuration mode
GetControllerConfigurationMode ControllerConfigurationMode Empty Retrieves current controller configuration mode
StartTeaching Empty SequenceTaskHandle Enables the teaching mode on a sequence
StopTeaching Empty Empty Disables the teaching mode on a sequence
AddSequenceTasks SequenceTasksRange SequenceTasksConfiguration Adds tasks to the specified sequence
UpdateSequenceTask Empty SequenceTaskConfiguration Updates a task within the specified sequence
SwapSequenceTasks Empty SequenceTasksPair Swaps two task indexes in a sequence
ReadSequenceTask SequenceTask SequenceTaskHandle Reads a specific task from the specified sequence
ReadAllSequenceTasks SequenceTasks SequenceHandle Reads all tasks from the specified sequence
DeleteSequenceTask Empty SequenceTaskHandle Deletes a specific task from the specified sequence
DeleteAllSequenceTasks Empty SequenceHandle Deletes all tasks from the specified sequence
TakeSnapshot Empty Snapshot Take a snapshot of current robot Cartesian, joint or gripper position
GetFirmwareBundleVersions FirmwareBundleVersions Empty Retrieves current firmware bundle versions
ExecuteWaypointTrajectory Empty WaypointList Executes a trajectory defined by a series of waypoints in joint space or in Cartesian space
MoveSequenceTask Empty SequenceTasksPair Move task to new index in a sequence
DuplicateMapping MappingHandle MappingHandle Duplicates an existing mapping
DuplicateMap MapHandle MapHandle Duplicates an existing map
SetControllerConfiguration Empty ControllerConfiguration Sets controller configuration
GetControllerConfiguration ControllerConfiguration ControllerHandle Retrieves current controller configuration
GetAllControllerConfigurations ControllerConfigurationList Empty Retrieves all controller configurations
ComputeForwardKinematics Pose JointAngles Get the forward kinematics given specified angular positions of actuators
ComputeInverseKinematics JointAngles IKData Get the inverse kinematics given a specified cartesian pose and guess of joint angles
ValidateWaypointList WaypointValidationReport WaypointList 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 return.
SetWifiEnableState Empty WifiEnableState Enable or disable the wifi capabilities on the arm
GetWifiEnableState WifiEnableState Empty Get the wifi capabilities state (enabled or disabled)
SetBluetoothEnableState Empty BluetoothEnableState Enable or disable the Bluetooth capabilities on the arm
GetBluetoothEnableState BluetoothEnableState Empty Get the Bluetooth capabilities state (enabled or disabled)

Class reference

This section describes the data classes used in this API.

Messages

Class Description
Action Defines an action. An action is some task performed on the robot.
ActionExecutionState Indicates the execution state of an action (not implemented yet)
ActionHandle Reference to a specific action
ActionList Array of actions
ActionNotification Notification about a single action event
ActionNotificationList Array of action notifications
ActivateMapHandle Reference to a specific new active map for the specified mapping and map group
ActuatorInformation A count of the number of actuators in the robot
Admittance An admittance mode
AdvancedSequenceHandle Reference to a sequence along with execution options
AngularWaypoint An angular Waypoint
AppendActionInformation Representation of the result of appending (adding at the end) an action to an existing sequence (not implemented yet)
ArmStateInformation Information about the arm state
ArmStateNotification Notification about a single arm state event
BluetoothEnableState  
BridgeConfig Bridge configuration information. It is used to either create a bridge or to retrieve information about an existing bridge
BridgeIdentifier Bridge identifier
BridgeList An array of configuration information for different bridges.
BridgePortConfig Port configuration information for a TCP port bridge
BridgeResult The result of an operation on a specific bridge
CapSenseConfig Capacitive sensor configuration information
CartesianLimitation Translation and orientation limits for a specified limit type for Cartesian configuration
CartesianLimitationList Array of Cartesian limitations
CartesianSpeed A Cartesian tool speed (translation speed and angular speed)
CartesianTrajectoryConstraint Cartesian trajectory constraint that can be applied when controlling in Cartesian trajectory mode
CartesianWaypoint A Cartesian Waypoint
ChangeJointSpeeds Action to change the maximum angular velocity per joint by a specific increment
ChangeTwist Action to change the maximum Cartesian velocity by a specific increment
ChangeWrench Action to change the maximum Cartesian force by a specific increment
CommunicationInterfaceConfiguration Configuration information for enabling or disabling a specific communication interface (e.g. Wi-Fi, Wired Ethernet)
ConfigurationChangeNotification Representation of a configuration change event
ConfigurationChangeNotificationList Array of configuration change notifications
ConstrainedJointAngle A single joint angle value with specifed constraint
ConstrainedJointAngles An array of joint angles values with specified constraint
ConstrainedOrientation Cartesian tool orientation with specified constraint
ConstrainedPose Cartesian tool pose with specified constraint
ConstrainedPosition Cartesian tool position with specified constraint
ControlModeInformation Control mode information This message may be removed in a future release. It has been moved to ControlConfig service.
ControlModeNotification Notification about a single control mode event
ControlModeNotificationList Array of control mode notifications
ControllerConfiguration Controller configuration information
ControllerConfigurationList Controller configuration information for multiple controllers
ControllerConfigurationMode Controller configuration mode information
ControllerElementHandle Reference ro a specific button (or axis) of a controller device
ControllerElementState Indicates if a specific button (or axis) was pressed (or moved)
ControllerEvent A controller event
ControllerHandle Reference to a specific controller device
ControllerList Array of references to different controllers
ControllerNotification Notification about a single controller event
ControllerNotificationList Array of controller notifications
ControllerState Indicates if a specific controller is connected (or disconnected)
Delay Action to apply a delay
EmergencyStop Action to force an emergency of the robot
FactoryNotification Notification about a single factory event
Faults Action to clear faults
Finger Movement of a specified gripper finger
FirmwareBundleVersions Firmware bundle versions including main firmware bundle version and components versions
FirmwareComponentVersion Individual component with its version
FullIPv4Configuration IPv4 configuration for a specific network
FullUserProfile Information about a user, together with a password. Full set of information needed to create a user profile.
GpioCommand A command to control expansion port's GPIO
GpioConfiguration GPIO port configuration information
GpioConfigurationList List of GPIO port configurations
GpioEvent A GPIO event
GpioPinConfiguration GPIO pin configuration information
Gripper Gripper movement composed of a series of fingers movement
GripperCommand A command to control the gripper movement
GripperRequest Request to apply a specific gripper mode
IKData Input needed for the calculation of inverse kinematics
IPv4Configuration IPv4 configuration information
IPv4Information Information about an IPv4 endpoint
JointAngle Angle value of a specific joint
JointAngles An array of joint angles
JointLimitation Limitation for a specified robot joint
JointSpeed Speed of a specific joint
JointSpeeds An array of joints speeds
JointTorque joint torque for a specified joint
JointTorques An array of joint torques
JointTrajectoryConstraint Joint trajectory constraint that can be applied when controlling a joint in trajectory mode
JointsLimitationsList Array of joint limitations
KinematicTrajectoryConstraints Angular and Cartesian kinematic constraints (maximum velocities)
Map A map as an array of map elements
MapElement Associates an event to an action
MapEvent A map event
MapGroup All information about a map group including the list of maps that it contains and its relationship versus other map groups (not implemented yet)
MapGroupHandle Reference to a specific map group (not implemented yet)
MapGroupList Array of map groups (not implemented yet)
MapHandle Reference to a specific map
MapList Array of maps
Mapping All information about a mapping including the controller to which it is associated, the array of map groups it contains, the currently active map group, the array of maps it contains and the currently active map
MappingHandle Reference to a specific Mapping
MappingInfoNotification Notification about a single mapping information event
MappingInfoNotificationList Array of mapping information notifications
MappingList Array of mappings
NetworkHandle Reference to a network
NetworkNotification Notification about a single network event
NetworkNotificationList Array of network event notifications
OperatingModeInformation Information about the operating mode
OperatingModeNotification Notification about a single operating mode event
OperatingModeNotificationList Array of operating mode notifications
Orientation A Cartesian tool orientation. Defines orientation as sequence of three Euler angles using x-y-z Tait-Bryan extrinsic convention. That is, rotation around fixed X-axis, then rotation around fixed Y-axis, then rotation around fixed Z-axis.
PasswordChange Information required to change user password
Point Coordinates of a Cartesian point
Pose A Cartesian tool pose (position and orientation). Orientation is defined as a sequence of three Euler angles using x-y-z Tait-Bryan extrinsic convention. That is, rotation around fixed X-axis, then rotation around fixed Y-axis, then rotation around fixed Z-axis.
Position A Cartesian tool position
PreComputedJointTrajectory Pre-computed joint trajectory subject to specified continuity constraints. The starting point of the trajectory must have an elapsed time of 0 ms and the angular values must reflect the current state of the robot. The robot control libraries will validate the trajectory fulfills the specified continuity constraints before playing the trajectory.
PreComputedJointTrajectoryElement Set of angle, speed, acceleration, and elapsed time values for each joint for a given 1 ms interval. A PreComputedJointTrajectory is made up of a series of these elements.
ProtectionZone Protection zone configuration
ProtectionZoneHandle Reference to a specific protection zone
ProtectionZoneInformation Information about a protection zone event
ProtectionZoneList Array of protection zones
ProtectionZoneNotification Notification about a single protection zone event
ProtectionZoneNotificationList Array of protection zone notifications
Query Parameters of an event log query (not implemented yet)
RFConfiguration  
RequestedActionType Message used for requesting all action instances of a specific action type
RobotEventNotification Notification about a single robot event
RobotEventNotificationList Array of robot event notifications
RotationMatrix Representation of a 3x3 rotation matrix. To be a valid rotation matrix, the rows must be orthonormal (the rows must each have norm of 1 and the row vectors must be orthogonal to each other). The determinant of the matrix must also be +1.
RotationMatrixRow Single row of a 3x3 rotation matrix. To be a valid possible row of a rotation matrix, the norm of the row must be 1 (the sum of the squares of the row elements has to equal 1).
SafetyEvent A safety event (not implemented yet)
SafetyNotificationList Array of safety notifications
Sequence Information about a sequence
SequenceHandle Reference to a specific sequence
SequenceInfoNotification Notification about a single sequence information event
SequenceInfoNotificationList Array of sequence information notifications
SequenceInformation Information about a sequence
SequenceList An array of sequences
SequenceTask Information on a single task within a sequence
SequenceTaskConfiguration Reference to a specific task within a sequence, and configuration information on task to be updated
SequenceTaskHandle Reference to a specific task inside a sequence
SequenceTasks Information on multiple tasks within a sequence
SequenceTasksConfiguration Reference to a specific task within a sequence, and information on list of sequence tasks to be inserted
SequenceTasksPair Information on a sequence and a pair of tasks to be operated on
SequenceTasksRange Information on a range of task indexes
ServoingModeInformation Information about the servoing mode
ServoingModeNotification Notification about a single servoing mode event
ServoingModeNotificationList Array of servoing mode notifications
Snapshot Action parameter to take a snapshot of current robot position
Ssid Wi-Fi SSID
Stop Action to stop robot movement
SwitchControlMapping Action parameter to switch the active controller map
SystemTime Identifies the system time (not implemented yet)
Timeout Timeout for a specified duration
TrajectoryErrorElement Details for a single trajectory validation error
TrajectoryErrorReport Report collecting information on different validation errors for a particular trajectory
TrajectoryInfo Additional trajectory information
TransformationMatrix A 4x4 homogeneous transformation matrix representing the transformation between two reference frames.
TransformationRow A single row of a 4x4 homogeneous transformation matrix
Twist A twist (linear and angular velocity).
TwistCommand A twist command to be applied to the tool
TwistLimitation Linear and angular speed limitations for twist configuration
UserList Array of user profile handles
UserNotification Notification about a single user event
UserNotificationList Array of user notifications
UserProfile Information about a user
UserProfileList Array of user profiles
Waypoint A waypoint describing part of a trajectory.
WaypointList A waypoint list
WaypointValidationReport Waypoint Validation results
WifiConfiguration Wi-Fi connection configuration
WifiConfigurationList Array of Wi-Fi connection configuration for different networks
WifiEnableState  
WifiInformation Information about a specific Wi-Fi network
WifiInformationList Array of information about different Wi-Fi networks
Wrench A wrench (force and torque)
WrenchCommand A wrench command to be applied to the tool
WrenchLimitation Force and torque limitations for wrench configuration
ZoneShape Protection zone shape description

Enumerators

Enumerator Description
ActionEvent Admissible action event types
ActionType Admissible types of actions
AdmittanceMode Admissible admittance modes
BackupEvent Admissible backup events (not implemented yet)
BridgeStatus Bridge operation status
BridgeType Type of port forward bridge to create
CapSenseMode Admissible capacitive sensor modes
ConfigurationNotificationEvent Admissible configuration events
ControlMode Admissible robot control modes. This enum may be removed in a future release. It has been moved to ControlConfig service.
ControllerBehavior Admissible controller input behaviors
ControllerElementEventType Admissible controller element event types
ControllerEventType Admissible controller event types
ControllerInputType Admissible controller input types
ControllerType Admissible controller types
EventIdSequenceInfoNotification Admissible sequence event types
FactoryEvent Admissible factory events
Gen3GpioPinId Available GPIO PIN (See the user guide at section Base expansion connector)
GpioAction Admissible GPIO actions
GpioBehavior Admissible GPIO behavior
GpioPinPropertyFlags Admissible gpio pin properties
GripperMode Admissible gripper control mode
JointNavigationDirection Admissible joint navigation directions
JointTrajectoryConstraintType Admissible constraint types that can be applied when controlling a joint in trajectory mode
LedState Admissible LED states (not implemented yet)
LimitationType Admissible limitation types
NavigationDirection Admissible map navigation directions
NetworkEvent Admissible network events
NetworkType Admissible network types
OperatingMode Admissible robot operating modes (used to report robot firmware upgrade current state)
ProtectionZoneEvent Admissible protection zone events
RobotEvent Admissible robot events
SafetyIdentifier Admissible Base safeties. Used with BaseCyclic.BaseFeedback.[fault_bank_a
ServiceVersion Identifies Base service current version
ServoingMode Admissible servoing modes
ShapeType Admissible protection zone shape types
SignalQuality Admissible signal quality values
SnapshotType Admissible types of snapshots
SoundType Admissible sound types (not implemented yet)
TrajectoryContinuityMode Admissible trajectory continuity mode
TrajectoryErrorIdentifier This enum is deprecated and will be removed in a future release
TrajectoryErrorType Trajectory validation error types
TrajectoryInfoType Additional trajectory info type
UserEvent Admissible user event types
WifiEncryptionType Admissible Wi-Fi encryption types
WifiSecurityType Admissible Wi-Fi Security types
WrenchMode Admissible wrench (force) modes
WristDigitalInputIdentifier Admissible Wrist digital inputs
Xbox360AnalogInputIdentifier Admissible XBOX360 analog inputs
Xbox360DigitalInputIdentifier Admissible XBOX360 digital inputs