Flexiv RDK APIs  0.10
Robot.hpp
Go to the documentation of this file.
1 
6 #ifndef FLEXIVRDK_ROBOT_HPP_
7 #define FLEXIVRDK_ROBOT_HPP_
8 
9 #include "Data.hpp"
10 #include "Mode.hpp"
11 
12 #include <array>
13 #include <vector>
14 #include <memory>
15 #include <functional>
16 
17 namespace flexiv {
18 
24 class Robot
25 {
26 public:
40  Robot(const std::string& serverIP, const std::string& localIP);
41  virtual ~Robot();
42 
47  const RobotInfo info(void);
48 
49  //============================= SYSTEM CONTROL =============================
59  void enable(void);
60 
66  void stop(void);
67 
78  bool isOperational(bool verbose = true) const;
79 
89  bool isBusy(void) const;
90 
96  bool isConnected(void) const;
97 
102  bool isFault(void) const;
103 
108  bool isEstopReleased(void) const;
109 
114  bool isEnablingButtonPressed(void) const;
115 
128  bool isRecoveryState(void) const;
129 
135  void connect(void);
136 
142  void disconnect(void);
143 
150  void clearFault(void);
151 
166  void setMode(Mode mode);
167 
172  Mode getMode(void) const;
173 
174  //============================ ROBOT OPERATIONS ============================
182 
197  void executePlan(unsigned int index, bool continueExec = false);
198 
212  void executePlan(const std::string& name, bool continueExec = false);
213 
223  void pausePlan(bool pause);
224 
232  std::vector<std::string> getPlanNameList(void) const;
233 
243  void getPlanInfo(PlanInfo& output);
244 
264  void executePrimitive(const std::string& ptCmd);
265 
275  std::vector<std::string> getPrimitiveStates(void) const;
276 
293  void setGlobalVariables(const std::string& globalVars);
294 
302  std::vector<std::string> getGlobalVariables(void) const;
303 
308  bool isStopped(void) const;
309 
323  void switchTcp(unsigned int index);
324 
334  void runAutoRecovery(void);
335 
336  //========================== DIRECT JOINT CONTROL ==========================
354  void streamJointTorque(const std::vector<double>& torques,
355  bool enableGravityComp = true, bool enableSoftLimits = true);
356 
374  void streamJointPosition(const std::vector<double>& positions,
375  const std::vector<double>& velocities,
376  const std::vector<double>& accelerations);
377 
406  void sendJointPosition(const std::vector<double>& positions,
407  const std::vector<double>& velocities,
408  const std::vector<double>& accelerations,
409  const std::vector<double>& maxVel, const std::vector<double>& maxAcc);
410 
411  //======================== DIRECT CARTESIAN CONTROL ========================
450  void streamCartesianMotionForce(const std::vector<double>& pose,
451  const std::vector<double>& wrench = std::vector<double>(6));
452 
495  void sendCartesianMotionForce(const std::vector<double>& pose,
496  const std::vector<double>& wrench = std::vector<double>(6),
497  double maxLinearVel = 0.5, double maxAngularVel = 1.0);
498 
516  void setCartesianStiffness(const std::vector<double>& stiffness);
517 
524 
544  void setMaxContactWrench(const std::vector<double>& maxWrench);
545 
552 
575  void setNullSpacePosture(const std::vector<double>& preferredPositions);
576 
583 
601  void setForceControlAxis(const std::vector<bool>& enabledAxis);
602 
635  void setForceControlFrame(const std::string& referenceFrame);
636 
662  void setPassiveForceControl(bool isEnabled);
663 
664  //=============================== IO CONTROL ===============================
680  void writeDigitalOutput(const std::vector<unsigned int>& portIdx,
681  const std::vector<bool>& values);
682 
688  std::array<bool, k_IOPorts> readDigitalInput(void);
689 
690 private:
691  class Impl;
692  std::unique_ptr<Impl> m_pimpl;
693 
694  friend class Model;
695  friend class Gripper;
696 };
697 
698 } /* namespace flexiv */
699 
700 #endif /* FLEXIVRDK_ROBOT_HPP_ */
Mode
Robot control modes. Must put the robot into the correct control mode before sending any correspondin...
Definition: Mode.hpp:17
Interface with grippers supported by Flexiv.
Definition: Gripper.hpp:19
Robot model with integrated dynamics engine.
Definition: Model.hpp:22
Main interface with the robot, containing several function categories and background services.
Definition: Robot.hpp:25
bool isEnablingButtonPressed(void) const
[Non-blocking] Check if the enabling button is pressed.
void setForceControlFrame(const std::string &referenceFrame)
[Blocking] Set force control reference frame for the Cartesian motion-force control modes....
void stop(void)
[Blocking] Stop the robot and transit robot mode to Idle.
void setGlobalVariables(const std::string &globalVars)
[Blocking] Set global variables for the robot by specifying name and value.
void setPassiveForceControl(bool isEnabled)
[Blocking] Enable or disable passive force control for the Cartesian motion-force control modes....
void getPlanInfo(PlanInfo &output)
[Blocking] Get detailed information about the currently running plan. Contains information like plan ...
void executePlan(const std::string &name, bool continueExec=false)
[Blocking] Execute a plan by specifying its name.
void switchTcp(unsigned int index)
[Blocking] If the mounted tool has more than one TCP, switch the TCP being used by the robot....
bool isRecoveryState(void) const
[Non-blocking] Check if the robot system is in recovery state.
void runAutoRecovery(void)
[Blocking] Run automatic recovery to bring joints that are outside the allowed position range back in...
void resetMaxContactWrench(void)
[Non-blocking] Reset max contact wrench regulation to nominal state, i.e. disabled.
void clearFault(void)
[Blocking] Clear minor fault of the robot.
void executePrimitive(const std::string &ptCmd)
[Blocking] Execute a primitive by specifying its name and parameters, which can be found in the Flexi...
void getRobotStates(RobotStates &output)
[Non-blocking] Get the latest robot states.
void resetCartesianStiffness(void)
[Non-blocking] Reset motion stiffness for the Cartesian motion-force control modes to nominal value.
bool isConnected(void) const
[Non-blocking] Check if the connection with the robot is established.
std::vector< std::string > getPrimitiveStates(void) const
[Blocking] Get feedback states of the currently executing primitive.
bool isStopped(void) const
[Non-blocking] Check if the robot has come to a complete stop.
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.
std::array< bool, k_IOPorts > readDigitalInput(void)
[Non-blocking] Read all digital input ports on the control box.
void writeDigitalOutput(const std::vector< unsigned int > &portIdx, const std::vector< bool > &values)
[Blocking] Write to a single or multiple digital output port(s) on the control box.
bool isFault(void) const
[Non-blocking] Check if the robot is in fault state.
void setMode(Mode mode)
[Blocking] Set a new control mode to the robot and wait until the mode transition is finished.
std::vector< std::string > getGlobalVariables(void) const
[Blocking] Get available global variables from the robot.
void streamJointTorque(const std::vector< double > &torques, bool enableGravityComp=true, bool enableSoftLimits=true)
[Non-blocking] Continuously stream joint torque command to the robot.
void setCartesianStiffness(const std::vector< double > &stiffness)
[Non-blocking] Set motion stiffness for the Cartesian motion-force control modes.
bool isBusy(void) const
[Non-blocking] Check if the robot is currently executing a task. This includes any user commanded ope...
void pausePlan(bool pause)
[Blocking] Pause or resume the execution of the current plan.
void streamCartesianMotionForce(const std::vector< double > &pose, const std::vector< double > &wrench=std::vector< double >(6))
[Non-blocking] Continuously stream Cartesian motion and/or force command for the robot to track using...
void setMaxContactWrench(const std::vector< double > &maxWrench)
[Non-blocking] Set maximum contact wrench for the motion control part of the Cartesian motion-force c...
bool isEstopReleased(void) const
[Non-blocking] Check if the Emergency Stop is released.
const RobotInfo info(void)
[Non-blocking] Access general information of the robot.
void connect(void)
[Blocking] Try establishing connection with the robot.
void sendCartesianMotionForce(const std::vector< double > &pose, const std::vector< double > &wrench=std::vector< double >(6), double maxLinearVel=0.5, double maxAngularVel=1.0)
[Non-blocking] Discretely send Cartesian motion and/or force command for the robot to track using its...
void resetNullSpacePosture(void)
[Non-blocking] Reset preferred joint positions to the ones automatically recorded when entering the a...
void setForceControlAxis(const std::vector< bool > &enabledAxis)
[Blocking] Set force-controlled Cartesian axis(s) for the Cartesian motion-force control modes....
void sendJointPosition(const std::vector< double > &positions, const std::vector< double > &velocities, const std::vector< double > &accelerations, const std::vector< double > &maxVel, const std::vector< double > &maxAcc)
[Non-blocking] Discretely send joint position, velocity, and acceleration command....
void enable(void)
[Blocking] Enable the robot, if E-stop is released and there's no fault, the robot will release brake...
Robot(const std::string &serverIP, const std::string &localIP)
[Blocking] Create a flexiv::Robot instance as the main robot interface. RDK services will initialize ...
bool isOperational(bool verbose=true) const
[Non-blocking] Check if the robot is normally operational, which requires the following conditions to...
void disconnect(void)
[Blocking] Disconnect with the robot.
std::vector< std::string > getPlanNameList(void) const
[Blocking] Get a list of all available plans from the robot.
void executePlan(unsigned int index, bool continueExec=false)
[Blocking] Execute a plan by specifying its index.
Mode getMode(void) const
[Non-blocking] Get the current control mode of the robot.
void setNullSpacePosture(const std::vector< double > &preferredPositions)
[Non-blocking] Set preferred joint positions for the null-space posture control module used in the Ca...
Data struct containing information of the on-going primitive/plan.
Definition: Data.hpp:208
General information of the connected robot.
Definition: Data.hpp:23
Data struct containing the joint- and Cartesian-space robot states.
Definition: Data.hpp:78