Header file containing various constant expressions, data structures, and enums.  
More...
#include <array>
#include <vector>
#include <string>
#include <ostream>
#include <variant>
#include <chrono>
Go to the source code of this file.
 | 
| using  | flexiv::rdk::FlexivDataTypes = std::variant< int, double, std::string, rdk::JPos, rdk::Coord, std::vector< int >, std::vector< double >, std::vector< std::string >, std::vector< rdk::JPos >, std::vector< rdk::Coord > > | 
|   | 
 | 
| enum class   | flexiv::rdk::OperationalStatus {  
  UNKNOWN = 0
, READY
, BOOTING
, ESTOP_NOT_RELEASED
,  
  NOT_ENABLED
, RELEASING_BRAKE
, MINOR_FAULT
, CRITICAL_FAULT
,  
  IN_REDUCED_STATE
, IN_RECOVERY_STATE
, IN_MANUAL_MODE
, IN_AUTO_MODE
 
 } | 
|   | Operational status of the robot. Except for the first two, the other enumerators indicate the cause of the robot being not ready to operate.  More...
  | 
|   | 
| enum class   | flexiv::rdk::CoordType { WORLD
, TCP
 } | 
|   | Type of commonly-used reference coordinates.  More...
  | 
|   | 
Header file containing various constant expressions, data structures, and enums. 
- Copyright
 - Copyright (C) 2016-2025 Flexiv Ltd. All Rights Reserved. 
 
Definition in file data.hpp.
 
◆ FlexivDataTypes
      
        
          | using flexiv::rdk::FlexivDataTypes = typedef std::variant<int, double, std::string, rdk::JPos, rdk::Coord, std::vector<int>, std::vector<double>, std::vector<std::string>, std::vector<rdk::JPos>, std::vector<rdk::Coord> > | 
        
      
 
Alias of the variant that holds all possible types of data exchanged with Flexiv robots 
Definition at line 435 of file data.hpp.
 
 
◆ CoordType
◆ OperationalStatus
Operational status of the robot. Except for the first two, the other enumerators indicate the cause of the robot being not ready to operate. 
- See also
 - Robot::operational_status(). 
 
| Enumerator | 
|---|
| UNKNOWN  | Unkown status.  
 | 
| READY  | Ready to be operated.  
 | 
| BOOTING  | System still booting, please wait.  
 | 
| ESTOP_NOT_RELEASED  | E-Stop is not released.  
 | 
| NOT_ENABLED  | Not enabled, call Enable() to send the signal.  
 | 
| RELEASING_BRAKE  | Brake release in progress, please wait.  
 | 
| MINOR_FAULT  | Minor fault occurred, call ClearFault() to try clearing it.  
 | 
| CRITICAL_FAULT  | Critical fault occurred, call ClearFault() to try clearing it.  
 | 
| IN_REDUCED_STATE  | In reduced state, see reduced().  
 | 
| IN_RECOVERY_STATE  | In recovery state, see recovery().  
 | 
| IN_MANUAL_MODE  | In Manual mode, need to switch to Auto (Remote) mode.  
 | 
| IN_AUTO_MODE  | In regular Auto mode, need to switch to Auto (Remote) mode.  
 | 
Definition at line 39 of file data.hpp.
 
 
◆ operator<<() [1/4]
      
        
          | std::ostream& flexiv::rdk::operator<<  | 
          ( | 
          std::ostream &  | 
          ostream,  | 
        
        
           | 
           | 
          const PlanInfo &  | 
          plan_info  | 
        
        
           | 
          ) | 
           |  | 
        
      
 
Operator overloading to out stream all members of PlanInfo in JSON format. 
- Parameters
 - 
  
    | [in] | ostream | Ostream instance.  | 
    | [in] | plan_info | PlanInfo data structure to out stream.  | 
  
   
- Returns
 - Updated ostream instance. 
 
 
 
◆ operator<<() [2/4]
      
        
          | std::ostream& flexiv::rdk::operator<<  | 
          ( | 
          std::ostream &  | 
          ostream,  | 
        
        
           | 
           | 
          const RobotEvent &  | 
          robot_event  | 
        
        
           | 
          ) | 
           |  | 
        
      
 
Operator overloading to out stream all members of RobotEvent in JSON format. 
- Parameters
 - 
  
    | [in] | ostream | Ostream instance.  | 
    | [in] | robot_event | RobotEvent data structure to out stream.  | 
  
   
- Returns
 - Updated ostream instance. 
 
- Note
 - The event timestamp is converted to local timezone when printed. 
 
 
 
◆ operator<<() [3/4]
      
        
          | std::ostream& flexiv::rdk::operator<<  | 
          ( | 
          std::ostream &  | 
          ostream,  | 
        
        
           | 
           | 
          const RobotInfo &  | 
          robot_info  | 
        
        
           | 
          ) | 
           |  | 
        
      
 
Operator overloading to out stream all members of RobotInfo in JSON format. 
- Parameters
 - 
  
    | [in] | ostream | Ostream instance.  | 
    | [in] | robot_info | RobotInfo data structure to out stream.  | 
  
   
- Returns
 - Updated ostream instance. 
 
 
 
◆ operator<<() [4/4]
      
        
          | std::ostream& flexiv::rdk::operator<<  | 
          ( | 
          std::ostream &  | 
          ostream,  | 
        
        
           | 
           | 
          const RobotStates &  | 
          robot_states  | 
        
        
           | 
          ) | 
           |  | 
        
      
 
Operator overloading to out stream all members of RobotStates in JSON format. 
- Parameters
 - 
  
    | [in] | ostream | Ostream instance.  | 
    | [in] | robot_states | RobotStates data structure to out stream.  | 
  
   
- Returns
 - Updated ostream instance. 
 
 
 
◆ kCartDoF
  
  
      
        
          | constexpr size_t flexiv::rdk::kCartDoF = 6 | 
         
       
   | 
  
constexpr   | 
  
 
Cartesian-space degrees of freedom 
Definition at line 20 of file data.hpp.
 
 
◆ kIOPorts
  
  
      
        
          | constexpr size_t flexiv::rdk::kIOPorts = 18 | 
         
       
   | 
  
constexpr   | 
  
 
Number of digital IO ports (16 on control box + 2 inside the wrist connector) 
Definition at line 29 of file data.hpp.
 
 
◆ kMaxExtAxes
  
  
      
        
          | constexpr size_t flexiv::rdk::kMaxExtAxes = 6 | 
         
       
   | 
  
constexpr   | 
  
 
Maximum number of external axes 
Definition at line 32 of file data.hpp.
 
 
◆ kPoseSize
  
  
      
        
          | constexpr size_t flexiv::rdk::kPoseSize = 7 | 
         
       
   | 
  
constexpr   | 
  
 
Size of pose array (3 position + 4 quaternion) 
Definition at line 26 of file data.hpp.
 
 
◆ kSerialJointDoF
  
  
      
        
          | constexpr size_t flexiv::rdk::kSerialJointDoF = 7 | 
         
       
   | 
  
constexpr   | 
  
 
Joint-space degrees of freedom of Flexiv's serial robots 
Definition at line 23 of file data.hpp.