Flexiv RDK APIs  1.8.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:
52  Robot(const std::string& robot_sn,
53  const std::vector<std::string>& network_interface_whitelist = {}, bool verbose = true,
54  bool lite = false);
55  virtual ~Robot();
56 
57  //========================================= ACCESSORS ==========================================
62  bool lite() const;
63 
68  bool connected() const;
69 
74  RobotInfo info() const;
75 
80  Mode mode() const;
81 
87 
92  bool stopped() const;
93 
101  bool operational() const;
102 
108 
116  bool busy() const;
117 
122  bool fault() const;
123 
134  bool reduced() const;
135 
147  bool recovery() const;
148 
153  bool estop_released() const;
154 
160 
168  std::vector<RobotEvent> event_log() const;
169 
170  //======================================= SYSTEM CONTROL =======================================
178  void Enable();
179 
190  void Brake(bool engage);
191 
206 
212  void Stop();
213 
226  bool ClearFault(unsigned int timeout_sec = 30);
227 
238 
250  void SetGlobalVariables(const std::map<std::string, FlexivDataTypes>& global_vars);
251 
260  std::map<std::string, FlexivDataTypes> global_variables() const;
261 
271  void LockExternalAxes(bool toggle);
272 
282  void SyncWithPositioner(bool toggle);
283 
291  void SetTimelinessFailureLimit(unsigned int limit = 3);
292 
293  //======================================= PLAN EXECUTION =======================================
312  unsigned int index, bool continue_exec = false, bool block_until_started = true);
313 
331  const std::string& name, bool continue_exec = false, bool block_until_started = true);
332 
342  void PausePlan(bool toggle);
343 
351  void StopPlan();
352 
359  std::vector<std::string> plan_list() const;
360 
371 
382  void SetBreakpointMode(bool is_enabled);
383 
395 
408  void SetVelocityScale(unsigned int velocity_scale);
409 
410  //==================================== PRIMITIVE EXECUTION =====================================
437  void ExecutePrimitive(const std::string& primitive_name,
438  const std::map<std::string, FlexivDataTypes>& input_params,
439  bool block_until_started = true);
440 
448  std::map<std::string, FlexivDataTypes> primitive_states() const;
449 
450  //==================================== DIRECT JOINT CONTROL ====================================
466  void StreamJointTorque(const std::vector<double>& torques, bool enable_gravity_comp = true,
467  bool enable_soft_limits = true);
468 
487  void StreamJointPosition(const std::vector<double>& positions,
488  const std::vector<double>& velocities, const std::vector<double>& accelerations);
489 
513  void SendJointPosition(const std::vector<double>& positions,
514  const std::vector<double>& velocities, const std::vector<double>& max_vel,
515  const std::vector<double>& max_acc);
516 
534  void SetJointImpedance(const std::vector<double>& K_q, const std::vector<double>& Z_q = {});
535 
549  void SetMaxContactTorque(const std::vector<double>& max_torques);
550 
567  void SetJointInertiaScale(const std::vector<double>& inertia_scales);
568 
569  //================================== DIRECT CARTESIAN CONTROL ==================================
615  void StreamCartesianMotionForce(const std::array<double, kPoseSize>& pose,
616  const std::array<double, kCartDoF>& wrench = {},
617  const std::array<double, kCartDoF>& velocity = {},
618  const std::array<double, kCartDoF>& acceleration = {});
619 
666  void SendCartesianMotionForce(const std::array<double, kPoseSize>& pose,
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);
670 
692  void SetCartesianImpedance(const std::array<double, kCartDoF>& K_x,
693  const std::array<double, kCartDoF>& Z_x = {0.7, 0.7, 0.7, 0.7, 0.7, 0.7});
694 
713  void SetMaxContactWrench(const std::array<double, kCartDoF>& max_wrench);
714 
738  void SetNullSpacePosture(const std::vector<double>& ref_positions);
739 
762  void SetNullSpaceObjectives(double linear_manipulability = 0.0,
763  double angular_manipulability = 0.0, double ref_positions_tracking = 0.5);
764 
785  void SetForceControlAxis(const std::array<bool, kCartDoF>& enabled_axes,
786  const std::array<double, kCartDoF / 2>& max_linear_vel = {1.0, 1.0, 1.0});
787 
820  const std::array<double, kPoseSize>& T_in_root = {0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0});
821 
843  void SetPassiveForceControl(bool is_enabled);
844 
845  //======================================== IO CONTROL ========================================
856  void SetDigitalOutputs(const std::map<unsigned int, bool>& digital_outputs);
857 
864  std::array<bool, kIOPorts> digital_inputs() const;
865 
866 private:
867  class Impl;
868  std::unique_ptr<Impl> pimpl_;
869 
870  friend class Device;
871  friend class FileIO;
872  friend class Gripper;
873  friend class Maintenance;
874  friend class Model;
875  friend class Safety;
876  friend class Tool;
877  friend class WorkCoord;
878 };
879 
880 } /* namespace rdk */
881 } /* namespace flexiv */
882 
883 #endif /* FLEXIV_RDK_ROBOT_HPP_ */
Interface to control the peripheral device(s) connected to the robot.
Definition: device.hpp:23
Interface to exchange files with the robot. Only certain types of file can be transferred.
Definition: file_io.hpp:19
Interface to control the gripper installed on the robot. Because gripper is also a type of robot devi...
Definition: gripper.hpp:77
Interface to run maintenance operations on the robot.
Definition: maintenance.hpp:19
Interface to obtain certain model data of the robot, including kinematics and dynamics.
Definition: model.hpp:21
Main interface to control 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...
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...
Definition: safety.hpp:48
Interface to manage tools of the robot. All updates take effect immediately without a power cycle....
Definition: tool.hpp:42
Interface to manage work coordinates of the robot. All updates take effect immediately without a powe...
Definition: work_coord.hpp:20
Header file containing various constant expressions, data structures, and enums.
CoordType
Type of commonly-used reference coordinates.
Definition: data.hpp:59
OperationalStatus
Operational status of the robot. Except for the first two, the other enumerators indicate the cause o...
Definition: data.hpp:40
Mode
Robot control modes. The robot needs to be switched into the correct control mode before the correspo...
Definition: mode.hpp:22
Information of the on-going primitive/plan.
Definition: data.hpp:312
General information about the connected robot.
Definition: data.hpp:108
Robot states data in joint and Cartesian space.
Definition: data.hpp:168