AUBO SDK  0.26.0
Loading...
Searching...
No Matches
arcs::common_interface::RobotSafetyParameterRange Struct Reference

#include <type_def.h>

Collaboration diagram for arcs::common_interface::RobotSafetyParameterRange:

Public Member Functions

 RobotSafetyParameterRange ()
 

Public Attributes

uint32_t crc32 { 0 }
 
struct { 
 
   float   power 
 sum of joint torques times joint angular speeds More...
 
   float   momentum 
 robot momentum limit More...
 
   float   stop_time 
 stop time in milliseconds More...
 
   float   stop_distance 
 stop distance in meters More...
 
   float   reduced_entry_time 
 maximum time to enter reduced mode More...
 
   float   reduced_entry_distance 
 maximum distance to enter reduced mode (can be triggered by safety planes) More...
 
   float   tcp_speed 
 
   float   elbow_speed 
 
   float   tcp_force 
 
   float   elbow_force 
 
   std::vector< float >   qmin 
 
   std::vector< float >   qmax 
 
   std::vector< float >   qdmax 
 
   std::vector< float >   joint_torque 
 
   Vector3f   tool_orientation 
 
   float   tool_deviation 
 
   Vector4f   planes [SAFETY_PLANES_NUM
 
   int   restrict_elbow [SAFETY_PLANES_NUM
 x,y,z,displacement More...
 
params [SAFETY_PARAM_SELECT_NUM
 At most 2 sets of parameters can be saved, default is the 0th set.
 
struct { 
 
   Vector4f   plane 
 
   int   restrict_elbow 
 x,y,z,displacement More...
 
trigger_planes [SAFETY_PLANES_NUM
 8 trigger planes
 
struct { 
 
   Vector6f   orig 
 origin of the cubic (x,y,z,rx,ry,rz) More...
 
   Vector3f   size 
 size of the cubic (x,y,z) More...
 
   int   restrict_elbow 
 
cubic [SAFETY_CUBIC_NUM
 10 safety spaces
 
Vector4f tools [TOOL_CONFIGURATION_NUM]
 3 tools
 
float tool_inclination
 x,y,z,radius
 
float tool_azimuth { 0. }
 azimuth angle
 
std::vector< float > safety_home
 
uint32_t safety_input_emergency_stop
 Configurable IO input and output safety functions.
 
uint32_t safety_input_safeguard_stop
 
uint32_t safety_input_safeguard_reset
 
uint32_t safety_input_auto_safeguard_stop
 
uint32_t safety_input_auto_safeguard_reset
 
uint32_t safety_input_three_position_switch
 
uint32_t safety_input_operational_mode
 
uint32_t safety_input_reduced_mode
 
uint32_t safety_input_handguide
 
uint32_t safety_output_emergency_stop
 
uint32_t safety_output_not_emergency_stop
 
uint32_t safety_output_robot_moving
 
uint32_t safety_output_robot_steady
 
uint32_t safety_output_reduced_mode
 
uint32_t safety_output_not_reduced_mode
 
uint32_t safety_output_safe_home
 
uint32_t safety_output_robot_not_stopping
 
uint32_t safety_output_safetyguard_stop
 
int tp_3pe_for_handguide
 Whether to use the three-position switch of the teach pendant as a hand guiding function switch.
 
int allow_manual_high_speed
 

Detailed Description

Definition at line 37 of file type_def.h.

Constructor & Destructor Documentation

◆ RobotSafetyParameterRange()

Member Data Documentation

◆ allow_manual_high_speed

int arcs::common_interface::RobotSafetyParameterRange::allow_manual_high_speed

Definition at line 177 of file type_def.h.

Referenced by RobotSafetyParameterRange().

◆ crc32

uint32_t arcs::common_interface::RobotSafetyParameterRange::crc32 { 0 }

Definition at line 105 of file type_def.h.

◆ [struct]

struct { ... } arcs::common_interface::RobotSafetyParameterRange::cubic[SAFETY_CUBIC_NUM]

10 safety spaces

Referenced by RobotSafetyParameterRange().

◆ elbow_force

float arcs::common_interface::RobotSafetyParameterRange::elbow_force

Definition at line 120 of file type_def.h.

◆ elbow_speed

float arcs::common_interface::RobotSafetyParameterRange::elbow_speed

Definition at line 118 of file type_def.h.

◆ joint_torque

std::vector<float> arcs::common_interface::RobotSafetyParameterRange::joint_torque

Definition at line 124 of file type_def.h.

Referenced by RobotSafetyParameterRange().

◆ momentum

float arcs::common_interface::RobotSafetyParameterRange::momentum

robot momentum limit

Definition at line 112 of file type_def.h.

◆ orig

Vector6f arcs::common_interface::RobotSafetyParameterRange::orig

origin of the cubic (x,y,z,rx,ry,rz)

Definition at line 140 of file type_def.h.

◆ [struct]

struct { ... } arcs::common_interface::RobotSafetyParameterRange::params[SAFETY_PARAM_SELECT_NUM]

At most 2 sets of parameters can be saved, default is the 0th set.

Referenced by RobotSafetyParameterRange().

◆ plane

Vector4f arcs::common_interface::RobotSafetyParameterRange::plane

Definition at line 134 of file type_def.h.

◆ planes

Vector4f arcs::common_interface::RobotSafetyParameterRange::planes[SAFETY_PLANES_NUM]

Definition at line 127 of file type_def.h.

◆ power

float arcs::common_interface::RobotSafetyParameterRange::power

sum of joint torques times joint angular speeds

Definition at line 111 of file type_def.h.

◆ qdmax

std::vector<float> arcs::common_interface::RobotSafetyParameterRange::qdmax

Definition at line 123 of file type_def.h.

Referenced by RobotSafetyParameterRange().

◆ qmax

std::vector<float> arcs::common_interface::RobotSafetyParameterRange::qmax

Definition at line 122 of file type_def.h.

Referenced by RobotSafetyParameterRange().

◆ qmin

std::vector<float> arcs::common_interface::RobotSafetyParameterRange::qmin

Definition at line 121 of file type_def.h.

Referenced by RobotSafetyParameterRange().

◆ reduced_entry_distance

float arcs::common_interface::RobotSafetyParameterRange::reduced_entry_distance

maximum distance to enter reduced mode (can be triggered by safety planes)

Definition at line 116 of file type_def.h.

◆ reduced_entry_time

float arcs::common_interface::RobotSafetyParameterRange::reduced_entry_time

maximum time to enter reduced mode

Definition at line 115 of file type_def.h.

◆ restrict_elbow

int arcs::common_interface::RobotSafetyParameterRange::restrict_elbow

x,y,z,displacement

Definition at line 128 of file type_def.h.

◆ safety_home

std::vector<float> arcs::common_interface::RobotSafetyParameterRange::safety_home

Definition at line 152 of file type_def.h.

Referenced by RobotSafetyParameterRange().

◆ safety_input_auto_safeguard_reset

uint32_t arcs::common_interface::RobotSafetyParameterRange::safety_input_auto_safeguard_reset

Definition at line 160 of file type_def.h.

Referenced by RobotSafetyParameterRange().

◆ safety_input_auto_safeguard_stop

uint32_t arcs::common_interface::RobotSafetyParameterRange::safety_input_auto_safeguard_stop

Definition at line 159 of file type_def.h.

Referenced by RobotSafetyParameterRange().

◆ safety_input_emergency_stop

uint32_t arcs::common_interface::RobotSafetyParameterRange::safety_input_emergency_stop

Configurable IO input and output safety functions.

Definition at line 156 of file type_def.h.

Referenced by RobotSafetyParameterRange().

◆ safety_input_handguide

uint32_t arcs::common_interface::RobotSafetyParameterRange::safety_input_handguide

Definition at line 164 of file type_def.h.

Referenced by RobotSafetyParameterRange().

◆ safety_input_operational_mode

uint32_t arcs::common_interface::RobotSafetyParameterRange::safety_input_operational_mode

Definition at line 162 of file type_def.h.

Referenced by RobotSafetyParameterRange().

◆ safety_input_reduced_mode

uint32_t arcs::common_interface::RobotSafetyParameterRange::safety_input_reduced_mode

Definition at line 163 of file type_def.h.

Referenced by RobotSafetyParameterRange().

◆ safety_input_safeguard_reset

uint32_t arcs::common_interface::RobotSafetyParameterRange::safety_input_safeguard_reset

Definition at line 158 of file type_def.h.

Referenced by RobotSafetyParameterRange().

◆ safety_input_safeguard_stop

uint32_t arcs::common_interface::RobotSafetyParameterRange::safety_input_safeguard_stop

Definition at line 157 of file type_def.h.

Referenced by RobotSafetyParameterRange().

◆ safety_input_three_position_switch

uint32_t arcs::common_interface::RobotSafetyParameterRange::safety_input_three_position_switch

Definition at line 161 of file type_def.h.

Referenced by RobotSafetyParameterRange().

◆ safety_output_emergency_stop

uint32_t arcs::common_interface::RobotSafetyParameterRange::safety_output_emergency_stop

Definition at line 166 of file type_def.h.

Referenced by RobotSafetyParameterRange().

◆ safety_output_not_emergency_stop

uint32_t arcs::common_interface::RobotSafetyParameterRange::safety_output_not_emergency_stop

Definition at line 167 of file type_def.h.

Referenced by RobotSafetyParameterRange().

◆ safety_output_not_reduced_mode

uint32_t arcs::common_interface::RobotSafetyParameterRange::safety_output_not_reduced_mode

Definition at line 171 of file type_def.h.

Referenced by RobotSafetyParameterRange().

◆ safety_output_reduced_mode

uint32_t arcs::common_interface::RobotSafetyParameterRange::safety_output_reduced_mode

Definition at line 170 of file type_def.h.

Referenced by RobotSafetyParameterRange().

◆ safety_output_robot_moving

uint32_t arcs::common_interface::RobotSafetyParameterRange::safety_output_robot_moving

Definition at line 168 of file type_def.h.

Referenced by RobotSafetyParameterRange().

◆ safety_output_robot_not_stopping

uint32_t arcs::common_interface::RobotSafetyParameterRange::safety_output_robot_not_stopping

Definition at line 173 of file type_def.h.

Referenced by RobotSafetyParameterRange().

◆ safety_output_robot_steady

uint32_t arcs::common_interface::RobotSafetyParameterRange::safety_output_robot_steady

Definition at line 169 of file type_def.h.

Referenced by RobotSafetyParameterRange().

◆ safety_output_safe_home

uint32_t arcs::common_interface::RobotSafetyParameterRange::safety_output_safe_home

Definition at line 172 of file type_def.h.

Referenced by RobotSafetyParameterRange().

◆ safety_output_safetyguard_stop

uint32_t arcs::common_interface::RobotSafetyParameterRange::safety_output_safetyguard_stop

Definition at line 174 of file type_def.h.

Referenced by RobotSafetyParameterRange().

◆ size

Vector3f arcs::common_interface::RobotSafetyParameterRange::size

size of the cubic (x,y,z)

Definition at line 141 of file type_def.h.

◆ stop_distance

float arcs::common_interface::RobotSafetyParameterRange::stop_distance

stop distance in meters

Definition at line 114 of file type_def.h.

◆ stop_time

float arcs::common_interface::RobotSafetyParameterRange::stop_time

stop time in milliseconds

Definition at line 113 of file type_def.h.

◆ tcp_force

float arcs::common_interface::RobotSafetyParameterRange::tcp_force

Definition at line 119 of file type_def.h.

◆ tcp_speed

float arcs::common_interface::RobotSafetyParameterRange::tcp_speed

Definition at line 117 of file type_def.h.

◆ tool_azimuth

float arcs::common_interface::RobotSafetyParameterRange::tool_azimuth { 0. }

azimuth angle

Definition at line 151 of file type_def.h.

Referenced by RobotSafetyParameterRange().

◆ tool_deviation

float arcs::common_interface::RobotSafetyParameterRange::tool_deviation

Definition at line 126 of file type_def.h.

◆ tool_inclination

float arcs::common_interface::RobotSafetyParameterRange::tool_inclination
Initial value:
{
0.
}

x,y,z,radius

inclination angle

Definition at line 148 of file type_def.h.

Referenced by RobotSafetyParameterRange().

◆ tool_orientation

Vector3f arcs::common_interface::RobotSafetyParameterRange::tool_orientation

Definition at line 125 of file type_def.h.

◆ tools

Vector4f arcs::common_interface::RobotSafetyParameterRange::tools[TOOL_CONFIGURATION_NUM]

3 tools

Definition at line 146 of file type_def.h.

Referenced by RobotSafetyParameterRange().

◆ tp_3pe_for_handguide

int arcs::common_interface::RobotSafetyParameterRange::tp_3pe_for_handguide

Whether to use the three-position switch of the teach pendant as a hand guiding function switch.

Definition at line 176 of file type_def.h.

Referenced by RobotSafetyParameterRange().

◆ [struct]

struct { ... } arcs::common_interface::RobotSafetyParameterRange::trigger_planes[SAFETY_PLANES_NUM]

8 trigger planes

Referenced by RobotSafetyParameterRange().


The documentation for this struct was generated from the following file: