Flexiv RDK APIs  1.6.0
robot.hpp
Go to the documentation of this file.
1 
6 #ifndef FLEXIV_RDK_ROBOT_HPP_
7 #define FLEXIV_RDK_ROBOT_HPP_
8 
9 #include "data.hpp"
10 #include "mode.hpp"
11 #include <vector>
12 #include <memory>
13 #include <exception>
14 #include <map>
15 
16 namespace flexiv {
17 namespace rdk {
18 
24 class Robot
25 {
26 public:
44  Robot(const std::string& robot_sn,
45  const std::vector<std::string>& network_interface_whitelist = {});
46  virtual ~Robot();
47 
48  //========================================= ACCESSORS ==========================================
53  bool connected() const;
54 
59  const RobotInfo info() const;
60 
65  Mode mode() const;
66 
72  const RobotStates states() const;
73 
78  bool stopped() const;
79 
89  bool operational(bool verbose = true) const;
90 
96 
104  bool busy() const;
105 
110  bool fault() const;
111 
122  bool reduced() const;
123 
135  bool recovery() const;
136 
141  bool estop_released() const;
142 
148 
157  const std::vector<std::string> mu_log() const;
158 
159  //======================================= SYSTEM CONTROL =======================================
167  void Enable();
168 
179  void Brake(bool engage);
180 
194 
200  void Stop();
201 
214  bool ClearFault(unsigned int timeout_sec = 30);
215 
225 
237  void SetGlobalVariables(const std::map<std::string, FlexivDataTypes>& global_vars);
238 
247  std::map<std::string, FlexivDataTypes> global_variables() const;
248 
249  //======================================= PLAN EXECUTION =======================================
268  unsigned int index, bool continue_exec = false, bool block_until_started = true);
269 
287  const std::string& name, bool continue_exec = false, bool block_until_started = true);
288 
298  void PausePlan(bool pause);
299 
306  const std::vector<std::string> plan_list() const;
307 
317  const PlanInfo plan_info() const;
318 
329  void SetBreakpointMode(bool is_enabled);
330 
342 
355  void SetVelocityScale(unsigned int velocity_scale);
356 
357  //==================================== PRIMITIVE EXECUTION =====================================
384  void ExecutePrimitive(const std::string& primitive_name,
385  const std::map<std::string, FlexivDataTypes>& input_params,
386  const std::map<std::string, FlexivDataTypes>& properties = {},
387  bool block_until_started = true);
388 
397  std::map<std::string, FlexivDataTypes> primitive_states() const;
398 
399  //==================================== DIRECT JOINT CONTROL ====================================
415  void StreamJointTorque(const std::vector<double>& torques, bool enable_gravity_comp = true,
416  bool enable_soft_limits = true);
417 
436  void StreamJointPosition(const std::vector<double>& positions,
437  const std::vector<double>& velocities, const std::vector<double>& accelerations);
438 
464  void SendJointPosition(const std::vector<double>& positions,
465  const std::vector<double>& velocities, const std::vector<double>& accelerations,
466  const std::vector<double>& max_vel, const std::vector<double>& max_acc);
467 
484  void SetJointImpedance(const std::vector<double>& K_q,
485  const std::vector<double>& Z_q = {0.7, 0.7, 0.7, 0.7, 0.7, 0.7, 0.7});
486 
487  //================================== DIRECT CARTESIAN CONTROL ==================================
533  void StreamCartesianMotionForce(const std::array<double, kPoseSize>& pose,
534  const std::array<double, kCartDoF>& wrench = {},
535  const std::array<double, kCartDoF>& velocity = {},
536  const std::array<double, kCartDoF>& acceleration = {});
537 
578  void SendCartesianMotionForce(const std::array<double, kPoseSize>& pose,
579  const std::array<double, kCartDoF>& wrench = {}, double max_linear_vel = 0.5,
580  double max_angular_vel = 1.0, double max_linear_acc = 2.0, double max_angular_acc = 5.0);
581 
601  void SetCartesianImpedance(const std::array<double, kCartDoF>& K_x,
602  const std::array<double, kCartDoF>& Z_x = {0.7, 0.7, 0.7, 0.7, 0.7, 0.7});
603 
620  void SetMaxContactWrench(const std::array<double, kCartDoF>& max_wrench);
621 
643  void SetNullSpacePosture(const std::vector<double>& ref_positions);
644 
666  void SetNullSpaceObjectives(double linear_manipulability = 0.0,
667  double angular_manipulability = 0.0, double ref_positions_tracking = 0.5);
668 
688  void SetForceControlAxis(const std::array<bool, kCartDoF>& enabled_axes,
689  const std::array<double, kCartDoF / 2>& max_linear_vel = {1.0, 1.0, 1.0});
690 
722  const std::array<double, kPoseSize>& T_in_root = {0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0});
723 
745  void SetPassiveForceControl(bool is_enabled);
746 
747  //======================================== IO CONTROL ========================================
761  const std::vector<unsigned int>& port_idx, const std::vector<bool>& values);
762 
769  const std::array<bool, kIOPorts> digital_inputs() const;
770 
771 private:
772  class Impl;
773  std::unique_ptr<Impl> pimpl_;
774 
775  friend class Device;
776  friend class FileIO;
777  friend class Gripper;
778  friend class Maintenance;
779  friend class Model;
780  friend class Safety;
781  friend class Tool;
782  friend class WorkCoord;
783 };
784 
785 } /* namespace rdk */
786 } /* namespace flexiv */
787 
788 #endif /* FLEXIV_RDK_ROBOT_HPP_ */
Interface with the robot device(s).
Definition: device.hpp:20
Interface for file transfer with the robot. The robot must be put into IDLE mode when transferring fi...
Definition: file_io.hpp:20
Interface with the robot gripper. Because gripper is also a type of device, this API uses the same un...
Definition: gripper.hpp:78
Interface to carry out robot maintenance operations. The robot must be in IDLE mode when triggering a...
Definition: maintenance.hpp:20
Interface to access certain robot kinematics and dynamics data.
Definition: model.hpp:21
Main interface with the robot, containing several function categories and background services.
Definition: robot.hpp:25
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...
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...
void SetDigitalOutputs(const std::vector< unsigned int > &port_idx, const std::vector< bool > &values)
[Blocking] Set one or more digital output ports, including 16 on the control box plus 2 inside the wr...
const RobotStates states() const
[Non-blocking] Current states data of the robot.
const std::vector< std::string > plan_list() const
[Blocking] Get a list of all available plans.
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 impedanc...
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 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 ExecutePrimitive(const std::string &primitive_name, const std::map< std::string, FlexivDataTypes > &input_params, const std::map< std::string, FlexivDataTypes > &properties={}, bool block_until_started=true)
[Blocking] Execute a primitive by specifying its name and parameters, which can be found in the Flexi...
const RobotInfo info() const
[Non-blocking] General information about the connected robot.
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.
bool operational(bool verbose=true) const
[Non-blocking] Whether the robot is ready to be operated, which requires the following conditions to ...
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.
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...
void SetVelocityScale(unsigned int velocity_scale)
[Blocking] Set overall velocity scale for robot motions during plan and primitive execution.
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....
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 robot mode to IDLE.
void PausePlan(bool pause)
[Blocking] Pause or resume the execution of the current plan.
const 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...
Robot(const std::string &robot_sn, const std::vector< std::string > &network_interface_whitelist={})
[Blocking] Create an instance as the main robot control interface. RDK services will initialize and c...
const std::vector< std::string > mu_log() const
[Non-blocking] Get multilingual log messages of the connected robot.
void SwitchMode(Mode mode)
[Blocking] Switch to a new control mode and wait until mode transition is finished.
std::map< std::string, FlexivDataTypes > global_variables() const
[Blocking] Existing global variables and their current values.
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.
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 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] State parameters of the executing primitive and their current values.
void SetBreakpointMode(bool is_enabled)
[Blocking] Enable or disable the breakpoint mode during plan execution. When enabled,...
void ExecutePlan(const std::string &name, bool continue_exec=false, bool block_until_started=true)
[Blocking] Execute a plan by specifying its name.
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...
const PlanInfo plan_info() const
[Blocking] Get detailed information about the currently executing plan. Contains information like pla...
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....
void Enable()
[Blocking] Enable the robot, if E-stop is released and there's no fault, the robot will release brake...
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 of the robot without a power cycle.
bool estop_released() const
[Non-blocking] Whether the emergency stop is released.
bool busy() const
[Non-blocking] Whether the robot is currently executing a task. This includes any user commanded oper...
void RunAutoRecovery()
[Blocking] Run automatic recovery to bring joints that are outside the allowed position range back in...
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 change robot safety settings. The robot must be in IDLE mode when applying any changes....
Definition: safety.hpp:47
Interface to online update and interact with the robot tools. All updates will take effect immediatel...
Definition: tool.hpp:42
Interface to online update and interact with the robot's work coordinates. All updates will take effe...
Definition: work_coord.hpp:21
Header file containing various constant expressions, data structs, and enums.
CoordType
Type of commonly-used reference coordinates.
Definition: data.hpp:58
OperationalStatus
Operational status of the robot. Except for the first two, the other enumerators indicate the cause o...
Definition: data.hpp:39
Mode
Robot control modes. The robot needs to be switched into the correct control mode before the correspo...
Definition: mode.hpp:22
Data structure containing information of the on-going primitive/plan.
Definition: data.hpp:266
General information about the connected robot.
Definition: data.hpp:69
Data structure containing the joint- and Cartesian-space robot states.
Definition: data.hpp:130