Flexiv RDK APIs
1.5
|
Main interface with the robot, containing several function categories and background services. More...
#include <robot.hpp>
Public Member Functions | |
Robot (const std::string &robot_sn) | |
[Blocking] Create an instance as the main robot control interface. RDK services will initialize and connection with the robot will be established. More... | |
bool | connected () const |
[Non-blocking] Whether the connection with the robot is established. More... | |
const RobotInfo | info () const |
[Non-blocking] General information about the connected robot. More... | |
Mode | mode () const |
[Non-blocking] Current control mode of the robot. More... | |
const RobotStates | states () const |
[Non-blocking] Current states data of the robot. More... | |
bool | stopped () const |
[Non-blocking] Whether the robot has come to a complete stop. More... | |
bool | operational (bool verbose=true) const |
[Non-blocking] Whether the robot is ready to be operated, which requires the following conditions to be met: enabled, brakes fully released, in auto mode, no fault, and not in reduced state. More... | |
OperationalStatus | operational_status () const |
[Non-blocking] Current operational status of the robot. More... | |
bool | busy () const |
[Non-blocking] Whether 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 | fault () const |
[Non-blocking] Whether the robot is in fault state. More... | |
bool | reduced () const |
[Non-blocking] Whether the robot is in reduced state. More... | |
bool | recovery () const |
[Non-blocking] Whether the robot is in recovery state. More... | |
bool | estop_released () const |
[Non-blocking] Whether the emergency stop is released. More... | |
bool | enabling_button_pressed () const |
[Non-blocking] Whether the enabling button is pressed. More... | |
const std::vector< std::string > | mu_log () const |
[Non-blocking] Get multilingual log messages of the connected robot. More... | |
void | Enable () |
[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 | Brake (bool engage) |
[Blocking] Force robot brakes to engage or release during normal operation. Restrictions apply, see warning. More... | |
void | SwitchMode (Mode mode) |
[Blocking] Switch to a new control mode and wait until mode transition is finished. More... | |
void | Stop () |
[Blocking] Stop the robot and transit robot mode to IDLE. More... | |
bool | ClearFault (unsigned int timeout_sec=30) |
[Blocking] Try to clear minor or critical fault of the robot without a power cycle. More... | |
void | RunAutoRecovery () |
[Blocking] Run automatic recovery to bring joints that are outside the allowed position range back into allowed range. More... | |
void | SetGlobalVariables (const std::map< std::string, FlexivDataTypes > &global_vars) |
[Blocking] Set values to global variables that already exist in the robot. More... | |
void | SetGlobalVariables (const std::string &global_vars) |
std::map< std::string, FlexivDataTypes > | global_variables () const |
[Blocking] Existing global variables and their current values. More... | |
const std::vector< std::string > | global_variables (bool dummy) |
Unused parameter [dummy] is needed for function overloading. | |
void | ExecutePlan (unsigned int index, bool continue_exec=false, bool block_until_started=true) |
[Blocking] Execute a plan by specifying its index. More... | |
void | ExecutePlan (const std::string &name, bool continue_exec=false, bool block_until_started=true) |
[Blocking] Execute a plan by specifying its name. More... | |
void | PausePlan (bool pause) |
[Blocking] Pause or resume the execution of the current plan. More... | |
const std::vector< std::string > | plan_list () const |
[Blocking] Get a list of all available plans. More... | |
const PlanInfo | plan_info () const |
[Blocking] Get detailed information about the currently executing plan. Contains information like plan name, primitive name, node name, node path, node path time period, etc. More... | |
void | SetBreakpointMode (bool is_enabled) |
[Blocking] Enable or disable the breakpoint mode during plan execution. When enabled, the currently executing plan will pause at the pre-defined breakpoints. Use StepBreakpoint() to continue the execution and pause at the next breakpoint. More... | |
void | StepBreakpoint () |
[Blocking] If breakpoint mode is enabled, step to the next breakpoint. The plan execution will continue and pause at the next breakpoint. More... | |
void | SetVelocityScale (unsigned int velocity_scale) |
[Blocking] Set overall velocity scale for robot motions during plan and primitive execution. More... | |
void | ExecutePrimitive (const std::string &primitive_name, const std::map< std::string, FlexivDataTypes > &input_params, bool block_until_started=true) |
[Blocking] Execute a primitive by specifying its name and parameters, which can be found in the Flexiv Primitives documentation. More... | |
void | ExecutePrimitive (const std::string &pt_cmd, bool block_until_started=true) |
std::map< std::string, FlexivDataTypes > | primitive_states () const |
[Blocking] State parameters of the executing primitive and their current values. More... | |
const std::vector< std::string > | primitive_states (bool dummy) |
Unused parameter [dummy] is needed for function overloading. | |
void | StreamJointTorque (const std::vector< double > &torques, bool enable_gravity_comp=true, bool enable_soft_limits=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. The commands are tracked by either the joint impedance controller or the joint position controller, depending on the control mode. More... | |
void | SendJointPosition (const std::vector< double > &positions, const std::vector< double > &velocities, const std::vector< double > &accelerations, const std::vector< double > &max_vel, const std::vector< double > &max_acc) |
[Non-blocking] Discretely send joint position, velocity, and acceleration command to the robot. The robot's internal motion generator will smoothen the discrete commands, which are tracked by either the joint impedance controller or the joint position controller, depending on the control mode. More... | |
void | SetJointImpedance (const std::vector< double > &K_q, const std::vector< double > &Z_q={0.7, 0.7, 0.7, 0.7, 0.7, 0.7, 0.7}) |
[Blocking] Set impedance properties of the robot's joint motion controller used in the joint impedance control modes. More... | |
void | StreamCartesianMotionForce (const std::array< double, kPoseSize > &pose, const std::array< double, kCartDoF > &wrench={}, const std::array< double, kCartDoF > &velocity={}, const std::array< double, kCartDoF > &acceleration={}) |
[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::array< double, kPoseSize > &pose, const std::array< double, kCartDoF > &wrench={}, double max_linear_vel=0.5, double max_angular_vel=1.0, double max_linear_acc=2.0, double max_angular_acc=5.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 | SetCartesianImpedance (const std::array< double, kCartDoF > &K_x, const std::array< double, kCartDoF > &Z_x={0.7, 0.7, 0.7, 0.7, 0.7, 0.7}) |
[Blocking] Set impedance properties of the robot's Cartesian motion controller used in the Cartesian motion-force control modes. More... | |
void | SetMaxContactWrench (const std::array< double, kCartDoF > &max_wrench) |
[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 | SetNullSpacePosture (const std::vector< double > &ref_positions) |
[Blocking] Set reference joint positions for the null-space posture control module used in the Cartesian motion-force control modes. More... | |
void | SetNullSpaceObjectives (double linear_manipulability=0.0, double angular_manipulability=0.0, double ref_positions_tracking=0.5) |
[Blocking] Set weights of the three optimization objectives while computing the robot's null-space posture. Change the weights to optimize robot performance for different use cases. More... | |
void | SetForceControlAxis (const std::array< bool, kCartDoF > &enabled_axes, const std::array< double, kCartDoF/2 > &max_linear_vel={1.0, 1.0, 1.0}) |
[Blocking] Set Cartesian axes to enable force control while in the Cartesian motion-force control modes. Axes not enabled for force control will be motion-controlled. More... | |
void | SetForceControlFrame (CoordType root_coord, const std::array< double, kPoseSize > &T_in_root={0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0}) |
[Blocking] Set reference frame for force control while in the Cartesian motion-force control modes. The force control frame is defined by specifying its transformation with regard to the root coordinate. More... | |
void | SetPassiveForceControl (bool is_enabled) |
[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. More... | |
void | SetDigitalOutputs (const std::vector< unsigned int > &port_idx, const std::vector< bool > &values) |
[Blocking] Set one or more digital output port(s) on the control box. More... | |
void | WriteDigitalOutput (const std::vector< unsigned int > &port_idx, const std::vector< bool > &values) |
const std::array< bool, kIOPorts > | digital_inputs () |
[Non-blocking] Current reading of all digital input ports on the control box. More... | |
const std::array< bool, kIOPorts > | ReadDigitalInput () |
Friends | |
class | Device |
class | FileIO |
class | Gripper |
class | Model |
class | Tool |
class | WorkCoord |
Main interface with the robot, containing several function categories and background services.
flexiv::rdk::Robot::Robot | ( | const std::string & | robot_sn | ) |
[Blocking] Create an instance as the main robot control interface. RDK services will initialize and connection with the robot will be established.
[in] | robot_sn | Serial number of the robot to connect. The accepted formats are: "Rizon 4s-123456" and "Rizon4s-123456". |
std::invalid_argument | if the format of [robot_sn] is invalid. |
std::runtime_error | if the initialization sequence failed. |
std::logic_error | if the connected robot does not have a valid RDK license; or this RDK library version is incompatible with the connected robot; or model of the connected robot is not supported. |
void flexiv::rdk::Robot::Brake | ( | bool | engage | ) |
[Blocking] Force robot brakes to engage or release during normal operation. Restrictions apply, see warning.
[in] | engage | True: engage brakes; false: release brakes. |
std::logic_error | if the connected robot is not a medical one or the robot is moving. |
std::runtime_error | if failed to engage/release the brakes. |
bool flexiv::rdk::Robot::busy | ( | ) | const |
[Non-blocking] Whether 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::rdk::Robot::ClearFault | ( | unsigned int | timeout_sec = 30 | ) |
[Blocking] Try to clear minor or critical fault of the robot without a power cycle.
[in] | timeout_sec | Maximum time in seconds to wait for the fault to be successfully cleared. Normally, a minor fault should take no more than 3 seconds to clear, and a critical fault should take no more than 30 seconds to clear. |
std::runtime_error | if failed to deliver the request to the connected robot. |
bool flexiv::rdk::Robot::connected | ( | ) | const |
[Non-blocking] Whether the connection with the robot is established.
const std::array<bool, kIOPorts> flexiv::rdk::Robot::digital_inputs | ( | ) |
[Non-blocking] Current reading of all digital input ports on the control box.
void flexiv::rdk::Robot::Enable | ( | ) |
[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.
std::logic_error | if the robot is not connected. |
std::runtime_error | if failed to deliver the request to the connected robot. |
bool flexiv::rdk::Robot::enabling_button_pressed | ( | ) | const |
[Non-blocking] Whether the enabling button is pressed.
bool flexiv::rdk::Robot::estop_released | ( | ) | const |
[Non-blocking] Whether the emergency stop is released.
void flexiv::rdk::Robot::ExecutePlan | ( | const std::string & | name, |
bool | continue_exec = false , |
||
bool | block_until_started = true |
||
) |
[Blocking] Execute a plan by specifying its name.
[in] | name | Name of the plan to execute, can be obtained via plan_list(). |
[in] | continue_exec | Whether to continue executing the plan when the RDK program is closed or the connection is lost. |
[in] | block_until_started | Whether to wait for the commanded plan to finish loading and start execution before the function returns. Depending on the amount of computation needed to get the plan ready, the loading process typically takes no more than 200 ms. |
std::logic_error | if robot is not in an applicable control mode. |
std::runtime_error | if failed to deliver the request to the connected robot. |
void flexiv::rdk::Robot::ExecutePlan | ( | unsigned int | index, |
bool | continue_exec = false , |
||
bool | block_until_started = true |
||
) |
[Blocking] Execute a plan by specifying its index.
[in] | index | Index of the plan to execute, can be obtained via plan_list(). |
[in] | continue_exec | Whether to continue executing the plan when the RDK program is closed or the connection is lost. |
[in] | block_until_started | Whether to wait for the commanded plan to finish loading and start execution before the function returns. Depending on the amount of computation needed to get the plan ready, the loading process typically takes no more than 200 ms. |
std::invalid_argument | if [index] is outside the valid range. |
std::logic_error | if robot is not in an applicable control mode. |
std::runtime_error | if failed to deliver the request to the connected robot. |
void flexiv::rdk::Robot::ExecutePrimitive | ( | const std::string & | primitive_name, |
const std::map< std::string, FlexivDataTypes > & | input_params, | ||
bool | block_until_started = true |
||
) |
[Blocking] Execute a primitive by specifying its name and parameters, which can be found in the Flexiv Primitives documentation.
[in] | primitive_name | Primitive name. For example, "Home", "MoveL", "ZeroFTSensor", etc. |
[in] | input_params | A map of {input_parameter_name, input_parameter_value(s)}. Use int 1 and 0 to represent booleans. For example, {{"target", rdk::Coord({0.65, -0.3, 0.2}, {180, 0, 180}, {"WORLD", "WORLD_ORIGIN"})}, {"vel", 0.6}, {"zoneRadius", "Z50"}}. |
[in] | block_until_started | Whether to wait for the commanded primitive to finish loading and start execution before the function returns. Depending on the amount of computation needed to get the primitive ready, the loading process typically takes no more than 200 ms. |
std::length_error | if [input_params] is too long to transmit in one request. |
std::logic_error | if robot is not in an applicable control mode. |
std::runtime_error | if failed to deliver the request to the connected robot. |
bool flexiv::rdk::Robot::fault | ( | ) | const |
[Non-blocking] Whether the robot is in fault state.
std::map<std::string, FlexivDataTypes> flexiv::rdk::Robot::global_variables | ( | ) | const |
[Blocking] Existing global variables and their current values.
std::runtime_error | if failed to get a reply from the connected robot. |
const RobotInfo flexiv::rdk::Robot::info | ( | ) | const |
[Non-blocking] General information about the connected robot.
Mode flexiv::rdk::Robot::mode | ( | ) | const |
[Non-blocking] Current control mode of the robot.
const std::vector<std::string> flexiv::rdk::Robot::mu_log | ( | ) | const |
[Non-blocking] Get multilingual log messages of the connected robot.
bool flexiv::rdk::Robot::operational | ( | bool | verbose = true | ) | const |
[Non-blocking] Whether the robot is ready to be operated, 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. |
OperationalStatus flexiv::rdk::Robot::operational_status | ( | ) | const |
[Non-blocking] Current operational status of the robot.
void flexiv::rdk::Robot::PausePlan | ( | bool | pause | ) |
[Blocking] Pause or resume the execution of the current plan.
[in] | pause | True: pause plan; false: resume plan. |
std::logic_error | if robot is not in an applicable control mode. |
std::runtime_error | if failed to deliver the request to the connected robot. |
const PlanInfo flexiv::rdk::Robot::plan_info | ( | ) | const |
[Blocking] Get detailed information about the currently executing plan. Contains information like plan name, primitive name, node name, node path, node path time period, etc.
std::logic_error | if robot is not in an applicable control mode. |
std::runtime_error | if failed to get a reply from the connected robot. |
const std::vector<std::string> flexiv::rdk::Robot::plan_list | ( | ) | const |
[Blocking] Get a list of all available plans.
std::runtime_error | if failed to get a reply from the connected robot. |
std::map<std::string, FlexivDataTypes> flexiv::rdk::Robot::primitive_states | ( | ) | const |
[Blocking] State parameters of the executing primitive and their current values.
std::runtime_error | if failed to get a reply from the connected robot. |
bool flexiv::rdk::Robot::recovery | ( | ) | const |
[Non-blocking] Whether the robot is in recovery state.
bool flexiv::rdk::Robot::reduced | ( | ) | const |
[Non-blocking] Whether the robot is in reduced state.
void flexiv::rdk::Robot::RunAutoRecovery | ( | ) |
[Blocking] Run automatic recovery to bring joints that are outside the allowed position range back into allowed range.
std::runtime_error | if failed to enter automatic recovery mode. |
void flexiv::rdk::Robot::SendCartesianMotionForce | ( | const std::array< double, kPoseSize > & | pose, |
const std::array< double, kCartDoF > & | wrench = {} , |
||
double | max_linear_vel = 0.5 , |
||
double | max_angular_vel = 1.0 , |
||
double | max_linear_acc = 2.0 , |
||
double | max_angular_acc = 5.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 world 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] | max_linear_vel | Maximum Cartesian linear velocity when moving to the target pose. A safe value is provided as default. Unit: \( [m/s] \). |
[in] | max_angular_vel | Maximum Cartesian angular velocity when moving to the target pose. A safe value is provided as default. Unit: \( [rad/s] \). |
[in] | max_linear_acc | Maximum Cartesian linear acceleration when moving to the target pose. A safe value is provided as default. Unit: \( [m/s^2] \). |
[in] | max_angular_acc | Maximum Cartesian angular acceleration when moving to the target pose. A safe value is provided as default. Unit: \( [rad/s^2] \). |
std::invalid_argument | if any of the last 4 input parameters is negative. |
std::logic_error | if robot is not in an applicable control mode. |
void flexiv::rdk::Robot::SendJointPosition | ( | const std::vector< double > & | positions, |
const std::vector< double > & | velocities, | ||
const std::vector< double > & | accelerations, | ||
const std::vector< double > & | max_vel, | ||
const std::vector< double > & | max_acc | ||
) |
[Non-blocking] Discretely send joint position, velocity, and acceleration command to the robot. The robot's internal motion generator will smoothen the discrete commands, which are tracked by either the joint impedance controller or the joint position controller, depending on the control mode.
[in] | positions | Target joint positions: \( q_d \in \mathbb{R}^{n \times 1} \). Unit: \( [rad] \). |
[in] | velocities | Target joint velocities: \( \dot{q}_d \in \mathbb{R}^{n \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}^{n \times 1} \). Each joint will maintain this amount of acceleration when it reaches the target position. Unit: \( [rad/s^2] \). |
[in] | max_vel | Maximum joint velocities for the planned trajectory: \( \dot{q}_{max} \in \mathbb{R}^{n \times 1} \). Unit: \( [rad/s] \). |
[in] | max_acc | Maximum joint accelerations for the planned trajectory: \( \ddot{q}_{max} \in \mathbb{R}^{n \times 1} \). Unit: \( [rad/s^2] \). |
std::invalid_argument | if size of any input vector does not match robot DoF. |
std::logic_error | if robot is not in an applicable control mode. |
void flexiv::rdk::Robot::SetBreakpointMode | ( | bool | is_enabled | ) |
[Blocking] Enable or disable the breakpoint mode during plan execution. When enabled, the currently executing plan will pause at the pre-defined breakpoints. Use StepBreakpoint() to continue the execution and pause at the next breakpoint.
[in] | is_enabled | True: enable; false: disable. By default, breakpoint mode is disabled. |
std::logic_error | if robot is not in an applicable control mode. |
std::runtime_error | if failed to deliver the request to the connected robot. |
void flexiv::rdk::Robot::SetCartesianImpedance | ( | const std::array< double, kCartDoF > & | K_x, |
const std::array< double, kCartDoF > & | Z_x = {0.7, 0.7, 0.7, 0.7, 0.7, 0.7} |
||
) |
[Blocking] Set impedance properties of the robot's Cartesian motion controller used in the Cartesian motion-force control modes.
[in] | K_x | Cartesian motion stiffness: \( K_x \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, RobotInfo::K_x_nom]. Unit: \( [N/m]:[Nm/rad] \). |
[in] | Z_x | Cartesian motion damping ratio: \( Z_x \in \mathbb{R}^{6 \times 1} \). Consists of \( \mathbb{R}^{3 \times 1} \) linear damping ratio and \( \mathbb{R}^{3 \times 1} \) angular damping ratio: \( [\zeta_x, \zeta_y, \zeta_z, \zeta_{Rx}, \zeta_{Ry}, \zeta_{Rz}]^T \). Valid range: [0.3, 0.8]. The nominal (safe) value is provided as default. |
std::invalid_argument | if [K_x] or [Z_x] contains any value outside the valid range. |
std::logic_error | if robot is not in an applicable control mode. |
void flexiv::rdk::Robot::SetDigitalOutputs | ( | const std::vector< unsigned int > & | port_idx, |
const std::vector< bool > & | values | ||
) |
[Blocking] Set one or more digital output port(s) on the control box.
[in] | port_idx | Index of port(s) to set, 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 set to the specified ports. True: set port high, false: set port low. Vector size must match the size of port_idx. |
std::invalid_argument | if [port_idx] contains any index number outside the valid range. |
std::length_error | if the two input vectors have different sizes. |
std::runtime_error | if failed to deliver the request to the connected robot. |
void flexiv::rdk::Robot::SetForceControlAxis | ( | const std::array< bool, kCartDoF > & | enabled_axes, |
const std::array< double, kCartDoF/2 > & | max_linear_vel = {1.0, 1.0, 1.0} |
||
) |
[Blocking] Set Cartesian axes to enable force control while in the Cartesian motion-force control modes. Axes not enabled for force control will be motion-controlled.
[in] | enabled_axes | Flags to enable/disable force control for certain Cartesian axes in the force control reference frame (configured by SetForceControlFrame()). The axis order is \( [X, Y, Z, Rx, Ry, Rz] \). |
[in] | max_linear_vel | For linear Cartesian axes that are enabled for force control, limit the moving velocity to these values as a protection mechanism in case of contact loss. The axis order is \( [X, Y, Z] \). Valid range: [0.005, 2.0]. Unit: \( [m/s] \). |
std::invalid_argument | if [max_linear_vel] contains any value outside the valid range. |
std::logic_error | if robot is not in an applicable control mode. |
std::runtime_error | if failed to deliver the request to the connected robot. |
void flexiv::rdk::Robot::SetForceControlFrame | ( | CoordType | root_coord, |
const std::array< double, kPoseSize > & | T_in_root = {0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0} |
||
) |
[Blocking] Set reference frame for force control while in the Cartesian motion-force control modes. The force control frame is defined by specifying its transformation with regard to the root coordinate.
[in] | root_coord | Reference coordinate of [T_in_root]. |
[in] | T_in_root | Transformation from [root_coord] to the user-defined force control frame: \( ^{root}T_{force} \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]:[] \). If root coordinate is a fixed one (e.g. WORLD), then the force control frame will also be fixed; if root coordinate is a moving one (e.g. TCP), then the force control frame will also be moving with the root coordinate. An identity transformation is provided as default. |
std::logic_error | if robot is not in an applicable control mode. |
std::runtime_error | if failed to deliver the request to the connected robot. |
void flexiv::rdk::Robot::SetGlobalVariables | ( | const std::map< std::string, FlexivDataTypes > & | global_vars | ) |
[Blocking] Set values to global variables that already exist in the robot.
[in] | global_vars | A map of {global_var_name, global_var_value(s)}. Use int 1 and 0 to represent booleans. For example, {{"camera_offset", {0.1, -0.2, 0.3}}, {"start_plan", 1}}. |
std::length_error | if [global_vars] is empty or too long to transmit in one request. |
std::logic_error | if any of the specified global variables does not exist. |
std::runtime_error | if failed to deliver the request to the connected robot. |
void flexiv::rdk::Robot::SetJointImpedance | ( | const std::vector< double > & | K_q, |
const std::vector< double > & | Z_q = {0.7, 0.7, 0.7, 0.7, 0.7, 0.7, 0.7} |
||
) |
[Blocking] Set impedance properties of the robot's joint motion controller used in the joint impedance control modes.
[in] | K_q | Joint motion stiffness: \( K_q \in \mathbb{R}^{n \times 1} \). Setting motion stiffness of a joint axis to 0 will make this axis free-floating. Valid range: [0, RobotInfo::K_q_nom]. Unit: \( [Nm/rad] \). |
[in] | Z_q | Joint motion damping ratio: \( Z_q \in \mathbb{R}^{n \times 1} \). Valid range: [0.3, 0.8]. The nominal (safe) value is provided as default. |
std::invalid_argument | if [K_q] or [Z_q] contains any value outside the valid range or size of any input vector does not match robot DoF. |
std::logic_error | if robot is not in an applicable control mode. |
void flexiv::rdk::Robot::SetMaxContactWrench | ( | const std::array< double, kCartDoF > & | max_wrench | ) |
[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] | max_wrench | 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] \). |
std::invalid_argument | if [max_wrench] contains any negative value. |
std::logic_error | if robot is not in an applicable control mode. |
void flexiv::rdk::Robot::SetNullSpaceObjectives | ( | double | linear_manipulability = 0.0 , |
double | angular_manipulability = 0.0 , |
||
double | ref_positions_tracking = 0.5 |
||
) |
[Blocking] Set weights of the three optimization objectives while computing the robot's null-space posture. Change the weights to optimize robot performance for different use cases.
[in] | linear_manipulability | Increase this weight to improve the robot's capability to translate freely in Cartesian space, i.e. a broader range of potential translation movements. Valid range: [0.0, 1.0]. |
[in] | angular_manipulability | Increase this weight to improve the robot's capability to rotate freely in Cartesian space, i.e. a broader range of potential rotation movements. Valid range: [0.0, 1.0]. |
[in] | ref_positions_tracking | Increase this weight to make the robot track closer to the reference joint positions specified using SetNullSpacePosture(). Valid range: [0.1, 1.0]. |
std::invalid_argument | if any of the input parameters is outside its valid range. |
std::logic_error | if robot is not in an applicable control mode. |
std::runtime_error | if failed to deliver the request to the connected robot. |
void flexiv::rdk::Robot::SetNullSpacePosture | ( | const std::vector< double > & | ref_positions | ) |
[Blocking] Set reference joint positions for the null-space posture control module used in the Cartesian motion-force control modes.
[in] | ref_positions | Reference joint positions for the null-space posture control: \( q_{ns} \in \mathbb{R}^{n \times 1} \). Valid range: [RobotInfo::q_min, RobotInfo::q_max]. Unit: \( [rad] \). |
std::invalid_argument | if [ref_positions] contains any value outside the valid range or size of any input vector does not match robot DoF. |
std::logic_error | if robot is not in an applicable control mode. |
void flexiv::rdk::Robot::SetPassiveForceControl | ( | bool | is_enabled | ) |
[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.
[in] | is_enabled | True: enable; false: disable. By default, passive force control is disabled and active force control is used. |
std::logic_error | if robot is not in an applicable control mode. |
std::runtime_error | if failed to deliver the request to the connected robot. |
void flexiv::rdk::Robot::SetVelocityScale | ( | unsigned int | velocity_scale | ) |
[Blocking] Set overall velocity scale for robot motions during plan and primitive execution.
[in] | velocity_scale | Percentage scale to adjust the overall velocity of robot motions. Valid range: [0, 100]. Setting to 100 means to move with 100% of specified motion velocity, and 0 means not moving at all. |
std::invalid_argument | if [velocity_scale] is outside the valid range. |
std::logic_error | if robot is not in an applicable control mode. |
std::runtime_error | if failed to deliver the request to the connected robot. |
const RobotStates flexiv::rdk::Robot::states | ( | ) | const |
void flexiv::rdk::Robot::StepBreakpoint | ( | ) |
[Blocking] If breakpoint mode is enabled, step to the next breakpoint. The plan execution will continue and pause at the next breakpoint.
std::logic_error | if robot is not in an applicable control mode. |
std::runtime_error | if failed to deliver the request to the connected robot. |
void flexiv::rdk::Robot::Stop | ( | ) |
[Blocking] Stop the robot and transit robot mode to IDLE.
std::runtime_error | if failed to stop the robot. |
bool flexiv::rdk::Robot::stopped | ( | ) | const |
[Non-blocking] Whether the robot has come to a complete stop.
void flexiv::rdk::Robot::StreamCartesianMotionForce | ( | const std::array< double, kPoseSize > & | pose, |
const std::array< double, kCartDoF > & | wrench = {} , |
||
const std::array< double, kCartDoF > & | velocity = {} , |
||
const std::array< double, kCartDoF > & | acceleration = {} |
||
) |
[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 world 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] | velocity | Target TCP velocity (linear and angular) in world frame: \( ^{0}\dot{x}_d \in \mathbb{R}^{6 \times 1} \). Providing properly calculated target velocity can improve the robot's overall tracking performance at the cost of reduced robustness. Leaving this input 0 can maximize robustness at the cost of reduced tracking performance. Consists of \( \mathbb{R}^{3 \times 1} \) linear and \( \mathbb{R}^{3 \times 1} \) angular velocity. Unit: \( [m/s]:[rad/s] \). |
[in] | acceleration | Target TCP acceleration (linear and angular) in world frame: \( ^{0}\ddot{x}_d \in \mathbb{R}^{6 \times 1} \). Feeding forward target acceleration can improve the robot's tracking performance for highly dynamic motions, but it's also okay to leave this input 0. Consists of \( \mathbb{R}^{3 \times 1} \) linear and \( \mathbb{R}^{3 \times 1} \) angular acceleration. Unit: \( [m/s^2]:[rad/s^2] \). |
std::logic_error | if robot is not in an applicable control mode. |
std::runtime_error | if number of timeliness failures has reached limit. |
void flexiv::rdk::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. The commands are tracked by either the joint impedance controller or the joint position controller, depending on the control mode.
[in] | positions | Target joint positions: \( q_d \in \mathbb{R}^{n \times 1} \). Unit: \( [rad] \). |
[in] | velocities | Target joint velocities: \( \dot{q}_d \in \mathbb{R}^{n \times 1} \). Unit: \( [rad/s] \). |
[in] | accelerations | Target joint accelerations: \( \ddot{q}_d \in \mathbb{R}^{n \times 1} \). Unit: \( [rad/s^2] \). |
std::invalid_argument | if size of any input vector does not match robot DoF. |
std::logic_error | if robot is not in an applicable control mode. |
std::runtime_error | if number of timeliness failures has reached limit. |
void flexiv::rdk::Robot::StreamJointTorque | ( | const std::vector< double > & | torques, |
bool | enable_gravity_comp = true , |
||
bool | enable_soft_limits = true |
||
) |
[Non-blocking] Continuously stream joint torque command to the robot.
[in] | torques | Target joint torques: \( {\tau_J}_d \in \mathbb{R}^{n \times 1} \). Unit: \( [Nm] \). |
[in] | enable_gravity_comp | Enable/disable robot gravity compensation. |
[in] | enable_soft_limits | Enable/disable soft limits to keep the joints from moving outside allowed position range, which will trigger a safety fault that requires recovery operation. |
std::invalid_argument | if size of any input vector does not match robot DoF. |
std::logic_error | if robot is not in an applicable control mode. |
std::runtime_error | if number of timeliness failures has reached limit. |
void flexiv::rdk::Robot::SwitchMode | ( | Mode | mode | ) |
[Blocking] Switch to a new control mode and wait until mode transition is finished.
[in] | mode | flexiv::rdk::Mode enum. |
std::invalid_argument | if the requested mode is invalid or unlicensed. |
std::logic_error | if robot is in an unknown control mode or is not operational. |
std::runtime_error | if failed to transit the robot into the specified control mode after several attempts. |