Flexiv RDK APIs  0.10
Public Member Functions | Friends | List of all members
flexiv::Robot Class Reference

Main interface with the robot, containing several function categories and background services. More...

#include <Robot.hpp>

Public Member Functions

 Robot (const std::string &serverIP, const std::string &localIP)
 [Blocking] Create a flexiv::Robot instance as the main robot interface. RDK services will initialize and connection with the robot will be established. More...
 
const RobotInfo info (void)
 [Non-blocking] Access general information of the robot. More...
 
void enable (void)
 [Blocking] Enable the robot, if E-stop is released and there's no fault, the robot will release brakes, and becomes operational a few seconds later. More...
 
void stop (void)
 [Blocking] Stop the robot and transit robot mode to Idle. More...
 
bool isOperational (bool verbose=true) const
 [Non-blocking] Check if the robot is normally operational, which requires the following conditions to be met: enabled, brakes fully released, in auto mode, no fault, and not in reduced state. More...
 
bool isBusy (void) const
 [Non-blocking] Check if the robot is currently executing a task. This includes any user commanded operations that requires the robot to execute. For example, plans, primitives, Cartesian and joint motions, etc. More...
 
bool isConnected (void) const
 [Non-blocking] Check if the connection with the robot is established. More...
 
bool isFault (void) const
 [Non-blocking] Check if the robot is in fault state. More...
 
bool isEstopReleased (void) const
 [Non-blocking] Check if the Emergency Stop is released. More...
 
bool isEnablingButtonPressed (void) const
 [Non-blocking] Check if the enabling button is pressed. More...
 
bool isRecoveryState (void) const
 [Non-blocking] Check if the robot system is in recovery state. More...
 
void connect (void)
 [Blocking] Try establishing connection with the robot. More...
 
void disconnect (void)
 [Blocking] Disconnect with the robot. More...
 
void clearFault (void)
 [Blocking] Clear minor fault of the robot. More...
 
void setMode (Mode mode)
 [Blocking] Set a new control mode to the robot and wait until the mode transition is finished. More...
 
Mode getMode (void) const
 [Non-blocking] Get the current control mode of the robot. More...
 
void getRobotStates (RobotStates &output)
 [Non-blocking] Get the latest robot states. More...
 
void executePlan (unsigned int index, bool continueExec=false)
 [Blocking] Execute a plan by specifying its index. More...
 
void executePlan (const std::string &name, bool continueExec=false)
 [Blocking] Execute a plan by specifying its name. More...
 
void pausePlan (bool pause)
 [Blocking] Pause or resume the execution of the current plan. More...
 
std::vector< std::string > getPlanNameList (void) const
 [Blocking] Get a list of all available plans from the robot. More...
 
void getPlanInfo (PlanInfo &output)
 [Blocking] Get detailed information about the currently running plan. Contains information like plan name, primitive name, node name, node path, node path time period, etc. More...
 
void executePrimitive (const std::string &ptCmd)
 [Blocking] Execute a primitive by specifying its name and parameters, which can be found in the Flexiv Primitives documentation. More...
 
std::vector< std::string > getPrimitiveStates (void) const
 [Blocking] Get feedback states of the currently executing primitive. More...
 
void setGlobalVariables (const std::string &globalVars)
 [Blocking] Set global variables for the robot by specifying name and value. More...
 
std::vector< std::string > getGlobalVariables (void) const
 [Blocking] Get available global variables from the robot. More...
 
bool isStopped (void) const
 [Non-blocking] Check if the robot has come to a complete stop. More...
 
void switchTcp (unsigned int index)
 [Blocking] If the mounted tool has more than one TCP, switch the TCP being used by the robot. Default to the 1st one (index = 0). More...
 
void runAutoRecovery (void)
 [Blocking] Run automatic recovery to bring joints that are outside the allowed position range back into allowed range. More...
 
void streamJointTorque (const std::vector< double > &torques, bool enableGravityComp=true, bool enableSoftLimits=true)
 [Non-blocking] Continuously stream joint torque command to the robot. More...
 
void streamJointPosition (const std::vector< double > &positions, const std::vector< double > &velocities, const std::vector< double > &accelerations)
 [Non-blocking] Continuously stream joint position, velocity, and acceleration command to the robot. More...
 
void sendJointPosition (const std::vector< double > &positions, const std::vector< double > &velocities, const std::vector< double > &accelerations, const std::vector< double > &maxVel, const std::vector< double > &maxAcc)
 [Non-blocking] Discretely send joint position, velocity, and acceleration command. The robot's internal motion generator will smoothen the discrete commands. More...
 
void streamCartesianMotionForce (const std::vector< double > &pose, const std::vector< double > &wrench=std::vector< double >(6))
 [Non-blocking] Continuously stream Cartesian motion and/or force command for the robot to track using its unified motion-force controller, which allows doing force control in zero or more Cartesian axes and motion control in the rest axes. More...
 
void sendCartesianMotionForce (const std::vector< double > &pose, const std::vector< double > &wrench=std::vector< double >(6), double maxLinearVel=0.5, double maxAngularVel=1.0)
 [Non-blocking] Discretely send Cartesian motion and/or force command for the robot to track using its unified motion-force controller, which allows doing force control in zero or more Cartesian axes and motion control in the rest axes. The robot's internal motion generator will smoothen the discrete commands. More...
 
void setCartesianStiffness (const std::vector< double > &stiffness)
 [Non-blocking] Set motion stiffness for the Cartesian motion-force control modes. More...
 
void resetCartesianStiffness (void)
 [Non-blocking] Reset motion stiffness for the Cartesian motion-force control modes to nominal value. More...
 
void setMaxContactWrench (const std::vector< double > &maxWrench)
 [Non-blocking] Set maximum contact wrench for the motion control part of the Cartesian motion-force control modes. The controller will regulate its output to maintain contact wrench (force and moment) with the environment under the set values. More...
 
void resetMaxContactWrench (void)
 [Non-blocking] Reset max contact wrench regulation to nominal state, i.e. disabled. More...
 
void setNullSpacePosture (const std::vector< double > &preferredPositions)
 [Non-blocking] Set preferred joint positions for the null-space posture control module used in the Cartesian motion-force control modes. More...
 
void resetNullSpacePosture (void)
 [Non-blocking] Reset preferred joint positions to the ones automatically recorded when entering the applicable control modes. More...
 
void setForceControlAxis (const std::vector< bool > &enabledAxis)
 [Blocking] Set force-controlled Cartesian axis(s) for the Cartesian motion-force control modes. The axis(s) not enabled for force control will be motion controlled. This function can only be called when the robot is in IDLE mode. More...
 
void setForceControlFrame (const std::string &referenceFrame)
 [Blocking] Set force control reference frame for the Cartesian motion-force control modes. This function can only be called when the robot is in IDLE mode. More...
 
void setPassiveForceControl (bool isEnabled)
 [Blocking] Enable or disable passive force control for the Cartesian motion-force control modes. When enabled, an open-loop force controller will be used to feed forward the target wrench, i.e. passive force control. When disabled, a closed-loop force controller will be used to track the target wrench, i.e. active force control. This function can only be called when the robot is in IDLE mode. More...
 
void writeDigitalOutput (const std::vector< unsigned int > &portIdx, const std::vector< bool > &values)
 [Blocking] Write to a single or multiple digital output port(s) on the control box. More...
 
std::array< bool, k_IOPorts > readDigitalInput (void)
 [Non-blocking] Read all digital input ports on the control box. More...
 

Friends

class Model
 
class Gripper
 

Detailed Description

Main interface with the robot, containing several function categories and background services.

Examples
basics1_display_robot_states.cpp, basics2_clear_fault.cpp, basics3_primitive_execution.cpp, basics4_plan_execution.cpp, basics5_zero_force_torque_sensors.cpp, basics6_gripper_control.cpp, basics7_auto_recovery.cpp, intermediate1_realtime_joint_position_control.cpp, intermediate2_realtime_joint_torque_control.cpp, intermediate3_realtime_joint_floating.cpp, intermediate4_realtime_cartesian_pure_motion_control.cpp, intermediate5_realtime_cartesian_motion_force_control.cpp, intermediate6_robot_dynamics.cpp, and intermediate7_teach_by_demonstration.cpp.

Definition at line 24 of file Robot.hpp.

Constructor & Destructor Documentation

◆ Robot()

flexiv::Robot::Robot ( const std::string &  serverIP,
const std::string &  localIP 
)

[Blocking] Create a flexiv::Robot instance as the main robot interface. RDK services will initialize and connection with the robot will be established.

Parameters
[in]serverIPIP address of the robot to connect (remote).
[in]localIPIP address of the workstation PC (local).
Exceptions
InitExceptionif the instance failed to initialize.
CompatibilityExceptionif the RDK library version is incompatible with the connected robot.
CommExceptionif failed to establish connection with the robot.
Warning
This constructor blocks until the initialization sequence is successfully finished and connection with the robot is established.

Member Function Documentation

◆ clearFault()

void flexiv::Robot::clearFault ( void  )

◆ connect()

void flexiv::Robot::connect ( void  )

[Blocking] Try establishing connection with the robot.

Exceptions
CommExceptionif failed to establish connection.
Warning
This function blocks until the reconnection is finished.

◆ disconnect()

void flexiv::Robot::disconnect ( void  )

[Blocking] Disconnect with the robot.

Exceptions
ExecutionExceptionif error occurred during execution.
Warning
This function blocks until the disconnection is finished.

◆ enable()

void flexiv::Robot::enable ( void  )

[Blocking] Enable the robot, if E-stop is released and there's no fault, the robot will release brakes, and becomes operational a few seconds later.

Exceptions
ExecutionExceptionif error occurred during execution.
CommExceptionif the robot is not connected.
Warning
This function blocks until the request is successfully delivered to the robot.
Examples
basics1_display_robot_states.cpp, intermediate1_realtime_joint_position_control.cpp, intermediate2_realtime_joint_torque_control.cpp, intermediate3_realtime_joint_floating.cpp, intermediate4_realtime_cartesian_pure_motion_control.cpp, intermediate5_realtime_cartesian_motion_force_control.cpp, and intermediate6_robot_dynamics.cpp.

◆ executePlan() [1/2]

void flexiv::Robot::executePlan ( const std::string &  name,
bool  continueExec = false 
)

[Blocking] Execute a plan by specifying its name.

Parameters
[in]nameName of the plan to execute, can be obtained via getPlanNameList().
[in]continueExecWhether to continue executing the plan when the RDK program is closed or the connection is lost.
Exceptions
LogicExceptionif robot is not in the correct control mode.
ExecutionExceptionif error occurred during execution.
Note
Applicable control mode: NRT_PLAN_EXECUTION.
isBusy() can be used to check if a plan task has finished.
Warning
This function blocks until the request is successfully delivered to the robot and fully processed.

◆ executePlan() [2/2]

void flexiv::Robot::executePlan ( unsigned int  index,
bool  continueExec = false 
)

[Blocking] Execute a plan by specifying its index.

Parameters
[in]indexIndex of the plan to execute, can be obtained via getPlanNameList().
[in]continueExecWhether to continue executing the plan when the RDK program is closed or the connection is lost.
Exceptions
InputExceptionif index is invalid.
LogicExceptionif robot is not in the correct control mode.
ExecutionExceptionif error occurred during execution.
Note
Applicable control mode: NRT_PLAN_EXECUTION.
isBusy() can be used to check if a plan task has finished.
Warning
This function blocks until the request is successfully delivered to the robot and fully processed.

◆ executePrimitive()

void flexiv::Robot::executePrimitive ( const std::string &  ptCmd)

[Blocking] Execute a primitive by specifying its name and parameters, which can be found in the Flexiv Primitives documentation.

Parameters
[in]ptCmdPrimitive command with the following string format: "primitiveName(inputParam1=xxx, inputParam2=xxx, ...)".
Exceptions
InputExceptionif size of the input string is greater than 5kb.
LogicExceptionif robot is not in the correct control mode.
ExecutionExceptionif error occurred during execution.
Note
Applicable control mode: NRT_PRIMITIVE_EXECUTION.
Warning
The primitive input parameters may not use SI units, please refer to the Flexiv Primitives documentation for exact unit definition.
Some primitives may not terminate automatically and require users to manually terminate them based on specific primitive states, for example, most [Move] primitives. In such case, isBusy() will stay true even if it seems everything is done for that primitive.
This function blocks until the request is successfully delivered to the robot and fully processed.
Examples
intermediate1_realtime_joint_position_control.cpp, intermediate2_realtime_joint_torque_control.cpp, intermediate3_realtime_joint_floating.cpp, intermediate4_realtime_cartesian_pure_motion_control.cpp, intermediate5_realtime_cartesian_motion_force_control.cpp, and intermediate6_robot_dynamics.cpp.

◆ getGlobalVariables()

std::vector<std::string> flexiv::Robot::getGlobalVariables ( void  ) const

[Blocking] Get available global variables from the robot.

Returns
Global variables in the format of a string list.
Exceptions
CommExceptionif there's no response from the robot.
ExecutionExceptionif error occurred during execution.
Warning
This function blocks until the reply from the robot is received.

◆ getMode()

Mode flexiv::Robot::getMode ( void  ) const

[Non-blocking] Get the current control mode of the robot.

Returns
flexiv::Mode enum.

◆ getPlanInfo()

void flexiv::Robot::getPlanInfo ( PlanInfo output)

[Blocking] Get detailed information about the currently running plan. Contains information like plan name, primitive name, node name, node path, node path time period, etc.

Parameters
[out]outputReference of output data object.
Exceptions
CommExceptionif there's no response from the robot.
ExecutionExceptionif error occurred during execution.
Warning
This function blocks until the reply from the robot is received.

◆ getPlanNameList()

std::vector<std::string> flexiv::Robot::getPlanNameList ( void  ) const

[Blocking] Get a list of all available plans from the robot.

Returns
Available plans in the format of a string list.
Exceptions
CommExceptionif there's no response from the robot.
ExecutionExceptionif error occurred during execution.
Warning
This function blocks until the reply from the robot is received.

◆ getPrimitiveStates()

std::vector<std::string> flexiv::Robot::getPrimitiveStates ( void  ) const

[Blocking] Get feedback states of the currently executing primitive.

Returns
Primitive states in the format of a string list.
Exceptions
CommExceptionif there's no response from the robot or the result is invalid.
ExecutionExceptionif error occurred during execution.
Warning
This function blocks until the reply from the robot is received.

◆ getRobotStates()

void flexiv::Robot::getRobotStates ( RobotStates output)

◆ info()

const RobotInfo flexiv::Robot::info ( void  )

[Non-blocking] Access general information of the robot.

Returns
RobotInfo struct.
Examples
intermediate4_realtime_cartesian_pure_motion_control.cpp.

◆ isBusy()

bool flexiv::Robot::isBusy ( void  ) const

[Non-blocking] Check if the robot is currently executing a task. This includes any user commanded operations that requires the robot to execute. For example, plans, primitives, Cartesian and joint motions, etc.

Returns
True: busy, false: idle.
Warning
Some exceptions exist for primitives, see executePrimitive() warning for more details.
Examples
intermediate1_realtime_joint_position_control.cpp, intermediate2_realtime_joint_torque_control.cpp, intermediate3_realtime_joint_floating.cpp, intermediate4_realtime_cartesian_pure_motion_control.cpp, intermediate5_realtime_cartesian_motion_force_control.cpp, and intermediate6_robot_dynamics.cpp.

◆ isConnected()

bool flexiv::Robot::isConnected ( void  ) const

[Non-blocking] Check if the connection with the robot is established.

Returns
True: connected, false: disconnected.

◆ isEnablingButtonPressed()

bool flexiv::Robot::isEnablingButtonPressed ( void  ) const

[Non-blocking] Check if the enabling button is pressed.

Returns
True: pressed, false: released.

◆ isEstopReleased()

bool flexiv::Robot::isEstopReleased ( void  ) const

[Non-blocking] Check if the Emergency Stop is released.

Returns
True: released, false: pressed.

◆ isFault()

bool flexiv::Robot::isFault ( void  ) const

◆ isOperational()

bool flexiv::Robot::isOperational ( bool  verbose = true) const

[Non-blocking] Check if the robot is normally operational, which requires the following conditions to be met: enabled, brakes fully released, in auto mode, no fault, and not in reduced state.

Parameters
[in]verboseWhether to print warning message indicating why the robot is not operational when this function returns false.
Returns
True: operational, false: not operational.
Warning
The robot won't execute any user command until it becomes normally operational.
Examples
basics1_display_robot_states.cpp, intermediate1_realtime_joint_position_control.cpp, intermediate2_realtime_joint_torque_control.cpp, intermediate3_realtime_joint_floating.cpp, intermediate4_realtime_cartesian_pure_motion_control.cpp, intermediate5_realtime_cartesian_motion_force_control.cpp, and intermediate6_robot_dynamics.cpp.

◆ isRecoveryState()

bool flexiv::Robot::isRecoveryState ( void  ) const

[Non-blocking] Check if the robot system is in recovery state.

Returns
True: in recovery state, false: not in recovery state.
Note
Use runAutoRecovery() to carry out automatic recovery operation.
Recovery state
The robot system will enter recovery state if it needs to recover from joint position limit violation (a critical system fault that requires a recovery operation, during which the joints that moved outside the allowed position range will need to move very slowly back into the allowed range). Refer to user manual for more details about system recovery state.

◆ isStopped()

bool flexiv::Robot::isStopped ( void  ) const

[Non-blocking] Check if the robot has come to a complete stop.

Returns
True: stopped, false: still moving.

◆ pausePlan()

void flexiv::Robot::pausePlan ( bool  pause)

[Blocking] Pause or resume the execution of the current plan.

Parameters
[in]pauseTrue: pause plan, false: resume plan.
Exceptions
LogicExceptionif robot is not in the correct control mode.
ExecutionExceptionif error occurred during execution.
Note
Applicable control mode: NRT_PLAN_EXECUTION.
Warning
This function blocks until the request is successfully delivered to the robot and fully processed.

◆ readDigitalInput()

std::array<bool, k_IOPorts> flexiv::Robot::readDigitalInput ( void  )

[Non-blocking] Read all digital input ports on the control box.

Returns
Digital input readings array whose index corresponds to the digital input port index. True: port high, false: port low.

◆ resetCartesianStiffness()

void flexiv::Robot::resetCartesianStiffness ( void  )

[Non-blocking] Reset motion stiffness for the Cartesian motion-force control modes to nominal value.

Note
Applicable control modes: RT/NRT_CARTESIAN_MOTION_FORCE.
Examples
intermediate4_realtime_cartesian_pure_motion_control.cpp.

◆ resetMaxContactWrench()

void flexiv::Robot::resetMaxContactWrench ( void  )

[Non-blocking] Reset max contact wrench regulation to nominal state, i.e. disabled.

Note
Applicable control modes: RT/NRT_CARTESIAN_MOTION_FORCE.
Examples
intermediate4_realtime_cartesian_pure_motion_control.cpp, and intermediate5_realtime_cartesian_motion_force_control.cpp.

◆ resetNullSpacePosture()

void flexiv::Robot::resetNullSpacePosture ( void  )

[Non-blocking] Reset preferred joint positions to the ones automatically recorded when entering the applicable control modes.

Note
Applicable control modes: RT/NRT_CARTESIAN_MOTION_FORCE.
Examples
intermediate4_realtime_cartesian_pure_motion_control.cpp.

◆ runAutoRecovery()

void flexiv::Robot::runAutoRecovery ( void  )

[Blocking] Run automatic recovery to bring joints that are outside the allowed position range back into allowed range.

Exceptions
ExecutionExceptionif error occurred during execution.
Note
Refer to user manual for more details.
Warning
This function blocks until the automatic recovery process is finished.
See also
isRecoveryState()

◆ sendCartesianMotionForce()

void flexiv::Robot::sendCartesianMotionForce ( const std::vector< double > &  pose,
const std::vector< double > &  wrench = std::vector< double >(6),
double  maxLinearVel = 0.5,
double  maxAngularVel = 1.0 
)

[Non-blocking] Discretely send Cartesian motion and/or force command for the robot to track using its unified motion-force controller, which allows doing force control in zero or more Cartesian axes and motion control in the rest axes. The robot's internal motion generator will smoothen the discrete commands.

Parameters
[in]poseTarget TCP pose in base frame: \( {^{O}T_{TCP}}_{d} \in \mathbb{R}^{7 \times 1} \). Consists of \( \mathbb{R}^{3 \times 1} \) position and \( \mathbb{R}^{4 \times 1} \) quaternion: \( [x, y, z, q_w, q_x, q_y, q_z]^T \). Unit: \( [m]~[] \).
[in]wrenchTarget TCP wrench (force and moment) in the force control reference frame (configured by setForceControlFrame()): \( ^{0}F_d \in \mathbb{R}^{6 \times 1} \). The robot will track the target wrench using an explicit force controller. Consists of \( \mathbb{R}^{3 \times 1} \) force and \( \mathbb{R}^{3 \times 1} \) moment: \( [f_x, f_y, f_z, m_x, m_y, m_z]^T \). Unit: \( [N]~[Nm] \).
[in]maxLinearVelMaximum Cartesian linear velocity when moving to the target pose. A safe value is provided as default. Unit: \( [m/s] \).
[in]maxAngularVelMaximum Cartesian angular velocity when moving to the target pose. A safe value is provided as default. Unit: \( [rad/s] \).
Exceptions
InputExceptionif input is invalid.
LogicExceptionif robot is not in the correct control mode.
ExecutionExceptionif error occurred during execution.
Note
Applicable control modes: NRT_CARTESIAN_MOTION_FORCE.
How to achieve pure motion control?
Use setForceControlAxis() to disable force control for all Cartesian axes to achieve pure motion control. This function does pure motion control out of the box.
How to achieve pure force control?
Use setForceControlAxis() to enable force control for all Cartesian axes to achieve pure force control, active or passive.
How to achieve unified motion-force control?
Use setForceControlAxis() to enable force control for one or more Cartesian axes and leave the rest axes motion-controlled, then provide target pose for the motion-controlled axes and target wrench for the force-controlled axes.
See also
setCartesianStiffness(), setMaxContactWrench(), setNullSpacePosture(), setForceControlAxis(), setForceControlFrame(), setPassiveForceControl().
Examples
intermediate5_realtime_cartesian_motion_force_control.cpp.

◆ sendJointPosition()

void flexiv::Robot::sendJointPosition ( const std::vector< double > &  positions,
const std::vector< double > &  velocities,
const std::vector< double > &  accelerations,
const std::vector< double > &  maxVel,
const std::vector< double > &  maxAcc 
)

[Non-blocking] Discretely send joint position, velocity, and acceleration command. The robot's internal motion generator will smoothen the discrete commands.

Parameters
[in]positionsTarget joint positions: \( q_d \in \mathbb{R}^{DOF \times 1} \). Unit: \( [rad] \).
[in]velocitiesTarget joint velocities: \( \dot{q}_d \in \mathbb{R}^{DOF \times 1} \). Each joint will maintain this amount of velocity when it reaches the target position. Unit: \( [rad/s] \).
[in]accelerationsTarget joint accelerations: \( \ddot{q}_d \in \mathbb{R}^{DOF \times 1} \). Each joint will maintain this amount of acceleration when it reaches the target position. Unit: \( [rad/s^2] \).
[in]maxVelMaximum joint velocities for the planned trajectory: \( \dot{q}_{max} \in \mathbb{R}^{DOF \times 1} \). Unit: \( [rad/s] \).
[in]maxAccMaximum joint accelerations for the planned trajectory: \( \ddot{q}_{max} \in \mathbb{R}^{DOF \times 1} \). Unit: \( [rad/s^2] \).
Exceptions
InputExceptionif input is invalid.
LogicExceptionif robot is not in the correct control mode.
ExecutionExceptionif error occurred during execution.
Note
Applicable control mode: NRT_JOINT_POSITION.
Warning
Calling this function a second time while the motion from the previous call is still ongoing will trigger an online re-planning of the joint trajectory, such that the previous command is aborted and the new command starts to execute.

◆ setCartesianStiffness()

void flexiv::Robot::setCartesianStiffness ( const std::vector< double > &  stiffness)

[Non-blocking] Set motion stiffness for the Cartesian motion-force control modes.

Parameters
[in]stiffnessCartesian motion stiffness: \( K_d \in \mathbb{R}^{6 \times 1} \). Setting motion stiffness of a motion-controlled Cartesian axis to 0 will make this axis free-floating. Consists of \( \mathbb{R}^{3 \times 1} \) linear stiffness and \( \mathbb{R}^{3 \times 1} \) angular stiffness: \( [k_x, k_y, k_z, k_{Rx}, k_{Ry}, k_{Rz}]^T \). Valid range: 0 to RobotInfo::nominalK. Unit: \( [N/m]~[Nm/rad] \).
Exceptions
InputExceptionif input is invalid.
LogicExceptionif robot is not in the correct control mode.
ExecutionExceptionif error occurred during execution.
Note
Applicable control modes: RT/NRT_CARTESIAN_MOTION_FORCE.
Warning
The robot will automatically reset to its nominal stiffness upon re-entering the applicable control modes.
Examples
intermediate4_realtime_cartesian_pure_motion_control.cpp.

◆ setForceControlAxis()

void flexiv::Robot::setForceControlAxis ( const std::vector< bool > &  enabledAxis)

[Blocking] Set force-controlled Cartesian axis(s) for the Cartesian motion-force control modes. The axis(s) not enabled for force control will be motion controlled. This function can only be called when the robot is in IDLE mode.

Parameters
[in]enabledAxisFlags to enable/disable force control for certain Cartesian axis(s) in the force control reference frame (configured by setForceControlFrame()). The corresponding order is \( [X, Y, Z, Rx, Ry, Rz] \). By default, force control is disabled for all Cartesian axes.
Exceptions
InputExceptionif input is invalid.
LogicExceptionif robot is not in the correct control mode.
ExecutionExceptionif failed to execute the request.
Note
Applicable control modes: IDLE.
Warning
This setting will reset to all axes disabled upon disconnection.
This function blocks until the request is successfully delivered to the robot.
Examples
intermediate5_realtime_cartesian_motion_force_control.cpp.

◆ setForceControlFrame()

void flexiv::Robot::setForceControlFrame ( const std::string &  referenceFrame)

[Blocking] Set force control reference frame for the Cartesian motion-force control modes. This function can only be called when the robot is in IDLE mode.

Parameters
[in]referenceFrameThe reference frame to use for force control. Options are: "TCP" and "BASE". The target wrench and force control axis should also be expressed in the selected reference frame. By default, base frame is used for force control.
Exceptions
InputExceptionif input is invalid.
LogicExceptionif robot is not in the correct control mode.
ExecutionExceptionif failed to execute the request.
Note
Applicable control modes: IDLE.
Warning
This setting will reset to robot base frame upon disconnection.
This function blocks until the request is successfully delivered to the robot.
Force control reference frame
In Cartesian motion-force control modes, the reference frame of motion control is always the robot base frame, but the reference frame of force control can be either robot base frame or the robot's current TCP frame. While the robot base frame is the commonly used global coordinate, the current TCP frame is a dynamic local coordinate whose transformation with regard to the robot base frame changes as the robot TCP moves. When using robot base frame for force control, the force-controlled axis(s) and motion-controlled axis(s) are guaranteed to be orthogonal. However, when using current TCP frame for force control, the force-controlled axis(s) and motion-controlled axis(s) are NOT guaranteed to be orthogonal because different reference frames are used. In this case, it's recommended but not required to set the target pose such that the actual robot motion direction(s) are orthogonal to force direction(s). If they are not orthogonal, the motion control's vector component(s) in the force direction(s) will be eliminated.
Examples
intermediate5_realtime_cartesian_motion_force_control.cpp.

◆ setGlobalVariables()

void flexiv::Robot::setGlobalVariables ( const std::string &  globalVars)

[Blocking] Set global variables for the robot by specifying name and value.

Parameters
[in]globalVarsCommand to set global variables using the format: globalVar1=value(s), globalVar2=value(s), ...
Exceptions
InputExceptionif size of the input string is greater than 5kb.
LogicExceptionif robot is not in the correct control mode.
ExecutionExceptionif error occurred during execution.
Note
Applicable control mode: NRT_PLAN_EXECUTION.
Warning
The specified global variable(s) must have already been created in the robot using Flexiv Elements, otherwise setting a nonexistent global variable will have no effect. To check if a global variable is successfully set, use getGlobalVariables().
This function blocks until the request is successfully delivered to the robot and fully processed.

◆ setMaxContactWrench()

void flexiv::Robot::setMaxContactWrench ( const std::vector< double > &  maxWrench)

[Non-blocking] Set maximum contact wrench for the motion control part of the Cartesian motion-force control modes. The controller will regulate its output to maintain contact wrench (force and moment) with the environment under the set values.

Parameters
[in]maxWrenchMaximum contact wrench (force and moment): \( F_max \in \mathbb{R}^{6 \times 1} \). Consists of \( \mathbb{R}^{3 \times 1} \) maximum force and \( \mathbb{R}^{3 \times 1} \) maximum moment: \( [f_x, f_y, f_z, m_x, m_y, m_z]^T \). Unit: \( [N]~[Nm] \).
Exceptions
InputExceptionif input is invalid.
LogicExceptionif robot is not in the correct control mode.
Note
The maximum contact wrench regulation only applies to the motion control part.
Applicable control modes: RT/NRT_CARTESIAN_MOTION_FORCE.
Warning
The maximum contact wrench regulation will automatically reset to disabled upon re-entering the applicable control modes.
The maximum contact wrench regulation cannot be enabled if any of the rotational Cartesian axes is enabled for moment control.
Examples
intermediate4_realtime_cartesian_pure_motion_control.cpp, and intermediate5_realtime_cartesian_motion_force_control.cpp.

◆ setMode()

void flexiv::Robot::setMode ( Mode  mode)

[Blocking] Set a new control mode to the robot and wait until the mode transition is finished.

Parameters
[in]modeflexiv::Mode enum.
Exceptions
InputExceptionif requested mode is invalid.
LogicExceptionif robot is in an unknown control mode.
ServerExceptionif robot is not operational.
ExecutionExceptionif failed to transit the robot into specified control mode after several attempts.
Warning
If the robot is still moving when this function is called, it will automatically stop then make the mode transition.
This function blocks until the robot has successfully transited into the specified control mode.
Examples
intermediate1_realtime_joint_position_control.cpp, intermediate2_realtime_joint_torque_control.cpp, intermediate3_realtime_joint_floating.cpp, intermediate4_realtime_cartesian_pure_motion_control.cpp, intermediate5_realtime_cartesian_motion_force_control.cpp, and intermediate6_robot_dynamics.cpp.

◆ setNullSpacePosture()

void flexiv::Robot::setNullSpacePosture ( const std::vector< double > &  preferredPositions)

[Non-blocking] Set preferred joint positions for the null-space posture control module used in the Cartesian motion-force control modes.

Parameters
[in]preferredPositionsPreferred joint positions for the null-space posture control: \( q_{ns} \in \mathbb{R}^{DOF \times 1} \). Unit: \( [rad] \).
Exceptions
InputExceptionif input is invalid.
LogicExceptionif robot is not in the correct control mode.
ExecutionExceptionif error occurred during execution.
Note
Applicable control modes: RT/NRT_CARTESIAN_MOTION_FORCE.
Warning
Upon entering the applicable control modes, the robot will automatically set its current joint positions as the preferred joint positions.
Null-space posture control
Similar to human arm, a robotic arm with redundant degree(s) of freedom (DOF > 6) can change its overall posture without affecting the ongoing primary task. This is achieved through a technique called "null-space control". After the preferred joint positions for a desired robot posture is set using this function, the robot's null-space control module will try to pull the arm as close to this posture as possible without affecting the primary Cartesian motion-force control task.
Examples
intermediate4_realtime_cartesian_pure_motion_control.cpp.

◆ setPassiveForceControl()

void flexiv::Robot::setPassiveForceControl ( bool  isEnabled)

[Blocking] Enable or disable passive force control for the Cartesian motion-force control modes. When enabled, an open-loop force controller will be used to feed forward the target wrench, i.e. passive force control. When disabled, a closed-loop force controller will be used to track the target wrench, i.e. active force control. This function can only be called when the robot is in IDLE mode.

Parameters
[in]isEnabledTrue: enable, false: disable. By default, passive force control is disabled and active force control is used.
Exceptions
LogicExceptionif robot is not in the correct control mode.
ExecutionExceptionif failed to execute the request.
Note
Applicable control modes: IDLE.
Warning
This setting will reset to disabled upon disconnection.
This function blocks until the request is successfully delivered to the robot.
Difference between active and passive force control
Active force control uses a feedback loop to reduce the error between target wrench and measured wrench. This method results in better force tracking performance, but at the cost of additional Cartesian damping which could potentially decrease motion tracking performance. On the other hand, passive force control simply feeds forward the target wrench. This methods results in worse force tracking performance, but is more robust and does not introduce additional Cartesian damping. The choice of active or passive force control depends on the actual application.

◆ stop()

void flexiv::Robot::stop ( void  )

[Blocking] Stop the robot and transit robot mode to Idle.

Exceptions
ExecutionExceptionif error occurred during execution.
Warning
This function blocks until the robot comes to a complete stop.
Examples
intermediate4_realtime_cartesian_pure_motion_control.cpp, and intermediate5_realtime_cartesian_motion_force_control.cpp.

◆ streamCartesianMotionForce()

void flexiv::Robot::streamCartesianMotionForce ( const std::vector< double > &  pose,
const std::vector< double > &  wrench = std::vector< double >(6) 
)

[Non-blocking] Continuously stream Cartesian motion and/or force command for the robot to track using its unified motion-force controller, which allows doing force control in zero or more Cartesian axes and motion control in the rest axes.

Parameters
[in]poseTarget TCP pose in base frame: \( {^{O}T_{TCP}}_{d} \in \mathbb{R}^{7 \times 1} \). Consists of \( \mathbb{R}^{3 \times 1} \) position and \( \mathbb{R}^{4 \times 1} \) quaternion: \( [x, y, z, q_w, q_x, q_y, q_z]^T \). Unit: \( [m]~[] \).
[in]wrenchTarget TCP wrench (force and moment) in the force control reference frame (configured by setForceControlFrame()): \( ^{0}F_d \in \mathbb{R}^{6 \times 1} \). The robot will track the target wrench using an explicit force controller. Consists of \( \mathbb{R}^{3 \times 1} \) force and \( \mathbb{R}^{3 \times 1} \) moment: \( [f_x, f_y, f_z, m_x, m_y, m_z]^T \). Unit: \( [N]~[Nm] \).
Exceptions
InputExceptionif input is invalid.
LogicExceptionif robot is not in the correct control mode.
ExecutionExceptionif error occurred during execution.
Note
Applicable control modes: RT_CARTESIAN_MOTION_FORCE.
Real-time (RT).
Warning
Always stream smooth and continuous motion commands to avoid sudden movements. The force commands don't need to be continuous.
How to achieve pure motion control?
Use setForceControlAxis() to disable force control for all Cartesian axes to achieve pure motion control. This function does pure motion control out of the box.
How to achieve pure force control?
Use setForceControlAxis() to enable force control for all Cartesian axes to achieve pure force control, active or passive.
How to achieve unified motion-force control?
Use setForceControlAxis() to enable force control for one or more Cartesian axes and leave the rest axes motion-controlled, then provide target pose for the motion-controlled axes and target wrench for the force-controlled axes.
See also
setCartesianStiffness(), setMaxContactWrench(), setNullSpacePosture(), setForceControlAxis(), setForceControlFrame(), setPassiveForceControl().
Examples
intermediate4_realtime_cartesian_pure_motion_control.cpp, and intermediate5_realtime_cartesian_motion_force_control.cpp.

◆ streamJointPosition()

void flexiv::Robot::streamJointPosition ( const std::vector< double > &  positions,
const std::vector< double > &  velocities,
const std::vector< double > &  accelerations 
)

[Non-blocking] Continuously stream joint position, velocity, and acceleration command to the robot.

Parameters
[in]positionsTarget joint positions: \( q_d \in \mathbb{R}^{DOF \times 1} \). Unit: \( [rad] \).
[in]velocitiesTarget joint velocities: \( \dot{q}_d \in \mathbb{R}^{DOF \times 1} \). Unit: \( [rad/s] \).
[in]accelerationsTarget joint accelerations: \( \ddot{q}_d \in \mathbb{R}^{DOF \times 1} \). Unit: \( [rad/s^2] \).
Exceptions
InputExceptionif input is invalid.
LogicExceptionif robot is not in the correct control mode.
ExecutionExceptionif error occurred during execution.
Note
Applicable control mode: RT_JOINT_POSITION.
Real-time (RT).
Warning
Always stream smooth and continuous commands to avoid sudden movements.
Examples
intermediate1_realtime_joint_position_control.cpp.

◆ streamJointTorque()

void flexiv::Robot::streamJointTorque ( const std::vector< double > &  torques,
bool  enableGravityComp = true,
bool  enableSoftLimits = true 
)

[Non-blocking] Continuously stream joint torque command to the robot.

Parameters
[in]torquesTarget joint torques: \( {\tau_J}_d \in \mathbb{R}^{DOF \times 1} \). Unit: \( [Nm] \).
[in]enableGravityCompEnable/disable robot gravity compensation.
[in]enableSoftLimitsEnable/disable soft limits to keep the joints from moving outside the allowed position range, which will trigger a safety fault that requires recovery operation.
Exceptions
InputExceptionif input is invalid.
LogicExceptionif robot is not in the correct control mode.
ExecutionExceptionif error occurred during execution.
Note
Applicable control mode: RT_JOINT_TORQUE.
Real-time (RT).
Warning
Always stream smooth and continuous commands to avoid sudden movements.
Examples
intermediate2_realtime_joint_torque_control.cpp, and intermediate3_realtime_joint_floating.cpp.

◆ switchTcp()

void flexiv::Robot::switchTcp ( unsigned int  index)

[Blocking] If the mounted tool has more than one TCP, switch the TCP being used by the robot. Default to the 1st one (index = 0).

Parameters
[in]indexIndex of the TCP on the mounted tool to switch to.
Exceptions
ExecutionExceptionif error occurred during execution.
Note
No need to call this function if the mounted tool on the robot has only one TCP, it'll be used by default.
New TCP index will take effect upon control mode switch, or upon sending a new primitive command. However, this function has no effect in plan execution mode as TCP index should be defined in the plan itself.
Warning
This function blocks until the request is successfully delivered to the robot.

◆ writeDigitalOutput()

void flexiv::Robot::writeDigitalOutput ( const std::vector< unsigned int > &  portIdx,
const std::vector< bool > &  values 
)

[Blocking] Write to a single or multiple digital output port(s) on the control box.

Parameters
[in]portIdxIndex of port(s) to write, can be a single port or multiple ports. E.g. {0, 5, 7, 15} or {1, 3, 10} or {8}. Valid range of the index number is [0–15].
[in]valuesCorresponding values to write to the specified ports. True: set port high, false: set port low. Vector size must match the size of portIdx.
Exceptions
InputExceptionif any index number in portIdx is not within [0–15], or if the two input vectors have different sizes.
ExecutionExceptionif failed to execute the request.
Warning
This function blocks until the request is successfully delivered to the robot.

The documentation for this class was generated from the following file: