Flexiv RDK APIs  1.4
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 
15 namespace flexiv {
16 namespace rdk {
17 
23 class Robot
24 {
25 public:
39  Robot(const std::string& robot_sn);
40  virtual ~Robot();
41 
42  //========================================= ACCESSORS ==========================================
47  bool connected() const;
48 
53  const RobotInfo info() const;
54 
59  Mode mode() const;
60 
66  const RobotStates states() const;
67 
72  bool stopped() const;
73 
83  bool operational(bool verbose = true) const;
84 
92  bool busy() const;
93 
98  bool fault() const;
99 
110  bool recovery() const;
111 
116  bool estop_released() const;
117 
123 
132  const std::vector<std::string> mu_log() const;
133 
134  //======================================= SYSTEM CONTROL =======================================
142  void Enable();
143 
154  void Brake(bool engage);
155 
169 
175  void Stop();
176 
189  bool ClearFault(unsigned int timeout_sec = 30);
190 
200 
213  void SetVelocityScale(unsigned int velocity_scale);
214 
215  //======================================= PLAN EXECUTION =======================================
228  void ExecutePlan(unsigned int index, bool continue_exec = false);
229 
241  void ExecutePlan(const std::string& name, bool continue_exec = false);
242 
251  void PausePlan(bool pause);
252 
259  const std::vector<std::string> plan_list() const;
260 
270  const PlanInfo plan_info() const;
271 
285  void SetGlobalVariables(const std::string& global_vars);
286 
293  const std::vector<std::string> global_variables() const;
294 
305  void SetBreakpointMode(bool is_enabled);
306 
318 
319  //==================================== PRIMITIVE EXECUTION =====================================
338  void ExecutePrimitive(const std::string& pt_cmd);
339 
347  const std::vector<std::string> primitive_states() const;
348 
349  //==================================== DIRECT JOINT CONTROL ====================================
365  void StreamJointTorque(const std::vector<double>& torques, bool enable_gravity_comp = true,
366  bool enable_soft_limits = true);
367 
386  void StreamJointPosition(const std::vector<double>& positions,
387  const std::vector<double>& velocities, const std::vector<double>& accelerations);
388 
414  void SendJointPosition(const std::vector<double>& positions,
415  const std::vector<double>& velocities, const std::vector<double>& accelerations,
416  const std::vector<double>& max_vel, const std::vector<double>& max_acc);
417 
436  void SetJointImpedance(const std::vector<double>& K_q,
437  const std::vector<double>& Z_q = {0.7, 0.7, 0.7, 0.7, 0.7, 0.7, 0.7});
438 
446 
447  //================================== DIRECT CARTESIAN CONTROL ==================================
484  void StreamCartesianMotionForce(const std::array<double, kPoseSize>& pose,
485  const std::array<double, kCartDoF>& wrench = {},
486  const std::array<double, kCartDoF>& acceleration = {});
487 
525  void SendCartesianMotionForce(const std::array<double, kPoseSize>& pose,
526  const std::array<double, kCartDoF>& wrench = {}, double max_linear_vel = 0.5,
527  double max_angular_vel = 1.0, double max_linear_acc = 2.0, double max_angular_acc = 5.0);
528 
550  void SetCartesianImpedance(const std::array<double, kCartDoF>& K_x,
551  const std::array<double, kCartDoF>& Z_x = {0.7, 0.7, 0.7, 0.7, 0.7, 0.7});
552 
560 
579  void SetMaxContactWrench(const std::array<double, kCartDoF>& max_wrench);
580 
586 
608  void SetNullSpacePosture(const std::vector<double>& preferred_positions);
609 
616 
639  void SetForceControlAxis(const std::array<bool, kCartDoF>& enabled_axis,
640  const std::array<double, kCartDoF / 2>& max_linear_vel = {1.0, 1.0, 1.0});
641 
668  void SetForceControlFrame(const std::string& reference_frame);
669 
692  void SetPassiveForceControl(bool is_enabled);
693 
694  //======================================== IO CONTROL ========================================
707  const std::vector<unsigned int>& port_idx, const std::vector<bool>& values);
708 
714  const std::array<bool, kIOPorts> ReadDigitalInput();
715 
716 private:
717  class Impl;
718  std::unique_ptr<Impl> pimpl_;
719 
720  friend class Model;
721  friend class Gripper;
722  friend class Device;
723  friend class Tool;
724  friend class FileIO;
725 };
726 
727 } /* namespace rdk */
728 } /* namespace flexiv */
729 
730 #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.
Definition: gripper.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:24
void StreamCartesianMotionForce(const std::array< double, kPoseSize > &pose, const std::array< double, kCartDoF > &wrench={}, const std::array< double, kCartDoF > &acceleration={})
[Non-blocking] Continuously stream Cartesian motion and/or force command for the robot to track using...
void SetMaxContactWrench(const std::array< double, kCartDoF > &max_wrench)
[Non-blocking] Set maximum contact wrench for the motion control part of the Cartesian motion-force c...
const RobotStates states() const
[Non-blocking] Access the current robot states.
const std::vector< std::string > primitive_states() const
[Blocking] Get feedback states of the currently executing primitive.
const std::vector< std::string > plan_list() const
[Blocking] Get a list of all available plans.
void WriteDigitalOutput(const std::vector< unsigned int > &port_idx, const std::vector< bool > &values)
[Blocking] Write to single or multiple digital output port(s) on the control box.
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})
[Non-blocking] Set impedance properties of the robot's joint motion controller used in the joint impe...
bool recovery() const
[Non-blocking] Whether the robot system is in recovery state.
void Brake(bool engage)
[Blocking] Force robot brakes to engage or release during normal operation. Restrictions apply,...
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.
const RobotInfo info() const
[Non-blocking] Access general information of the robot.
Mode mode() const
[Non-blocking] Access current control mode of the connected robot.
bool operational(bool verbose=true) const
[Non-blocking] Whether the robot is normally operational, which requires the following conditions to ...
void ExecutePrimitive(const std::string &pt_cmd)
[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 command to the robot.
void SetVelocityScale(unsigned int velocity_scale)
[Blocking] Set overall velocity scale for robot motions during plan and primitive execution.
void SetGlobalVariables(const std::string &global_vars)
[Blocking] Set global variables for the robot by specifying name and value.
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 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.
void ResetMaxContactWrench()
[Non-blocking] Reset max contact wrench regulation to nominal state, i.e. disabled.
const std::vector< std::string > mu_log() const
[Non-blocking] Access the 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.
void ResetJointImpedance()
[Non-blocking] Reset impedance properties of the robot's joint motion controller to nominal 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})
[Non-blocking] Set impedance properties of the robot's Cartesian motion controller used in the Cartes...
Robot(const std::string &robot_sn)
[Blocking] Create an instance as the main robot control interface. RDK services will initialize and c...
const std::vector< std::string > global_variables() const
[Blocking] Get available global variables from the robot.
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 ExecutePlan(unsigned int index, bool continue_exec=false)
[Blocking] Execute a plan by specifying its index.
const std::array< bool, kIOPorts > ReadDigitalInput()
[Non-blocking] Read all digital input ports on the control box.
void SetBreakpointMode(bool is_enabled)
[Blocking] Enable or disable the breakpoint mode during plan execution. When enabled,...
void SetForceControlAxis(const std::array< bool, kCartDoF > &enabled_axis, const std::array< double, kCartDoF/2 > &max_linear_vel={1.0, 1.0, 1.0})
[Blocking] Set force-controlled Cartesian axis(s) for the Cartesian motion-force control modes....
void ExecutePlan(const std::string &name, bool continue_exec=false)
[Blocking] Execute a plan by specifying its name.
void SetForceControlFrame(const std::string &reference_frame)
[Blocking] Set force control reference frame for the Cartesian motion-force control modes....
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 ResetNullSpacePosture()
[Non-blocking] Reset preferred joint positions to the ones automatically recorded when entering the a...
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 SetNullSpacePosture(const std::vector< double > &preferred_positions)
[Non-blocking] Set preferred joint positions for the null-space posture control module used in the Ca...
void RunAutoRecovery()
[Blocking] Run automatic recovery to bring joints that are outside the allowed position range back in...
void ResetCartesianImpedance()
[Non-blocking] Reset impedance properties of the robot's Cartesian motion controller to nominal value...
Interface to online update and interact with the robot tools. All changes made to the robot tool syst...
Definition: tool.hpp:21
Header file containing various data structs.
Mode
Robot control modes. The robot needs to be switched into the correct control mode before the correspo...
Definition: mode.hpp:19
Data structure containing information of the on-going primitive/plan.
Definition: data.hpp:202
General information about the connected robot.
Definition: data.hpp:32
Data structure containing the joint- and Cartesian-space robot states.
Definition: data.hpp:89