6 #ifndef FLEXIV_RDK_ROBOT_HPP_ 
    7 #define FLEXIV_RDK_ROBOT_HPP_ 
   52     Robot(
const std::string& robot_sn,
 
   53         const std::vector<std::string>& network_interface_whitelist = {}, 
bool verbose = 
true,
 
  312         unsigned int index, 
bool continue_exec = 
false, 
bool block_until_started = 
true);
 
  331         const std::string& name, 
bool continue_exec = 
false, 
bool block_until_started = 
true);
 
  438         const std::map<std::string, FlexivDataTypes>& input_params,
 
  439         bool block_until_started = 
true);
 
  467         bool enable_soft_limits = 
true);
 
  488         const std::vector<double>& velocities, 
const std::vector<double>& accelerations);
 
  514         const std::vector<double>& velocities, 
const std::vector<double>& max_vel,
 
  515         const std::vector<double>& max_acc);
 
  616         const std::array<double, kCartDoF>& wrench = {},
 
  617         const std::array<double, kCartDoF>& velocity = {},
 
  618         const std::array<double, kCartDoF>& acceleration = {});
 
  667         const std::array<double, kCartDoF>& wrench = {},
 
  668         const std::array<double, kCartDoF>& velocity = {}, 
double max_linear_vel = 0.5,
 
  669         double max_angular_vel = 1.0, 
double max_linear_acc = 2.0, 
double max_angular_acc = 5.0);
 
  693         const std::array<double, kCartDoF>& Z_x = {0.7, 0.7, 0.7, 0.7, 0.7, 0.7});
 
  763         double angular_manipulability = 0.0, 
double ref_positions_tracking = 0.5);
 
  786         const std::array<double, kCartDoF / 2>& max_linear_vel = {1.0, 1.0, 1.0});
 
  820         const std::array<double, kPoseSize>& T_in_root = {0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0});
 
  868     std::unique_ptr<Impl> pimpl_;
 
Interface to control the peripheral device(s) connected to the robot.
 
Interface to exchange files with the robot. Only certain types of file can be transferred.
 
Interface to control the gripper installed on the robot. Because gripper is also a type of robot devi...
 
Interface to run maintenance operations on the robot.
 
Interface to obtain certain model data of the robot, including kinematics and dynamics.
 
Main interface to control the robot, containing several function categories and background services.
 
void ExecutePlan(unsigned int index, bool continue_exec=false, bool block_until_started=true)
[Blocking] Execute a plan by specifying its index.
 
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 po...
 
RobotInfo info() const
[Non-blocking] General information about the robot.
 
void SetMaxContactTorque(const std::vector< double > &max_torques)
[Blocking] Set maximum contact torques for the robot's joint motion controller used in the joint impe...
 
void SetJointInertiaScale(const std::vector< double > &inertia_scales)
[Blocking] Set inertia shaping scales for the robot's joint motion controller used in the joint imped...
 
void SetMaxContactWrench(const std::array< double, kCartDoF > &max_wrench)
[Blocking] Set maximum contact wrench for the motion control part of the Cartesian motion-force contr...
 
RobotStates states() const
[Non-blocking] Current states data of the robot.
 
bool recovery() const
[Non-blocking] Whether the robot is in recovery state.
 
void Brake(bool engage)
[Blocking] Force robot brakes to engage or release during normal operation. Restrictions apply,...
 
OperationalStatus operational_status() const
[Non-blocking] Current operational status of the robot.
 
void SetJointImpedance(const std::vector< double > &K_q, const std::vector< double > &Z_q={})
[Blocking] Set impedance properties of the robot's joint motion controller used in the joint impedanc...
 
void StepBreakpoint()
[Blocking] If breakpoint mode is enabled, step to the next breakpoint. The plan execution will contin...
 
bool stopped() const
[Non-blocking] Whether the robot has come to a complete stop.
 
void SetGlobalVariables(const std::map< std::string, FlexivDataTypes > &global_vars)
[Blocking] Set values to global variables that already exist in the robot.
 
Mode mode() const
[Non-blocking] Current control mode of the robot.
 
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 Flexi...
 
void StreamJointTorque(const std::vector< double > &torques, bool enable_gravity_comp=true, bool enable_soft_limits=true)
[Non-blocking] Continuously stream joint torque commands to the robot.
 
void SetDigitalOutputs(const std::map< unsigned int, bool > &digital_outputs)
[Blocking] Set one or more digital output ports, including 16 on the control box plus 2 inside the wr...
 
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 commands for the robot to track usin...
 
void SetVelocityScale(unsigned int velocity_scale)
[Blocking] Set overall velocity scale of robot motions during plan and primitive execution.
 
std::vector< RobotEvent > event_log() const
[Non-blocking] Robot events stored since the last successful instantiation of this class.
 
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....
 
void Stop()
[Blocking] Stop the robot and transit its control mode to IDLE.
 
void SendJointPosition(const std::vector< double > &positions, const std::vector< double > &velocities, const std::vector< double > &max_vel, const std::vector< double > &max_acc)
[Non-blocking] Discretely send joint position and velocity commands to the robot. The robot's interna...
 
void SwitchMode(Mode mode)
[Blocking] Switch the robot to a new control mode and wait for the mode transition to finish.
 
std::map< std::string, FlexivDataTypes > global_variables() const
[Blocking] Existing global variables and their current values.
 
void PausePlan(bool toggle)
[Blocking] Pause or resume the execution of the current plan.
 
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 ...
 
bool reduced() const
[Non-blocking] Whether the robot is in reduced state.
 
void StopPlan()
[Blocking] Stop the execution of the current plan.
 
bool connected() const
[Non-blocking] Whether the connection with the robot is established.
 
bool enabling_button_pressed() const
[Non-blocking] Whether the enabling button is pressed.
 
void SetTimelinessFailureLimit(unsigned int limit=3)
[Non-blocking] Set the maximum tolerable number of failed timeliness checks within 60 seconds when ru...
 
void SyncWithPositioner(bool toggle)
[Blocking] Sync/unsync the robot TCP's motion with the movement of the positioner (if any) during pri...
 
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 mod...
 
std::map< std::string, FlexivDataTypes > primitive_states() const
[Blocking] Names and values of the executing primitive's state parameters.
 
std::vector< std::string > plan_list() const
[Blocking] A list of all available plans.
 
bool operational() const
[Non-blocking] Whether the robot is ready to be operated, which requires the following conditions to ...
 
void SetBreakpointMode(bool is_enabled)
[Blocking] Enable or disable the breakpoint mode during plan execution. When enabled,...
 
void LockExternalAxes(bool toggle)
[Blocking] Lock/unlock external axes (if any) during primitive execution, direct joint control,...
 
void ExecutePlan(const std::string &name, bool continue_exec=false, bool block_until_started=true)
[Blocking] Execute a plan by specifying its name.
 
Robot(const std::string &robot_sn, const std::vector< std::string > &network_interface_whitelist={}, bool verbose=true, bool lite=false)
[Blocking] Instantiate the robot control interface. RDK services will be started and establish connec...
 
PlanInfo plan_info() const
[Blocking] Detailed information about the executing plan. Contains plan name, primitive name,...
 
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 commands to the robot....
 
void Enable()
[Blocking] Enable the robot. If E-stop is released and there's no fault, the robot will release brake...
 
bool lite() const
[Non-blocking] Whether this rdk::Robot instance is a lite one.
 
bool fault() const
[Non-blocking] Whether the robot is in fault state.
 
void SetPassiveForceControl(bool is_enabled)
[Blocking] Enable or disable passive force control for the Cartesian motion-force control modes....
 
bool ClearFault(unsigned int timeout_sec=30)
[Blocking] Try to clear minor or critical fault for the robot without a power cycle.
 
bool estop_released() const
[Non-blocking] Whether the emergency stop (E-stop) is released.
 
void SendCartesianMotionForce(const std::array< double, kPoseSize > &pose, const std::array< double, kCartDoF > &wrench={}, const std::array< double, kCartDoF > &velocity={}, 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 commands for the robot to track using it...
 
bool busy() const
[Non-blocking] Whether the robot is busy. This includes any user commanded operations that requires t...
 
void RunAutoRecovery()
[Blocking] Run automatic recovery to bring joints that are outside the allowed position range back in...
 
std::array< bool, kIOPorts > digital_inputs() const
[Non-blocking] Current reading from all digital input ports, including 16 on the control box plus 2 i...
 
void SetNullSpacePosture(const std::vector< double > &ref_positions)
[Blocking] Set reference joint positions for the null-space posture control module used in the Cartes...
 
Interface to manage safety settings of the robot. A password is required to authenticate this interfa...
 
Interface to manage work coordinates of the robot. All updates take effect immediately without a powe...
 
Header file containing various constant expressions, data structures, and enums.
 
CoordType
Type of commonly-used reference coordinates.
 
OperationalStatus
Operational status of the robot. Except for the first two, the other enumerators indicate the cause o...
 
Mode
Robot control modes. The robot needs to be switched into the correct control mode before the correspo...
 
Information of the on-going primitive/plan.
 
General information about the connected robot.
 
Robot states data in joint and Cartesian space.