Flexiv RDK APIs
0.10
|
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 |
Main interface with the robot, containing several function categories and background services.
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.
[in] | serverIP | IP address of the robot to connect (remote). |
[in] | localIP | IP address of the workstation PC (local). |
InitException | if the instance failed to initialize. |
CompatibilityException | if the RDK library version is incompatible with the connected robot. |
CommException | if failed to establish connection with the robot. |
void flexiv::Robot::clearFault | ( | void | ) |
[Blocking] Clear minor fault of the robot.
ExecutionException | if error occurred during execution. |
void flexiv::Robot::connect | ( | void | ) |
[Blocking] Try establishing connection with the robot.
CommException | if failed to establish connection. |
void flexiv::Robot::disconnect | ( | void | ) |
[Blocking] Disconnect with the robot.
ExecutionException | if error occurred during execution. |
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.
ExecutionException | if error occurred during execution. |
CommException | if the robot is not connected. |
void flexiv::Robot::executePlan | ( | const std::string & | name, |
bool | continueExec = false |
||
) |
[Blocking] Execute a plan by specifying its name.
[in] | name | Name of the plan to execute, can be obtained via getPlanNameList(). |
[in] | continueExec | Whether to continue executing the plan when the RDK program is closed or the connection is lost. |
LogicException | if robot is not in the correct control mode. |
ExecutionException | if error occurred during execution. |
void flexiv::Robot::executePlan | ( | unsigned int | index, |
bool | continueExec = false |
||
) |
[Blocking] Execute a plan by specifying its index.
[in] | index | Index of the plan to execute, can be obtained via getPlanNameList(). |
[in] | continueExec | Whether to continue executing the plan when the RDK program is closed or the connection is lost. |
InputException | if index is invalid. |
LogicException | if robot is not in the correct control mode. |
ExecutionException | if error occurred during execution. |
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.
[in] | ptCmd | Primitive command with the following string format: "primitiveName(inputParam1=xxx, inputParam2=xxx, ...)". |
InputException | if size of the input string is greater than 5kb. |
LogicException | if robot is not in the correct control mode. |
ExecutionException | if error occurred during execution. |
std::vector<std::string> flexiv::Robot::getGlobalVariables | ( | void | ) | const |
[Blocking] Get available global variables from the robot.
CommException | if there's no response from the robot. |
ExecutionException | if error occurred during execution. |
Mode flexiv::Robot::getMode | ( | void | ) | const |
[Non-blocking] Get the current control mode of the robot.
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.
[out] | output | Reference of output data object. |
CommException | if there's no response from the robot. |
ExecutionException | if error occurred during execution. |
std::vector<std::string> flexiv::Robot::getPlanNameList | ( | void | ) | const |
[Blocking] Get a list of all available plans from the robot.
CommException | if there's no response from the robot. |
ExecutionException | if error occurred during execution. |
std::vector<std::string> flexiv::Robot::getPrimitiveStates | ( | void | ) | const |
[Blocking] Get feedback states of the currently executing primitive.
CommException | if there's no response from the robot or the result is invalid. |
ExecutionException | if error occurred during execution. |
void flexiv::Robot::getRobotStates | ( | RobotStates & | output | ) |
[Non-blocking] Get the latest robot states.
[out] | output | Reference of output data object. |
const RobotInfo flexiv::Robot::info | ( | void | ) |
[Non-blocking] Access general information of the robot.
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.
bool flexiv::Robot::isConnected | ( | void | ) | const |
[Non-blocking] Check if the connection with the robot is established.
bool flexiv::Robot::isEnablingButtonPressed | ( | void | ) | const |
[Non-blocking] Check if the enabling button is pressed.
bool flexiv::Robot::isEstopReleased | ( | void | ) | const |
[Non-blocking] Check if the Emergency Stop is released.
bool flexiv::Robot::isFault | ( | void | ) | const |
[Non-blocking] Check if the robot is in fault state.
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.
[in] | verbose | Whether to print warning message indicating why the robot is not operational when this function returns false. |
bool flexiv::Robot::isRecoveryState | ( | void | ) | const |
[Non-blocking] Check if the robot system is in recovery state.
bool flexiv::Robot::isStopped | ( | void | ) | const |
[Non-blocking] Check if the robot has come to a complete stop.
void flexiv::Robot::pausePlan | ( | bool | pause | ) |
[Blocking] Pause or resume the execution of the current plan.
[in] | pause | True: pause plan, false: resume plan. |
LogicException | if robot is not in the correct control mode. |
ExecutionException | if error occurred during execution. |
std::array<bool, k_IOPorts> flexiv::Robot::readDigitalInput | ( | void | ) |
[Non-blocking] Read all digital input ports on the control box.
void flexiv::Robot::resetCartesianStiffness | ( | void | ) |
[Non-blocking] Reset motion stiffness for the Cartesian motion-force control modes to nominal value.
void flexiv::Robot::resetMaxContactWrench | ( | void | ) |
[Non-blocking] Reset max contact wrench regulation to nominal state, i.e. disabled.
void flexiv::Robot::resetNullSpacePosture | ( | void | ) |
[Non-blocking] Reset preferred joint positions to the ones automatically recorded when entering the applicable control modes.
void flexiv::Robot::runAutoRecovery | ( | void | ) |
[Blocking] Run automatic recovery to bring joints that are outside the allowed position range back into allowed range.
ExecutionException | if error occurred during execution. |
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.
[in] | pose | Target 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] | wrench | Target 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] | maxLinearVel | Maximum Cartesian linear velocity when moving to the target pose. A safe value is provided as default. Unit: \( [m/s] \). |
[in] | maxAngularVel | Maximum Cartesian angular velocity when moving to the target pose. A safe value is provided as default. Unit: \( [rad/s] \). |
InputException | if input is invalid. |
LogicException | if robot is not in the correct control mode. |
ExecutionException | if error occurred during execution. |
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.
[in] | positions | Target joint positions: \( q_d \in \mathbb{R}^{DOF \times 1} \). Unit: \( [rad] \). |
[in] | velocities | Target 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] | accelerations | Target 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] | maxVel | Maximum joint velocities for the planned trajectory: \( \dot{q}_{max} \in \mathbb{R}^{DOF \times 1} \). Unit: \( [rad/s] \). |
[in] | maxAcc | Maximum joint accelerations for the planned trajectory: \( \ddot{q}_{max} \in \mathbb{R}^{DOF \times 1} \). Unit: \( [rad/s^2] \). |
InputException | if input is invalid. |
LogicException | if robot is not in the correct control mode. |
ExecutionException | if error occurred during execution. |
void flexiv::Robot::setCartesianStiffness | ( | const std::vector< double > & | stiffness | ) |
[Non-blocking] Set motion stiffness for the Cartesian motion-force control modes.
[in] | stiffness | Cartesian 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] \). |
InputException | if input is invalid. |
LogicException | if robot is not in the correct control mode. |
ExecutionException | if error occurred during execution. |
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.
[in] | enabledAxis | Flags 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. |
InputException | if input is invalid. |
LogicException | if robot is not in the correct control mode. |
ExecutionException | if failed to execute the request. |
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.
[in] | referenceFrame | The 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. |
InputException | if input is invalid. |
LogicException | if robot is not in the correct control mode. |
ExecutionException | if failed to execute the request. |
void flexiv::Robot::setGlobalVariables | ( | const std::string & | globalVars | ) |
[Blocking] Set global variables for the robot by specifying name and value.
[in] | globalVars | Command to set global variables using the format: globalVar1=value(s), globalVar2=value(s), ... |
InputException | if size of the input string is greater than 5kb. |
LogicException | if robot is not in the correct control mode. |
ExecutionException | if error occurred during execution. |
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.
[in] | maxWrench | Maximum 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] \). |
InputException | if input is invalid. |
LogicException | if robot is not in the correct control mode. |
void flexiv::Robot::setMode | ( | Mode | mode | ) |
[Blocking] Set a new control mode to the robot and wait until the mode transition is finished.
[in] | mode | flexiv::Mode enum. |
InputException | if requested mode is invalid. |
LogicException | if robot is in an unknown control mode. |
ServerException | if robot is not operational. |
ExecutionException | if failed to transit the robot into specified control mode after several attempts. |
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.
[in] | preferredPositions | Preferred joint positions for the null-space posture control: \( q_{ns} \in \mathbb{R}^{DOF \times 1} \). Unit: \( [rad] \). |
InputException | if input is invalid. |
LogicException | if robot is not in the correct control mode. |
ExecutionException | if error occurred during execution. |
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.
[in] | isEnabled | True: enable, false: disable. By default, passive force control is disabled and active force control is used. |
LogicException | if robot is not in the correct control mode. |
ExecutionException | if failed to execute the request. |
void flexiv::Robot::stop | ( | void | ) |
[Blocking] Stop the robot and transit robot mode to Idle.
ExecutionException | if error occurred during execution. |
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.
[in] | pose | Target 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] | wrench | Target 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] \). |
InputException | if input is invalid. |
LogicException | if robot is not in the correct control mode. |
ExecutionException | if error occurred during execution. |
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.
[in] | positions | Target joint positions: \( q_d \in \mathbb{R}^{DOF \times 1} \). Unit: \( [rad] \). |
[in] | velocities | Target joint velocities: \( \dot{q}_d \in \mathbb{R}^{DOF \times 1} \). Unit: \( [rad/s] \). |
[in] | accelerations | Target joint accelerations: \( \ddot{q}_d \in \mathbb{R}^{DOF \times 1} \). Unit: \( [rad/s^2] \). |
InputException | if input is invalid. |
LogicException | if robot is not in the correct control mode. |
ExecutionException | if error occurred during execution. |
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.
[in] | torques | Target joint torques: \( {\tau_J}_d \in \mathbb{R}^{DOF \times 1} \). Unit: \( [Nm] \). |
[in] | enableGravityComp | Enable/disable robot gravity compensation. |
[in] | enableSoftLimits | Enable/disable soft limits to keep the joints from moving outside the allowed position range, which will trigger a safety fault that requires recovery operation. |
InputException | if input is invalid. |
LogicException | if robot is not in the correct control mode. |
ExecutionException | if error occurred during execution. |
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).
[in] | index | Index of the TCP on the mounted tool to switch to. |
ExecutionException | if error occurred during execution. |
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.
[in] | portIdx | Index 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] | values | Corresponding values to write to the specified ports. True: set port high, false: set port low. Vector size must match the size of portIdx. |
InputException | if any index number in portIdx is not within [0–15], or if the two input vectors have different sizes. |
ExecutionException | if failed to execute the request. |